ROS API

The following ROS API is provided by cartographer_node.

Command-line Flags

–configuration_directory
First directory in which configuration files are searched, second is always the Cartographer installation to allow including files from there.
–configuration_basename
Basename (i.e. not containing any directory prefix) of the configuration file (e.g. backpack_3d.lua).

Subscribed Topics

The following range data topics are mutually exclusive. At least one source of range data is required.

scan (sensor_msgs/LaserScan)
Supported in 2D and 3D (e.g. using an axially rotating planar laser scanner). If use_laser_scan is enabled in the Configuration, this topic will be used as input for SLAM.
echoes (sensor_msgs/MultiEchoLaserScan)
Supported in 2D and 3D (e.g. using an axially rotating planar laser scanner). If use_multi_echo_laser_scan is enabled in the Configuration, this topic will be used as input for SLAM. Only the first echo is used.
points2 (sensor_msgs/PointCloud2)
Only supported in 3D. If num_point_clouds is set to 1 in the Configuration, this topic will be used as input for SLAM. If num_point_clouds is greater than 1, multiple numbered points2 topics (i.e. points2_1, points2_2, points2_3, ... up to and including num_point_clouds) will be used as inputs for SLAM.

The following additional sensor data topics may also be provided.

imu (sensor_msgs/Imu)
Supported in 2D (optional) and 3D (required). This topic will be used as input for SLAM.
odom (nav_msgs/Odometry)
Supported in 2D (optional) and 3D (optional). If use_odometry is enabled in the Configuration, this topic will be used as input for SLAM.

Published Topics

map (nav_msgs/OccupancyGrid)
Only supported in 2D. If subscribed to, a background thread will continuously compute and publish the map. The time between updates will increase with the size of the map. For faster updates, use the submaps APIs.
scan_matched_points2 (sensor_msgs/PointCloud2)
Point cloud as it was used for the purpose of scan-to-submap matching. This cloud may be both filtered and projected depending on the Configuration.
submap_list (cartographer_ros_msgs/SubmapList)
List of all submaps, including the pose and latest version number of each submap, across all trajectories.

Services

submap_query (cartographer_ros_msgs/SubmapQuery)
Fetches the requested submap.
finish_trajectory (cartographer_ros_msgs/FinishTrajectory)
Finishes the current trajectory by flushing all queued sensor data, running a final optimization, and writing artifacts (e.g. the map) to disk. The stem argument is used as a prefix for the various files which are written. Files will usually end up in ~/.ros or ROS_HOME if it is set.

Required tf Transforms

Transforms from all incoming sensor data frames to the configured tracking_frame and published_frame must be available. Typically, these are published periodically by a robot_state_publisher or a static_transform_publisher.

Provided tf Transforms

The transformation between the configured map_frame and published_frame is always provided.

If provide_odom_frame is enabled in the Configuration, a continuous (i.e. unaffected by loop closure) transform between the configured odom_frame and published_frame will be provided.