ros的pcl库中对于自己定义的消息,调用pcl库时总是报错 c++

首先定义自己的消息类型

struct CustomPoint { // 定义点类型结构
  PCL_ADD_POINT4D; // 该点类型有4个元素
  float intensity = 0.0;
  uint32_t zone;
  uint32_t ring;
  uint32_t sector;
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW // 确保new操作符对齐操作
} EIGEN_ALIGN16; // 强制SSE对齐
 
 
POINT_CLOUD_REGISTER_POINT_STRUCT( // 注册点类型宏
    CustomPoint,
    (float, x, x)
    (float, y, y)
    (float, z, z)
    (float, intensity, intensity)
    (uint32_t, zone, zone)
    (uint32_t, ring, ring)
    (uint32_t, sector, sector)
)

// typedef pcl::PointXYZI VPoint;
typedef CustomPoint VPoint;
typedef pcl::PointCloud<VPoint> VPointType;

在定义完自己的消息类型之后,调用pcl::removeNaNFromPointCloud等自带的函数时会报错:

(.text+0x14631): undefined reference to `pcl::PCLBase<CustomPoint>::PCLBase(
cl::removeNaNFromPointCloud<CustomPoint>(pcl::PointCloud<CustomPoint> const&, pcl::PointCloud<CustomPoint>&, std::vector<int, std::allocator<int> >&)'
collect2: error: ld returned 1 exit status

代码如下:

 void PatchWorkpp::pointcloud_callback(const sensor_msgs::PointCloud2::ConstPtr &input)
 {
 VPointType::Ptr cloud_in = boost::make_shared<VPointType>();
        VPointType::Ptr src_cloud(new VPointType);
        pcl::fromROSMsg(*input, *cloud_in);
        std::vector<int> mapping;
        pcl::removeNaNFromPointCloud(*cloud_in, *cloud_in, mapping); // 必须要移除NAN点}

此时需要添加头文件如下:

#include <pcl/impl/pcl_base.hpp>
#include <pcl/filters/impl/crop_box.hpp> 
#include <pcl/filters/impl/filter.hpp>
#include <pcl/kdtree/impl/kdtree_flann.hpp>
#include <pcl/search/impl/organized.hpp>
#include <pcl/surface/impl/convex_hull.hpp>

参考文章:
https://blog.csdn.net/qq_43427457/article/details/125052803

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值