cartographer-project / cartographer

Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) in 2D and 3D across multiple platforms and sensor configurations.
Apache License 2.0
7.08k stars 2.24k forks source link

Wrong point cloud origin when accumulating data of different sensors #947

Open fabln opened 6 years ago

fabln commented 6 years ago

Hi, I'm going to map with four LIDARs which have some position separation. The occupancy grid (see screenshot) then gets some free-space lines drawn between e.g. sensor 1 (the upper right) and the orange data points measured by sensor 4 (the sensor most left). I think this shouldn't be the case, i.e. only free-space lines between each sensor and its own measured point cloud.

This is observed with setting TRAJECTORY_BUILDER_2D.num_accumulated_range_data >=1. With TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1, the behavior is correct, however scan matching quality is lowered then. I tested only the 2D version. multi-lidar-map

gaschler commented 6 years ago

I believe your urdf config is incorrect. After you fixed the urdf config, you should accumulate as many range data sets as you have sensors (or even multiple thereof if the packets to do contain a full scanner revolution.)

fabln commented 6 years ago

Well, the sensor positions are fairly OK as set in the urdf (I did not yet calibrate the sensor positions. It seems that point clouds of multiple measurements are accumulated together and then joined with the map assuming that all data are originating from the same origin which is not the case.

gaschler commented 6 years ago

No, cartographer_ros queries tf and transforms the data to the tracking frame.

For more help, please give more details on your config following the issue template https://raw.githubusercontent.com/googlecartographer/cartographer_ros/master/.github/ISSUE_TEMPLATE

fabln commented 6 years ago

I cloned the master branch on 2018-02-28 and executed with the default values of your backpack 2D demo. Running the cartographer_rosbag_validate returned only timing issues not important so far.

With the 4 LIDARs (in this case, onboard a car just standing in the garage), I would expect a map like this (couldn't tune to get this, so I photoshopped): multi-lidar-map-expect

gaschler commented 6 years ago

Cartographer makes the occupancy grid insertions by rays from the return point to the single tracking frame origin. (In 3D, the insertion ray starts at the return point and is very short.) So, what you are describing I would call a feature request to insert rays to their respective sensor positions. Sounds interesting for vehicles with multiple sensors at either side that go through smaller passages.

fabln commented 6 years ago

Yes, that's what I mean.

cschuet commented 6 years ago

If it is true that Cartographer makes the occupancy grid insertions by rays from the return point to the single tracking frame origin rather than to their respective ray origins, should we not classify this as a bug?

gaschler commented 6 years ago

Just some context, the LocalTrajectoryBuilder::AddAccumulatedRangeData and the RangeDataInserters accept only one origin. (So this is not a regression, but rather a well-justified feature request.)

maxschnettler commented 5 years ago

Is this issue as well as #1242 already fixed with the referenced merge #1357 ? We are experiencing the same problem of the wrong origin of laser rays with version 1.0.0 and think about upgrading Cartographer to a newer version

wkwkw commented 5 years ago

I think the answer is no. We are also experiencing the same problem as #1242 and just tested the latest cartographer/cartographer_ros yesterday to find the problem being still alive.

FabianSchurig commented 5 years ago

I also tested the current master version of Cartographer. The problem still persists. It seems not solved yet.

I am convinced, that this is a critical bug. It can be easily tested if you use range sensors mounted somewhat far from the tracking_frame, which have no overlapping field of view to this frame.

The following image is a good example. The laser is mounted in front of the robot's coordinate frame (base). The highlighted triangle is a dead spot. Cartographer says the area is free, although we don't know if that is true. raycasting_origin_bug

This bug is not only related to accumulating multiple sensors, but can be also reconstructed with one single laser scanner.

jonbinney commented 4 years ago

This does seem to be a very severe bug - any robot which has either of

will have freespace calculated incorrectly by cartographer. I think this might take a fair bit of work to fix, however, because you can no longer take the approach of "convert all data to the tracking frame and then deal with it". Instead, each scan will need to keep some information about its origin.