kzampog / kabamaru

Point cloud (RGBD) C++ tools for registration, 3D SLAM, box detection/fitting, and more.
MIT License
43 stars 13 forks source link

Build error... #1

Closed antithing closed 7 years ago

antithing commented 7 years ago

Hi, and thank you for making this code available. I have been looking for an ICP implementation, and this looks great! I am trying to compile on windows, and am getting a build error from PCL.

LNK2001 unresolved external symbol "private: virtual void __cdecl pcl::NormalEstimationOMP<struct pcl::PointXYZRGB,struct pcl::Normal>::computeFeature(class pcl::PointCloud<struct pcl::Normal> &)" (?computeFeature@?$NormalEstimationOMP@UPointXYZRGB@pcl@@UNormal@2@@pcl@@EEAAXAEAV?$PointCloud@UNormal@pcl@@@2@@Z) sisyphus D:\sisyphus\sisyphus-master\build\sift_rgbd_slam.obj 1

Do you have any thoughts on what this could be?

Also, if you have a minute, can you run me through the functions to pass my data into? Does it take depth images, or PCL clouds directly?

Thanks again, much appreciated.

kzampog commented 7 years ago

Hi!

Unfortunately, I can't tell why this linking error occurs. Are you linking against all PCL libraries? I've only tested this with PCL 1.8 on Ubuntu 14.04 and 16.04. If you don't find a workaround, you could try changing NormalEstimationOMP to NormalEstimation.

About the code usage, the most straightforward interface is to use PointXYZRGB point clouds directly. The following code snippet shows how to use it:

#include <sisyphus/sift_rgbd_slam.hpp>
// ...

SLAM slam_obj;

pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
// Populate the cloud!
SLAM::View view = slam_obj.createView(cloud);

// Two options for map building:

// 1) enqueue views and integrate all of them in the end:
slam_obj.enqueueView(view);
// (update cloud/view and repeat)
int num_integrated = slam_obj.integrateAllQueuedViews();

// 2) integrate views as they come and (optionally) enqueue the failed ones to retry later:
int success = integrateView(view);
if (!success) {
    slam_obj.enqueueView(view);
}
// (update cloud/view and repeat)
int num_integrated = slam_obj.integrateAllQueuedViews();

I hope this helps! I'm sorry I did not provide any kind of documentation in the first place!

Best, Kostas

antithing commented 7 years ago

Hi, and thanks for getting back to me. If anyone else has this issue, i have solved it by adding:

#define PCL_NO_PRECOMPILE

tosift_rgbd_slam.cpp, above the other headers.

Thanks for the instruction also, i will try to get it up and running! What kind of latency / frame time are you getting?

Thank you again!

kzampog commented 7 years ago

Hi,

No problem and thanks for the hint!

It's not really optimized for continuous/real-time mapping. The main bottlenecks are normal estimation (no GPU implementation used) and (mainly) PCL's point to plane ICP (you might get it to work faster if you downsample further). SIFT computation and matching is quite fast (~30fps on an old laptop with Quadro 2000M).

It has been a while since I last ran it, but from what I remember the whole pipeline took roughly 1 second/frame, with the time varying somewhat as the model gets bigger. So, this is more suitable for reconstructions from a sparse set of RGBD views.

Let me know if you need further info!

Best, Kostas