ROS知识点——生成点云,发布、订阅ROS点云话题

1 点云基本概念

1.1 点云结构公共字段

PCL包含一个重要的数据结构,被设计成一个模板类,把点的类型当做模板类的参数。pcl::PointCloud<point T>类似于vector。

header:pcl::PCLHeader 记录了点云的获取时间
points:std::vector<PointT,…>储存所有点的容器。vector定义中的PointT对应的类的模板参数,即点的类型
width:指定点云组织成图像时的宽度
height:指定点云组成图像时的高度
is_dense: 指定点云中是否有无效值
sensor_origin_:是Eigen::Vector4f类型,传感器相对于原点平移所得的位姿
sensor_orientation_:是Eigen::Quaternionf类型,定义传感器旋转所得的位姿

1.2 点云类型

PointT是pcl::PointCloud类的模板参数,定义点云的类型

pcl::PointXYZ 位置
pcl::PointXYZI 位置+亮度
pcl::PointXYZRGBA 位置+颜色+透明度
pcl::PointXYZRGB 位置+颜色
pcl::Normal 表示曲面上给定点处的法线以及测量的曲率
pcl::PointNormal 曲率信息+位置

在这里插入图片描述

1.3 ROS的PCL接口

定义不同的消息类型去处理点云的数据

std_msgs::Header 不是真的消息类型,它包含发送的时间、序列号等
sensor_msgs::PointCloud2 用来转换pcl::PointCloud类型
pcl_msgs::PointIndices 储存点云的索引
pcl_msgs::PolygonMesh 保存了描绘网格、定点和多边形
pcl_msgs::Vertices 将一组定点的索引保存在数组中
pcl_msgs::ModelCoefficients 储存一个模型的不同系数,如描述一个平面需要四个参数

1.4 pcl-ros点云格式转换

三种格式:

sensor_msgs::PointCloud
sensor_msgs::PointCloud2
pcl::PointCloud<T>

其中,PointCloud2和pcl::PointCloud可以相互转换,PointCloud和PointCloud2可以相互转换,PointCloud和pcl::PointCloud的转换需要使用PointCloud2中转

PointCloud⟺PointCloud2⟺pcl::PointCloud<T>

ROS中sensor_msgs::PointCloud2类型消息解读,参考:https://blog.csdn.net/weixin_40826634/article/details/108767704
上述变换的实现:
1、PointCloud2to PointCloud

#include "sensor_msgs/point_cloud_conversion.h"
static inline bool convertPointCloud2ToPointCloud (
		const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output);

2、PointCloudto PointCloud2

#include "sensor_msgs/point_cloud_conversion.h"
static inline bool convertPointCloudToPointCloud2 (
		const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)

3、pcl::PointCloud<T>to PointCloud2

#include "pcl_conversions/pcl_conversions.h"
template<typename T>
void toROSMsg(const pcl::PointCloud<T> &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
{
    pcl::PCLPointCloud2 pcl_pc2;
    pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2);
    pcl_conversions::moveFromPCL(pcl_pc2, cloud);
}

4、PointCloud2to pcl::PointCloud<T>

#include "pcl_conversions/pcl_conversions.h"
template<typename T>
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
{
    pcl::PCLPointCloud2 pcl_pc2;
    pcl_conversions::toPCL(cloud, pcl_pc2);
    pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
}

2 创建点云并发布ROS点云话题

2.1 创建功能包

catkin_create_pkg point_cloud_pkg std_msgs rospy roscpp sensor_msgs pcl_ros pcl_conversions std_srvs message_generation

2.2 发布ROS点云话题

create_point_cloud_pub.cpp

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

int main(int argc, char** argv)
{
   
    ros::init(argc, argv, "point_cloud_node");
    ros::NodeHandle nh;
    ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("/point_cloud_publisher_topic", 1000);
    ros::Rate rate(10);
    unsigned int num_points = 10;

    //建立pcl点云
    pcl::PointCloud<pcl::PointXYZRGB> cloud;
    // 点云初始化
    cloud.points.resize(</
  • 5
    点赞
  • 80
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值