Wiki

Nodes

rtabmap

This is the main node of this package. It is a wrapper of the RTAB-Map Core library. This is where the graph of the map is incrementally built and optimized when a loop closure is detected. The online output of the node is the local graph with the latest added data to the map. The default location of the RTAB-Map database is "~/.ros/rtabmap.db" and the workspace is also set to "~/.ros". To get a 3D point cloud or a 2D occupancy grid of the environment, subscribe to cloud_map or grid_map topics.

Arguments

Subscribed Topics

odom (nav_msgs/Odometry) rgb/image (sensor_msgs/Image) rgb/camera_info (sensor_msgs/CameraInfo) depth/image (sensor_msgs/Image) scan (sensor_msgs/LaserScan) scan_cloud (sensor_msgs/PointCloud2) left/image_rect (sensor_msgs/Image) left/camera_info (sensor_msgs/CameraInfo) right/image_rect (sensor_msgs/Image) right/camera_info (sensor_msgs/CameraInfo) goal (geometry_msgs/PoseStamped) rgbd_image (rtabmap_msgs/RGBDImage) rgbd_image# (rtabmap_msgs/RGBDImage) rgbd_images (rtabmap_msgs/RGBDImages) imu (sensor_msgs/Imu) gps/fix (sensor_msgs/NavSatFix) global_pose (geometry_msgs/PoseWithCovarianceStamped) tag_detections (apriltag_ros/AprilTagDetectionArray) fiducial_transforms (fiducial_msgs/FiducialTransformArray)

Published Topics

info (rtabmap_msgs/Info) mapData (rtabmap_msgs/MapData) mapGraph (rtabmap_msgs/MapGraph) grid_map (nav_msgs/OccupancyGrid) proj_map (nav_msgs/OccupancyGrid) cloud_map (sensor_msgs/PointCloud2) cloud_obstacles (sensor_msgs/PointCloud2) cloud_ground (sensor_msgs/PointCloud2) scan_map (sensor_msgs/PointCloud2) labels (visualization_msgs/MarkerArray) global_path (nav_msgs/Path) local_path (nav_msgs/Path) goal_reached (std_msgs/Bool) goal_out (geometry_msgs/PoseStamped) octomap_full (octomap_msgs/Octomap) octomap_binary (octomap_msgs/Octomap) octomap_occupied_space (sensor_msgs/PointCloud2) octomap_obstacles (sensor_msgs/PointCloud2) octomap_ground (sensor_msgs/PointCloud2) octomap_empty_space (sensor_msgs/PointCloud2) octomap_grid (nav_msgs/OccupancyGrid)

Services

get_map (nav_msgs/GetMap) get_map_data (rtabmap_msgs/GetMap) publish_map (rtabmap_msgs/PublishMap) list_labels (rtabmap_msgs/ListLabels) update_parameters (std_srvs/Empty) reset (std_srvs/Empty) pause (std_srvs/Empty) resume (std_srvs/Empty) trigger_new_map (std_srvs/Empty) backup (std_srvs/Empty) set_mode_localization (std_srvs/Empty) set_mode_mapping (std_srvs/Empty) set_label (rtabmap_msgs/SetLabel) set_goal (rtabmap_msgs/SetGoal) octomap_full (octomap_msgs/GetOctomap) octomap_binary (octomap_msgs/GetOctomap)

Parameters

~subscribe_depth (bool, default: "true") ~subscribe_scan (bool, default: "false") ~subscribe_scan_cloud (bool, default: "false") ~subscribe_stereo (bool, default: "false") ~subscribe_rgbd (bool, default: "false") ~frame_id (string, default: "base_link") ~map_frame_id (string, default: "map") ~odom_frame_id (string, default: "") ~odom_tf_linear_variance (double, default: 0.001) ~odom_tf_angular_variance (double, default: 0.001) ~queue_size (int, default: 10) ~publish_tf (bool, default: "true") ~tf_delay (double, default: 0.05) ~tf_prefix (string, default: "") ~wait_for_transform (bool, default: "true") ~wait_for_transform_duration (double, default: 0.1) ~config_path (string, default: "") ~database_path (string, default: "~/.ros/rtabmap.db") ~gen_scan (bool, default: "false") ~gen_scan_max_depth (double, default: 4.0) ~approx_sync (bool, default: "false") ~rgbd_cameras (int, default: 1) ~use_action_for_goal (bool, default: "false") ~odom_sensor_sync (bool, default: "false") ~gen_depth (bool, default: "false") ~gen_depth_decimation (int, default: 1) ~gen_depth_fill_holes_size (int, default: 0) ~gen_depth_fill_iterations (double, default: 0.1) ~gen_depth_fill_holes_error (int, default: 1) ~map_filter_radius (double, default: 0.0) ~map_filter_angle (double, default: 30.0) ~map_cleanup (bool, default: "true") ~latch (bool, default: "true") ~map_always_update (bool, default: "false") ~map_empty_ray_tracing (bool, default: "true") ~cloud_output_voxelized (bool, default: "true") ~cloud_subtract_filtering (bool, default: "true") ~cloud_subtract_filtering_min_neighbors (int, default: 2)

Required tf Transforms

base_link<the frame attached to sensors of incoming data> odombase_link

Provided tf Transforms

mapodom

Wiki: rtabmap_slam (last edited 2023-08-05 22:52:45 by MathieuLabbe)