Mapping Operations
This guide covers creating, updating, and managing maps for the RCR Common Robotics Platform.
Overview
Mapping is the process of creating a representation of the robot’s environment using sensor data, primarily from the LiDAR sensor. This map is essential for navigation and localization.
Mapping Methods
1. SLAM (Simultaneous Localization and Mapping) Using Cartographer
SLAM allows the robot to build a map while simultaneously tracking its position within that map.
Do this Once for Setup
cp ~/repos/common_platform/launch/cartographer_simple.launch.py ~/ros2_ws/src/cartographer_ros/cartographer_ros/launch/ colcon build --packages-select cartographer_ros --symlink-install
Launch SLAM
cd ~/repos/common_platform/common_platform_ws/ source install/setup.bash ros2 launch common_platform pub_robot_state.launch.py use_sim_time:=false
cd ~/ros2_ws/ ros2 launch cartographer_ros cartographer_simple.launch.py
cd ~/ros2_ws/ ros2 run cartographer_ros cartographer_occupancy_grid_node --ros-args -p resolution:=0.05 -p publish_period_sec:=1.0 -r __ns:=${ROS_NAMESPACE}
Nodes Created:
robot_state_publisher- Publishes robot transformsjoint_state_publisher- Publishes robot joint statuscartographer_node- Main SLAM processing nodecartographer_occupancy_grid_node- Occupancy grid publisher
Expected Topics:
Subscriptions (cartographer_node):
/scan(sensor_msgs/LaserScan) - LiDAR scan data/tf(tf2_msgs/TFMessage) - Transform data/tf_static(tf2_msgs/TFMessage) - Static transform data/odom(nav_msgs/Odometry) - Odometry data
Publications (cartographer_node):
/tf(tf2_msgs/TFMessage) - Transform from map to odom/constraint_list(cartographer_ros_msgs/ConstraintList) - Loop closure constraints/trajectory_node_list(cartographer_ros_msgs/TrajectoryNodeList) - Trajectory nodes
Publications (cartographer_occupancy_grid_node):
/map(nav_msgs/OccupancyGrid) - Final occupancy grid map/submap_list(cartographer_ros_msgs/SubmapList) - Submap information
Verify Topics:
# Check active topics ros2 topic list # Monitor map updates ros2 topic echo /map # Check transform tree ros2 run tf2_tools view_frames
Teleop Control
See Keyboard Teleoperation Setup for robot control setup.
Setup a relay for the odom topic In the linux environment running your DDS server, you need to setup a repeater for the odom topic because the DDS client available on the Teensy is an eXtremely Resource Constrained Environment (XRCE) version that doesn’t add all the correct metadata to the published messages. Replace n in rcr00n with your robot number.
cd ~/repos/common_platform/common_platform_ws source install/setup.bash ROS_NAME=rcr00n ros2 launch qos_relay qos_relay.launch.py
Drive the Robot
Use keyboard controls to drive the robot
Cover the entire area you want to map
Move slowly for better map quality
Ensure good LiDAR coverage
Save the Map
# Save the map using Cartographer's built-in functionality ros2 service call ${ROS_NAMESPACE}/finish_trajectory cartographer_ros_msgs/srv/FinishTrajectory "{trajectory_id: 0}" ros2 service call ${ROS_NAMESPACE}/write_state cartographer_ros_msgs/srv/WriteState "{filename: 'my_map.pbstream'}" # Convert to standard map format (optional) ros2 run cartographer_ros cartographer_pbstream_to_ros_map -pbstream_filename my_map.pbstream -map_filename my_map
2. Manual Mapping
For areas where autonomous mapping is difficult:
Use RViz for Visualization
ros2 launch common_platform view_robot.launch.py
Manual Control
Use joystick or keyboard control
Monitor map building in RViz
Adjust speed based on map quality
Mapping Best Practices
Environment Preparation
Lighting
Ensure adequate lighting
Avoid direct sunlight on LiDAR
Minimize shadows and reflections
Obstacles
Remove temporary obstacles
Ensure clear pathways
Mark permanent obstacles clearly
Area Coverage
Plan mapping route in advance
Ensure complete area coverage
Overlap paths for better accuracy
Robot Operation
Speed Control
Move slowly (0.1-0.3 m/s)
Avoid sudden direction changes
Maintain consistent speed
Path Planning
Use systematic coverage patterns
Ensure good LiDAR visibility
Avoid tight spaces initially
Quality Monitoring
Monitor map quality in RViz
Watch for mapping errors
Adjust parameters if needed
Map Quality Assessment
Visual Inspection
Check Map Completeness
All areas should be covered
No large gaps in walls
Obstacles clearly defined
Verify Accuracy
Compare with actual environment
Check wall straightness
Verify obstacle positions
Look for Artifacts
Ghost walls or obstacles
Inconsistent wall thickness
Mapping errors or loops
Quantitative Metrics
Coverage Percentage
Calculate mapped vs. total area
Identify unmapped regions
Plan additional mapping if needed
Map Resolution
Verify appropriate resolution
Check for over/under-sampling
Adjust parameters if necessary
Map Management
File Organization
maps/
├── office_floor1/
│ ├── office_floor1.yaml
│ └── office_floor1.pgm
├── warehouse/
│ ├── warehouse.yaml
│ └── warehouse.pgm
└── test_area/
├── test_area.yaml
└── test_area.pgm
Map Metadata
Each map includes a .yaml file with metadata:
image: warehouse.pgm
resolution: 0.05
origin: [-10.0, -10.0, 0.0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196
Map Updates
Incremental Updates
Use SLAM for map updates
Merge new data with existing map
Maintain map consistency
Complete Remapping
Delete old map files
Create new map from scratch
Update navigation parameters
Troubleshooting
Common Mapping Issues
Poor Map Quality
Check LiDAR calibration
Verify sensor mounting
Adjust mapping parameters
Incomplete Coverage
Plan better mapping route
Increase mapping time
Use systematic coverage patterns
Mapping Errors
Check for sensor obstructions
Verify robot odometry
Review SLAM parameters
Parameter Tuning
Cartographer Parameters
Cartographer uses Lua configuration files located in config/cartographer/. The most important parameters for tuning:
Trajectory Builder Parameters
-- In cartographer_2d.lua TRAJECTORY_BUILDER_2D = { min_range = 0.3, -- Minimum LiDAR range (m) max_range = 8.0, -- Maximum LiDAR range (m) min_z = 0.1, -- Minimum height for points max_z = 2.0, -- Maximum height for points missing_data_ray_length = 1.0, -- Length for missing data rays num_accumulated_range_data = 1, -- Number of scans to accumulate voxel_filter_size = 0.025, -- Voxel filter size (m) adaptive_voxel_filter_max_length = 0.5, adaptive_voxel_filter_min_num_points = 200, adaptive_voxel_filter_max_range = 50.0, use_intensities = false, -- Use LiDAR intensity data }
Why Voxels in 2D SLAM?
Even though Cartographer creates 2D maps, it processes 3D point cloud data from the LiDAR sensor. The voxel filtering serves several purposes:
3D Point Cloud Processing: LiDAR sensors provide 3D points (x, y, z coordinates)
Height Filtering:
min_zandmax_zparameters filter out points outside the robot’s height rangeNoise Reduction: Voxel filtering reduces noise and duplicate points in 3D space
Computational Efficiency: Downsampling 3D points before projecting to 2D map
Data Quality: Removes outliers and inconsistent measurements
The final 2D map is created by projecting the filtered 3D points onto the ground plane.
Pose Graph Parameters
POSE_GRAPH = { optimize_every_n_nodes = 90, -- Optimize every N nodes constraint_builder = { sampling_ratio = 0.03, -- Loop closure sampling ratio max_constraint_distance = 15.0, -- Max distance for constraints min_score = 0.55, -- Minimum score for loop closure global_localization_min_score = 0.6, }, }
Launch File Parameters
# Adjustable via launch arguments ros2 launch common_platform cartographer_2d.launch.py \ resolution:=0.05 \ publish_period_sec:=1.0
Tuning Procedure
Start with Default Parameters
# Use default configuration ros2 launch common_platform cartographer_2d.launch.py
Monitor Mapping Quality
Watch for loop closure detection
Check for consistent wall thickness
Verify accurate pose estimation
Detecting Loop Closures
Visual Indicators in RViz:
Pose Graph Visualization: Look for constraint lines connecting distant poses
Map Alignment: Watch for sudden map corrections when returning to previously visited areas
Trajectory Smoothing: Notice when the robot’s path becomes more consistent
Console Output Indicators:
# Look for these messages in the terminal:
[INFO] [cartographer_node]: Adding loop closure constraint
[INFO] [cartographer_node]: Optimization completed
[INFO] [cartographer_node]: Pose graph optimization took X ms
RViz Display Settings:
# Enable these displays in RViz:
- Map (occupancy grid)
- Pose Graph (constraints and nodes)
- Trajectory (robot path)
- LaserScan (current scan data)
Monitoring Commands:
# Monitor Cartographer topics
ros2 topic echo /${ROS_NAME}/constraint_list
ros2 topic echo /${ROS_NAME}/trajectory_node_list
# Check for optimization events
ros2 topic hz /${ROS_NAME}/constraint_list
Adjust Based on Environment
For Large Open Spaces:
-- Increase loop closure search distance max_constraint_distance = 25.0 loop_search_maximum_distance = 5.0
For Cluttered Environments:
-- Reduce minimum range, increase sampling min_range = 0.2 sampling_ratio = 0.05
For High-Speed Mapping:
-- Reduce optimization frequency optimize_every_n_nodes = 120 num_accumulated_range_data = 2
Fine-tune Loop Closure
-- Adjust loop closure sensitivity min_score = 0.5 # Lower = more sensitive global_localization_min_score = 0.55
Optimize Performance
-- Balance accuracy vs. performance optimize_every_n_nodes = 60 # Lower = more frequent optimization num_accumulated_range_data = 1 # Higher = more data per scan
Common Tuning Scenarios
Poor Loop Closure:
Increase
max_constraint_distanceDecrease
min_scoreIncrease
sampling_ratio
Inconsistent Wall Thickness:
Adjust
voxel_filter_sizeTune
adaptive_voxel_filter_min_num_pointsCheck
min_rangeandmax_range
Slow Performance:
Increase
optimize_every_n_nodesReduce
num_accumulated_range_dataDecrease
sampling_ratio
Memory Issues:
Increase
optimize_every_n_nodesReduce
max_constraint_distanceLower
adaptive_voxel_filter_max_range
Map Validation
Testing Procedures
Localization Test
Test robot localization accuracy
Verify pose estimation quality
Check for localization failures
Navigation Test
Test path planning capabilities
Verify obstacle avoidance
Check navigation performance
Edge Case Testing
Test in narrow passages
Verify performance near walls
Check behavior in open areas
For localization procedures, see Localization For path planning, see Path Planning For troubleshooting, see Troubleshooting