cartographer-project / cartographer_ros

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

Frame rate of the bagfile #257

Closed jvlevia closed 7 years ago

jvlevia commented 7 years ago

We have found out that the frame rate of the example bag file has reached 1500Hz, which is quite impossible for the Velodyne Lidar that is used in the example bag file to have this kind of frame rate, as the maximum frame rate that can be reached is 20Hz, based on the datasheet. Why will the frame rate be so high ?

wohe commented 7 years ago

The VLP-16 in the example bags is configured to rotate at 20 Hz. This has no influence though on the frequency of UDP packets the VLP-16 sends which is probably the 15 kHz you have seen. The example bags contain a sensor_msgs/PointCloud2 per UDP packet, not one per revolution. If you look at the backpack_3d.lua you see

TRAJECTORY_BUILDER_3D.scans_per_accumulation = 160

which means we accumulate 160 of these to a point cloud for matching. Since there are two VLP-16s this number is data from slightly more than one revolution. Doing this during SLAM allows for unwarping the point cloud based on rotation velocities from the IMU and a constant velocity model. If you have more questions, just let me know.

SirVer commented 7 years ago

The reason is that we converted each UDP packet that the velodyne sent into a tiny PointCloud2 and sent that to Cartographer.

Generally people like to wait for a full revolution before constructing a point cloud, but that is generally a bad idea: Your platform moves during the time you require to accumulate the point cloud, and you would like to give your SLAM a chance of figuring out this movement. Otoh, you also require enough points to constrain your scan in all directions, so your estimate does not slide. Cartographer expresses the number of those tiny things that should be waited for before a scan match is attempted as the option scans_per_accumulation.

Edit: replied at the same time as @wohe, my answer essentially contains the same information.

mdemirst commented 7 years ago

Each UDP packet comes with timestamp. Do you process each scan in accumulation with respective timestamps or calculate only one average timestamp for each accumulation? If the latter is the case, this would have the same effect as having one packet per revolution, right? (I assume when scans_per_accumulation = 160 , it is equal to one full 360 degree scan)

SirVer commented 7 years ago

Inside the SLAM, timestamps do not matter anymore. Timestamped returns of lasers are input data, but the SLAM is only concerned with (x, y, z) tuples, i.e. returns in space that are consistent with respect to each other. Cartographer uses its current information about the movement (constant velocity model) to place each individual UDP packet's points into a common frame. Once there are scans_per_accumulation packets accumulated, this is considered one scan that is matched against the already existing submap data.

If the latter is the case, this would have the same effect as having one packet per revolution, right?

The difference is using a zero-velocity model or a constant velocity model interpolation.

I assume when scans_per_accumulation = 160 , it is equal to one full 360 degree scan

Not quite. Since we have two lasers and they send their data simultaneously and we accumulate it into the same point cloud, this actually represents roughly 2 full revolutions, one from each laser.

mdemirst commented 7 years ago

Thank you. I agree, in SLAM, timestamps do not mean anything. But the local origin for points from each packet in accumulation is not same but determined based on constant velocity model.

SirVer commented 7 years ago

Precisely.