ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Hi lealem,

At first view the optimized trajectory after loop closure looks good: image description

For the 3D map, there are indeed some problems with the 3D projection. I noticed that the scale of some point clouds are not the same, which would be caused by a poor synchronization between the left and right frames, in particular when the robot is rotating. Here two examples of frames taken before and after rotating at the same place: image description image description

In first screenshot the far wall is about ~10/11 meters from the robot, as in the second screenshot the far wall is about ~5-6 meters from the robot. When rotating, as left and right frames are not synchronized, the disparity changes, making objects appearing more closer. With stereo, it is strongly recommend to use exactly synchronized cameras (e.g., hardware synchronization between left and right cameras), then with rtabmap use approx_sync parameter set to false.

PS: To get the 2D grid map as above, I used parameters: Grid/MaxObstacleHeight=2, Grid/NoiseFilteringRadius=0.15, Grid/NoiseFilteringMinNeighbors=10, Grid/NormalsSegmentation=false, Grid/3D=false and Grid/ProjRayTracing=true.

cheers, Mathieu

Hi lealem,

At first view the optimized trajectory after loop closure looks good: image description

For the 3D map, there are indeed some problems with the 3D projection. I noticed that the scale of some point clouds are not the same, which would be caused by a poor synchronization between the left and right frames, in particular when the robot is rotating. Here two examples of frames taken before and after rotating at the same place: image description image description

In first screenshot the far wall is about ~10/11 meters from the robot, as in the second screenshot the far wall is about ~5-6 meters from the robot. When rotating, as left and right frames are not synchronized, the disparity changes, making objects appearing more closer. With stereo, it is strongly recommend to use exactly synchronized cameras (e.g., hardware synchronization between left and right cameras), then with rtabmap use approx_sync parameter set to false.

PS: To get the 2D grid map as above, I used parameters: Grid/MaxObstacleHeight=2, Grid/NoiseFilteringRadius=0.15, Grid/NoiseFilteringMinNeighbors=10, Grid/NormalsSegmentation=false, Grid/3D=false and Grid/ProjRayTracing=true.

EDIT: just noticed that you were using approx_sync because of wheel odometry. To use approx_sync=false with wheel odometry, set odom_frame_id so that rtabmap uses TF to get odometry instead of the topic (for which approx_sync should be true).

cheers, Mathieu