cartographer-project / cartographer_ros

Provides ROS integration for Cartographer.
Apache License 2.0
1.65k stars 1.2k forks source link

Cartographer off alignment map compare to gmapping #628

Closed KnightArthurRen closed 6 years ago

KnightArthurRen commented 6 years ago

I was running cartographer mapping on on this bag and config, I noticed there are some misalignment on the centre-right part of the map, where there are double walls on the bottom wall. imageedit_2_5329513691

Here is the original sceen shot rizve_screem_shot

The same misalignment also happened on the island obstacles right above the misaligned wall, as seen in the rivz screen shot, the circular obstacle become two misaligned half circles.

I believe this caused the generated map to be very poor around those obstacles, I saved the map by subscribing to the last "/map" topic published, and thresholded it by let cells with occupancy value >= 60 to be marked as black(occupied), 0 <= value <= 19 to be marked as white(free) and every other cells as gray(unknown)
cartographer_map

However when I use gmapping on this bag, the result map is very sharp in the island obstacles and there were no misalignment among it. gmapping_map

I would really appreciate any help I can get to improve cartographer's mapping quality or suggestions for the configuration parameters I have attached, thanks!

cschuet commented 6 years ago

Thanks for trying out Cartographer! I looked at your data and passed it through our cartographer_rosbag_validate tool which is a good way to rule out most of the common issues we see in sensor data. The output was a little cluttered since your bag also contained the topics

which seem unrelated to what Cartographer consumes. After filtering these out cartographer_rosbag_validate gave me

I1218 10:09:09.015027 93837 rosbag_validate_main.cc:332] Time delta histogram for consecutive messages on topic "avidbots/base/dead_reckon" (frame_id: "back_wheel_odom"):
Count: 39992  Min: 0.012886  Max: 0.037093  Mean: 0.025002
[0.012886, 0.015307)                            Count: 1 (0.002501%)    Total: 1 (0.002501%)
[0.015307, 0.017727)                            Count: 0 (0.000000%)    Total: 1 (0.002501%)
[0.017727, 0.020148)                            Count: 0 (0.000000%)    Total: 1 (0.002501%)
[0.020148, 0.022569)                            Count: 3 (0.007502%)    Total: 4 (0.010002%)
[0.022569, 0.024989)                  ######    Count: 12663 (31.663834%)       Total: 12667 (31.673834%)
[0.024989, 0.027410)          ##############    Count: 27321 (68.316162%)       Total: 39988 (99.989998%)
[0.027410, 0.029831)                            Count: 3 (0.007502%)    Total: 39991 (99.997498%)
[0.029831, 0.032251)                            Count: 0 (0.000000%)    Total: 39991 (99.997498%)
[0.032251, 0.034672)                            Count: 0 (0.000000%)    Total: 39991 (99.997498%)
[0.034672, 0.037093]                            Count: 1 (0.002501%)    Total: 39992 (100.000000%)
I1218 10:09:09.016189 93837 rosbag_validate_main.cc:332] Time delta histogram for consecutive messages on topic "scan" (frame_id: "laser_front_link"):
Count: 31897  Min: 0.001340  Max: 0.045062  Mean: 0.031343
[0.001340, 0.005712)                            Count: 445 (1.395115%)  Total: 445 (1.395115%)
[0.005712, 0.010085)                      ##    Count: 2892 (9.066684%) Total: 3337 (10.461799%)
[0.010085, 0.014457)                       #    Count: 1390 (4.357777%) Total: 4727 (14.819575%)
[0.014457, 0.018829)                       #    Count: 1215 (3.809136%) Total: 5942 (18.628712%)
[0.018829, 0.023201)                       #    Count: 1772 (5.555381%) Total: 7714 (24.184093%)
[0.023201, 0.027573)                       #    Count: 1856 (5.818729%) Total: 9570 (30.002821%)
[0.027573, 0.031945)                       #    Count: 1633 (5.119604%) Total: 11203 (35.122425%)
[0.031945, 0.036317)                      ##    Count: 2611 (8.185722%) Total: 13814 (43.308147%)
[0.036317, 0.040690)             ###########    Count: 17598 (55.171333%)       Total: 31412 (98.479485%)
[0.040690, 0.045062]                            Count: 485 (1.520519%)  Total: 31897 (100.000000%)

These are reasonable timings and the tool found no other issues so data look ok :)

What struck me when looking at your mapping process in rviz was that local SLAM looked very much ok in the beginning of the recording - essentially on the first leg of your back and forth motion - but after the turn one sees a tremendous downward drift bending the corridor.

What's important to know about Cartographer is that we accumulate scans with their local SLAM poses in submaps and subsequent global SLAM constraint searches are always performed between a scan and a submap. Submaps after having been written are never updated and any local SLAM errors in a submap are not corrected by insights from the global SLAM solution. This has performance reasons. The assumption is that the typical drift acquired over the scans a submap is made of is small.

In your case that assumption is violated and the most straight-forward thing to do is make the size of the submaps smaller:

diff --git a/configuration_files/trajectory_builder_2d.lua b/configuration_files/trajectory_builder_2d.lua
index 7779719..4c8bd34 100644
--- a/configuration_files/trajectory_builder_2d.lua
+++ b/configuration_files/trajectory_builder_2d.lua
@@ -15,7 +15,7 @@
 TRAJECTORY_BUILDER_2D = {
   use_imu_data = true,
   min_range = 0.,
-  max_range = 30.,
+  max_range = 10.,
   min_z = -0.8,
   max_z = 2.,
   missing_data_ray_length = 5.,
@@ -25,13 +25,13 @@ TRAJECTORY_BUILDER_2D = {
   adaptive_voxel_filter = {
     max_length = 0.5,
     min_num_points = 200,
-    max_range = 50.,
+    max_range = 10.,
   },

   loop_closure_adaptive_voxel_filter = {
     max_length = 0.9,
     min_num_points = 100,
-    max_range = 50.,
+    max_range = 10.,
   },

   use_online_correlative_scan_matching = false,
@@ -63,7 +63,7 @@ TRAJECTORY_BUILDER_2D = {

   submaps = {
     resolution = 0.05,
-    num_range_data = 90,
+    num_range_data = 30,
     range_data_inserter = {
       insert_free_space = true,
       hit_probability = 0.55,

You can see that I also limited the trusted range of laser scanner returns as the laser scanner you seem to be using is quite noisy and it seems safe to assume that for anything further away than some 10 meters the scanner readings are too noisy.

This is the map I received with the above parameters:

map

SirVer commented 6 years ago

Agreeing with everything @cschuet said here. One more thing that I find peculiar is the timing jitter of your scan topic: Min: 0.001340 Max: 0.045062 Mean: 0.031343. These values vary over an order of magnitude, if your timing would be good, this should have a way smaller variance. This can be an issue in and of itself too.

KnightArthurRen commented 6 years ago

Thank you so much for the help!

We have a know issue of odometer having error when turning, a part of reason of us chose to use the cartographer is that we hope with it's scan matcher we would be able to correct that error, so I just want to make sure, does the scan matcher run at every laser scan? As to my understanding it should correct the odom's error within it's search space.

The parameter definitely improved the quality of the map, but another issue raised with this change is that we sometimes need to handle large maps as this one, where the 10m range seems not sufficient enough, and the result map would also have a poor quality as seen below cartographer_map

The map generated with my original config actually did better (though it still miss part of island obstacles at the bottom), I believe it's because this have a larger range of 30m original_config

Where the gmapping output is original_map

I'm just wondering if it's a must to have different configs towards different maps' nature, or is there a way to config the cartographer to handle different kind of maps nicely?

And for @SirVer 's question, the scan topic's large variance is because the robot have two lasers, publish "scan_front" and "scan_back", when running, one of the nodes would take both topics and merge them together to publish the scan topic, I tested your idea too by remap the topics and let scan become the direct raw laser data from the front laser, without changing the config (i.e. use the same config as the original post, not cschuet's recommendation), but this seems to worse the mapping as below one_laser_map

And again I really appreciate you guys' help and the work on cartographer. The global optimization amaze me every time :1st_place_medal:

KnightArthurRen commented 6 years ago

Sorry I noticed the link of bag file above is not working, here is the new link

cschuet commented 6 years ago

I'm just wondering if it's a must to have different configs towards different maps' nature, or is there a way to config the cartographer to handle different kind of maps nicely?

You can certainly achieve the best possible mapping result by tuning Cartographer to every specific environment - robot combination individually, but I think this is just not practical. We made the experience that tuning Cartographer to a specific robot and sensor combination gives good result in a wide range of environments. I would aim for that.

As far as the max_range setting is concerned: I chose 10 meters by rule of thumb based on the example you gave me, but I am certain you can raise it to 20 or higher and get a good result out of both environment 1 and 2.

In general you have a better idea of the distribution of your environments than me, so just experiment a bit till you get something that works for you.