Giter VIP home page Giter VIP logo

removert's Introduction

Removert

What is removert?

  • Static map construction in the wild.
  • A dynamic points removing tool by constructing a static map
  • The name is from the abbreviation of our title "Remove-then-revert" (IROS 2020): paper, video

What can we do using removert?

  • We can easily construct and save a static map.
  • We can easily parse dynamic points

Example

Preparations

  • Step 1: Get a set of LiDAR scans and corresponding poses by running any open source LiDAR odometry or SLAM algorithm (e.g., pose-and-scan saver of SC-LIO-SAM or pose-and-scan saver of SC-A-LOAM)
  • Step 2: Make a pair of a scan's point cloud and a corresponding pose using associated timestamps. We note that you need to save a scan as a binary format as KITTI and the pose file as a single text file where SE(3) poses are written line-by-line (12 numbers for a single line), which is also the equivalent format as KITTI odometry's ground truth pose txt file.

Requirements

  • Based on C++17
  • ROS (and Eigen, PCL, OpenMP): the all examples in this readme are tested under Ubuntu 18.04 and ROS Melodic.
  • FYI: We uses ROS's parameter parser for the convenience, despite no topic flows within our system (our repository currently runs at offline on the pre-prepared scans saved on a HDD or a SSD). But the speed is fast (over 10Hz for a single removing) and plan to extend to real-time slam integration in future.

How to use

  • First, compile the source
$ mkdir -p ~/catkin/removert_ws/src
$ cd ~/catkin/removert_ws/src
$ git clone https://github.com/irapkaist/removert.git
$ cd ..
$ catkin_make
$ source devel/setup.bash
  • Before to start the launch file, you need to replace data paths in the config/params.yaml file. More details about it, you can refer the above tutorial video (KITTI 09)

  • Then, you can start the Removert

$ roslaunch removert run_kitti.launch # if you use KITTI dataset 
 or
$ roslaunch removert run_scliosam.launch # see this tutorial: https://youtu.be/UiYYrPMcIRU
  • (Optional) we supports Matlab tools to visulaize comparasions of original/cleaned maps (see tools/matlab).

Further Improvements

  • We propose combining recent deep learning-based dynamic removal (e.g., LiDAR-MOS) and our method for better map cleaning
    • Deep learning-based removal could run online and good for proactive removal of bunch of points.
    • Removert currently runs offline but good at finer cleaning for the remained 3D points after LiDAR-MOS ran.
  • A tutorial video and an example result for the KITTI 01 sequence:

Contact

Cite Removert

@INPROCEEDINGS { gskim-2020-iros,
    AUTHOR = { Giseop Kim and Ayoung Kim },
    TITLE = { Remove, then Revert: Static Point cloud Map Construction using Multiresolution Range Images },
    BOOKTITLE = { Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) },
    YEAR = { 2020 },
    MONTH = { Oct. },
    ADDRESS = { Las Vegas },
    NOTE = { Accepted. To appear. },
}

License

Creative Commons License
This work is supported by Naver Labs Corporation and by the National Research Foundation of Korea (NRF). This work is also licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License.

TODO (in order)

Near future

  • Full sequence cleaned-scan saver by automatically iterating batches (because using 50-100 scans for a single batch is recommended for computation speed)
  • Adding revert steps (I think certainly removing dynamic points is generally more worthy for many applications, so reverting step is omitted currently)
  • Automatically parse dynamic segments from the dynamic points in a scan (e.g., using DBSCAN on dynamic points in a scan)
  • Exmaples from MulRan dataset (for showing removert's availability for various LiDAR configurations) — see this tutorial
  • (scan, pose) pair saver using SC-LeGO-LOAM or SC-LIO-SAM, which includes a loop closing that can make a globally consistent map. — see this tutorial
  • Examples from the arbitrary datasets using the above input data pair saver.
  • Providing a SemanticKITTI (as a truth) evaluation tool (i.e., calculating the number of points of TP, FP, TN, and FN)
  • (Not certain now) Changing all floats to double

Future

  • Real-time LiDAR SLAM integration for better odometry robust to dynamic objects in urban sites (e.g., with LIO-SAM in the Riverside sequences of MulRan dataset)
  • Multi-session (i.e., inter-session) change detection example
  • Defining and measuring the quality of a static map
  • Using the above measure, deciding when removing can be stopped with which resolution (generally 1-3 removings are empirically enough but for highly crowded environments such as urban roads)

removert's People

Contributors

gisbi-kim avatar irapkaist avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

removert's Issues

Static Map Issue

Hi,
I have a question regarding the Static map result.
the run includes ~500 scans with around ~14,000 detections in each scan.
I get the following result:
image

You can see that in the low x-values (< 100 [m]) the map is very detailed but in the range above 100 [m] the map is not detailed (just blue color).
what is the reason for that? how can I improve the map?

Thanks :)

catkin_make question

Hello, I'm reproducing your code. When catkin_make, I encountered "requires GCC version > = 8". Before I install gcc8 This problem still occurs after 3? How do you solve this problem? Looking forward to your reply.

In file included from /home/cml/remvert_ws/src/removert/src/utility.cpp:1:0:
/home/cml/remvert_ws/src/removert/include/removert/utility.h:70:10: fatal error: filesystem: no such file or directory
#include // requires gcc version >= 8
^~~~~~~~~~~~
In file included from /home/cml/remvert_ws/src/removert/include/removert/RosParamServer.h:3:0,
from /home/cml/remvert_ws/src/removert/src/RosParamServer.cpp:1:
/home/cml/remvert_ws/src/removert/include/removert/utility.h:70:10: fatal error: filesystem: no such file or directory

some question about poses

Hello, can I get the poses and scans of Kitti dataset by using sc-lio-sam and then remove dynamic objectives by removert? Will It function?

Regarding Revert step in the implementation

Hi,

I really appreciate the work you have done in the "Remove-then-Revert" publication and thanks for uploading its code. I was going through your code and stumbled upon the revert step. I wanted to ask, has this repository been updated to add the reverting steps or would it be done in future ?

dynamic_point_indexes

Hi author,
Thanks for your hard work !
I have a question about dynamic_point_indexes returned by calcDescrepancyAndParseDynamicPointIdxForEachScan() function.
We use calcDescrepancyAndParseDynamicPointIdx() to parse dynamic points for each kscan.
https://github.com/irapkaist/removert/blob/828753fed2aeb714b1af513eb06fd353cd4e0b5d/src/Removerter.cpp#L568
Every point in map_local_curr_, whose index in map_local_curr_ is stored in the corrresponding row and col pixel of map_rimg_ptidx. map_local_curr_ is the map points converted into the kscan's frame using transformGlobalMapToLocal(idx_scan);

Question:
It seems that when we call auto [map_rimg, map_rimg_ptidx] = map2RangeImg(map_local_curr_, kFOV, _rimg_shape); to calculate every point's index of map_local_curr_ point cloud, should be index of map_global_curr_ point cloud, not in
index of map_local_curr_ point cloud ?

  • first reason:
    Because when we for_each scan Done, we use std::set<> to remove repeated indexes makes sense, otherwise, even if dynamic_point_indexes has duplicated number, they maybe different. For example point_a index comes from map_global_curr_ converted into mscan, point_b index comes from map_global_curr_ converted into nscan, their index are the same , but they are different points in map. Similarly, different index points may be the same point in the map.
    https://github.com/irapkaist/removert/blob/828753fed2aeb714b1af513eb06fd353cd4e0b5d/src/Removerter.cpp#L582-L584
  • second reason:
    When we parseDynamicMapPointcloudUsingPtIdx(), we use map_global_curr_, the line 441.

I' m not sure i totally understand code correctly and not miss something, look forward to disscuss with you ! Thanks for your time!
https://github.com/irapkaist/removert/blob/828753fed2aeb714b1af513eb06fd353cd4e0b5d/src/Removerter.cpp#L436-L448

terminate called after throwing an instance of 'std::out_of_range'

Hi

Thank you for this repo!

I have the following error when I try running your code (actually a variant for C++14 - https://github.com/kinggreat24/removert).
Nevertheless, any idea what could be causing this error?

I also wanted to confirm if I am using the right data. So for the point cloud, I download the 09 kitti sequence from here
http://www.cvlibs.net/datasets/kitti/raw_data.php and for the pose, I used the ground-truth pose given www.cvlibs.net/datasets/kitti/eval_odometry.php. I know I can use LiDAR odometry or SLAM algorithm you mentioned but this technically is the output I'd get right?

Many thanks!

compile error

When I compiled the program meet some error as the follows:
Screenshot from 2021-10-26 16-58-21
I changed to the gcc to 8.4.0 did't work

My software environment as the follows:
ubuntu 18.04 ROS Melodic
eigen: 3.3.4
opencv: 3.4.0
pcl: 1.8.1

kitti poses format

Hi,
I'm new to the subject of SLAM.
I have GPS data that includes latitude, longitude and yaw, pitch, roll.
I'm trying to convert this data to the pose format (12 numbers).
I know how to convert the yaw, pitch and roll to the 3x3 rotation matrix.
I'm having problem with the translation (tx, ty, tz).
what is the conversion from (lat, lon) to the tx, ty, tz? is there a good reference for this conversion?
I came a cross with multiple different conversions.
Thanks

some questions about removert?

hi, gisbi-kim, Thank you for your shared code about dynamic remove.
I try to use your code and Youtube video to implement this demo, but there appear a few problems that confused me,
such as:

  1. The kitti path: I can get "sequence_scan_dir" in kitti dataset, but there can't find "poses.txt" in the "sequence_pose_path",
    The data only I can find which locate in "../2011_09_26/2011_09_26_drive_0009_sync/velodyne_points/data/.bin" and
    "../2011_09_26/2011_09_26_drive_0009_sync/velodyne_points/oxts/
    .txt"

  2. It seems that function “revertOnce” need to be reedit, dose it right? how's the difference between the exist of this function?

  3. Does "scansideRemovalForEachScanAndSaveThem" is the BR function in your paper?

Thank you for your reply!

About the parameter: downsample_voxel_size

Hi, G. Kim, Thank you for your shared code about dynamic removal.

About the parameter:

downsample_voxel_size: 0.1 # user parameter but recommend to use 0.05 to make sure an enough density (this value is related to the removing resolution's expected performance)

I would like to ask, when I set it to 0.05, it works well, but when I set it to 0.1, there are a lot of FPs on the ground, resulting in hole in gound.

In my opinion, large resolution leads to the appearance or aggravation of visibility-based incidence angle ambiguity. What do you think?

Thank you for your reply!

Some question about the variable "map_global_curr_"

Thanks for your excellent work!
I have some question about the variable "map_global_curr_".
I can see your code "pcl::PointCloud::Ptr map_global_curr_; // the M_i. i.e., removert is: M1 -> S1 + D1, D1 -> M2 , M2 -> S2 + D2 ... repeat ..." which is accord with your paper. However, I see 650 lines "*map_global_curr_ = *map_global_curr_static_;" in the file Removerter.cpp . Why that lines look like M1->S1 + D1, S1->M2 , M2-> S2 + D2 ...

Compile error

I got the following errors when compiling under ROS Kinetic in Ubuntu-16.04, can you tell me the version of PCL?
Removerter.cpp:(.text+0x3271): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty> >::OctreePointCloud(double)'
Removerter.cpp:(.text+0x3319): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty> >::defineBoundingBox()' Removerter.cpp:(.text+0x3321): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty> >::addPointsFromInputCloud()'
Removerter.cpp:(.text+0x3461): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty> >::~OctreePointCloud()' Removerter.cpp:(.text+0x362a): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty> >::~OctreePointCloud()'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function pcl::octree::OctreePointCloudVoxelCentroid<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty>::addPointIdx(int)': Removerter.cpp:(.text._ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEE11addPointIdxEi[_ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEE11addPointIdxEi]+0x4b): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty> >::adoptBoundingBoxToPoint(pcl::PointXYZI const&)'
Removerter.cpp:(.text._ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEE11addPointIdxEi[_ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEE11addPointIdxEi]+0x59): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty> >::genOctreeKeyforPoint(pcl::PointXYZI const&, pcl::octree::OctreeKey&) const' Removerter.cpp:(.text._ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEE11addPointIdxEi[_ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEE11addPointIdxEi]+0x73): undefined reference to pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty>::createLeafRecursive(pcl::octree::OctreeKey const&, unsigned int, pcl::octree::OctreeBranchNodepcl::octree::OctreeContainerEmpty, pcl::octree::OctreeLeafNode<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI >&, pcl::octree::OctreeBranchNodepcl::octree::OctreeContainerEmpty*&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function pcl::octree::OctreePointCloudVoxelCentroid<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty>::~OctreePointCloudVoxelCentroid()': Removerter.cpp:(.text._ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEED2Ev[_ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEED5Ev]+0xf): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty> >::~OctreePointCloud()'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function pcl::octree::OctreePointCloudVoxelCentroid<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty>::~OctreePointCloudVoxelCentroid()': Removerter.cpp:(.text._ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEED0Ev[_ZN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEED5Ev]+0x13): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainerpcl::PointXYZI, pcl::octree::OctreeContainerEmpty> >::~OctreePointCloud()'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEEE[_ZTVN3pcl6octree29OctreePointCloudVoxelCentroidINS_9PointXYZIENS0_38OctreePointCloudVoxelCentroidContainerIS2_EENS0_20OctreeContainerEmptyEEE]+0x38): undefined reference to pcl::octree::OctreePointCloud<pcl::PointXYZI, pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty, pcl::octree::OctreeBase<pcl::octree::OctreePointCloudVoxelCentroidContainer<pcl::PointXYZI>, pcl::octree::OctreeContainerEmpty> >::genOctreeKeyForDataT(int const&, pcl::octree::OctreeKey&) const' collect2: error: ld returned 1 exit status removert/CMakeFiles/removert_removert.dir/build.make:539: recipe for target '/home/kinggreat24/direct_lidar_align_ws/devel/lib/removert/removert_removert' failed make[2]: *** [/home/kinggreat24/direct_lidar_align_ws/devel/lib/removert/removert_removert] Error 1 CMakeFiles/Makefile2:3810: recipe for target 'removert/CMakeFiles/removert_removert.dir/all' failed make[1]: *** [removert/CMakeFiles/removert_removert.dir/all] Error 2 Makefile:138: recipe for target 'all' failed make: *** [all] Error 2

Regarding number of points in the output point cloud.

Hi @gisbi-kim,

While I was going through the output of the "Removert", I found out that the number of points in the cleaned scans were less than the number of points in the original scan, could you please let me know if this is the case and what way did you use to upsample the point cloud to get the number of points same as the original point cloud.

Thanks,
Regards,
Mehul Arora

Not working for in place (not moving) LiDAR

Hello,

I have tried to use Removert to remove dynamic Objects however it doesn't work for statics/in-place LiDARs (Infrastructure). Do you know how to solve this?

Thanks!

Removert for large sequences

First of all kudos for the great work.

Is there any utility available to run removert for large maps in a single go (Considering the computation speed limitation)?

Questions about run the program.

Excuse me, what data do 'sequence_scan_dir' and 'sequence_pose_path' correspond to in yaml file? Is it generated by the code or given by me?

An error occurred while I was running the kitti dataset,Which version of PCL library do you use?

Thank you very much for your excellent work.A few errors occurred while I was running your algorithm.
So I added some printing instructions to find out where the error was,As is shown in.

1111
I use "cout<<"b*"<<endl;" to find the error. So I changed the code a little bit:
222
That means it was the sentence " octree.addPointsFromInputCloud();" that caused the error
Why does this happen? Has anyone come across it? Is it because I have the wrong version of PCL library?
I use PCL 1.8

batch_size is not used?

Hey Auther @gisbi-kim @ayoungk ,
Thanks for your great work!

image

I found the parameter batch_size is not used,and no code indicates the Batch of dynamics point removal in the paper.
Is that right?

Revert Part

Thanks for your invential method. And can you apply the revert part that for the ground-disappeared weakness of only remove part.

compiling error

Operating Sys:18.04
ROS version: melodic
gcc -version:8.0

/usr/bin/ld: warning: libboost_thread.so.1.65.1, needed by /opt/ros/melodic/lib/libroscpp.so, may conflict with libboost_thread.so.1.78.0
/usr/bin/ld: warning: libboost_chrono.so.1.65.1, needed by /opt/ros/melodic/lib/libroscpp.so, may conflict with libboost_chrono.so.1.78.0
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function Removerter::parseMapPointcloudSubsetUsingPtIdx(std::vector<int, std::allocator<int> >&, boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> >&)': Removerter.cpp:(.text+0x6af2): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
Removerter.cpp:(.text+0x6b0c): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<std::vector<int, std::allocator<int> > > const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function Removerter::parsePointcloudSubsetUsingPtIdx(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI > const&, std::vector<int, std::allocator >&, boost::shared_ptr<pcl::PointCloudpcl::PointXYZI >&)':
Removerter.cpp:(.text+0x6e6b): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setInputCloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> const> const&)' Removerter.cpp:(.text+0x6e85): undefined reference to pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<std::vector<int, std::allocator > > const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function Removerter::parseStaticMapPointcloudUsingPtIdx(std::vector<int, std::allocator<int> >&)': Removerter.cpp:(.text+0x708d): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
Removerter.cpp:(.text+0x70a7): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<std::vector<int, std::allocator<int> > > const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function Removerter::parseDynamicMapPointcloudUsingPtIdx(std::vector<int, std::allocator >&)':
Removerter.cpp:(.text+0x72ad): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setInputCloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> const> const&)' Removerter.cpp:(.text+0x72c7): undefined reference to pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<std::vector<int, std::allocator > > const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o: In function Removerter::readValidScans()': Removerter.cpp:(.text+0xf087): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl11KdTreeFLANNINS_9PointXYZIEN5flann9L2_SimpleIfEEEE[_ZTVN3pcl11KdTreeFLANNINS_9PointXYZIEN5flann9L2_SimpleIfEEEE]+0x10): undefined reference to pcl::KdTreeFLANN<pcl::PointXYZI, flann::L2_Simple<float> >::setInputCloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> const> const&, boost::shared_ptr<std::vector<int, std::allocator<int> > const> const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl7PCLBaseINS_9PointXYZIEEE[_ZTVN3pcl7PCLBaseINS_9PointXYZIEEE]+0x20): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl7PCLBaseINS_9PointXYZIEEE[_ZTVN3pcl7PCLBaseINS_9PointXYZIEEE]+0x28): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<std::vector<int, std::allocator<int> > > const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl7PCLBaseINS_9PointXYZIEEE[_ZTVN3pcl7PCLBaseINS_9PointXYZIEEE]+0x30): undefined reference to pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<std::vector<int, std::allocator > const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl7PCLBaseINS_9PointXYZIEEE[_ZTVN3pcl7PCLBaseINS_9PointXYZIEEE]+0x38): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<pcl::PointIndices const> const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl6FilterINS_9PointXYZIEEE[_ZTVN3pcl6FilterINS_9PointXYZIEEE]+0x20): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl6FilterINS_9PointXYZIEEE[_ZTVN3pcl6FilterINS_9PointXYZIEEE]+0x28): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<std::vector<int, std::allocator<int> > > const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl6FilterINS_9PointXYZIEEE[_ZTVN3pcl6FilterINS_9PointXYZIEEE]+0x30): undefined reference to pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<std::vector<int, std::allocator > const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl6FilterINS_9PointXYZIEEE[_ZTVN3pcl6FilterINS_9PointXYZIEEE]+0x38): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<pcl::PointIndices const> const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl9VoxelGridINS_9PointXYZIEEE[_ZTVN3pcl9VoxelGridINS_9PointXYZIEEE]+0x20): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl9VoxelGridINS_9PointXYZIEEE[_ZTVN3pcl9VoxelGridINS_9PointXYZIEEE]+0x28): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<std::vector<int, std::allocator<int> > > const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl9VoxelGridINS_9PointXYZIEEE[_ZTVN3pcl9VoxelGridINS_9PointXYZIEEE]+0x30): undefined reference to pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<std::vector<int, std::allocator > const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl9VoxelGridINS_9PointXYZIEEE[_ZTVN3pcl9VoxelGridINS_9PointXYZIEEE]+0x38): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<pcl::PointIndices const> const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE[_ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE]+0x20): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE[_ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE]+0x28): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<std::vector<int, std::allocator<int> > > const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE[_ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE]+0x30): undefined reference to pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<std::vector<int, std::allocator > const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE[_ZTVN3pcl13FilterIndicesINS_9PointXYZIEEE]+0x38): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<pcl::PointIndices const> const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE[_ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE]+0x20): undefined reference to pcl::PCLBasepcl::PointXYZI::setInputCloud(boost::shared_ptr<pcl::PointCloudpcl::PointXYZI const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE[_ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE]+0x28): undefined reference to pcl::PCLBase<pcl::PointXYZI>::setIndices(boost::shared_ptr<std::vector<int, std::allocator<int> > > const&)' CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE[_ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE]+0x30): undefined reference to pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<std::vector<int, std::allocator > const> const&)'
CMakeFiles/removert_removert.dir/src/Removerter.cpp.o:(.data.rel.ro._ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE[_ZTVN3pcl14ExtractIndicesINS_9PointXYZIEEE]+0x38): undefined reference to `pcl::PCLBasepcl::PointXYZI::setIndices(boost::shared_ptr<pcl::PointIndices const> const&)'
collect2: error: ld returned 1 exit status
removert/CMakeFiles/removert_removert.dir/build.make:673: recipe for target '/home/alex/Documents/WorkingArea/TEST_CODE/removert/catkin/removert_ws/devel/lib/removert/removert_removert' failed
make[2]: *** [/home/alex/Documents/WorkingArea/TEST_CODE/removert/catkin/removert_ws/devel/lib/removert/removert_removert] Error 1
CMakeFiles/Makefile2:1954: recipe for target 'removert/CMakeFiles/removert_removert.dir/all' failed
make[1]: *** [removert/CMakeFiles/removert_removert.dir/all] Error 2
Makefile:145: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j12 -l12" failed

Parameters for not-fixed vertical resolution LiDARs

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?

Can this algorithm run in real time?

Can this algorithm run with SLAM algorithm (for example ,loam、lego-loam ...),and finally get a cleaner map.
In other words, can the removert algorithm have online version?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.