ROS引用自定义库文件

1、建立头文件

在~/qt_ws/pcl_topic/include/pcl_topic/pcl_pub.h

存放头文件

pcl_pub.h

#ifndef PCL_PUB_H
#define PCL_PUB_H

#include <ros/ros.h>
#include <pcl/point_cloud.h>
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>

class pcl_pub
{
private:
  ros::NodeHandle n;
  ros::Publisher pubCloud;
  ros::Subscriber subCloud;
  sensor_msgs::PointCloud2 msg;//接收到的点云消息
  sensor_msgs::PointCloud2 adjust_msg;//等待发送的消息
  pcl::PointCloud<pcl::PointXYZRGB> adjust_pcl;//建立一个pcl的点云,作为中间过程


public:
  pcl_pub();
  ~pcl_pub();
  void getcloud(const sensor_msgs::PointCloud2ConstPtr & laserCloudMsg);

};


#endif // PCL_PUB_H

2、建立源文件

在~/qt_ws/src/pcl_topic/src/source/pcl_pub.cpp

中存放源文件

pcl_pub.cpp

#include "pcl_topic/pcl_pub.h"

pcl_pub::pcl_pub()
{
  subCloud = n.subscribe<sensor_msgs::PointCloud2>("/color_cloud",1,&pcl_pub::getcloud,this);//接收点云数据,进入回调函数getcloud()
  pubCloud = n.advertise<sensor_msgs::PointCloud2>("/adjust_cloud",100);//建立一个发布器,主题是adjust_cloud,方便之后发布调整后的点云
}

pcl_pub::~pcl_pub()
{

}

void pcl_pub::getcloud(const sensor_msgs::PointCloud2ConstPtr &laserCloudMsg)
{
  pcl::PointCloud<pcl::PointXYZRGB>::Ptr adjust_pcl_ptr(new pcl::PointCloud<pcl::PointXYZRGB>);//每次都需要重新初始化
  pcl::fromROSMsg(*laserCloudMsg,*adjust_pcl_ptr);//将msg消息转化为点云
  adjust_pcl = *adjust_pcl_ptr;
  for(int i = 0;i<adjust_pcl.points.size();i++)
  {
    adjust_pcl.points[i].r = 0;
    adjust_pcl.points[i].g = 255;
    adjust_pcl.points[i].b = 0;
  }
  pcl::toROSMsg(adjust_pcl,adjust_msg);//将点云转化为消息
  pubCloud.publish(adjust_msg);
}

3、配置CMakeLists.txt文件

find_package(catkin REQUIRED COMPONENTS
  pcl_conversions
  pcl_ros
  roscpp
  sensor_msgs
  std_msgs
  std_srvs
)


include_directories(
 include//这里将#去掉
  ${catkin_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS}
)
add_library(pcl_pub include
/pcl_topic/pcl_pub.h src/source/pcl_pub.cpp )
add_dependencies(pcl_pub ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(pcl_pub ${PCL_LIBRARIES} ${catkin_LIBRARIES} )

4、调用库

在~/qt_ws/src/pcl_topic/src/pcl_topic.cpp

#include"pcl_topic/pcl_pub.h"


int main(int argc, char** argv) {

  ros::init(argc, argv, "colored");  //初始化了一个节点,名字为colored

  pcl_pub pb;

  ros::spin();
  return 0;
}

5、配置CMakeLists.txt文件

add_executable(pcl_topic src/pcl_topic.cpp)
add_dependencies(pcl_topic ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(pcl_topic pcl_pub ${catkin_LIBRARIES} ${PCL_LIBRARIES} )

6、测试

cd ~/qt_ws
catkin_make - DCATKIN_WHITELIST_PACKAGES="pcl_topic"
rosrun pcl_topic pcl_topic
rostopic list

可以查看到新增话题

参考博客:https://blog.csdn.net/weixin_43807148/article/details/113838489

       https://blog.csdn.net/qq_35758003/article/details/105592709

                 https://windistance.blog.csdn.net/article/details/87967237

 

posted @ 2022-03-28 21:38  楸壳  阅读(266)  评论(0编辑  收藏  举报