introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.71k stars 775 forks source link

Slam 3D with RoboSense Lidar #524

Open balletg opened 4 years ago

balletg commented 4 years ago

Hi,

Thanks for your open source project I am trying to perform a 3D Slam with a rslidar only on rrtamap_ros but I am stuck. I used your test_velodyne.launch file and tried to adapt it to rslidar but without success. I have the following messages : /rtabmap/point_cloud_assembler: Did not receive data since 5 seconds!/rtabmap/point_cloud_assembler subscribed to (exact sync): /rslidar_points /assembled_cloud /rtabmap/odom/rtabmap/rtabmap subscribed to (approx sync): /rtabmap/odom, /rtabmap Do you have any hint or ideas to help me moving on this project ?

Thanks

matlabbe commented 4 years ago

Hi,

Is /rtabmap/odom published? Are rslidar_points published? If odometry is published, can you try to set /rslidar_points here too. point_cloud_assembler node has been updated recently, just to see if it is that node not working correctly.

cheers, Mathieu

tomlogan501 commented 4 years ago

Hi, I'm working with @balletg but with a simulated robosense. I achieve to do this with rtabmap rtabmap_erl_s

I would like to get a projected map without the floor considered as obstacles What parameters can I play on to optimize this ? Also I plan to integrate it with EKF from the husky for a full simulation, what matrix can I provide with rtabmap/odom ?

Thanks

matlabbe commented 4 years ago

You can feed odometry topic directly to rtabmap node. <remap from="odom" to="/husky/odom_topic"/>

icp_odometry node would not be needed. Enable RGBD/NeighborLinkRefining on rtabmap side to refine wheel odometry with lidar.

On a 3D terrain, set:

<param name="Grid/GroundIsObstacle"  type="string" value="false"/>

If you assume moving on a 2D plane, you can set:

<param name="Reg/Force3DoF"  value="true"/>
<param name="Grid/NormalsSegmentation"  value="false"/>
<param name="Grid/MaxGroundHeight"      value="0.05"/>
<param name="Grid/MaxObstacleHeight"    value="2"/>
tomlogan501 commented 4 years ago

Thanks I try it, but I would like to merge both odom, can I reinject rtabmap's odom into robot_localization to make it more robust ?

tomlogan501 commented 4 years ago

Hi, the parameters work fine in 2D mode. For the ground height, what is the reference frame ? I try negative value to reach the distance from the ground with the sensor and it seems to be that frame. Also is there a parameter to update the obstacles and the map ? I have some artefacts during the mapping process.

Thanks for your time

tomlogan501 commented 4 years ago

Sorry to bother you again, seems I end in a strange behavior with the frames provided to rtabmap

image

Comparing to my test with the sensor alone, the red pointcloud seems to be fixed on odom, the reconstruct map seems to be good as the input odom from the husky. In this state, I can't get a map.BTW both obstacle_cloud and ground_cloud are good.

matlabbe commented 4 years ago

Hi, Grid/MaxGroundHeight is based on the base frame of your robot. If you want to match the ground, you may need a base_footprint frame on your vehicle, as the base frame of the robot.

You can feed the odometry from rtabmap into robot_localization. You should set publish_tf parameter to false on icp_odometry node to avoid conflicts in TF tree.

To update obstacles, do you mean dynamic obstacles? If so, you need to enable Grid/RayTracing. The 2D occpancy grid or the 3D octomap point clouds will be updated.

For your last comment, not sure I understand what the red point cloud represents. Can you show your TF tree? there is maybe a problem with multiple frames with same name published by multiple nodes.

tomlogan501 commented 4 years ago

Hi, Thanks for your help. Here is the TF tree : frames

Hmm, I just notice that the footprint and base are switched from the default husky, does it matter ?

On my previous comment, the red point cloud is the current robosense point clound and the white one the assembled_cloud.

matlabbe commented 4 years ago

The red cloud is based on odometry pose received, while the white one is based on both map and odom poses. Do you have multiple odometry topics published? In the example, did you start icp_odometry and ekf_localization at the same time? These two could give two different odometry frames.

You can also check in RVIZ if you see the same problem. Make sure in the global options of RVIZ that the frame id is map, add point cloud of the lidar and /rtabmap/mapCloud.

tomlogan501 commented 4 years ago

I publish only one odom topic from ekf_localization, icp_odometry is disabled. Should I turn it on and merge with the ekf one ? Normally it will be the next step to improve the odometry.

Also this warning keep appearing constantly

[ WARN] (2020-04-22 14:51:05.212) util3d.cpp:486::cloudFromDepthRGB() Decimation (4) is not valid for current image size (depth=1x2). Highest compatible decimation used=1.
[ WARN] (2020-04-22 14:51:05.212) util3d.cpp:604::cloudFromDepthRGB() Cloud with only NaN values created!
matlabbe commented 4 years ago

This would be a warning from rtabmapviz, you can ignore it or just uncheck the top Map checkbox in Preferences->3D renderings.

Can you record a small rosbag of all topics without rtabmap running?

tomlogan501 commented 4 years ago

Sure, here it is https://we.tl/t-BIHiGRuFPo

tomlogan501 commented 4 years ago

Hi, After helping @balletg with the real robot, we found good parameters and I solved my issue for the simulation. It seems that the problem was the use of the odom directly from the husky_controller and not the one from ekf_localization (odometry/filtered)

rosgraph_husky_tf rosgraph_husky

I got one question remaining : why is required the point_cloud assembler nodelet ? Can't it worked without and use only the live pointcloud ?

For now, I think we can close this issue.

matlabbe commented 4 years ago

You don't need point_cloud_assembler, unless you want to accumulate all the scans in a single one for each map update. In general, we plug directly the live point cloud to rtabmap.

balletg commented 4 years ago

Hi Mat,

Thanks for your help on above subjects. We have another issue when rotating the robot, it seems that it does not take into account the rotation when creating the map (find attached a screenshot of the issue). Could you please point us to the right parameters to modify in order to correct this issue ? Rotate_bug_RTABmap

matlabbe commented 4 years ago

It is either the odometry drifting, TF between base and lidar is not accurate or both. For the first case, it is possible to refine odometry with the lidar by setting RGBD/NeighborLinkRefining to true. Depending of your environment and lidar, you would have also to tune Icp/VoxelSize, Icp/MaxCorrespondenceDistance and Icp/CorrespondenceRatio. For 3D lidars, I also recommend to build rtabmap with libpointmatcher support (so that Icp/PM is available), then use parameters similar to velodyne example or ouster example.