ros-perception / perception_pcl

PCL (Point Cloud Library) ROS interface stack
http://wiki.ros.org/perception_pcl
423 stars 332 forks source link

Using pcl_ros::transformPointCloud<pointT> with own pointT: Linker Error #364

Open Scyten opened 2 years ago

Scyten commented 2 years ago

Hi Community, I have an issue using this function

template<typename PointT >
bool pcl_ros::transformPointCloud (const std::string &target_frame, const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::TransformListener &tf_listener)

If I use it with a "standard" pointT-type it works fine. If I use my own datatype it compiles, but I get undefined reference to the function above (pcl_ros::transformPointCloud) while linking.

PCL requires #define PCL_NO_PRECOMPILE to work with new point types (https://pointclouds.org/documentation/tutorials/adding_custom_ptype.html)

My pointT is

struct mmWaveCloudType
{
    PCL_ADD_POINT4D;
    union
    {
        struct
        {
            float intensity;
            float velocity;
        };
        float data_c[4];
    };
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGN_ALIGN16;

POINT_CLOUD_REGISTER_POINT_STRUCT (mmWaveCloudType,
                                    (float, x, x)
                                    (float, y, y)
                                    (float, z, z)
                                    (float, intensity, intensity)
                                    (float, velocity, velocity))

Is this define used by ros_pcl? Has someone tested new pointTypes with ros_pcl?

mvieth commented 2 years ago

Have you tried including pcl_ros/impl/transforms.hpp? That's where the implementation is

Scyten commented 2 years ago

I had included this file, but it does not changed anything. Same error. My work arround: I copied the function into my file and this works. Normaly this should not be necessary. :)

Scyten commented 2 years ago

Ok, I tried again, now it compiles. I was sure that I have tested it. Thank you!

Why isn´t pcl_ros/transforms.h enough?

mvieth commented 2 years ago

@Scyten pcl_ros/transforms.h only contains the declaration of the templated function. pcl_ros/impl/transforms.hpp contains the implementation. If the implementation is available to your compiler, it can instantiate it with any point type.