Giter Site home page Giter Site logo

pal-robotics / aruco_ros Goto Github PK

View Code? Open in Web Editor NEW
423.0 16.0 301.0 1.12 MB

Software package and ROS wrappers of the Aruco Augmented Reality marker detector library

License: MIT License

CMake 1.00% Python 1.18% C 0.42% C++ 97.40%
aruco aruco-detector aruco-library aruco-marker-detection fiducial-marker robotics ros aruco-ros fiducial-marker-detector robot

aruco_ros's Introduction

aruco_ros

Software package and ROS wrappers of the Aruco Augmented Reality marker detector library.

Features

  • High-framerate tracking of AR markers

  • Generate AR markers with given size and optimized for minimal perceptive ambiguity (when there are more markers to track)

  • Enhanced precision tracking by using boards of markers

  • ROS wrappers

Applications

  • Object pose estimation
  • Visual servoing: track object and hand at the same time

ROS API

Messages

  • aruco_ros/Marker.msg

     Header header
     uint32 id
     geometry_msgs/PoseWithCovariance pose
     float64 confidence
    
  • aruco_ros/MarkerArray.msg

     Header header
     aruco_ros/Marker[] markers
    

Kinetic changes

  • Updated the Aruco library to version 3.0.4

  • Changed the coordinate system to match the library's, the convention is shown in the image below, following rviz conventions, X is red, Y is green and Z is blue.

Test it with REEM

  • Open a REEM in simulation with a marker floating in front of the robot. This will start the stereo cameras of the robot too. Since this is only a vision test, there is nothing else in this world apart from the robot and a marker floating in front of it. An extra light source had to be added to compensate for the default darkness.

    roslaunch reem_gazebo reem_gazebo.launch world:=floating_marker
    
  • Launch the image_proc node to get undistorted images from the cameras of the robot.

    ROS_NAMESPACE=/stereo/right rosrun image_proc image_proc image_raw:=image
    
  • Start the single node which will start tracking the specified marker and will publish its pose in the camera frame

    roslaunch aruco_ros single.launch markerId:=26 markerSize:=0.08 eye:="right"
    

    the frame in which the pose is refered to can be chosen with the 'ref_frame' argument. The next example forces the marker pose to be published with respect to the robot base_link frame:

    roslaunch aruco_ros single.launch markerId:=26 markerSize:=0.08 eye:="right" ref_frame:=/base_link
    
  • Visualize the result

    rosrun image_view image_view image:=/aruco_single/result
    

aruco_ros's People

Contributors

4lhc avatar bmagyar avatar cehberlin avatar fsuarez6 avatar jbohren avatar jdlangs avatar jordan-palacios avatar jordi-pages avatar jrgnicho avatar karsten1987 avatar mvieth avatar noel215 avatar saikishor avatar svozar avatar ugnelis avatar v-lopez avatar voidminded avatar wep21 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

aruco_ros's Issues

Does not build

I keep getting the following error:

ws/src/aruco_ros/aruco_ros/src/marker_publish.cpp:46:36: fatal error: aruco_msgs/MarkerArray.h: No such file or directory
compilation terminated.
aruco_ros/aruco_ros/CMakeFiles/marker_publisher.dir/build.make:62: recipe for target 'aruco_ros/aruco_ros/CMakeFiles/marker_publisher.dir/src/marker_publish.cpp.o' failed
make[2]: *** [aruco_ros/aruco_ros/CMakeFiles/marker_publisher.dir/src/marker_publish.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
[100%] Linking CXX shared library /home/user/dev/catkin_ws/devel/lib/libaruco_ros_utils.so
CMakeFiles/Makefile2:16004: recipe for target 'aruco_ros/aruco_ros/CMakeFiles/marker_publisher.dir/all' failed

I think it may be a dependency issue, but I don't know how to get around it. Please advise. I am using ros kinetic.

Marker Publisher Node Not Found

Hi,

Thank you for sharing this package! I tried to run the marker_publisher.launch file but I get the following error:

ERROR: cannot launch node of type [aruco_ros/marker_publisher]: can't locate node [marker_publisher] in package [aruco_ros]

I use the following command: $roslaunch marker_publisher.launch

I am able to get the single.launch file working perfectly and can see that the marker is detected. Also, the package was compiled without errors and installed in my catkin workspace.

Would you have any tips to fix this.

Thanks!

Pose estimation accuracy?

May I ask the accuracy/tolerance of the pose estimation (translation and rotation) of the ArUco marker? Is it millimeter-level for translation or bigger? And with rotation?

Thank you very much!

ARuco tf position does not match actual

I placed ARuco in front of the camera, but when RViz looked at the tf, the marker_frame was above the camera.

<launch>
  <arg name="markerId"          default="101"/>
  <arg name="markerSize"        default="0.045"/> <!-- in m -->
  <arg name="marker_frame"      default="aruco_marker_$(arg markerId)"/>
    
  <arg name="camera"            default="/camera/color"/>
  <arg name="camera_frame"      default="camera_link"/>
    
  <arg name="ref_frame"         default="/base_link"/> <!-- leave empty and the pose will be published wrt param parent_name -->
  <arg name="corner_refinement" default="LINES"/> <!-- NONE, HARRIS, LINES, SUBPIX -->

  <node pkg="aruco_ros" type="single" name="aruco_single">
    <remap from="/camera_info" to="$(arg camera)/camera_info" />
    <remap from="/image" to="$(arg camera)/image_raw" />
    <param name="camera_frame"       value="$(arg camera_frame)"/>
    
    <param name="image_is_rectified" value="True"/>
    <param name="marker_id"          value="$(arg markerId)"/>
    <param name="marker_size"        value="$(arg markerSize)"/>
    <param name="reference_frame"    value="$(arg ref_frame)"/> <!-- frame in which the marker pose will be refered -->  
    <param name="marker_frame"       value="$(arg marker_frame)" />
    <param name="corner_refinement"  value="$(arg corner_refinement)" />
  </node>
</launch>

Is there a maximum detection distance?

I noticed that the aruco markers are no longer detected when the camera is any further than ~1.5m. When the camera is within the range of 1.5-1.8m, the entire marker and the surrounding white border is still visible. Is there a configuration parameter that I can change? What exactly is causing this constraint?

I am using a ZED camera which is calibrated.

Monocular camera calibration

Good evening,

I have a monocular camera mounted on the end-effector of a kinova manipulator and I am trying to use Aruco_ros to detect the marker for getting the camera extrinsic parameters witih Ros Kinetic.
In the documentation I see how to use it with a reem gazebo simulator and a stereo camera.

Can I ask you the commands to run it without simulator and with a mono camera?
I tried but when I run rosrun image_view image_view image:=/aruco_single/result It does not work.

Thank you very much

Ros wrapper for Aruco 3.0.x

Hi ,

First of all thanks for the hard work. I would like to inquire if you are planning to update the aruco library to Aruco 3.0.X version any time soon.

problem in aruco/src/cameraParameters.cpp

any one found that in file aruco/src/cameraParameters.cpp, in this function cv::Point3f CameraParameters::getCameraLocation(cv::Mat Rvec,cv::Mat Tvec), line 103, m44.inv() should be m44 = m44.inv(), this function is to calculate the translation vector from camera to marker, so this place the m44 shoulder be its inverse matrix. But in the origin function, thr return values is the m44, but not the inverse. I download the source code of Aruco from their website, it still has this problem.

[aruco_tracker-26] process has died

Hi,this is my problem, as follows:
[aruco_tracker-26] process has died [pid 30152, exit code -11, cmd /home/tete/ur3_move/devel/lib/aruco_ros/single /image:=/camera/rgb/image_raw /camera_info:=/camera/rgb/camera_info __name:=aruco_tracker __log:=/home/tete/.ros/log/c99d989a-09ad-11e9-818c-8cec4b137f82/aruco_tracker-26.log].
log file: /home/tete/.ros/log/c99d989a-09ad-11e9-818c-8cec4b137f82/aruco_tracker-26*.log

How should I solve it?
Thanks!

Kinetic to Melodic orientation change

I upgraded from ROS Kinetic to Melodic, and noticed that my frames were broken. After some inspection it appeared that the marker frames were rotated by quaternion [w: -0.707, x:0, y:0, z:0.707] or euler [z:-90 deg]. I am sharing this as it may be useful to those upgrading from Kinetic to Melodic.

The frame shown in the readme looks outdated, currently the z-axis is orthogonal to the marker, pointing outwards.(There are two frames one is wrong, the second seems correct) It maybe helpful to keep a reference for the marker-transform relation somewhere in the docs. Thank you!

ERROR: cannot launch node of type [aruco_ros/single]: aruco_ros======What should I DO?

~/catkin_ws/src/aruco_ros/aruco_ros/launch$ roslaunch single.launch
... logging to /home/frank/.ros/log/4194766c-98ef-11ea-a685-e4f89c9e6c27/roslaunch-frank-Lenovo-XiaoXin-V4000-11084.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://192.168.43.39:32887/

SUMMARY

PARAMETERS

  • /aruco_single/camera_frame: stereo_gazebo_lef...
  • /aruco_single/corner_refinement: LINES
  • /aruco_single/image_is_rectified: True
  • /aruco_single/marker_frame: aruco_marker_frame
  • /aruco_single/marker_id: 582
  • /aruco_single/marker_size: 0.034
  • /aruco_single/reference_frame:
  • /rosdistro: kinetic
  • /rosversion: 1.12.14

NODES
/
aruco_single (aruco_ros/single)

auto-starting new master
process[master]: started with pid [11094]
ROS_MASTER_URI=http://192.168.43.39:11311

setting /run_id to 4194766c-98ef-11ea-a685-e4f89c9e6c27
process[rosout-1]: started with pid [11107]
started core service [/rosout]
ERROR: cannot launch node of type [aruco_ros/single]: aruco_ros
ROS path [0]=/opt/ros/kinetic/share/ros
ROS path [1]=/opt/ros/kinetic/share
^C[rosout-1] killing on exit
[master] killing on exit
1shutting down processing monitor...
... shutting down processing monitor complete
done

Error - "process has died"

Hello,

Thanks for sharing this package. I am traying to work with Aruco and ROS and I have though that this package could be useful for me.

The problem is that I get the following error when I try to run the single.launch file:

laboratorio@ai2-labmix7:~/catkin_ws/src/aruco_ros/aruco_ros/launch$ roslaunch single.launch
... logging to /home/laboratorio/.ros/log/b49e99ec-fa18-11e4-895a-4c72b9b133b4/roslaunch-ai2-labmix7-13054.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://ai2-labmix7:39150/

SUMMARY

PARAMETERS

  • /aruco_single/camera_frame
  • /aruco_single/image_is_rectified
  • /aruco_single/marker_frame
  • /aruco_single/marker_id
  • /aruco_single/marker_size
  • /aruco_single/reference_frame
  • /rosdistro
  • /rosversion

NODES
/
aruco_single (aruco_ros/single)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[aruco_single-1]: started with pid [13072]
[aruco_single-1] process has died [pid 13072, exit code -11, cmd /home/laboratorio/catkin_ws/devel/lib/aruco_ros/single /camera_info:=/stereo/left/camera_info /image:=/stereo/left/image_rect_color __name:=aruco_single __log:=/home/laboratorio/.ros/log/b49e99ec-fa18-11e4-895a-4c72b9b133b4/aruco_single-1.log].
log file: /home/laboratorio/.ros/log/b49e99ec-fa18-11e4-895a-4c72b9b133b4/aruco_single-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done

I don't know how to solve this problem, so if anyone could help me it would be great.
Thank you.

Markers not detected

I switched from ar track alvar to aruco due to some issues with camera model and the matrix used to compute the marker pose but I am now having problems getting aruco to detect the markers. Here is one example of the thresholded image using default parameters:
aruco
Why is this marker not being detected??

Linking in weird/ancient platforms, error with libutil.so

Hello. I don't expect anyone else to actually run into this problem...

But if anyone finds himself/herself encountering this error while compiling aruco_ros:

/home/vm/bin/ld: /home/vm/lib/libpython2.7.a(posixmodule.o): undefined reference to symbol 'forkpty@@GLIBC_2.0'
/lib/libutil.so.1: error adding symbols: DSO missing from command line
collect2: error: ld returned 1 exit status

I managed to get over it by adding to the catkin_make / catkin_make_isolated the flag -DCMAKE_EXE_LINKER_FLAGS=-lutil

I hope google indexes the issue, feel free to close it, but at least this little piece of info is somewhere to be found.

issue with catkin_make

Hi,

For ROS-Kinetic, it seems that most tutorials mention a very simple procedure by copying to /catkin_ws/src and running catkin_make

as shown here
https://github.com/eYSIP-2017/eYSIP-2017_Navigation-in-Indoor-Environments-using-drone/wiki/Setup-ArUco-Mapping-package
and
https://github.com/warp1337/ros_aruco

Unfortunately, after long hours of trying, this still leads to "aruco_msgs" missing configuration file, or 'aruco'

Following
#49
and installing aruco, aruco-ros, aruco-msgs, and aruco-mapping from apt, i.e. sudo apt install ros-kinetic-aruco

but once these are installed from apt, compiling another library leads to issues.
We are trying to compile
https://github.com/ankitdhall/lidar_camera_calibration
and it leads to 'lidar_camera_calibration" missing configuration file when running catkin_make
yet it works fine without that folder in the src folder.

Anyone have a similar experience?

We tried building non-aruco libraries from src with catkin_make, and it was successful. Our feeling is that something goes wrong with aruco builds, hence it can't even make them from source but can only do so after installing from apt.

Thanks,

Compilation Error while running catkin_make

rahul@Rahul:~/aruco_drone_ws$ catkin_make
Base path: /home/rahul/aruco_drone_ws
Source space: /home/rahul/aruco_drone_ws/src
Build space: /home/rahul/aruco_drone_ws/build
Devel space: /home/rahul/aruco_drone_ws/devel
Install space: /home/rahul/aruco_drone_ws/install

Running command: "make cmake_check_build_system" in "/home/rahul/aruco_drone_ws/build"

Running command: "make -j8 -l8" in "/home/rahul/aruco_drone_ws/build"

[ 0%] Built target geometry_msgs_generate_messages_py
[ 0%] Built target std_msgs_generate_messages_cpp
[ 0%] Built target std_msgs_generate_messages_py
[ 0%] Built target std_msgs_generate_messages_eus
[ 0%] Built target geometry_msgs_generate_messages_cpp
[ 0%] Built target std_msgs_generate_messages_lisp
[ 0%] Built target geometry_msgs_generate_messages_eus
[ 0%] Built target geometry_msgs_generate_messages_lisp
[ 2%] Built target aruco
[ 2%] Built target geometry_msgs_generate_messages_nodejs
[ 2%] Built target std_msgs_generate_messages_nodejs
[ 2%] Built target _aruco_msgs_generate_messages_check_deps_Marker
[ 2%] Built target _aruco_msgs_generate_messages_check_deps_MarkerArray
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RC
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_HeadingCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_ThrustCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_ServoCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_MotorCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_AttitudeCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_Compass
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_YawrateCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_HeightCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_Supply
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_VelocityZCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RawImu
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_VelocityXYCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RuddersCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RawRC
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_MotorStatus
[ 3%] Built target pal_vision_segmentation_gencfg
[ 3%] Building CXX object pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/src/image_processing.cpp.o
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_Altitude
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_MotorPWM
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_ControllerState
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_RawMagnetic
[ 3%] Performing update step for 'ardronelib'
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_Altimeter
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_PositionXYCommand
[ 3%] Performing configure step for 'ardronelib'
No configure
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_time
[ 3%] Performing build step for 'ardronelib'
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_adc_data_frame
make[3]: warning: jobserver unavailable: using -j1. Add '+' to parent make rule.
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_pressure_raw
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_altitude
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_watchdog
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_euler_angles
Libs already extracted
Building target static
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_references
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_demo
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_video_stream
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_RecordEnable
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_zimmu_3000
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_trims
Architecture x86_64 is already built
Creating universal static lib file from architectures x86_64
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_matrix33
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_magneto
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_CamSelect
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_wifi
Build done.
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_gyros_offsets
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_FlightAnim
Building ARDroneTool/Lib
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_hdvideo_stream
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_vector21
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_kalman_pressure
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_trackers_send
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_phys_measures
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_pwm
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_raw_measures
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_vector31
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_LedAnim
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_games
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_rc_references
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision_of
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision_raw
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_Navdata
[ 3%] Built target aruco_ros_gencfg
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision_perf
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_wind_speed
[ 3%] Built target ardrone_autonomy_generate_messages_check_deps_navdata_vision_detect
[ 3%] Built target visualization_msgs_generate_messages_py
[ 3%] Built target dynamic_reconfigure_generate_messages_nodejs
[ 4%] Built target aruco_ros_utils
[ 4%] Built target dynamic_reconfigure_generate_messages_eus
[ 4%] Built target sensor_msgs_generate_messages_cpp
[ 4%] Built target roscpp_generate_messages_eus
[ 4%] Built target sensor_msgs_generate_messages_lisp
[ 4%] Built target dynamic_reconfigure_generate_messages_cpp
[ 4%] Built target sensor_msgs_generate_messages_py
[ 4%] Built target sensor_msgs_generate_messages_eus
[ 4%] Built target rosgraph_msgs_generate_messages_cpp
[ 4%] Built target sensor_msgs_generate_messages_nodejs
[ 4%] Built target dynamic_reconfigure_gencfg
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp: In function ‘void pal_vision_util::dctNormalization(const cv::Mat&, cv::Mat&, int, const pal_vision_util::ImageRoi&)’:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: error: no matching function for call to ‘cv::Mat::Mat(IplImage*, bool)’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1029:14: note: candidate: cv::Mat::Mat(const cv::cuda::GpuMat&)
explicit Mat(const cuda::GpuMat& m);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1029:14: note: candidate expects 1 argument, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1026:37: note: candidate: template cv::Mat::Mat(const cv::MatCommaInitializer
<Tp>&)
template explicit Mat(const MatCommaInitializer
<Tp>& commaInitializer);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1026:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::MatCommaInitializer
<_Tp>’ and ‘IplImage* {aka IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1022:37: note: candidate: template cv::Mat::Mat(const cv::Point3
<Tp>&, bool)
template explicit Mat(const Point3
<Tp>& pt, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1022:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Point3
<_Tp>’ and ‘IplImage* {aka IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1018:37: note: candidate: template cv::Mat::Mat(const cv::Point
<Tp>&, bool)
template explicit Mat(const Point
<Tp>& pt, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1018:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Point
<_Tp>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1014:51: note: candidate: template<class _Tp, int m, int n> cv::Mat::Mat(const cv::Matx<_Tp, m, n>&, bool)
template<typename _Tp, int m, int n> explicit Mat(const Matx<_Tp, m, n>& mtx, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1014:51: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Matx<_Tp, m, n>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1010:44: note: candidate: template<class _Tp, int n> cv::Mat::Mat(const cv::Vec<_Tp, m>&, bool)
template<typename _Tp, int n> explicit Mat(const Vec<_Tp, n>& vec, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1010:44: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Vec<_Tp, m>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:993:37: note: candidate: template cv::Mat::Mat(const std::vector<_Tp>&, bool)
template explicit Mat(const std::vector<_Tp>& vec, bool copyData=false);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:993:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const std::vector<_Tp>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:975:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const std::vectorcv::Range&)
Mat(const Mat& m, const std::vector& ranges);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:975:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:965:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const cv::Range*)
Mat(const Mat& m, const Range* ranges);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:965:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:955:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const Rect&)
Mat(const Mat& m, const Rect& roi);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:955:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:945:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const cv::Range&, const cv::Range&)
Mat(const Mat& m, const Range& rowRange, const Range& colRange=Range::all());
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:945:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:933:5: note: candidate: cv::Mat::Mat(const std::vector&, int, void*, const size_t*)
Mat(const std::vector& sizes, int type, void* data, const size_t* steps=0);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:933:5: note: candidate expects 4 arguments, 2 provided
[ 4%] Built target dynamic_reconfigure_generate_messages_py
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:919:5: note: candidate: cv::Mat::Mat(int, const int*, int, void*, const size_t*)
Mat(int ndims, const int* sizes, int type, void* data, const size_t* steps=0);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:919:5: note: candidate expects 5 arguments, 2 provided
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:3642:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:528:1: note: candidate: cv::Mat::Mat(cv::Size, int, void*, size_t)
Mat::Mat(Size _sz, int _type, void* _data, size_t _step)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:528:1: note: candidate expects 4 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:495:1: note: candidate: cv::Mat::Mat(int, int, int, void*, size_t)
Mat::Mat(int _rows, int _cols, int _type, void* _data, size_t _step)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:495:1: note: candidate expects 5 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:476:1: note: candidate: cv::Mat::Mat(const cv::Mat&)
Mat::Mat(const Mat& m)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:476:1: note: candidate expects 1 argument, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:467:1: note: candidate: cv::Mat::Mat(const std::vector&, int, const Scalar&)
Mat::Mat(const std::vector& _sz, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:467:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:450:1: note: candidate: cv::Mat::Mat(int, const int*, int, const Scalar&)
Mat::Mat(int _dims, const int* _sz, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:450:1: note: candidate expects 4 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:459:1: note: candidate: cv::Mat::Mat(const std::vector&, int)
Mat::Mat(const std::vector& _sz, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:459:1: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const std::vector&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:442:1: note: candidate: cv::Mat::Mat(int, const int*, int)
Mat::Mat(int _dims, const int* _sz, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:442:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:433:1: note: candidate: cv::Mat::Mat(cv::Size, int, const Scalar&)
Mat::Mat(Size _sz, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:433:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:416:1: note: candidate: cv::Mat::Mat(int, int, int, const Scalar&)
Mat::Mat(int _rows, int _cols, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:416:1: note: candidate expects 4 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:425:1: note: candidate: cv::Mat::Mat(cv::Size, int)
Mat::Mat(Size _sz, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:425:1: note: no known conversion for argument 1 from ‘IplImage* {aka IplImage*}’ to ‘cv::Size {aka cv::Size}’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:408:1: note: candidate: cv::Mat::Mat(int, int, int)
Mat::Mat(int _rows, int _cols, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:408:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:402:1: note: candidate: cv::Mat::Mat()
Mat::Mat()
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:402:1: note: candidate expects 0 arguments, 2 provided
[ 4%] Built target roscpp_generate_messages_py
[ 4%] Built target roscpp_generate_messages_cpp
[ 4%] Built target rosgraph_msgs_generate_messages_eus
[ 4%] Built target dynamic_reconfigure_generate_messages_lisp
[ 4%] Built target roscpp_generate_messages_lisp
[ 4%] Built target rosgraph_msgs_generate_messages_nodejs
[ 4%] Built target roscpp_generate_messages_nodejs
[ 4%] Built target rosgraph_msgs_generate_messages_lisp
[ 4%] Built target actionlib_msgs_generate_messages_py
[ 4%] Built target rosgraph_msgs_generate_messages_py
[ 4%] Built target actionlib_generate_messages_cpp
[ 4%] Built target actionlib_generate_messages_py
[ 4%] Built target tf2_msgs_generate_messages_cpp
[ 4%] Built target actionlib_generate_messages_eus
[ 4%] Built target actionlib_msgs_generate_messages_nodejs
[ 4%] Built target tf2_msgs_generate_messages_eus
[ 4%] Built target tf2_msgs_generate_messages_py
pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/build.make:62: recipe for target 'pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/src/image_processing.cpp.o' failed
make[2]: *** [pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/src/image_processing.cpp.o] Error 1
CMakeFiles/Makefile2:2866: recipe for target 'pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/all' failed
make[1]: *** [pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
[ 4%] Built target tf_generate_messages_cpp
[ 4%] Built target tf_generate_messages_eus
[ 4%] Built target tf_generate_messages_lisp
[ 4%] Built target tf2_msgs_generate_messages_nodejs
[ 4%] Built target actionlib_msgs_generate_messages_cpp
Building ARDroneTool/Lib
[ 5%] Performing install step for 'ardronelib'
make[3]: warning: jobserver unavailable: using -j1. Add '+' to parent make rule.
[ 5%] Completed 'ardronelib'
[ 6%] Built target ardronelib
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed
rahul@Rahul:/aruco_drone_ws$ rosdep install --from-paths /home/rahul/aruco_drone_ws/src --ignore-src
#All required rosdeps installed successfully
rahul@Rahul:
/aruco_drone_ws$ catkin_make
Base path: /home/rahul/aruco_drone_ws
Source space: /home/rahul/aruco_drone_ws/src
Build space: /home/rahul/aruco_drone_ws/build
Devel space: /home/rahul/aruco_drone_ws/devel
Install space: /home/rahul/aruco_drone_ws/install

Running command: "make cmake_check_build_system" in "/home/rahul/aruco_drone_ws/build"

Running command: "make -j8 -l8" in "/home/rahul/aruco_drone_ws/build"

[ 0%] Built target geometry_msgs_generate_messages_py
[ 0%] Built target geometry_msgs_generate_messages_cpp
[ 0%] Built target std_msgs_generate_messages_cpp
[ 0%] Built target std_msgs_generate_messages_eus
[ 0%] Built target std_msgs_generate_messages_py
[ 2%] Built target aruco
[ 2%] Built target geometry_msgs_generate_messages_eus
[ 2%] Built target geometry_msgs_generate_messages_nodejs
[ 2%] Built target geometry_msgs_generate_messages_lisp
[ 2%] Built target std_msgs_generate_messages_lisp
[ 2%] Built target std_msgs_generate_messages_nodejs
[ 2%] Built target _aruco_msgs_generate_messages_check_deps_MarkerArray
[ 2%] Built target _aruco_msgs_generate_messages_check_deps_Marker
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_ThrustCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RC
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_HeadingCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_MotorCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_ServoCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_AttitudeCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_YawrateCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_Compass
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_HeightCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RawImu
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_VelocityZCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RawRC
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_VelocityXYCommand
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_Supply
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_MotorStatus
[ 2%] Built target _cvg_sim_msgs_generate_messages_check_deps_RuddersCommand
[ 3%] Built target pal_vision_segmentation_gencfg
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_Altitude
[ 3%] Building CXX object pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/src/image_processing.cpp.o
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_RawMagnetic
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_MotorPWM
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_Altimeter
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_ControllerState
[ 3%] Built target _cvg_sim_msgs_generate_messages_check_deps_PositionXYCommand
[ 3%] Performing update step for 'ardronelib'
[ 3%] Performing configure step for 'ardronelib'
No configure
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_time
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_watchdog
[ 3%] Performing build step for 'ardronelib'
make[3]: warning: jobserver unavailable: using -j1. Add '+' to parent make rule.
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_altitude
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_adc_data_frame
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_pressure_raw
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_euler_angles
Libs already extracted
Building target static
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_references
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_demo
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_zimmu_3000
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_video_stream
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_trims
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_RecordEnable
Architecture x86_64 is already built
Creating universal static lib file from architectures x86_64
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_matrix33
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_magneto
Build done.
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_CamSelect
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_wifi
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_FlightAnim
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_gyros_offsets
Building ARDroneTool/Lib
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_hdvideo_stream
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_kalman_pressure
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_vector21
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_trackers_send
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_pwm
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_phys_measures
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_raw_measures
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_vector31
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_LedAnim
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_games
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_rc_references
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision_of
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision_raw
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_Navdata
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_vision_perf
[ 3%] Built target _ardrone_autonomy_generate_messages_check_deps_navdata_wind_speed
[ 3%] Built target aruco_ros_gencfg
[ 3%] Built target ardrone_autonomy_generate_messages_check_deps_navdata_vision_detect
[ 3%] Built target visualization_msgs_generate_messages_py
[ 3%] Built target dynamic_reconfigure_generate_messages_nodejs
[ 3%] Built target dynamic_reconfigure_generate_messages_eus
[ 4%] Built target aruco_ros_utils
[ 4%] Built target sensor_msgs_generate_messages_cpp
[ 4%] Built target sensor_msgs_generate_messages_lisp
[ 4%] Built target roscpp_generate_messages_eus
[ 4%] Built target dynamic_reconfigure_generate_messages_cpp
[ 4%] Built target sensor_msgs_generate_messages_py
[ 4%] Built target rosgraph_msgs_generate_messages_cpp
[ 4%] Built target sensor_msgs_generate_messages_eus
[ 4%] Built target dynamic_reconfigure_gencfg
[ 4%] Built target sensor_msgs_generate_messages_nodejs
[ 4%] Built target dynamic_reconfigure_generate_messages_py
[ 4%] Built target roscpp_generate_messages_py
[ 4%] Built target roscpp_generate_messages_cpp
[ 4%] Built target rosgraph_msgs_generate_messages_eus
[ 4%] Built target dynamic_reconfigure_generate_messages_lisp
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp: In function ‘void pal_vision_util::dctNormalization(const cv::Mat&, cv::Mat&, int, const pal_vision_util::ImageRoi&)’:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: error: no matching function for call to ‘cv::Mat::Mat(IplImage*, bool)’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1029:14: note: candidate: cv::Mat::Mat(const cv::cuda::GpuMat&)
explicit Mat(const cuda::GpuMat& m);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1029:14: note: candidate expects 1 argument, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1026:37: note: candidate: template cv::Mat::Mat(const cv::MatCommaInitializer
<Tp>&)
template explicit Mat(const MatCommaInitializer
<Tp>& commaInitializer);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1026:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::MatCommaInitializer
<_Tp>’ and ‘IplImage* {aka IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1022:37: note: candidate: template cv::Mat::Mat(const cv::Point3
<Tp>&, bool)
template explicit Mat(const Point3
<Tp>& pt, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1022:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Point3
<_Tp>’ and ‘IplImage* {aka IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1018:37: note: candidate: template cv::Mat::Mat(const cv::Point
<Tp>&, bool)
template explicit Mat(const Point
<Tp>& pt, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1018:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Point
<_Tp>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1014:51: note: candidate: template<class _Tp, int m, int n> cv::Mat::Mat(const cv::Matx<_Tp, m, n>&, bool)
template<typename _Tp, int m, int n> explicit Mat(const Matx<_Tp, m, n>& mtx, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1014:51: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Matx<_Tp, m, n>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1010:44: note: candidate: template<class _Tp, int n> cv::Mat::Mat(const cv::Vec<_Tp, m>&, bool)
template<typename _Tp, int n> explicit Mat(const Vec<_Tp, n>& vec, bool copyData=true);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:1010:44: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const cv::Vec<_Tp, m>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:993:37: note: candidate: template cv::Mat::Mat(const std::vector<_Tp>&, bool)
template explicit Mat(const std::vector<_Tp>& vec, bool copyData=false);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:993:37: note: template argument deduction/substitution failed:
/home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:474:53: note: mismatched types ‘const std::vector<_Tp>’ and ‘IplImage* {aka _IplImage*}’
normalizedImg = cv::Mat(output.getIplImg(), true);
^
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:975:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const std::vectorcv::Range&)
Mat(const Mat& m, const std::vector& ranges);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:975:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:965:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const cv::Range*)
Mat(const Mat& m, const Range* ranges);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:965:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:955:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const Rect&)
Mat(const Mat& m, const Rect& roi);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:955:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:945:5: note: candidate: cv::Mat::Mat(const cv::Mat&, const cv::Range&, const cv::Range&)
Mat(const Mat& m, const Range& rowRange, const Range& colRange=Range::all());
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:945:5: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const cv::Mat&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:933:5: note: candidate: cv::Mat::Mat(const std::vector&, int, void*, const size_t*)
Mat(const std::vector& sizes, int type, void* data, const size_t* steps=0);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:933:5: note: candidate expects 4 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:919:5: note: candidate: cv::Mat::Mat(int, const int*, int, void*, const size_t*)
Mat(int ndims, const int* sizes, int type, void* data, const size_t* steps=0);
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:919:5: note: candidate expects 5 arguments, 2 provided
In file included from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.hpp:3642:0,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core.hpp:59,
from /opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/core.hpp:48,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/include/pal_vision_segmentation/image_processing.h:41,
from /home/rahul/aruco_drone_ws/src/pal_vision_segmentation/src/image_processing.cpp:37:
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:528:1: note: candidate: cv::Mat::Mat(cv::Size, int, void*, size_t)
Mat::Mat(Size _sz, int _type, void* _data, size_t _step)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:528:1: note: candidate expects 4 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:495:1: note: candidate: cv::Mat::Mat(int, int, int, void*, size_t)
Mat::Mat(int _rows, int _cols, int _type, void* _data, size_t _step)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:495:1: note: candidate expects 5 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:476:1: note: candidate: cv::Mat::Mat(const cv::Mat&)
Mat::Mat(const Mat& m)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:476:1: note: candidate expects 1 argument, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:467:1: note: candidate: cv::Mat::Mat(const std::vector&, int, const Scalar&)
Mat::Mat(const std::vector& _sz, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:467:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:450:1: note: candidate: cv::Mat::Mat(int, const int*, int, const Scalar&)
Mat::Mat(int _dims, const int* _sz, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:450:1: note: candidate expects 4 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:459:1: note: candidate: cv::Mat::Mat(const std::vector&, int)
Mat::Mat(const std::vector& _sz, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:459:1: note: no known conversion for argument 1 from ‘IplImage* {aka _IplImage*}’ to ‘const std::vector&’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:442:1: note: candidate: cv::Mat::Mat(int, const int*, int)
Mat::Mat(int _dims, const int* _sz, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:442:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:433:1: note: candidate: cv::Mat::Mat(cv::Size, int, const Scalar&)
Mat::Mat(Size _sz, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:433:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:416:1: note: candidate: cv::Mat::Mat(int, int, int, const Scalar&)
Mat::Mat(int _rows, int _cols, int _type, const Scalar& _s)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:416:1: note: candidate expects 4 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:425:1: note: candidate: cv::Mat::Mat(cv::Size, int)
Mat::Mat(Size _sz, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:425:1: note: no known conversion for argument 1 from ‘IplImage* {aka IplImage*}’ to ‘cv::Size {aka cv::Size}’
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:408:1: note: candidate: cv::Mat::Mat(int, int, int)
Mat::Mat(int _rows, int _cols, int _type)
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:408:1: note: candidate expects 3 arguments, 2 provided
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:402:1: note: candidate: cv::Mat::Mat()
Mat::Mat()
^
/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv2/core/mat.inl.hpp:402:1: note: candidate expects 0 arguments, 2 provided
[ 4%] Built target roscpp_generate_messages_lisp
[ 4%] Built target roscpp_generate_messages_nodejs
[ 4%] Built target rosgraph_msgs_generate_messages_nodejs
[ 4%] Built target rosgraph_msgs_generate_messages_py
[ 4%] Built target rosgraph_msgs_generate_messages_lisp
[ 4%] Built target actionlib_msgs_generate_messages_py
[ 4%] Built target actionlib_generate_messages_cpp
[ 4%] Built target tf2_msgs_generate_messages_cpp
[ 4%] Built target actionlib_generate_messages_py
[ 4%] Built target tf2_msgs_generate_messages_eus
[ 4%] Built target actionlib_generate_messages_eus
[ 4%] Built target actionlib_msgs_generate_messages_nodejs
[ 4%] Built target tf2_msgs_generate_messages_py
[ 4%] Built target tf_generate_messages_eus
[ 4%] Built target tf_generate_messages_cpp
[ 4%] Built target tf_generate_messages_lisp
[ 4%] Built target tf2_msgs_generate_messages_nodejs
[ 4%] Built target actionlib_msgs_generate_messages_cpp
pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/build.make:62: recipe for target 'pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/src/image_processing.cpp.o' failed
make[2]: *** [pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/src/image_processing.cpp.o] Error 1
CMakeFiles/Makefile2:2866: recipe for target 'pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/all' failed
make[1]: *** [pal_vision_segmentation/CMakeFiles/pal_vision_segmentation.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
[ 4%] Built target actionlib_generate_messages_nodejs
[ 4%] Built target actionlib_generate_messages_lisp
[ 4%] Built target tf_generate_messages_py
[ 4%] Built target actionlib_msgs_generate_messages_eus
[ 4%] Built target tf_generate_messages_nodejs
[ 4%] Built target actionlib_msgs_generate_messages_lisp
Building ARDroneTool/Lib
[ 5%] Performing install step for 'ardronelib'
make[3]: warning: jobserver unavailable: using -j1. Add '+' to parent make rule.
[ 5%] Completed 'ardronelib'
[ 6%] Built target ardronelib
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

I have looked at the available solutions for this issue but still not able to figure out the problem. I have ran the rosdep command as well to check for dependencies and it says all dependencies have been installed correctly. I am using Kinect version of ROS. Please help. Thanks.

Multi Marker Detection problem

Hello, I have wrote a subscriber which subscribe to /aruco_marker_publisher/markers_list to get the detected marker id array.

Here is the code part in my subscriber (Code Part 1):

void detectionCallback (const std_msgs::UInt32MultiArray::ConstPtr& msg)
{
	for(std::vector<unsigned int>::const_iterator it = msg->data.begin(); it != msg->data.end(); ++it)
	{	
		//printf("%d\n",*it);
		marker_list[i] = *it;
		i++;
	}
	printf("Number of detected marker is %d\n",i);
	i=0;
	printf("Length of Marker List is %lu\n",sizeof(marker_list)/sizeof(marker_list[0]));
	printf("First marker in Marker List is %d\n",marker_list[0]);
	status = 1;
	printf("Status : %d\n",status);

	return;
}

After getting the data, I would like to compare the array whether some certain id has been detected or not.

Something like this (Code Part 2):

while(status)
	{	
		int id;
		int checking=0;
		std::cout<<"Enter the marker id you want to check"<<"\n";
		std::cin>>id;
		std::cout<<"Check wether Marker %d is detected or not?"<<"\n";

		for (int k=0;k<=i;k++)
		{
			if(marker_list[k]==id)
			{
				printf("Yes!\n");
				checking =1;	
			}
		}
		if(checking==0)
		{
			printf("The marker %d is not detected.\n",id);
		}
		status=0;
	}

My problem is when I run the code, it keep stuck in code part 1, it won't run the code part 2 for me.
May I know how to solve it?

cv_bridge exception

Hi,

After I run "rostopic echo /aruco_single/pose, then the error "cv_bridge exception: Unrecognized image encoding" keep looping inside the terminal and no data out from the topic /aruco_single/pose.

May I know how to solve this problem?

Regards,
Chun Jye

ROS Indigo weird TF errors

Hello I am trying to use this with a simple image_raw and camera_info topic but I am always getting the following errors:

TF_NAN_INPUT: Ignoring transform for child_frame_id "marker_frame" from authority "unknown_publisher" because of a nan value in the transform (-nan -inf -nan) (-0.542478 -0.431334 0.485505 0.532872) at line 244 in /tmp/binarydeb/ros-indigo-tf2-0.5.17/src/buffer_core.cpp

So it seems there is some rotation calculation but no translation.

I am using:

<arg name="marker_frame"    default="marker_frame"/>
<arg name="ref_frame"       default=""/>  <!-- leave empty and the pose will be published wrt param parent_name -->
<param name="camera_frame"       value="base_link"/>

This is just the simple example. I used it with our robots tf-publisher as well, where the camera_frame was linked to the rest of the robot, but still the same issue.

Looking at the image /aruco_single/result I can see a valid detection.

Any idea what is happening?

Kinetic support or install from source

Are there any plans to adapt this for kinetic?

I tried cloning and building from source, but it looks like there are problems with the opencv2 to opencv3 switch.

Building from source is fine.

Thanks

no aruco package for ros-melodic

I tried to install ros-melodic-aruco-ros on ros-melodic, but there're no aruco package.

$ sudo apt-get install ros-melodic-aruco-ros
パッケージリストを読み込んでいます... 完了
依存関係ツリーを作成しています                
状態情報を読み取っています... 完了
E: パッケージ ros-melodic-aruco-ros が見つかりません

Do you have any plans to release for ros-melodic-aruco-ros?

Robot localization using aruco marker in gazebo

We are trying to localize the robot in gazebo using aruco marker. We have successfully loaded the marker into gazebo, detected it, and obtained the transformation between camera frame and marker frame using aruco_ros (https://github.com/pal-robotics/aruco_ros) package. The transform between them obtained from tf package is in excellent agreement with the one obtained from the package.
image
However, the physical location of marker frame is not the same when we visualize it in RviZ. Please see the image below
image
As shown above, the location of marker frame in RViz does not match with that of gazebo. This really confuses us because we are not clear which dictates the physical location of marker in reality

Any help on this issue would be appreciated.
Thanks

Detect markers with N bits resolution

Hi all,

As mentioned in my previous issue, I'm looking to adapt the Aruco Detector to make it able to detect and identify markers with N-bits resolution, N in [4; 7].
So far, the bit resolution is hardcoded in the function detect in the file arucofidmarkers.cpp, as shown in the following snippet of code

int FiducidalMarkers::analyzeMarkerImage(Mat &grey,int &nRotations)
  {

    //Markers  are divided in 7x7 regions, of which the inner 5x5 belongs to marker info
    //the external border shoould be entirely black

    int swidth=grey.rows/7;
    for (int y=0;y<7;y++)
    {
      int inc=6;
      if (y==0 || y==6) inc=1;//for first and last row, check the whole border
      for (int x=0;x<7;x+=inc)
      {
        int Xstart=(x)*(swidth);
        int Ystart=(y)*(swidth);
        Mat square=grey(Rect(Xstart,Ystart,swidth,swidth));
        int nZ=countNonZero(square);
        if (nZ> (swidth*swidth) /2) {
          // 		cout<<"neb"<<endl;
          return -1;//can not be a marker because the border element is not black!
        }
      }
    }

    //now,
    vector<int> markerInfo(5);
    Mat _bits=Mat::zeros(5,5,CV_8UC1);
    //get information(for each inner square, determine if it is  black or white)

    for (int y=0;y<5;y++)
    {

      for (int x=0;x<5;x++)
      {
        int Xstart=(x+1)*(swidth);
        int Ystart=(y+1)*(swidth);
        Mat square=grey(Rect(Xstart,Ystart,swidth,swidth));
        int nZ=countNonZero(square);
        if (nZ> (swidth*swidth) /2)  _bits.at<uchar>( y,x)=1;
      }
    }
    // 		printMat<uchar>( _bits,"or mat");

    //checkl all possible rotations
    Mat _bitsFlip;
    Mat Rotations[4];
    Rotations[0]=_bits;
    int dists[4];
    dists[0]=hammDistMarker( Rotations[0]) ;
    pair<int,int> minDist( dists[0],0);
    for (int i=1;i<4;i++)
    {
      //rotate
      Rotations[i]=rotate(Rotations[i-1]);
      //get the hamming distance to the nearest possible word
      dists[i]=hammDistMarker( Rotations[i]) ;
      if (dists[i]<minDist.first)
      {
        minDist.first=  dists[i];
        minDist.second=i;
      }
    }
    // 		        printMat<uchar>( Rotations [ minDist.second]);
    // 		 	cout<<"MinDist="<<minDist.first<<" "<<minDist.second<<endl;

    nRotations=minDist.second;
    if (minDist.first!=0)	 //FUTURE WORK: correct if any error
      return -1;
    else {//Get id of the marker
      int MatID=0;
      cv::Mat bits=Rotations [ minDist.second];
      for (int y=0;y<5;y++)
      {
        MatID<<=1;
        if ( bits.at<uchar>(y,1)) MatID|=1;
        MatID<<=1;
        if ( bits.at<uchar>(y,3)) MatID|=1;
      }
      return MatID;
    }
  }

My initial guess was to change every 7 in N, every 6 in N-1 and every 5 in N-2, after adding N as a parameter of the function.
But this wasn't working. Does anyone has a better approach in mind?

I'll keep digging and keep you posted if I find a workaround :)

Thank you very much for your help

Aruco does not detect any marker.

Hi,
i'm testing the aruco_ros package in Tiago robot and i'm trying to run the aruco_ros simulation following the wiki ros tutorials of Tiago. So, first, I launch the Tiago's simulation:

roslaunch tiago_gazebo tiago_gazebo.launch public_sim:=true robot:=steel world:=tutorial_office gzpose:="-x -3.5 -y -0.85 -z 0 -R 0 -P 0 -Y -3.0"

Screenshot from 2020-03-26 17-05-21
Then, you can see the robot in front of the aruco board, the next step is to launch the detector.

rosrun aruco_ros single /camera_info:=/xtion/rgb/camera_info /image:=/xtion/rgb/image_rect_color _marker_id:=250 _marker_size:=0.6 _marker_frame:=/aruco_frame _camera_frame:=/xtion_optical_frame _image_is_rectified:=true _reference_frame:=/base_footprint

After launching that command, it appears this in the terminal.
[ INFO] [1585238075.740888622, 50.626000000]: Corner refinement method: 3
[ INFO] [1585238075.740995594, 50.626000000]: Threshold method: 1
[ INFO] [1585238075.741038275, 50.626000000]: Threshold method: th1: 7 th2: 7
[ INFO] [1585238075.741066778, 50.626000000]: Marker size min: 0.04 max: 0.5
[ INFO] [1585238075.741087506, 50.626000000]: Desired speed: 0
[ INFO] [1585238076.041515145, 50.680000000]: Aruco node started with marker size of 0.600000 m and marker id to track: 250
[ INFO] [1585238076.041839764, 50.680000000]: Aruco node will publish pose to TF with /base_footprint as parent and /aruco_frame as child.
[ WARN] [1585238076.041961474, 50.680000000]: normalizeImageIllumination is unimplemented!

I don't understand what's happening, if someone can help me please.

Marker Plate wrong axis?

Hey there,

I just wonder the following:

In the picture it looks like the y axis (green) is going out of the red plate but actually this should be the blue z - axis or??

marker-error

does that mean the marker axis are displayed wrong?!

This is my code:


   <arg name="start_camera_ex" default="False" />


<arg name="markerId" default="701"/>
<arg name="markerSize" default="0.10"/> <!-- in meter breite inc. schwarz des aruco markers (ausgedruckt hier angeben!) -->
<arg name="eye" default="right"/>
<arg name="marker_frame" default="plate_origin"/>
<arg name="ref_frame" default=""/> <!-- leave empty and the pose will be published wrt param parent_name -->
<arg name="corner_refinement" default="LINES" /> <!-- NONE, HARRIS, LINES, SUBPIX -->


    <!-- start xtion pro camera with topic names: /camera/ir/image, /camera/rgb/image_raw, /camera/depth/image -->
    <include if="$(arg start_camera_ex)"
         file="$(find openni2_launch)/launch/openni2.launch">
    </include>



<node pkg="aruco_ros" type="single" name="aruco_single">
    <remap from="/camera_info" to="/camera/rgb/camera_info" />
    <remap from="/image" to="/camera/rgb/image_rect_color" />
    <param name="image_is_rectified" value="True"/> <!-- set this to true?! -->
    <param name="marker_size" value="$(arg markerSize)"/>
    <param name="marker_id" value="$(arg markerId)"/>
    <param name="reference_frame" value="$(arg ref_frame)"/> <!-- frame in which the marker pose will be refered -->
    <param name="camera_frame" value="camera_link"/> <!-- this is just for the pose output - does not change anything to the pose calc itself! -->
    <param name="marker_frame" value="$(arg marker_frame)" />
    <param name="corner_refinement" value="$(arg corner_refinement)" />
</node>

Just tested the same thing again with this pack:
https://github.com/joselusl/aruco_eye

and got a whole different output picture which seems to be right:
screenshot - 05292018 - 01 38 41 pm

so I now guess that with this lib here the axes are just drawn wrong in the result pic!

Think I know my error I just should make the
to NONE not to LINES .....

Anyway does anyone has a description of the corner_refinement parameter?

Detection okay with real camera but complete failure with Gazebo

Hi all,

I'm working with Aruco markers to do some localization process.
It was working fine and giving me pretty good results so far.

However, I updated Gazebo to 7.12 in order to get some relevant functions on SDF format for frictions models, and now it's a complete failure.
The node detects and identifies markers correctly when I use my built-in webcam, but as soon as I feed it a fake image from Gazebo, with a big marker in front of the camera, nothing happened..

Has any of you faced the same issue here?
If so, did you find a work around?

Thank you for your help and advice :)

Setup info:
Ubuntu 16.04
ROS Kinetic
Gazebo 7.12

Cheers
Guillaume

rostopic echo /aruco_simple/pose not working

Config: ROS 1, Melodic, Ubuntu 18.04

Hi,

I am trying to track 2 markers with the double.launch file. The 2 markers are detected and I can see the result using image_view node in the usb_cam pkg. However, when I echo the pose and pose2 topics they are blank.

I can echo the /tf topic and see the hand and object frames being published. Please let me know if you need additional info!

aruco single not working on indigo

This was working fine on kinetic. I needed it on indigo. Here are the launch files and the errors i am getting.
Anyone know what the issue might be?

Thanks in advance.

main_error
single_and_usbcamstream

How to attach the AR markers on specific section of robot?

Hi, just try to attach AR markers on different section of robot, such as hand, as shown in your introduction ?

image

I checked reemc_simulation, and did not find result. It seems that marker26_8cm_massless as a standard model added in Gazebo with specitic position. But the robot model is consist of different joints and planes, should I change the texture of some part to AR markers ? or added the marker26_8cm_massless model fixed with some sections?

Thanks.

using namespace std in header

In the aruco header files aruco/markerdetector.h and aruco/boarddetector.h there's "using namespace std;". You probably already know this, but it's there because it was in the original aruco lib, but just to be sure: This should not be there as this forces that action onto every other file including those header files (or aruco/aruco.h). If you want to do this, only do so in the source file. Here's a question and answer about it, if you need more info: http://stackoverflow.com/questions/14575799/using-namespace-std-in-a-header-file.

Marker Dictionary

Hi,

Is it possible to use a different Aruco dictionary in this package? I know that now the package can detect markers from Original aruco dictionary. Please suggest a way to implement the detection on a different Aruco dictionary. Thanks.

Marker pose few cm off in TIAGo simulation

Hi,

I am trying to implement a grasp routine in the TIAGo simulation using the Aruco cube. I have determined that the size of the aruco marker on the cube is 4.5 cm, and I have placed it on a table in front of the robot.

While the marker gets almost perfectly detected in the image, there is something wrong in the transformation to base_footprint. As can be seen in the image below, the marker is off by almost 1 cm in the x-direction and about 2-3 cm in the y-direction. This causes significant issues later in the pipeline.

I have confirmed the reference and camera frames (xtion_optical_frame and base_footprint) and checked their tf which is [0.244, -0.013, 1.143]. What is interesting is that the y-direction of the aruco marker is off by twice the y component of the tf. Could it be that the 'wrong eye' of tiago is considered as xtion_optical_frame? If the tf of the other eye would be used then the error in y-direction would almost disappear. Could this be the case or am I on the wrong path?

Thanks in advance!
Screenshot from 2021-02-01 10-30-50

No output or frozen windows with realsense d435

I'm 90% sure I'm missing something easy but crucial, but I can't get this package to work. What I did:

  • install realsense2_ros (have had this working for a while now);
  • install aruco_ros;
  • built the catkin_ws (at first I was using gcc 7.4.0 but just in case that was the issue I just retried with 5.5.0 to no avail... I only get some warnings in both cases);
  • roslaunch realsense2_camera rs_rgbd.launch to get the camera up, and these topics/frames:

topics

/camera/aligned_depth_to_color/camera_info
/camera/aligned_depth_to_color/image_raw
/camera/aligned_depth_to_color/image_raw/compressed
/camera/aligned_depth_to_color/image_raw/compressed/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/compressed/parameter_updates
/camera/aligned_depth_to_color/image_raw/compressedDepth
/camera/aligned_depth_to_color/image_raw/compressedDepth/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/compressedDepth/parameter_updates
/camera/aligned_depth_to_color/image_raw/theora
/camera/aligned_depth_to_color/image_raw/theora/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/theora/parameter_updates
/camera/aligned_depth_to_infra1/camera_info
/camera/aligned_depth_to_infra1/image_raw
/camera/aligned_depth_to_infra1/image_raw/compressed
/camera/aligned_depth_to_infra1/image_raw/compressed/parameter_descriptions
/camera/aligned_depth_to_infra1/image_raw/compressed/parameter_updates
/camera/aligned_depth_to_infra1/image_raw/compressedDepth
/camera/aligned_depth_to_infra1/image_raw/compressedDepth/parameter_descriptions
/camera/aligned_depth_to_infra1/image_raw/compressedDepth/parameter_updates
/camera/aligned_depth_to_infra1/image_raw/theora
/camera/aligned_depth_to_infra1/image_raw/theora/parameter_descriptions
/camera/aligned_depth_to_infra1/image_raw/theora/parameter_updates
/camera/color/camera_info
/camera/color/image_raw
/camera/color/image_raw/compressed
/camera/color/image_raw/compressed/parameter_descriptions
/camera/color/image_raw/compressed/parameter_updates
/camera/color/image_raw/compressedDepth
/camera/color/image_raw/compressedDepth/parameter_descriptions
/camera/color/image_raw/compressedDepth/parameter_updates
/camera/color/image_raw/theora
/camera/color/image_raw/theora/parameter_descriptions
/camera/color/image_raw/theora/parameter_updates
/camera/color/image_rect_color
/camera/color/image_rect_color/compressed
/camera/color/image_rect_color/compressed/parameter_descriptions
/camera/color/image_rect_color/compressed/parameter_updates
/camera/color/image_rect_color/compressedDepth
/camera/color/image_rect_color/compressedDepth/parameter_descriptions
/camera/color/image_rect_color/compressedDepth/parameter_updates
/camera/color/image_rect_color/theora
/camera/color/image_rect_color/theora/parameter_descriptions
/camera/color/image_rect_color/theora/parameter_updates
/camera/color_rectify_color/parameter_descriptions
/camera/color_rectify_color/parameter_updates
/camera/depth/camera_info
/camera/depth/image_rect_raw
/camera/depth/image_rect_raw/compressed
/camera/depth/image_rect_raw/compressed/parameter_descriptions
/camera/depth/image_rect_raw/compressed/parameter_updates
/camera/depth/image_rect_raw/compressedDepth
/camera/depth/image_rect_raw/compressedDepth/parameter_descriptions
/camera/depth/image_rect_raw/compressedDepth/parameter_updates
/camera/depth/image_rect_raw/theora
/camera/depth/image_rect_raw/theora/parameter_descriptions
/camera/depth/image_rect_raw/theora/parameter_updates
/camera/depth_registered/points
/camera/extrinsics/depth_to_color
/camera/extrinsics/depth_to_infra1
/camera/extrinsics/depth_to_infra2
/camera/infra1/camera_info
/camera/infra1/image_rect_raw
/camera/infra1/image_rect_raw/compressed
/camera/infra1/image_rect_raw/compressed/parameter_descriptions
/camera/infra1/image_rect_raw/compressed/parameter_updates
/camera/infra1/image_rect_raw/compressedDepth
/camera/infra1/image_rect_raw/compressedDepth/parameter_descriptions
/camera/infra1/image_rect_raw/compressedDepth/parameter_updates
/camera/infra1/image_rect_raw/theora
/camera/infra1/image_rect_raw/theora/parameter_descriptions
/camera/infra1/image_rect_raw/theora/parameter_updates
/camera/infra2/camera_info
/camera/infra2/image_rect_raw
/camera/infra2/image_rect_raw/compressed
/camera/infra2/image_rect_raw/compressed/parameter_descriptions
/camera/infra2/image_rect_raw/compressed/parameter_updates
/camera/infra2/image_rect_raw/compressedDepth
/camera/infra2/image_rect_raw/compressedDepth/parameter_descriptions
/camera/infra2/image_rect_raw/compressedDepth/parameter_updates
/camera/infra2/image_rect_raw/theora
/camera/infra2/image_rect_raw/theora/parameter_descriptions
/camera/infra2/image_rect_raw/theora/parameter_updates
/camera/realsense2_camera_manager/bond
/camera/rgb_camera/parameter_descriptions
/camera/rgb_camera/parameter_updates
/camera/stereo_module/parameter_descriptions
/camera/stereo_module/parameter_updates

frames
frames

  • now then I have tried both roslaunch aruco_ros single.launch markerId:=42 markerSize:=0.07 camera_frame:=camera_color_optical_frame camera_info:=/camera/color/camera_info image:=/camera/color/image_rect_color and roslaunch aruco_ros single.launch markerId:=42 markerSize:=0.07 camera_frame:=camera_link camera_info:=/camera/color/camera_info image:=/camera/color/image_rect_color: in both cases I get these topics up and no errors in the output

topics

/aruco_single/debug
/aruco_single/debug/compressed
/aruco_single/debug/compressed/parameter_descriptions
/aruco_single/debug/compressed/parameter_updates
/aruco_single/debug/compressedDepth
/aruco_single/debug/compressedDepth/parameter_descriptions
/aruco_single/debug/compressedDepth/parameter_updates
/aruco_single/debug/theora
/aruco_single/debug/theora/parameter_descriptions
/aruco_single/debug/theora/parameter_updates
/aruco_single/marker
/aruco_single/parameter_descriptions
/aruco_single/parameter_updates
/aruco_single/pixel
/aruco_single/pose
/aruco_single/position
/aruco_single/result
/aruco_single/result/compressed
/aruco_single/result/compressed/parameter_descriptions
/aruco_single/result/compressed/parameter_updates
/aruco_single/result/compressedDepth
/aruco_single/result/compressedDepth/parameter_descriptions
/aruco_single/result/compressedDepth/parameter_updates
/aruco_single/result/theora
/aruco_single/result/theora/parameter_descriptions
/aruco_single/result/theora/parameter_updates
/aruco_single/transform
  • and of course I have a print of marker 42 in front of the camera;

  • if I rosrun image_view image_view image:=/aruco_single/result I get a forever frozen window, and no output on any topic. I'm instead expecting a window identical to the one I'd have by running rosrun image_view image_view image:=/camera/color/image_raw but with colored borders around the marker and a tf frame in the center of the marker, like everybody else's examples show.

  • if I ./aruco_simple ~/Desktop/image_raw_screenshot_23.04.2019.png where the screenshot is an unmodified screen from the aforementioned rosrun image_view image_view image:=/camera/color/image_raw I get the colored border and number 42 next to it.

Reading through other issues I have found I had an extra opencv installation (2.4) which seemed safe to uninstall, so now I only have the apt packaged ros-kinetic-opencv3:

$ apt-cache policy ros-kinetic-opencv3
ros-kinetic-opencv3:
  Installed: 3.3.1-5xenial-20180809-134307-0800
  Candidate: 3.3.1-5xenial-20180809-134307-0800
  Version table:
 *** 3.3.1-5xenial-20180809-134307-0800 500
        500 http://packages.ros.org/ros/ubuntu xenial/main amd64 Packages
        100 /var/lib/dpkg/status


sudo find / -name "OpenCVConfig.cmake" -print
/opt/ros/kinetic/share/OpenCV-3.3.1-dev/OpenCVConfig.cmake


dpkg -l | grep libopencv
<empty>

I cleaned and rebuilt library and catkin workspace after uninstalling to no avail, again.

How can I debug this situation?

EDIT: roswtf says:

WARNING The following node subscriptions are unconnected:
 * /aruco_single:
   * /stereo/left/camera_info
   * /tf
   * /stereo/left/image_rect_color

so I'll look there for a bit

EDIT2: rewriting the launch file connected the subscriptions, which made the image_view window work, but still with no frames/borders...

Build fail when using catkin build instead of catkin_make

I got the library working nicely when build with catkin_make.
However, when using catkin build instead catkin_make I got an error during the build

/usr/bin/ld: CMakeFiles/marker_publisher.dir/src/aruco_ros_utils.cpp.o: undefined reference to symbol '_ZN2cv9RodriguesERKNS_11_InputArrayERKNS_12_OutputArrayES5_'
/opt/ros/kinetic/lib/libopencv_calib3d3.so.3.3: error adding symbols: DSO missing from command line
collect2: error: ld returned 1 exit status
make[2]: *** [/catkin_ws/devel/.private/aruco_ros/lib/aruco_ros/marker_publisher] Error 1
make[1]: *** [CMakeFiles/marker_publisher.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
/usr/bin/ld: CMakeFiles/double.dir/src/aruco_ros_utils.cpp.o: undefined reference to symbol '_ZN2cv9RodriguesERKNS_11_InputArrayERKNS_12_OutputArrayES5_'
/opt/ros/kinetic/lib/libopencv_calib3d3.so.3.3: error adding symbols: DSO missing from command line
collect2: error: ld returned 1 exit status
make[2]: *** [/catkin_ws/devel/.private/aruco_ros/lib/aruco_ros/double] Error 1
make[1]: *** [CMakeFiles/double.dir/all] Error 2
/usr/bin/ld: CMakeFiles/single.dir/src/aruco_ros_utils.cpp.o: undefined reference to symbol '_ZN2cv9RodriguesERKNS_11_InputArrayERKNS_12_OutputArrayES5_'
/opt/ros/kinetic/lib/libopencv_calib3d3.so.3.3: error adding symbols: DSO missing from command line
collect2: error: ld returned 1 exit status
make[2]: *** [/catkin_ws/devel/.private/aruco_ros/lib/aruco_ros/single] Error 1
make[1]: *** [CMakeFiles/single.dir/all] Error 2
make: *** [all] Error 2

This is happening during the build of aruco_ros, aruco and aruco_msg build is ok.

It appears to be a problem with /libopencv_calib3d3.so.3.3 but I don t quiet know how to modify the CMakeLists.txt to fix it.

Anyone had this problem before ?

Thx

catkin_make have a error:can't find arucoConfig.cmake aruco-config.cmake

hi ,iam catkin_make the aruco_ros,but i have the error 👍
-- Could not find the required component 'aruco'. The following CMake error indicates that you either need to install the package with the same name or change your environment so that it can be found.
CMake Error at /opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake:83 (find_package):
Could not find a package configuration file provided by "aruco" with any of
the following names:

arucoConfig.cmake
aruco-config.cmake

Add the installation prefix of "aruco" to CMAKE_PREFIX_PATH or set
"aruco_DIR" to a directory containing one of the above files. If "aruco"
provides a separate development package or SDK, be sure it has been
installed.
i need some help,how to deal it? thx

aruco_ros/single: error while loading shared libraries: libopencv_calib3d3.so.3.1

catkin_handeye/devel/lib/aruco_ros/single: error while loading shared libraries: libopencv_calib3d3.so.3.1: cannot open shared object file: No such file or directory
[aruco_tracker-2] process has died [pid 12577, exit code 127, cmd /home/sia/catkin_handeye/devel/lib/aruco_ros/single /camera_info:=/kinect2/hd/camera_info /image:=/kinect2/hd/image_color_rect __name:=aruco_tracker __log:=/home/sia/.ros/log/1b49175c-6c63-11e8-ae99-2c946400b13d/aruco_tracker-2.log].
log file: /home/sia/.ros/log/1b49175c-6c63-11e8-ae99-2c946400b13d/aruco_tracker-2*.log
I try this on indigo-devel ,how can I solve this?

Position of marker is significantly inaccurate across different cameras, despite good calibration

OS: Ubuntu 16.04,
Kernel: 4.15.0
Cameras: Kinect V2, Realsense D435, Realsense D415

image

image

Markers are detecting fine, pose within 2D seems to be captured fine. Marker size (0.09 meter) is definitely correctly specified in the launch file. 3D pose is however, off by some translation, always further than the ground truth. Magnitude of the bias increases on the distance in a non-linear manner, meaning that if the marker is near, I probably have to multiply 0.98 to the returned position of the marker in the rgb camera frame to get close to the ground truth, and when it is far, I will have to multiply 0.94. I have verified that the point clouds are accurate by measuring the distances with a measuring tape. This occurs to all of my 1 x Kinect V2, 1 x Realsense D435 and 4 x Realsense D415.

When I showed my colleagues this problem, their immediate guesses were that the calibrations are off. After trying recalibration from multiple libraries, where I use
https://github.com/code-iai/iai_kinect2/tree/master/kinect2_calibration for the Kinect V2,
http://wiki.ros.org/visp_camera_calibration?distro=kinetic and
https://downloadcenter.intel.com/download/28517/Intel-RealSense-D400-Series-Calibration-Tools-and-API for the Intel Realsense D435 and D415,
The problem remains, while point cloud registration looks perfect for all of my 6 cameras. Correct if I am wrong but if there is no issue of any kind with the point clouds, is it necessary true that both the intrinsics and the extrinsics are good?

I am stuck at this problem for at least a month and at my wits end, and I am using ar_track_alvar for now which is inaccurate due to how it gets the marker pose from point cloud instead of 2D image feed.

I would really appreciate advice of any kind, I am not familiar with camera equations, so I'd wager there is a good chance I am missing out on something extremely obvious here.

ROS 2 compatability

Has anyone tried running aruco node in ROS2?
If so, what distributor did you use (Diademeta/ Elusor/ Fitzroy)?
Thank you.

The marker generator

Thanks for your contribution! But i still have some questions
How did you generate the ar marker and arrange the id to each marker, did you use the ros package ar_marker_alvar?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.