You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
First of all, thank you so much for your amazing work on RTAB-Map! It is an incredibly powerful tool, and I really appreciate all the effort you’ve put into its development and maintenance.
I have a couple of questions regarding RTAB-Map’s configuration and sensor fusion capabilities:
Combining Visual Odometry and LiDAR ICP
I am currently working with an Intel RealSense D455 camera and a 2D LiDAR. Additionally, I have a wheel odometer and an IMU available. My goal is to combine visual odometry from the D455 with ICP-based odometry from the LiDAR to achieve better robustness, especially in indoor environments.
I noticed that in the rtabmap.launch.py file, it seems only one odometry source can be specified as input.
Is it possible to fuse visual odometry and LiDAR ICP for better robustness?
If so, what would be the recommended approach to set this up in RTAB-Map?
2.Configuration Files for RTAB-Map and Odom Services
After launching RTAB-Map, I noticed that it creates a default rtabmap.ini file. However, it doesn’t seem to contain configurations related to odometry.
How should I configure the parameters for RTAB-Map and odometry services?
What should the config.ini file look like, especially for odometry settings?
3.Nav2 Integration: Costmap Sensor Inputs
I plan to use RTAB-Map with Nav2 for navigation.
Which topics should be used as inputs for local and global costmaps in Nav2?
What are the expected frame rates and delays for these topics? Are there any recommendations for optimizing performance?
I would greatly appreciate your guidance on these topics.
Thank you so much for your time and for developing such an excellent tool!
Best regards
The text was updated successfully, but these errors were encountered:
Combining Visual Odometry and LiDAR ICP
I am currently working with an Intel RealSense D455 camera and a 2D LiDAR. Additionally, I have a wheel odometer and an IMU available. My goal is to combine visual odometry from the D455 with ICP-based odometry from the LiDAR to achieve better robustness, especially in indoor environments.
I assume you are referring in environments that could be textureless at some point (making VO fails) or geometryless (making lidar odom fails). If you are in textureless and geometryless environment, you may also need somekind of wheel odometry too. You would need to do that in an external node, like robot_localization. If you launch icp_odometry and rgbd_odometry at the same time, make sure to remap their odom topic and odom_frame_id parameter to something different, and set publish_tf: false. You may set Odom/ResetCountdown: 1 to auto reset odom when lost, and probably with publish_null_when_lost: false to only publish when valid velocity can be computed. The combined odometry topic and/or odom TF would be fed as input to rtabmap node. Note that rtabmap node only care about twist covariance inside the odometry topic, so make sure the covariance relates to which odometry sources were used.
2.Configuration Files for RTAB-Map and Odom Services
After launching RTAB-Map, I noticed that it creates a default rtabmap.ini file. However, it doesn’t seem to contain configurations related to odometry.
There would be a rtabmapGUI.ini if you launch rtabmap_viz, but would containt only parameters related to UI. All rtabmap parameters will be read from rosparam server. For rtabmap and ####_odometry nodes, there is a parameter called config_path than can be used to set the parameters. Note also that you can also use default ROS parameter file approach too. For all RTAB-Map library parameters (the parameters shown when you do rtabmap --params), they should all have type of str.
3.Nav2 Integration: Costmap Sensor Inputs
I plan to use RTAB-Map with Nav2 for navigation.
From rtabmap side, a global "static" occupancy grid will be published to nav2 at 1 Hz (default), from which nav2 will generate the global costmap. rtabmap will also provide map->odom frame, while the odometry node (or node fusing all odometry sources) would provide odom->base_link frame. For the local costmap, it is configured in nav2 directly based on the sensor outputs. Ideally having sensors added at least at 5 Hz to the local costmap and odometry published at more than 10 Hz would work, though maybe a question to ask on nav2 project. For examples of rtabmap integration with nav2, see this page: https://github.com/introlab/rtabmap_ros/tree/ros2/rtabmap_demos
Hi,
First of all, thank you so much for your amazing work on RTAB-Map! It is an incredibly powerful tool, and I really appreciate all the effort you’ve put into its development and maintenance.
I have a couple of questions regarding RTAB-Map’s configuration and sensor fusion capabilities:
I am currently working with an Intel RealSense D455 camera and a 2D LiDAR. Additionally, I have a wheel odometer and an IMU available. My goal is to combine visual odometry from the D455 with ICP-based odometry from the LiDAR to achieve better robustness, especially in indoor environments.
I noticed that in the rtabmap.launch.py file, it seems only one odometry source can be specified as input.
2.Configuration Files for RTAB-Map and Odom Services
After launching RTAB-Map, I noticed that it creates a default rtabmap.ini file. However, it doesn’t seem to contain configurations related to odometry.
3.Nav2 Integration: Costmap Sensor Inputs
I plan to use RTAB-Map with Nav2 for navigation.
I would greatly appreciate your guidance on these topics.
Thank you so much for your time and for developing such an excellent tool!
Best regards
The text was updated successfully, but these errors were encountered: