MRPT / mrpt

:zap: The Mobile Robot Programming Toolkit (MRPT)
https://docs.mrpt.org/reference/latest/
BSD 3-Clause "New" or "Revised" License
1.93k stars 629 forks source link

error: ‘mrpt::utils::PointCloudAdapter<pcl::PointCloud<pcl::PointXYZ> > pca’ has incomplete type #451

Closed alexge233 closed 7 years ago

alexge233 commented 7 years ago

Hi,

I'm using MRPT 1.5.0 installed on Ubuntu 16.04 from a ppa repository. I've run into a pickle:

  1. I'm acquiring pcl::PointCloud from a Kinect v2 camera using freenect2
  2. I then want to insert an observation into an ICP builder

The code is shown below:

template <class builder_type>                                                                                                                                                                                                                                                             
void kinect<builder_type>::callback(const ros::TimerEvent & event)                                                                                                                                                                                                                        
{                                                                                                                                                                                                                                                                                         
    pcl::PointCloud<pcl::PointXYZ> cloud = read();
    auto obs = mrpt::obs::CObservation3DRangeScanPtr();
    mrpt::obs::T3DPointsProjectionParams params;
    params.takeIntoAccountSensorPoseOnRobot = true;
    params.robotPoseInTheWorld =  &__sensor__; 
    params.PROJ3D_USE_LUT = true;
    params.USE_SSE2 = true;
    params.MAKE_DENSE = false;
    obs->project3DPointsFromDepthImageInto(cloud, params);
    /// Then insert into icp
}  

The error I get is:

/usr/include/mrpt/obs/include/mrpt/obs/CObservation3DRangeScan_project3D_impl.h: In instantiation of ‘void mrpt::obs::detail::project3DPointsFromDepthImageInto(mrpt::obs::CObservation3DRangeScan&, POINTMAP&, const mrpt::obs::T3DPointsProjectionParams&, const mrpt::obs::TRangeImageFilterParams&) [with POINTMAP = pcl::PointCloud<pcl::PointXYZ>]’:
/usr/include/mrpt/obs/include/mrpt/obs/CObservation3DRangeScan.h:208:55:   required from ‘void mrpt::obs::CObservation3DRangeScan::project3DPointsFromDepthImageInto(POINTMAP&, const mrpt::obs::T3DPointsProjectionParams&, const mrpt::obs::TRangeImageFilterParams&) [with POINTMAP = pcl::PointCloud<pcl::PointXYZ>]’
/home/mario/mario_ws/src/mario/src/kinect.hpp:68:5:   required from ‘void kinect<builder_type>::callback(const ros::TimerEvent&) [with builder_type = icp_builder]’
/home/mario/mario_ws/src/mario/src/kinect.hpp:42:54:   required from ‘kinect<builder_type>::kinect(ros::NodeHandle&, builder_type&) [with builder_type = icp_builder]’
/home/mario/mario_ws/src/mario/src/main.cpp:25:45:   required from here
/usr/include/mrpt/obs/include/mrpt/obs/CObservation3DRangeScan_project3D_impl.h:32:63: error: ‘mrpt::utils::PointCloudAdapter<pcl::PointCloud<pcl::PointXYZ> > pca’ has incomplete type
   mrpt::utils::PointCloudAdapter<POINTMAP> pca(dest_pointcloud);

Can anyone help please?

jlblancoc commented 7 years ago

Hi,

Firstly, there's something strange in your code:

auto obs = mrpt::obs::CObservation3DRangeScanPtr();
...
obs ->XX

Since obs is an uninitialized smart pointer, the call to obs->xxx() should crash (!!). Is that your exact code, or was this a simplified version?

On the incomplete type, I guess you are missing the #include for template specializations: http://reference.mrpt.org/devel/group__mrpt__adapters__grp.html http://reference.mrpt.org/devel/maps_2_p_c_l__adapters_8h_source.html

    #include <mrpt/maps/PCL_adapters.h>
alexge233 commented 7 years ago

It was a minified version, it didn't compile so I never got to the segfault! Many thanks for the help, that was the issue. However I've decided to skip PCL altogether and simply populate the observation from libfreenect2 data.