cartographer-project / cartographer_turtlebot

Provides TurtleBot integration for Cartographer.
Apache License 2.0
151 stars 96 forks source link

demo_lidar_2d.launch cartographer_turtlebot_demo.bag shows double walls #83

Open gaschler opened 6 years ago

gaschler commented 6 years ago

The quality of demo_lidar_2d.launch on cartographer_turtlebot_demo.bag is not as expected, it shows double walls and the local trajectory is shaky.

Here is a screenshot. roslaunch cartographer_turtlebot demo_lidar_2d.launch bag_filename:=${HOME}/Downloads/cartographer_turtlebot_demo.bag rviz_screenshot_2018_01_03-17_29_40

When I set use_odometry = false, it becomes better. rviz_screenshot_2018_01_03-17_27_54

Is this perhaps a regression?

Of course, the bag file is not perfect. Here is report of

./devel_isolated/cartographer_ros/lib/cartographer_ros/cartographer_rosbag_validate -bag_filename=${HOME}/Downloads/cartographer_turtlebot_demo.bag

W0103 17:34:32.322019 241911 rosbag_validate_main.cc:103] frame_id gyro_link time 1474964028432292844: IMU linear acceleration is 0 m/s^2, expected is [3, 30] m/s^2. (It should include gravity and be given in m/s^2.) linear_acceleration 0 0 0 W0103 17:34:32.322496 241911 rosbag_validate_main.cc:103] frame_id gyro_link time 1474964028442292844: IMU linear acceleration is 0 m/s^2, expected is [3, 30] m/s^2. (It should include gravity and be given in m/s^2.) linear_acceleration 0 0 0 W0103 17:34:32.322543 241911 rosbag_validate_main.cc:103] frame_id gyro_link time 1474964028452238751: IMU linear acceleration is 0 m/s^2, expected is [3, 30] m/s^2. (It should include gravity and be given in m/s^2.) linear_acceleration 0 0 0 E0103 17:34:32.322903 241911 rosbag_validate_main.cc:251] Sensor with frame_id "gyro_link" jumps backwards in time. Make sure that the bag contains the data for each frame_id sorted by header.stamp, i.e. the order in which they were acquired from the sensor. E0103 17:34:32.328048 241911 rosbag_validate_main.cc:251] Sensor with frame_id "gyro_link" jumps backwards in time. Make sure that the bag contains the data for each frame_id sorted by header.stamp, i.e. the order in which they were acquired from the sensor. E0103 17:34:32.334275 241911 rosbag_validate_main.cc:251] Sensor with frame_id "gyro_link" jumps backwards in time. Make sure that the bag contains the data for each frame_id sorted by header.stamp, i.e. the order in which they were acquired from the sensor. E0103 17:34:33.523506 241911 rosbag_validate_main.cc:299] Average IMU linear acceleration is 0 m/s^2, expected is [9.5, 10.5] m/s^2. Linear acceleration data should include gravity and be given in m/s^2. I0103 17:34:33.524302 241911 rosbag_validate_main.cc:332] Time delta histogram for consecutive messages on topic "/mobile_base/sensors/imu_data_raw" (frame_id: "gyro_link"): Count: 34785 Min: -0.000888 Max: 0.014964 Mean: 0.009397 [-0.000888, 0.000697) Count: 532 (1.529395%) Total: 532 (1.529395%) [0.000697, 0.002283) # Count: 1565 (4.499066%) Total: 2097 (6.028461%) [0.002283, 0.003868) Count: 1 (0.002875%) Total: 2098 (6.031335%) [0.003868, 0.005453) Count: 0 (0.000000%) Total: 2098 (6.031335%) [0.005453, 0.007038) Count: 4 (0.011499%) Total: 2102 (6.042835%) [0.007038, 0.008623) Count: 40 (0.114992%) Total: 2142 (6.157826%) [0.008623, 0.010208) ################### Count: 32200 (92.568634%) Total: 34342 (98.726463%) [0.010208, 0.011794) Count: 433 (1.244789%) Total: 34775 (99.971252%) [0.011794, 0.013379) Count: 8 (0.022998%) Total: 34783 (99.994247%) [0.013379, 0.014964] Count: 2 (0.005750%) Total: 34785 (100.000000%) I0103 17:34:33.524739 241911 rosbag_validate_main.cc:332] Time delta histogram for consecutive messages on topic "/odom" (frame_id: "odom"): Count: 16343 Min: 0.016671 Max: 0.024952 Mean: 0.020001 [0.016671, 0.017499) Count: 7 (0.042832%) Total: 7 (0.042832%) [0.017499, 0.018327) Count: 8 (0.048951%) Total: 15 (0.091782%) [0.018327, 0.019155) ## Count: 1509 (9.233311%) Total: 1524 (9.325093%) [0.019155, 0.019984) ######## Count: 6162 (37.704216%) Total: 7686 (47.029308%) [0.019984, 0.020812) ######## Count: 6882 (42.109772%) Total: 14568 (89.139084%) [0.020812, 0.021640) ## Count: 1760 (10.769136%) Total: 16328 (99.908218%) [0.021640, 0.022468) Count: 9 (0.055069%) Total: 16337 (99.963287%) [0.022468, 0.023296) Count: 3 (0.018356%) Total: 16340 (99.981644%) [0.023296, 0.024124) Count: 2 (0.012238%) Total: 16342 (99.993881%) [0.024124, 0.024952] Count: 1 (0.006119%) Total: 16343 (100.000000%) E0103 17:34:33.524762 241911 rosbag_validate_main.cc:316] Point data (frame_id: "plate_top_link") has a large gap, largest is 0.103044 s, recommended is [0.0005, 0.05] s with no jitter. I0103 17:34:33.524869 241911 rosbag_validate_main.cc:332] Time delta histogram for consecutive messages on topic "/laser_scan" (frame_id: "plate_top_link"): Count: 3289 Min: 0.095438 Max: 0.103044 Mean: 0.099367 [0.095438, 0.096199) Count: 1 (0.030404%) Total: 1 (0.030404%) [0.096199, 0.096960) Count: 2 (0.060809%) Total: 3 (0.091213%) [0.096960, 0.097720) Count: 1 (0.030404%) Total: 4 (0.121618%) [0.097720, 0.098481) Count: 8 (0.243235%) Total: 12 (0.364853%) [0.098481, 0.099241) ##### Count: 891 (27.090302%) Total: 903 (27.455154%) [0.099241, 0.100002) ############## Count: 2357 (71.663116%) Total: 3260 (99.118271%) [0.100002, 0.100763) Count: 25 (0.760109%) Total: 3285 (99.878380%) [0.100763, 0.101523) Count: 0 (0.000000%) Total: 3285 (99.878380%) [0.101523, 0.102284) Count: 2 (0.060809%) Total: 3287 (99.939194%) [0.102284, 0.103044] Count: 2 (0.060809%) Total: 3289 (100.000000%)

gaschler commented 6 years ago

@SirVer Do you have an idea if this got worse (is a regression)? Or am I using the wrong launch file for this bag?

SirVer commented 6 years ago

I think this regressed a bit. 3D depth camera data has always been finicky though.

SubMishMar commented 6 years ago

@SirVer, In case I do not want to use odometry and imu data, how should I set map_frame = "map", tracking_frame = "gyro_frame", published_frame = "odom", odom_frame = "odom", in order to get consistent results. Right now, I have set the flags for using odometry and imu to false and with the above frame values my result looks completely wrong. From what it seems I need to fix these frames properly but I dont exactly understand how, even after reading your documentation. Can you please throw some light on this?