介绍
如何在ROS中使用镭神智能C16系列小型化16线混合固态激光雷达使用PCL进行可视化处理。
镭神智能16线激光雷达
镭神智能自主研发的16线激光雷达,其拥有超高性价比,可适用于室外无人车,汽车辅助驾驶(ADAS)、无人驾驶等领域
参数:测量距离 150m,精度 3cm,水平 360°,垂直 30°(±15°),数据获取速度为 32 万点每秒。
C16 激光雷达通过内置激光探头对周围环境进行 360 度扫描,依靠激光遇到障碍后的折返时间,计算出相对距离(TOF),并生成物体的 3D 轮廓,可绘出汽车周围环境的高精度地图,它比相对更普及的可见光摄像头看得更精确更远,且不受光线影响。
流程
运行雷达节点
$roslaunch lslidar_c16_decoder lslidar_c16.launch --screen
备注:
若出现timeout则表示接收不到数据,请检查硬件连接
若修改了雷达目的端口及转速,请打开 lslidar_C16.launch 进行相应的修改配置,默认IP为192.168.1.200,默认端口为2368,转速为 10HZ 即 point_num 为 2000
使用rviz可视化
$rosrun rviz rviz -d `rospack find lslidar_c16_decoder`/launch/lslidar_c16.rviz
在弹出的 Displays 窗口中,将“Fixed Frame”的值修改成 laser_link 即可,同时点击 add 按钮,在 By topic 下点击 PointCloud2 添加多线点云节点。
代码详情
使用PCL源码对雷达点云进行可视化。
#include <ros/ros.h>
#include <iostream>
// PCL specific includes
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/visualization/cloud_viewer.h>
using namespace std;
boost::shared_ptr<pcl