gisbi-kim / removert

Remove then revert (IROS 2020)
544 stars 108 forks source link

Parameters for not-fixed vertical resolution LiDARs #4

Closed Tomoya-Sato closed 3 years ago

Tomoya-Sato commented 3 years ago

Hi. Thank you for your amazing repository.

I'm trying this repository with VLP32C. I read the explanation about remove_resolution_list in config file and some previous issues, and it seems that this parameter assumes that LiDAR has fixed vertical resolution. However, VLP32C and some other LiDARs don't have fixed vertical resolution. Could you tell me how should I set parameters for those LiDARs? Can I do as same as fixed resolution LiDARs?

gisbi-kim commented 3 years ago

Hi, thank you for having an interest in our work.

I haven't tried such kinds of lidars but I think the resolution is "just" a guideline so you can try as a fixed value. The recommended resolution is just for avoiding too coarse or too fine pixel cases (because in those cases, map-to-scan discrepancy wrongly estimated or cannot be calculated), so using a precise fixed value is not that strictly required.

Currently, I have no plan to modify the code to use an adaptive resolution with respect to its vertical location.

Instead, I found the vertical fov distribution of the VLP32C lidar here https://perceptionengine.jp/blog/autoware/lidar-laser-distributions/

I see the VLP32C lidar has a few rays, at the top and the bottom, that are particularly far apart compared to other rays.

so, in my opinion, you can drop those 4 rays and assume the pixel size following like this way:

스크린샷 2020-12-09 오전 11 04 05

this is just my own opinion, and you need to empirically check it. I'll be happy if you report some experimental reports for those kinds of lidar. 😃

Tomoya-Sato commented 3 years ago

Thank you for your polite response, Giseop! I will try your suggestion and report result.

gisbi-kim commented 3 years ago

Thank you. I close the issue.

Tomoya-Sato commented 3 years ago

Hi. This is a short report about the VLP32C.

I tried two types of parameters.

  1. Use only 28 lasers except upper and lower 2 lasers each. This is what you've suggested. Vertical fov is -11.31 to 7 degree. I set vfov = 22 and remove_resolution_list = [2.5, 2.0, 1.5]
  2. Use all lasers. Vertical fov is -25 to 15 degree,. I set vfov = 50 and remove_resolution_list = [1.25, 1.0]

In both type, clean_for_all_scan is set as true. Other parameters are default, and pointcloud and pose data are same.

And the following pictures are results of two. Parameter 1 Parameter 1 Parameter 2 Parameter 2

The passing area is removed especially in Parameter 1. Do you have any idea about it?

gisbi-kim commented 3 years ago

Cool! thanks for reporting the experimental results! you are making this tool’s fruitful. I’ve never seen the VLP32C result so I’m excited and felt interested even I couldn’t catch the reasons exactly. (BTW, I'm also curious about if some real dynamic points were correctly removed in both cases (in both figures). )

in my opinion,

  1. in your experiment, did a human follow a robot behind during the whole trajectory? so the removed region in the first figure might be corresponding to the obstacles trajectory (i.e., the human)
  2. the lidar VLP32C has a very narrow vertical fov without the most up and bottom rays, so hard to touch the ground points maybe…?
Tomoya-Sato commented 3 years ago

At first, most of dynamic points were correctly removed as following pictures. Before before After after

In our experiment, data is acquired by backpack-logger system like the following picture, so a human was not projected. In the picture, two LiDARs are equipped, but only one LiDAR on the top is used for this experiment. seams1

gisbi-kim commented 3 years ago

Thank you! Then, I think it could be the removert's limitation and I need to keep going 😅

Thank you again.

narutojxl commented 3 years ago

I'm not sure whether i am correct. It seems that current code is only suit for vertical angle distributed evenly and the positive elevation angle and the negative elevation angle each account for half of the vertical FOV. For VLP32C, the code maybe need to change. https://github.com/irapkaist/removert/blob/828753fed2aeb714b1af513eb06fd353cd4e0b5d/src/Removerter.cpp#L253-L254

BTW, the three params in yaml file seems not be used anymore in current code.

  clean_for_all_scan: false # default is false
  batch_size: 150
  valid_ratio_to_save: 0.75 # i.e., no save cleaned scans located at the boundaries of a batch 
gisbi-kim commented 3 years ago

Thank you for finding the part to be adjusted by considering the lidar's characteristics.

Currently, I initialize a range image with some very big value, aka kFlagNoPOINT (which is >> kValidDiffUpperBound) https://github.com/irapkaist/removert/blob/828753fed2aeb714b1af513eb06fd353cd4e0b5d/src/Removerter.cpp#L237

and if a pixel's discrepancy value of a diff range image is larger than the kValidDiffUpperBound, the pixel does not be used for map update (for convenience, I think I could say this kind of pixels, "null pixels"?!) see https://github.com/irapkaist/removert/blob/828753fed2aeb714b1af513eb06fd353cd4e0b5d/src/Removerter.cpp#L509

so the naively covering enough vertical fov range, which has the same upper and lower range, could not be problematic. because the "points in the null pixels" practically does not contribute to the removals.

however, as you mentioned part, the current naive std::min and std::max-based clipping could not be always right if the scan's query point actually exists in the upper side of the user parameter vfov's upper bound. In that case, you can change that part, for example, if sph_point.el > kVFOV/float(2.0), then ignore this point and continue the for loop.

Thank you for discussing the general applicability of the project.

boazMgm commented 2 years ago

Hi @Tomoya-Sato, I'm using the same Velodyne Lidar (VLP32C). Is it possible to get your params_kitti.yaml configuration file? Thanks