Generating AR tags of varying size, resolution, and data/ID encoding.
Identifying and tracking the pose of individual AR tags, optionally integrating kinect depth data (when a kinect is available) for better pose estimates.
Identifying and tracking the pose of "bundles" consisting of multiple tags. This allows for more stable pose estimates, robustness to occlusions, and tracking of multi-sided objects.
Using camera images to automatically calculate spatial relationships between tags in a bundle.
$ sudo apt-get install ros-indigo-ar-track-alvar
rosrun ar_track_alvar createMarker
Instructions will appear describing the various options.
The node individualMarkers takes the following command line arguments:
The width in centimeters of one side of the black square marker border
marker_size
A threshold determining when new markers can be detected under uncertainty
max_new_marker_error
A threshold determining how much tracking error can be observed before an tag is considered
to have disappeared
max_track_error
The name of the topic that provides camera frames for detecting the AR tags. This can be mono or
color, but should be an UNrectified image, since rectification takes place in this package
camera_image
The name of the topic that provides the camera calibration parameters so that the image can be
rectified
camera_info
The name of the frame that the published Cartesian locations of the AR tags will be relative
to
output_frame
* If you are not using a kinect or do not desire to use depth data improvements, use individualMarkersNoKinect instead.
The node findMarkerBundles takes the following command line parameters:
marker_size
max_new_marker_error
max_track_error
camera_image
camera_info
output_frame
A list of XML file names, one for each bundle you wish to detect.
bundle_files
* If you are not using a kinect or do not desire to use depth data improvements, use findMarkerBundlesNoKinect instead.
/kinect_head/rgb/camera_info (sensor_msgs/CameraInfo)
Camera needs calibrated before this topic to become available.
(sensor_msgs/Image)
Image to be analyzed for markers.
visualization_marker (visualization_msgs/Marker)
An rviz message. When
subscribed to, displays colored square blocks at the location of identified AR tags. Also
overlay these
blocks in a camera image.
ar_pose_marker (ar_track_alvar/AlvarMarkers)
A list of the poses of all the
observed AR tags, with respect to the output frame.
Camera frame (from Camera info topic param) → AR tag frame
Provides a transform
from
the camera frame to each AR tag frame, named ar_marker_x, where x is the ID number of the tag.
visualization_marker
Display a red square block at the location of identified
"master" AR tags (one per bundle), green square block at the location of other
tags, and also overlay these blocks in a camera image.
ar_pose_marker
List of the poses of all the
observed "master" AR tags (one per bundle), with respect to the output frame.
Camera frame
Transform from
the camera frame to "master" AR tag frames, named ar_marker_x, where x is the ID number of
the tag.