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

Cartographer ROS Scan-lag issue in PointCloud with clockwise Lidar

asked 2020-10-21 09:29:07 -0600

updated 2020-10-30 09:18:04 -0600

On my TurtleBot3 the Lidar takes ~ 0.2 seconds to spin its 360 degree arc, clockwise. So, as the robot moves at say, 0.2 m/s, the first scan is taken some 0.04 metres (i.e. 4 cm) behind the last scan, and will therefore measure 4 cm longer against the same obstacle (e.g. a wall).

e.g. in RVIZ with SLAM Cartographer ROS I see: @ RVIZ screen-capture

In ROS the system standard has positive angles measured anti-clockwise, so the TurtleBot3 Lidar scan takes angle 359 first, and 0 degrees last, all reported in one array time stamped at the "start" position defined to be 0 degrees.

The laser_geometry package routine in ROS for correcting this scan-lag called "transformLaserScanToPointCloud" assumes an anti-clockwise spinning Lidar, ending its correction of 359 degrees assuming it was taken at the time stamp plus the Lidar's spin time (header.stamp + scan_time). The good news, is that this seems to work ok if you change the time_increment to add negative, so that transformLaserScanToPointCloud corrects 359 degrees to be at (header.stamp - scan_time).

With this modification, we remove the scan-lag in the pointcloud: @ RVIZ screen-capture

So the question is: can Cartographer ROS be fixed too ? Does it assume a CW or CCW lidar ? ... because for me this does not currently work.

Looking at the cartographer_ros code in Node::HandleLaserScanMessage, I could not follow exactly how it was addressed, or how to fix it (e.g. to feed a clockwise timing parameter into carto::sensor::TimedPointCloudData ?).

Thanks

Michael Hallett

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-10-30 09:29:57 -0600

updated 2020-10-30 09:33:02 -0600

I found a work-around to solve this:

Cartographer ROS lets you change the .lua file in ~slam/config to:

num_laser_scans = 0, { instead of = 1, } num_point_clouds = 1, { instead of = 0, }

So this works if you correct the laser scan scan-lag, converting it to a PointCloud2 (e.g with "transformLaserScanToPointCloud"), and publishing this in a topic called "/points2" for SLAM Cartographer ROS to subscribe to.

I do not now have a "kink" in my "walls" when I approach them, and more importantly the whole map is much more stable with the Turtlebot3 spinning or turning.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-10-21 09:29:07 -0600

Seen: 464 times

Last updated: Oct 30 '20