rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

Livox mid360 lidar low objects

Open pepper11com opened this issue 5 months ago • 3 comments

Hi, First of all thank you for your great work and being so active! I got a question I cant figure out. I'm using ros2 jazzy rtabmap_slam and use a livox mid360 lidar and was wondering if it can treat points between 0 and 0.7m as obstacles for the 2D map it creates, while ignoring points above that height as obstacles but still utilizing the full height range (e.g., up to 30 m or more) for robust localization and denser overall mapping for later localization on the map. So the 2d map is still useful for low-level/height robots that only need to see low objects as obstacles like in a garden with trees!

Looking forward if there is a solution to this problem! Thank you

pepper11com avatar Jul 18 '25 00:07 pepper11com

Hi!

Yes that is possible. Is the ground mostly flat? You may use parameters like this:

# Note that RTAB-Map's library parameters should be "str" type
parameters=[{
       'Grid/NormalsSegmentation': 'False',
       'Grid/MaxGroundHeight': '0.05',
       'Grid/MaxObstacleHeight': '0.7',
       'Grid/3D': 'False',        
       'Grid/RayTracing': 'True'}]

The height parameters are relative to the base frame of the robot (e..g, base_link or base_footprint), assuming it is on the ground. For more info about these parameters, do:

rtabmap --params | grep Grid

EDIT: One caveat when using Grid/MaxObstacleHeight is that points over that threshold are also not used for clearing dynamic obstacles, unlike Grid/RangeMax parameter. I've just created and issue about that, though when Grid/3D is false and the robot can see the ground, that wouldn't matter much.

cheers, Mathieu

matlabbe avatar Jul 18 '25 02:07 matlabbe

Hi @matlabbe Mathieu,

Thank you so much for the quick response! Your suggested parameters worked exactly as I needed.

As I was testing this, I made an interesting observation that leads to a follow up question. With Grid/3D: 'false', it appears the /rtabmap/cloud_map topic is also projected onto a 2D plane for visualization. I can tell or well I think the original height data is preserved (coloring the point cloud by the Z-axis shows the full height range in color), but all the points are rendered flat on the grid in RViz.

This leads me to wonder: is it possible to have the best of both worlds published as ROS topics?

Specifically, is there a parameter or method to have RTAB-Map generate the sliced 2D /map for navigation, while simultaneously publishing the full, non-projected 3D point cloud map to /rtabmap/cloud_map or perhaps a new topic?

Being able to visualize the full 3D map in RViz alongside the 2D navigation map in real time would be helpful for debugging and getting a better sense of the robot's complete perception during a run.

No problem if this isn't a feature, I just wanted to ask in case I missed a setting.

Thanks again for your incredible work and support for the community!

pepper11com avatar Jul 18 '25 13:07 pepper11com

With 'Grid/3D': 'false', the cloud_map topic will be also 2D. Internally, we remove a dimension to save space when we only need 2D grid. To debug though, I usually add a rtabmap_rviz_plugins/MapCloud plugin to rviz to see the 2D map along the 3D point cloud. For laser scans, check the corresponding box: Image

matlabbe avatar Jul 20 '25 21:07 matlabbe