laser_geometry将雷达scan发布为点云(scan to PointCloud2)

目前导航功能包只接受使用sensor_msgs/LaserScan或sensor_msgs/PointCloud消息类型发布的传感器数据。

sensor_msgs/LaserScansensor_msgs/PointCloud跟其他的消息一样,包括tf帧和与时间相关的信息。字段frame_id存储与数据相关联的tf帧信息。以激光扫描为例,它将是激光数据所在帧。

我们使用laser_geometry包将雷达的scan转换为点云,它只有一个C++类LaserProjection,没有ROS API.

有两个函数可以将sensor_msgs/LaserScan转换为sensor_msgs/PointCloud或者sensor_msgs/PointCloud2projectLaser()简单快速,不改变数据的frame; transformLaserScanToPointCloud()速度慢但是精度高,使用tfsensor_msgs/LaserScantime_increment转换每束激光,对倾斜的雷达或移动的机器人,推荐这种方法。

sensor_msgs/PointCloud还包括一些额外的通道,例如intensities, distances, timestamps, index 或者thew viewpoint
支持将三维空间中的点的数组以及任何保存在一个信道中的相关数据。例如,一条带有intensity信道的 PointCloud 可以保持点云数据中每一个点的强度。

projectLaser

它执行最简单的激光投射,每束激光投射出去的角度根据的是以下公式:

但最后形成的点云消息,坐标系还是laser,不适用于雷达移动或畸变不能忽略的情况。

transformLaserScanToPointCloud

这种方法需要tf变换,由于我们是扫描过程中一直收集数据,选择的target_frame必须是固定的。因为sensor_msgs/LaserScan的时间戳是第一次测量的时间,这个时间还无法转换到target_frame,得等到最后一个雷达的测量时间完成坐标系转换。

代码

依赖包是laser_geometry, pcl_conversions, pcl_ros
修改package.xml文件,添加

1
2
<build_depend>libpcl-all-dev</build_depend>
<exec_depend>libpcl-all</exec_depend>

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
#include "ros/ros.h"
#include "laser_geometry/laser_geometry.h"
#include "sensor_msgs/LaserScan.h"
#include "sensor_msgs/PointCloud.h"
#include "tf/transform_listener.h"
#include <boost/shared_ptr.hpp>

laser_geometry::LaserProjection projector;
ros::Publisher pub;
boost::shared_ptr<tf::TransformListener> listener_;

void chatterCallback(const sensor_msgs::LaserScan::ConstPtr& msg)
{
sensor_msgs::PointCloud2 cloud;
// projector.projectLaser(*msg, cloud); // 第一种方法

if(!listener_->waitForTransform(
"/base_link",
msg->header.frame_id,
msg->header.stamp + ros::Duration().fromSec(msg->ranges.size()*msg->time_increment),
ros::Duration(2.0)) )
{
ROS_WARN("no transform");
return;
}
projector.transformLaserScanToPointCloud("/base_link",*msg,
cloud, *listener_);
pub.publish(cloud);
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "laser_toCloud");
ros::NodeHandle nh;
listener_ = boost::make_shared<tf::TransformListener>();
pub = nh.advertise<sensor_msgs::PointCloud2>("cloud",10);
ros::Subscriber sub = nh.subscribe("/scan", 1000, chatterCallback); // 先有发布的scan话题

ros::spin();
return 0;
}

参考:
激光LeGO-LOAM生成pcd点云地图保存和格式转换
LaserScan转pcl::PointCloud
laser_geometry