Closed luoxiaoliaolan closed 7 years ago
TRAJECTORY_BUILDER_3D.scans_per_accumulation = 80
Is this correct? If your laser gives you full revolutions (which is likely if you did not change it), you accumulate full 80 revolutions into one cloud before scan matching. See this FAQ entry for more information.
Also note: on the second picture you can see that the tiny opening angle of the VLP16 is not ideal for full 3D slamming (which you are trying to do): nothing constraints this point cloud is z-direction, i.e. it will likely drift in Z. You will likely require a second sensor to constrain you in the up down direction, but maybe (depending on the features of your environment) it works.
Let me know if you require further assistance.
Today I record a set of data to test 3D slamming with a VLP-16 Laser , and the link is as below: My dataset (Note:My laser frequency is 10Hz) However I can't get ideal matching results, according to your advice. Could you help me to test this data? Thanks a lot.
Please provide a link to a cartographer_ros
fork that contains your configuration files and launch files.
My fork link is: https://github.com/luoxiaoliaolan/cartographer_ros The launch file is: demo_backpack_my_3d.launch
Thanks
I had a look at your data. There are obvious things wrong here:
scans_per_accumulation
should be 1 since you did not subdivide your point cloud. header:
seq: 16987
stamp:
secs: 1488505542
nsecs: 858946084
frame_id: imu_link
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 0.0
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity:
x: 6.30675e-15
y: -1.02985e-14
z: 1.41055e-14
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration:
x: -2.05425e-16
y: 9.4725e-17
z: 8.56125e-15
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
These are quite fundamental issues. Please fix them and read through past closed issues labeled 'tuning'. If you still have issues then, please open a new bug.
Hello, I tried to use a Velodyne VLP-16 laser (I tried to modify cartographer_ros’s configuration file so that I can use a Velodyne VLP-16 laser to collect points) and a IMU to generate indoor 3D pointcloud, then get a precise indoor map with google cartographer. However I always got a set of clutter points and the process of showing cloudpoints on the screen is very slow. The pointcloud are as below:
And I can’t get apparent trajectory map on these grids. My related configuration files: backpack_3d.urdf:
backpack_3d.lua:
My dataset: Bag file