Only released in EOL distros:  

Package Summary

This package allows user to create a map of Aruco markers in 2D or 3D space and estimate full 6 DOF pose of the camera.

Package Summary

This package allows user to create a map of Aruco markers in 2D or 3D space and estimate full 6 DOF pose of the camera.

Overview

Using Markers to estimate full 6 DOF position only by means of single calibrated camera is well known approach that has been utilized for quite a long time now. This package leverages basic aruco_ros functionality and provides tools to create a map of detected markers in 2D/3D space. It is designed for static markers - moving camera scenario and can be used for various navigation tasks for UAVs, UGVs, etc.

Usage

Marker placement

Mapping utilizes chaining principle:

  1. first marker is identified with world´s origin
  2. second marker's position is computed with respect to first one
  3. third's marker position is computed with respect to second one
  4. ...

In order to achieve successfull mapping, everytime when a new marker is detected, previous marker needs to be visible in the actual image to allow computing new marker's position. (See demonstration video for better understanding). Keep this principle in mind when placing markers in your environment and do not overdo their mutual distances.

Camera calibration

Proper camera calibration strongly affects overall system accuracy. Aruco mapping expects calibration file in Videre INI format, see the example of expected calibration file below:

# Prosilica camera intrinsics

[image]

width
2448

height
2050

[prosilica]

camera matrix
4827.93789 0.00000 1223.50000
0.00000 4835.62362 1024.50000
0.00000 0.00000 1.00000

distortion
-0.41527 0.31874 -0.00197 0.00071 0.00000

rectification
1.00000 0.00000 0.00000
0.00000 1.00000 0.00000
0.00000 0.00000 1.00000

projection
4827.93789 0.00000 1223.50000 0.00000
0.00000 4835.62362 1024.50000 0.00000
0.00000 0.00000 1.00000 0.00000

In order to to calibrate your camera and get results in INI format, we stongly suggest camera_calibrator package.

Launch file

Here is an example of launch file to run Rviz, usb_cam driver and aruco_mapping:

<launch>

  <!-- RVIZ -->
  <node name="rviz" pkg="rviz" type="rviz" args="-d $(find aruco_mapping)/launch/aruco_config.rviz" />

   <!--   usb_cam node -->
  <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen">
    <param name="video_device" value="/dev/video0" />
    <param name="image_width" value="640" />
    <param name="image_height" value="480" />
    <param name="pixel_format" value="mjpeg" />
    <param name="camera_frame_id" value="usb_cam" />
    <param name="io_method" value="mmap"/>
  </node>

  <!-- ArUco mapping -->
  <node pkg="aruco_mapping" type="aruco_mapping" name="aruco_mapping" output="screen">
    <remap from="/image_raw" to="/usb_cam/image_raw"/>

    <param name="calibration_file" type="string" value="$(find aruco_mapping)/data/F100.ini"/>
    <param name="num_of_markers" type="int" value="20" />
    <param name="marker_size" type="double" value="0.135"/>
    <param name="space_type" type="string" value="plane" />
    <param name="roi_allowed" type="bool" value="false" />
  </node>
</launch>

In case you use other camera driver, remap image_raw to your topic name. Do not forget to adopt calibration_file, marker_size and other params to your setup. If everything is set and ready, launch the aruco_mapping by following command:

roslaunch aruco_mapping aruco_mapping.launch

Additional image filter

If you are experiencing problems with basic aruco detector caused by lighting conditions (strong reflections, poor lighting, bad focus) try to include our image filter into your processing pipeline in order to improve the raw image.

ROS API

aruco_mapping

Node for Aruco Marker detection and mapping.

Subscribed Topics

image_raw (sensor_msgs/Image)
  • subscribe to camera image_raw

Published Topics

aruco_markers (visualization_msgs/Marker)
  • publishes Marker for visualization purposes
aruco_poses (aruco_mapping/ArucoMarker)
  • marker ID, visibility, relative and global poses

Parameters

calibration_file (std_msgs/String)
  • path to txt file with camera calibration data in INI format
num_of_markers (std_msgs/UInt8)
  • Maximum number of markers to detect and track
marker_size (std_msgs/Double64)
  • Real marker size in meters
space_type (std_msgs/String)
  • plane/3D space type
roi_allowed (std_msgs/Bool)
  • ROI on/off flag
roi_x (std_msgs/UInt8)
  • ROI start x - coordinate
roi_y (std_msgs/UInt8)
  • ROI start y - coordinate
roi_w (std_msgs/UInt8)
  • ROI width
roi_h (std_msgs/UInt8)
  • ROI height

Provided tf Transforms

worldcamera_pose
  • Global camera pose

Demonstration

Aruco_mapping has been successfully used for autonomous indoor UAV navigation:

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: aruco_mapping (last edited 2015-10-10 11:13:34 by FrantisekDurovsky)