Ros用PointCloud2封装点云,点云中表示坐标的格式是直角坐标。
C:\Windows\System32>rosmsg show sensor_msgs/PointCloud2 std_msgs/Header header uint32 seq time stamp string frame_id uint32 height uint32 width sensor_msgs/PointField[] fields uint8 INT8=1 uint8 UINT8=2 uint8 INT16=3 uint8 UINT16=4 uint8 INT32=5 uint8 UINT32=6 uint8 FLOAT32=7 uint8 FLOAT64=8 string name uint32 offset uint8 datatype uint32 count bool is_bigendian uint32 point_step uint32 row_step uint8[] data bool is_dense
PreparePointCloud2Message是cartographer如何填充PointCloud2的代码。参数timestamp是点云中最后一点的采集时刻,frame_id指示点云坐标所属的坐标系,num_points是点云中的点数。
<cartographer_ros>/cartographer_ros/msg_conversion.cc ------ sensor_msgs::PointCloud2 PreparePointCloud2Message(const int64_t timestamp, const std::string& frame_id, const int num_points) { sensor_msgs::PointCloud2 msg; msg.header.stamp = ToRos(::cartographer::common::FromUniversal(timestamp)); msg.header.frame_id = frame_id; msg.height = 1; msg.width = num_points; msg.fields.resize(3); msg.fields[0].name = "x"; msg.fields[0].offset = 0; msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32; msg.fields[0].count = 1; msg.fields[1].name = "y"; msg.fields[1].offset = 4; msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32; msg.fields[1].count = 1; msg.fields[2].name = "z"; msg.fields[2].offset = 8; msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32; msg.fields[2].count = 1; msg.is_bigendian = false; msg.point_step = 16; msg.row_step = 16 * msg.width; msg.is_dense = true; msg.data.resize(16 * num_points); return msg; }
字段 | 注释 | cartographer |
header.stamp | 点云中最后一点的采集时刻 | 参数timestamp |
header.frame_id | 该点云坐标所属的坐标系 | 参数frame_id,像“map” |
width(注1) | width * height = 点数 | 参数num_points |
height | width * height = 点数 | 1 |
point_step | 多少个字节表示一个点 | 16 |
row_step | 行距。point_step * width | 16 * num_points |
is_bigendian | 多字节表示一个点时,小端还是大端 | false |
is_dense | True if there are no invalid points | true |
fields(注2) | 描述row_step字节是如何表示一个点 | 3通道,每通道是4字节的FLOAT32 |
data | 存储点云坐标值的内存块 | 如何填充参考“ToPointCloud2Message(...)” |
注1:width、height
当看到坐标系显示雷达数据,它们分布在某个矩形内,有人会误以为存储在PointCloud2中的width、heigh就是这个矩形的宽度、高度。这种理解是错的,要存储N个点,一个一维数组就就行了。cartographer中PreparePointCloud2Message是固定把height置为1,这样width等于点数。
注2:fields、data
fields会被先分成通道,3D直角坐标就是x、y、z,须要3个通道。然后是具体通道内的值用什么类型。PointField::FLOAT32表示用4字节单精度浮点数表示x/y/z。is_bigendian=false,表示这4字节是小端序。按3*4算,应该是12字节表示一个点,那为什么row_step中写的是16?——的确是16个字节表示一个点,除那12字节外,最后4字节填了个固定值kPointCloudComponentFourMagic(1),有的文章把这分量称为强度或者反射值r。ToPointCloud2Message描述了如何填充data字段。
// The ros::sensor_msgs::PointCloud2 binary data contains 4 floats for each // point. The last one must be this value or RViz is not showing the point cloud // properly. constexpr float kPointCloudComponentFourMagic = 1.; sensor_msgs::PointCloud2 ToPointCloud2Message( const int64_t timestamp, const std::string& frame_id, const ::cartographer::sensor::TimedPointCloud& point_cloud) { auto msg = PreparePointCloud2Message(timestamp, frame_id, point_cloud.size()); ::ros::serialization::OStream stream(msg.data.data(), msg.data.size()); for (const cartographer::sensor::TimedRangefinderPoint& point : point_cloud) { stream.next(point.position.x()); stream.next(point.position.y()); stream.next(point.position.z()); stream.next(kPointCloudComponentFourMagic); } return msg; }