Wiki

Only released in EOL distros:  

Package Summary

Overhead Camera System for Tracking AR Tags

Package Summary

Overhead Camera System for Tracking AR Tags

About

Rail_ceiling is an overhead camera system for tracking the positions of obstacles in a closed space and publishing maps containing those obstacles for use in robot navigation. Rail_ceiling supports multiple cameras and can publish multiple maps with different obstacle footprints. Obstacle tracking is accomplished using ar tags and the ar_track_alvar ros package.

Nodes

calibration

Calibrates transforms between a global coordinate frame and the array of ceiling cameras based on AR markers of known location.

Subscribed Topics

ceiling_cam_tracker_[i]/ar_pose_marker (ar_track_alvar_msgs/AlvarMarkers)

Parameters

fixed_frame (string, default: map) camera_frame_id_prefix (string, default: ceiling_cam_) num_cameras (int, default: 1) num_samples (int, default: 10) ceiling_cam_[i]_pos_x (double, default: 0.0) ceiling_cam_[i]_pos_y (double, default: 0.0) ceiling_cam_[i]_pos_z (double, default: 0.0) ceiling_cam_[i]_rot_x (double, default: 0.0) ceiling_cam_[i]_rot_y (double, default: 0.0) ceiling_cam_[i]_rot_z (double, default: 0.0) ceiling_cam_[i]_rot_w (double, default: 1.0)

calibration_from_carl

Calibrates transforms between a global coordinate frame and the array of ceiling cameras based on an AR marker located on a localized robot.

Subscribed Topics

ceiling_cam_tracker_[i]/ar_pose_marker (ar_track_alvar_msgs/AlvarMarkers) start_calibration (std_msgs/Int16)

Parameters

num_cameras (int, default: 5) calibration_marker_id (int, default: 200)

furniture_tracker

Using the furniture configuration files, track positions of furniture obstacles from AR marker data and publish significant changes of furniture footprint positions to costmap layers.

Subscribed Topics

ceiling_cam_tracker_[i]/ar_pose_marker (ar_track_alvar_msgs/AlvarMarkers) start_calibration (std_msgs/Int16)

Published Topics

furniture_layer/update_obstacles (rail_ceiling/Obstacles)

Services

furniture_tracker/get_all_poses (rail_ceiling/getAllObstacles)

Parameters

num_marker_topics (int, default: 5) read_initial_poses (bool, default: false) markers_config (string, default: (path to rail_ceiling)/config/markers.yaml) furniture_footprints_config (string, default: (path to rail_ceiling)/config/furniture_footprints.yaml)

Installation

To install the rail_ceiling package, you can install from source with the following commands:

cd /(your catkin workspace)/src
git clone https://github.com/WPI-RAIL/rail_ceiling.git
cd ..
catkin_make

Camera Transform Calibration

The transforms between the global coordinate frame and the camera frames need to be accurately calibrated for furniture tracking to work properly. This can be done one of three ways: calibration from markers of known fixed position, calibration from a marker on a localized robot, or direct measurement.

Calibration from Floor Markers

The calibration node will run an automatic calibration procedure where each camera will take sample poses of an associated marker of known position in the environment. Once a sufficient number of samples have been taken for each camera, the transforms will be calculated and written to the ceiling.urdf.xacro file in your home directory, and must then be copied into the urdf directory of the rail_ceiling package if you wish to use it.

This process is fully automated and is recommended if you have a marker in a fixed, accurately measured location in the environment. Each marker must have an ID equal to the camera index plus 100 (camera 0 will be associated with marker 100, camera 1 will be associated with marker 101, etc.).

This process can be launched with the following launch file, which will also start the cameras and ar tracking nodes:

The process can be visualized with:

Calibration from Mobile Robot

The calibration_from_carl node provides a method of calibrating the camera transforms from a marker placed on a localized mobile robot, such as the CARL platform. This calibration method is executed as follows:

Next, the robot must be driven into the field of view of a camera to be calibrated. Once the robot is in the camera's field of view and it is confirmed to be accurately localized, publishing to the start_calibration topic with the id number of the camera to be calibrated replacing [camera_id]:

This will initiate sample collecting for the selected camera, and completion of sample collection will be denoted in the terminal. The process must then be repeated for all cameras. Note that if the robot is within the field of view of multiple cameras, they can be calibrated simultaneously.

Once sufficient samples are collected for all of the cameras, the transforms will be calculated and written to the ceiling.urdf.xacro file in your home directory, and must then be copied into the urdf directory of the rail_ceiling package if you wish to use it.

Calibration from Direct Measurement

The transforms can also be edited directly in the human-readable urdf file, urdf/ceiling.urdf.xacro. This should only be done if the camera positions and orientations can be accurately measured.

Furniture Configuration

Furniture footprints and marker information can be configured in the furniture_footprints.yaml and markers.yaml file in the config directory. The furniture_footprints.yaml configuration file defines general pieces of furniture with convex polygon footprints for localization and navigation, and the markers.yaml configuration file defines instances of furniture with attached markers and their associated poses.

Defining Furniture Footprints

To add a new type of furniture, simply add a new entry to the furniture_footprints.yaml file. Each entry must have a name (for identifying the type of furniture) a localization footprint (a set of convex polygons that a laser scanner will detect), and a navigation footprint (a set of convex polygons that represent the full area occupied by the piece of furniture that should be avoided during navigation). The entry format is as follows:

Points composing the polygons are defined with respect to the center of the piece of furniture, according to a coordinate system with x increasing right, y increasing forward, and z increasing up. In practice, the reference frame's position does not have to be at the center of the furniture piece, as long as it is consistent with the reference frame defined for instances of the furniture type in the markers.yaml file.

Note that polygons must consist of a minimum of 3 points, and an object can be defined with zero or more localization footprint polygons and zero or more navigation footprint polygons.

Defining Furniture Instances

Each piece of furniture in th eenvironment must have its own entry in the markers.yaml file. Each entry consists of a required type (corresponding with the furniture names defined in furniture_footprints.yaml), an optional initial_pose (an initial pose for the piece of furniture in the global coordinate frame), and a required set of markers. Markers are defined with the unique id used to generate them, and the pose of the marker with respect to the furniture reference frame. The entry format is as follows:

Note that each furniture instance requires one or more markers, and no two furniture instances can use the same marker id.

Startup

Once calibrated, a pose publisher for the camera positions can be run with:

The main functionality of the rail_ceiling package is furniture tracking. This can be launched with:

Alternatively, the cameras, the cameras and AR trackers can be launched individually with:

Support

Please send bug reports to the github issue tracker.

Wiki: rail_ceiling (last edited 2014-12-11 19:01:36 by davidkent)