ROS交流群
ROS Group 产品服务
Product Service 开源代码库
Github 官网
Official website 技术交流
Technological exchanges 激光雷达
LIDAR ROS教程
ROS Tourials 深度学习
Deep Learning 机器视觉
Computer Vision
ROS Group 产品服务
Product Service 开源代码库
Github 官网
Official website 技术交流
Technological exchanges 激光雷达
LIDAR ROS教程
ROS Tourials 深度学习
Deep Learning 机器视觉
Computer Vision
使用depthimage_to_laserscan包将kinect深度图像转换成2d激光雷达话题
-
kinect 1代的驱动包freenct_stack可以输出深度图像和点云,理论上可以使用pointcloud_to_laserscan包将点云转换成scan数据,但是freenct_stack包输出的点云数据所在的坐标系不是常用的base_link坐标系,要先进行坐标变换才能转换,这导致pointcloud_to_laserscan包效率很低。
#运行下列命令可以测试pointcloud_to_laserscan包的转换功能,用“rostopic hz /kinect/scan”查看输出的/kinect/scan话题发布频率,可以发现值很低,即转换效率太低不实用 roslaunch pointclound_to_laserscan xiaoqiang_lungu_kinect.launch
下文将介绍使用depthimage_to_laserscan包将kinect深度图像转换成2d激光雷达话题的详细步骤,这种方法输出的雷达话题/kinect/scan,频率高达20HZ,满足实时性要求。
1.安装depthimage_to_laserscan包
#需要安装到ros工作空间,以小强主机为例 cd ~/Documents/ros/src git clone https://github.com/BluewhaleRobot/depthimage_to_laserscan.git cd .. catkin_make
2.启动转换节点开始测试
freenct_stack驱动发布的深度图像/kinect/depth/image被 depthimage_to_laserscan节点订阅后将其转换成laserscan话题/kinect/scan,所在的frame_id则是“kinect_link”
#新开一个终端 #如果是小强xq5轮毂电机版本,请启动这个launch文件 roslaunch depthimage_to_laserscan xiaoqiang_lungu_kinect.launch #如果是小强xq4-pro普通电机版本,请启动这个launch文件 roslaunch depthimage_to_laserscan xiaoqiang_pro_kinect.launch #新开一个终端将kinect角度设为水平方向 rostopic pub /set_tilt_degree std_msgs/Int16 '{data: 0}' -1
正常的话,现在就可以获取10hz的laserscan类型话题数据了
#新开一个终端,查看转换后的/kinect/scan话题发布频率 rostopic hz /kinect/scan
4.在rviz中查看2d雷达数据
roscd depthimage_to_laserscan/launch/ rviz -d kinect.rviz #图中白线就是转换输出的2d雷达数据