Utility Parameters for KITTI dataset testing ?
saimanoj18 opened this issue · 7 comments
Hi,
Could you please provide the utility parameters to run LeGO-LOAM on KITTI dataset ?
When you implement new sensor, make sure that the ground_cloud has enough points for matching.
extern const int N_SCAN = 16;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 15.0;
extern const int groundScanInd = 7;
- What should the new parameters be ?
Here is a bag file that I am attaching.
https://transfer.pcloud.com/download.html?code=5Z61Ss7ZPV6UN87wU4kZAH3bZiIe8l4Y3IBJMUAHk9TSTmyAyT4Ek
-
Could you tell me what other changes you made such as the topic name needs to be changed and so on.
-
Any new static transform publishers need to be added ?
Thank you very much!
Hi @saimanoj18 ,
-
The parameters should be:
extern const int N_SCAN = 64;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 0.427;
extern const float ang_bottom = 24.9;
extern const int groundScanInd = 50; -
LeGO-LOAM is designed for raw point cloud from Velodyne. Like the original LOAM, it assumes there is point cloud distortion that is caused by the sensor motion. The point cloud in KITTI datasets is distortion-free. So the projection of these clouds on the range image is not accurate when using LeGO-LOAM - as many points may not be projected. In order to use LeGO-LOAM with KITTI datasets, you need to delete all the code that corrects point cloud distortion. Delete line 1752 and 1758 in
featureAssociation.cpp
. Line 849 change to 's=1'. Even with these changes, I think the ideal algorithm to test with KITTI dataset is still LOAM. -
No new transform needs to be added.
@TixiaoShan
Thanks for your reply. That works.
Could you please explain what you meant by "The point cloud in KITTI datasets is distortion-free"
Do you mean they do some kind of motion compensation or corrections in velodyne data to get rid of distortions ?
@saimanoj18
Yes, you can find their statements in the readme.txt.
@TixiaoShan
Thanks for your reply. That works.Could you please explain what you meant by "The point cloud in KITTI datasets is distortion-free"
Do you mean they do some kind of motion compensation or corrections in velodyne data to get rid of distortions ?
Do you succeed running lego-loam in kitti dataset ? what modifications do you make?
@saimanoj18
Yes, you can find their statements in the readme.txt.
true, but they also say that
IMPORTANT NOTE: Note that the velodyne scanner takes depth measurements
continuously while rotating around its vertical axis (in contrast to the cameras,
which are triggered at a certain point in time). This effect has been
eliminated from this postprocessed data by compensating for the egomotion!!
---- Note that this is in contrast to the raw data. ----
and there is also a mapping with respect to the raw data
Nr. Sequence name Start End
00: 2011_10_03_drive_0027 000000 004540
01: 2011_10_03_drive_0042 000000 001100
02: 2011_10_03_drive_0034 000000 004660
03: 2011_09_26_drive_0067 000000 000800
04: 2011_09_30_drive_0016 000000 000270
05: 2011_09_30_drive_0018 000000 002760
06: 2011_09_30_drive_0020 000000 001100
07: 2011_09_30_drive_0027 000000 001100
08: 2011_09_30_drive_0028 001100 005170
09: 2011_09_30_drive_0033 000000 001590
10: 2011_09_30_drive_0034 000000 001200
I have changed the parameters as mentioned above. The procedure is able to run but abnormally. Rviz displays nothing. I use the rosbag generated by bin files and the topic name is correct. Can anyone provide some clues?
@trigal hello,the 03: 2011_09_26_drive_0067 can't be found in official website. Do you have this dataset? Or,do you know why it can't be found? my Email 2661076951@qq.com