RobustFieldAutonomyLab / LeGO-LOAM

LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain
BSD 3-Clause "New" or "Revised" License
2.32k stars 1.11k forks source link

Higher density map #179

Closed MaxandreOgeret closed 3 years ago

MaxandreOgeret commented 4 years ago

Hello, and thanks for this amazing project.

Do you know what should I edit to make the generated map more dense ?

Thanks !

robot54 commented 4 years ago

Hello,

By reducing the values of "downSizeFilterGlobalMapKeyPoses.setLeafSize()" and "downSizeFilterGlobalMapKeyFrames.setLeafSize()" in "mapOptimization.cpp", I have been able to produce a denser map.

Have a nice day.

Pallav1299 commented 4 years ago

By reducing the values of "downSizeFilterGlobalMapKeyPoses.setLeafSize()" and "downSizeFilterGlobalMapKeyFrames.setLeafSize()" in "mapOptimization.cpp", I have been able to produce a denser map.

@robot54 I removed the downsizing functions, since the raw output PCD did't had enough density. Even after doing so, the output PCD density is still very low. I want to use the output for annotation.

I compared the results to NDT where, the output PCD is highly dense.

Given the same data, NDT gives 5603371 points while LeGo-LOAM gives around 110978 points, both without any downsampling.

Can I get such highly dense pointclouds from LeGO-LOAM? Is it wrong to expect such highly dense pointclouds from LeGO-LOAM?

@TixiaoShan We could use some help here. Thanks in advance.

getupgetup commented 4 years ago

By reducing the values of "downSizeFilterGlobalMapKeyPoses.setLeafSize()" and "downSizeFilterGlobalMapKeyFrames.setLeafSize()" in "mapOptimization.cpp", I have been able to produce a denser map.

@robot54 I removed the downsizing functions, since the raw output PCD did't had enough density. Even after doing so, the output PCD density is still very low. I want to use the output for annotation.

I compared the results to NDT where, the output PCD is highly dense.

Given the same data, NDT gives 5603371 points while LeGo-LOAM gives around 110978 points, both without any downsampling.

Can I get such highly dense pointclouds from LeGO-LOAM? Is it wrong to expect such highly dense pointclouds from LeGO-LOAM?

@TixiaoShan We could use some help here. Thanks in advance.

I think high dense pointcloud is bad for real-time display. If you want to get the whole dense pointcloud offline, you can record segment and ground points in each frame manually and then add them up according to their final poses.

Pallav1299 commented 4 years ago

I think high dense pointcloud is bad for real-time display. If you want to get the whole dense pointcloud offline, you can record segment and ground points in each frame manually and then add them up according to their final poses.

@getupgetup Doesn't that mean that I would also need to perform graph optimization and loop closure again?

getupgetup commented 4 years ago

I think high dense pointcloud is bad for real-time display. If you want to get the whole dense pointcloud offline, you can record segment and ground points in each frame manually and then add them up according to their final poses.

@getupgetup Doesn't that mean that I would also need to perform graph optimization and loop closure again?

I don't quite understand what you mean. Graph optimization and loop closure are performed automaticly in lego-loam. You can record segment and ground points in each frame using local frame coordinate. After mapping is all finished, just transform these points to global coordinate by pose of each frame and then add them up to get the whole dense map.

Pallav1299 commented 4 years ago

I don't quite understand what you mean. Graph optimization and loop closure are performed automaticly in lego-loam. You can record segment and ground points in each frame using local frame coordinate. After mapping is all finished, just transform these points to global coordinate by pose of each frame and then add them up to get the whole dense map.

I've already tried the same. Correct me if I am wrong here. Inspite of using the ground and segmented clouds, I used the raw input cloud and stitched each raw_cloud in local frame to global map by using the integrated_to_init transform from transformFusion node's output. I got the dense pointcloud. My question is, what if now there is a loop in the trajectory? What if I already have the map for a location w.r.t. global frame. Won't this create an overlapping PCD?

getupgetup commented 4 years ago

I don't quite understand what you mean. Graph optimization and loop closure are performed automaticly in lego-loam. You can record segment and ground points in each frame using local frame coordinate. After mapping is all finished, just transform these points to global coordinate by pose of each frame and then add them up to get the whole dense map.

I've already tried the same. Correct me if I am wrong here. Inspite of using the ground and segmented clouds, I used the raw input cloud and stitched each raw_cloud in local frame to global map by using the integrated_to_init transform from transformFusion node's output. I got the dense pointcloud. My question is, what if now there is a loop in the trajectory? What if I already have the map for a location w.r.t. global frame. Won't this create an overlapping PCD?

I don't think it is a good idea to merge each frame by using online poses. Online poses have accumulated errors and can cause inconsistant map when there's a loop(just like what you said). A better way is to use offline poses which are optimized after all loops closed. Accumulated error are removed after loop closure so that you can get the consistant map.

Pallav1299 commented 4 years ago

I don't think it is a good idea to merge each frame by using online poses. Online poses have accumulated errors and can cause inconsistant map when there's a loop(just like what you said). A better way is to use offline poses which are optimized after all loops closed. Accumulated error are removed after loop closure so that you can get the consistant map.

Can you please elaborate the approach. Does it mean, first saving the output pose from "integrated_to_init" topic. Then continue with another iteration of loop closure detection, map_optimization and pointcloud stitching. Please, correct me if I am wrong.

getupgetup commented 4 years ago

I don't think it is a good idea to merge each frame by using online poses. Online poses have accumulated errors and can cause inconsistant map when there's a loop(just like what you said). A better way is to use offline poses which are optimized after all loops closed. Accumulated error are removed after loop closure so that you can get the consistant map.

Can you please elaborate the approach. Does it mean, first saving the output pose from "integrated_to_init" topic. Then continue with another iteration of loop closure detection, map_optimization and pointcloud stitching. Please, correct me if I am wrong.

Sorry for my unclear expression. "integrated_to_init" topic is a online pose which updates realtimely, so it's not what you need. Nevertheless, cloudKeyPoses6D(in mapOtimization node) stores all key poses and it'll be optimized after loop closure. Here's my approach: 1.Once a key pose is input into cloudKeyPoses6D, record the pointcloud of this frame (using local coordinate). 2. After the program is finished(This is important, because all poses in cloudKeyPoses6D have been optimized after loop closure), use poses in cloudKeyPoses6D to transform pointcloud recorded to global coordinate. Pseudocode is something like: pcl::pointcloud global_map; for(int i = 0; i < cloudKeyPoses6D.size(); i++) { auto pointcloud_in_global_coordinate = transformPointCloud(pointcloud_you_recorded[i], cloudKeyPoses6D[i]); global_map += pointcloud_in_global_coordinate; }

Pallav1299 commented 4 years ago

Here's my approach: 1.Once a key pose is input into cloudKeyPoses6D, record the pointcloud of this frame (using local coordinate). 2. After the program is finished(This is important, because all poses in cloudKeyPoses6D have been optimized after loop closure), use poses in cloudKeyPoses6D to transform pointcloud recorded to global coordinate. Pseudocode is something like: pcl::pointcloudpcl::PointXYZ global_map; for(int i = 0; i < cloudKeyPoses6D.size(); i++) { auto pointcloud_in_global_coordinate = transformPointCloud(pointcloud_you_recorded[i], cloudKeyPoses6D[i]); global_map += pointcloud_in_global_coordinate; }

Thanks @getupgetup . Just to add to this. I think there should also be a timestamp check between the optimized poses and the raw_cloud messages.

stale[bot] commented 4 years ago

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

cbaus commented 2 years ago

I don't think it is a good idea to merge each frame by using online poses. Online poses have accumulated errors and can cause inconsistant map when there's a loop(just like what you said). A better way is to use offline poses which are optimized after all loops closed. Accumulated error are removed after loop closure so that you can get the consistant map.

Can you please elaborate the approach. Does it mean, first saving the output pose from "integrated_to_init" topic. Then continue with another iteration of loop closure detection, map_optimization and pointcloud stitching. Please, correct me if I am wrong.

Sorry for my unclear expression. "integrated_to_init" topic is a online pose which updates realtimely, so it's not what you need. Nevertheless, cloudKeyPoses6D(in mapOtimization node) stores all key poses and it'll be optimized after loop closure. Here's my approach: 1.Once a key pose is input into cloudKeyPoses6D, record the pointcloud of this frame (using local coordinate). 2. After the program is finished(This is important, because all poses in cloudKeyPoses6D have been optimized after loop closure), use poses in cloudKeyPoses6D to transform pointcloud recorded to global coordinate. Pseudocode is something like: pcl::pointcloudpcl::PointXYZ global_map; for(int i = 0; i < cloudKeyPoses6D.size(); i++) { auto pointcloud_in_global_coordinate = transformPointCloud(pointcloud_you_recorded[i], cloudKeyPoses6D[i]); global_map += pointcloud_in_global_coordinate; }

Excuse me bringing up this old topic but this might be interesting for some who need this. Thank you @getupgetup for the idea. It took me in the right direction but it's also more complicated as in this pseudo code. The main reasons are that in featureAssociation.cpp the point cloud get distortion corrected, several tranformations are made and only parts of the outlierCloud (mainly high elevation points and 1/5th of ground points) is separated. It is therefore not enough to work with the clouds you get by default in mapOptimization.cpp. Even if you remove the down sampling, it's not good enough!

Let me explain how I received extracted the highest quality clouds.

  1. Kept all ground points by removing the j%5 here
  2. Just after this line i added that the points will also be filled into a new cloud that you have to declare and define earlier in that file.
  3. Publish the new cloud with a publisher in this function just like the others. Subscribe to this topic in mapOptimization.cpp
  4. Add the outlier cloud thisOutlierKeyFrame and your new cloud in save it to pcd. Also save the cloudKeyPoses6D to a file. You can then reconstruct with @getupgetup 's pseudo code to a beautifully detailed cloud with all corrections applied.

If hope this will help somebody. If you want to ask something about this or need the code, please write to talk _at_ yodayoda.co. I can push the changed code somewhere but I actually did this on SC-LEGO-LOAM not on this particular repo.

enricobellocchio commented 2 years ago

I don't think it is a good idea to merge each frame by using online poses. Online poses have accumulated errors and can cause inconsistant map when there's a loop(just like what you said). A better way is to use offline poses which are optimized after all loops closed. Accumulated error are removed after loop closure so that you can get the consistant map.

Can you please elaborate the approach. Does it mean, first saving the output pose from "integrated_to_init" topic. Then continue with another iteration of loop closure detection, map_optimization and pointcloud stitching. Please, correct me if I am wrong.

Sorry for my unclear expression. "integrated_to_init" topic is a online pose which updates realtimely, so it's not what you need. Nevertheless, cloudKeyPoses6D(in mapOtimization node) stores all key poses and it'll be optimized after loop closure. Here's my approach: 1.Once a key pose is input into cloudKeyPoses6D, record the pointcloud of this frame (using local coordinate). 2. After the program is finished(This is important, because all poses in cloudKeyPoses6D have been optimized after loop closure), use poses in cloudKeyPoses6D to transform pointcloud recorded to global coordinate. Pseudocode is something like: pcl::pointcloudpcl::PointXYZ global_map; for(int i = 0; i < cloudKeyPoses6D.size(); i++) { auto pointcloud_in_global_coordinate = transformPointCloud(pointcloud_you_recorded[i], cloudKeyPoses6D[i]); global_map += pointcloud_in_global_coordinate; }

Excuse me bringing up this old topic but this might be interesting for some who need this. Thank you @getupgetup for the idea. It took me in the right direction but it's also more complicated as in this pseudo code. The main reasons are that in featureAssociation.cpp the point cloud get distortion corrected, several tranformations are made and only parts of the outlierCloud (mainly high elevation points and 1/5th of ground points) is separated. It is therefore not enough to work with the clouds you get by default in mapOptimization.cpp. Even if you remove the down sampling, it's not good enough!

Let me explain how I received extracted the highest quality clouds.

1. Kept all ground points by removing the `j%5` [here](https://github.com/RobustFieldAutonomyLab/LeGO-LOAM/blob/master/LeGO-LOAM/src/imageProjection.cpp#L329)

2. Just after [this line](https://github.com/RobustFieldAutonomyLab/LeGO-LOAM/blob/master/LeGO-LOAM/src/featureAssociation.cpp#L703) i added that the points will also be filled into a new cloud that you have to declare and define earlier in that file.

3. Publish the new cloud with a publisher in [this function](https://github.com/RobustFieldAutonomyLab/LeGO-LOAM/blob/master/LeGO-LOAM/src/imageProjection.cpp#L329) just like the others. Subscribe to this topic in `mapOptimization.cpp`

4. Add the outlier cloud `thisOutlierKeyFrame` and your new cloud in save it to pcd. Also save the `cloudKeyPoses6D` to a file. You can then reconstruct with @getupgetup 's pseudo code to a beautifully detailed cloud with all corrections applied.

If hope this will help somebody. If you want to ask something about this or need the code, please write to talk _at_ yodayoda.co. I can push the changed code somewhere but I actually did this on SC-LEGO-LOAM not on this particular repo.

@cbaus Thank you for the great suggestion, i have mailed you for a code request!