ROS API reference documentation

_images/nodes_graph_demo_2d.jpg

Cartographer Node

The cartographer_node is the SLAM node used for online, real-time SLAM.

Command-line Flags

Call the node with the --help flag to see all available options.

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 num_laser_scans is set to 1 in the Lua configuration reference documentation, this topic will be used as input for SLAM. If num_laser_scans is greater than 1, multiple numbered scan topics (i.e. scan_1, scan_2, scan_3, … up to and including num_laser_scans) will be used as inputs for SLAM.
echoes (sensor_msgs/MultiEchoLaserScan)
Supported in 2D and 3D (e.g. using an axially rotating planar laser scanner). If num_multi_echo_laser_scans is set to 1 in the Lua configuration reference documentation, this topic will be used as input for SLAM. Only the first echo is used. If num_multi_echo_laser_scans is greater than 1, multiple numbered echoes topics (i.e. echoes_1, echoes_2, echoes_3, … up to and including num_multi_echo_laser_scans) will be used as inputs for SLAM.
points2 (sensor_msgs/PointCloud2)
If num_point_clouds is set to 1 in the Lua configuration reference documentation, 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 Lua configuration reference documentation, this topic will be used as input for SLAM.

Published Topics

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 Lua configuration reference documentation.
submap_list (cartographer_ros_msgs/SubmapList)
List of all submaps, including the pose and latest version number of each submap, across all trajectories.
tracked_pose (geometry_msgs/PoseStamped)
Only published if the parameter publish_tracked_pose is set to true. The pose of the tracked frame with respect to the map frame.

Services

All services responses include also a StatusResponse that comprises a code and a message field. For consistency, the integer code is equivalent to the status codes used in the gRPC API.

submap_query (cartographer_ros_msgs/SubmapQuery)
Fetches the requested submap.
start_trajectory (cartographer_ros_msgs/StartTrajectory)
Starts a trajectory using default sensor topics and the provided configuration. An initial pose can be optionally specified. Returns an assigned trajectory ID.
trajectory_query (cartographer_ros_msgs/TrajectoryQuery)
Returns the trajectory data from the pose graph.
finish_trajectory (cartographer_ros_msgs/FinishTrajectory)
Finishes the given trajectory_id’s trajectory by running a final optimization.
write_state (cartographer_ros_msgs/WriteState)
Writes the current internal state to disk into filename. The file will usually end up in ~/.ros or ROS_HOME if it is set. This file can be used as input to the assets_writer_main to generate assets like probability grids, X-Rays or PLY files.
get_trajectory_states (cartographer_ros_msgs/GetTrajectoryStates)
Returns the IDs and the states of the trajectories. For example, this can be useful to observe the state of Cartographer from a separate node.
read_metrics (cartographer_ros_msgs/ReadMetrics)
Returns the latest values of all internal metrics of Cartographer. The collection of runtime metrics is optional and has to be activated with the --collect_metrics command line flag in the node.

Required tf Transforms

_images/frames_demo_2d.jpg

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 provided unless the parameter publish_to_tf is set to false.

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

Offline Node

The offline_node is the fastest way of SLAMing a bag of sensor data. It does not listen on any topics, instead it reads TF and sensor data out of a set of bags provided on the commandline. It also publishes a clock with the advancing sensor data, i.e. replaces rosbag play. In all other regards, it behaves like the cartographer_node. Each bag will become a separate trajectory in the final state. Once it is done processing all data, it writes out the final Cartographer state and exits.

Published Topics

In addition to the topics that are published by the online node, this node also publishes:

~bagfile_progress (cartographer_ros_msgs/BagfileProgress)
Bag files processing progress including detailed information about the bag currently being processed which will be published with a predefined interval that can be specified using ~bagfile_progress_pub_interval ROS parameter.

Parameters

~bagfile_progress_pub_interval (double, default=10.0):
The interval of publishing bag files processing progress in seconds.

Occupancy grid Node

The occupancy_grid_node listens to the submaps published by SLAM, builds an ROS occupancy_grid out of them and publishes it. This tool is useful to keep old nodes that require a single monolithic map to work happy until new nav stacks can deal with Cartographer’s submaps directly. Generating the map is expensive and slow, so map updates are in the order of seconds. You can can selectively include/exclude submaps from frozen (static) or active trajectories with a command line option. Call the node with the --help flag to see these options.

Subscribed Topics

It subscribes to Cartographer’s submap_list topic only.

Published Topics

map (nav_msgs/OccupancyGrid)
If subscribed to, the node 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.

Pbstream Map Publisher Node

The pbstream_map_publisher is a simple node that creates a static occupancy grid out of a serialized Cartographer state (pbstream format). It is an efficient alternative to the occupancy grid node if live updates are not important.

Subscribed Topics

None.

Published Topics

map (nav_msgs/OccupancyGrid)
The published occupancy grid topic is latched.