Repository Summary

Description A bridge between norlab_icp_mapper and ROS
Checkout URI https://github.com/norlab-ulaval/norlab_icp_mapper_ros.git
VCS Type git
VCS Version ros2
Last Updated 2025-06-25
Dev Status UNKNOWN
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
norlab_icp_mapper_ros 2.1.1

README

norlab_icp_mapper_ros

A bridge between norlab_icp_mapper and ROS. Check the mapper’s documentation for a detailed guide.

Node Parameters

Name Description Possible values Default Value
odom_frame Frame used for odometry. Any string “odom”
robot_frame Frame centered on the robot. Any string “base_link”
mapping_config Path to the file containing the mapping config. Any file path ””
initial_map_file_name Path of the file from which the initial map is loaded. Any file path ””
initial_robot_pose Transformation matrix in homogeneous coordinates describing the initial pose of the robot in the map frame. Any matrix of dimension 3 or 4 ”[[1, 0, 0, 0], [0, 1, 0, 0], [0, 0, 1, 0], [0, 0, 0, 1]]”
final_map_file_name Path of the file in which the final map is saved when is_online is false. Any file path “map.vtk”
final_trajectory_file_name Path of the file in which the final trajectory is saved when is_online is false. Any file path “trajectory.vtk”
map_publish_rate Rate at which the map is published (in Hertz). It can be slower depending on the map update rate. (0, ∞) 10.0
map_tf_publish_rate Rate at which the map tf is published (in Hertz). (0, ∞) 10.0
max_idle_time Delay to wait being idle before shutting down ROS when is_online is false (in seconds). [0, ∞) 10.0
is_mapping true when map updates are wanted, false when only localization is wanted. {true, false} true
localizing true when localization updates are wanted, false when localization is unwanted (relocalization in map). {true, false} true
is_online true when online mapping is wanted, false otherwise. {true, false} true
is_3D true when a 3D sensor is used, false when a 2D sensor is used. {true, false} true
save_map_cells_on_hard_drive true when map cell storage on hard drive is wanted, false when map cell storage in RAM is wanted. {true, false} true
publish_tfs_between_registrations When false, the map tf is published only after registration. Otherwise with map_tf_publish_rate. {true, false} true
deskew Set to true if you want to apply motion compensation on the input point cloud. {true, false} true
expected_unique_deskewing_TF_number How much memory should we reserve for the per-point transformations. A positive integer 4000
deskewing_round_to_nanosecs How much should each point’s timestamp be rounded for deskewing transformation search. A positive integer 50000

Dynamic Node Parameters

These parameters can be changed at runtime using the ROS parameter server.

Name Description Possible values Default Value
compression_voxel_size Size of a voxel in the octree tree of the output map point cloud message. 0=disabled A non-negative double 0.5

Node Topics

Name Description
points_in Topic from which the input points are retrieved.
map Topic in which the map is published.
icp_odom Topic in which the corrected odometry is published.
scan_after_input_filters The input scan, after all input filters are applied.
scan_after_deskew The input scan, after all input filters and deskewing are applied.
pose_in Topic from which the pose is retrieved to relocalize.

Node Services

Name Description Parameter Name Parameter Description
save_map Saves the current map. filename Path of the file in which the map is saved.
save_trajectory Saves the current trajectory. filename Path of the file in which the trajectory is saved.
reload_yaml_config Reload the YAML config file.    
enable_mapping Enables the mapping (If localization is disabled, it enables it too).    
disable_mapping Disables the mapping.    
enable_loc Enables the localization.    
disable_loc Disables the localization (If mapping is enabled, it disables it too).    

Mapper Node Graph

```mermaid flowchart LR

/mapper_node[ /mapper_node ]:::main

/points_in([ /points_in
sensor_msgs/msg/PointCloud2 ]):::bugged /pose_in([ /pose_in
geometry_msgs/msg/PoseWithCovarianceStamped ]):::bugged /icp_odom([ /icp_odom
nav_msgs/msg/Odometry ]):::bugged /map([ /map
sensor_msgs/msg/PointCloud2 ]):::bugged /scan_after_input_filters([ /map
sensor_msgs/msg/PointCloud2 ]):::bugged /scan_after_deskew([ /map
sensor_msgs/msg/PointCloud2 ]):::bugged /disable_mapping[/ /disable_mapping
std_srvs/srv/Empty ]:::bugged /enable_mapping[/ /enable_mapping
std_srvs/srv/Empty ]:::bugged /disable_loc[/ /disable_loc
std_srvs/srv/Empty ]:::bugged /enable_loc[/ /enable_loc
std_srvs/srv/Empty ]:::bugged /load_map[/ /load_map
norlab_icp_mapper_ros/srv/LoadMap ]:::bugged /reload_yaml_config[/ /reload_yaml_config
std_srvs/srv/Empty ]:::bugged /save_map[/ /save_map
norlab_icp_mapper_ros/srv/SaveMap ]:::bugged /save_trajectory[/ /save_trajectory
norlab_icp_mapper_ros/srv/SaveTrajectory ]:::bugged

/points_in –> /mapper_node /pose_in –> /mapper_node /mapper_node –> /icp_odom /mapper_node –> /map /disable_mapping o-.-o /mapper_node /enable_mapping o-.-o /mapper_node /disable_loc o-.-o /mapper_node /enable_loc o-.-o /mapper_node /load_map o-.-o /mapper_node /reload_yaml_config o-.-o /mapper_node /save_map o-.-o /mapper_node /save_trajectory o-.-o /mapper_node

subgraph keys[Keys] subgraph nodes[] topicb((No connected)):::bugged

File truncated at 100 lines see the full file