ROS交流群
ROS Group
产品服务
Product Service
开源代码库
Github
官网
Official website
技术交流
Technological exchanges
激光雷达
LIDAR
ROS教程
ROS Tourials
深度学习
Deep Learning
机器视觉
Computer Vision

使用pointcloud_to_laserscan包将速腾聚创3d激光雷达转换成高质量2d激光雷达



  • 将3d激光雷达转换成2d雷达,有两种方式:一种是只使用3d雷达中的一条扫描线,另一种是将多条扫描线合成一条2d雷达扫描线。使用pointcloud_to_laserscan包可以很方便地实现第二种办法,第二种方法因为使用了多条扫描线,因此可以输出更高质量的2d雷达数据。
    下文将演示如何将速腾聚创激光雷达rslidar-16的三维点云数据转换成平面的ros laserscan话题。

    1.安装pointcloud_to_laserscan包

    #需要安装到ros工作空间,以小强主机为例
    cd ~/Documents/ros/src
    git clone https://github.com/BluewhaleRobot/pointcloud_to_laserscan.git
    cd  ..
    catkin_make
    

    2.启动ros_rslidiar雷达驱动包和pointcloud_to_laserscan节点

    雷达驱动发布三维点云数据/rsldiar_points, pointcloud_to_laserscan节点订阅后将其转换成laserscan话题/rslidar/scan,两者的frame_id都是“rsldiar”

    #新开一个终端,启动3d雷达驱动
    #如果是小强xq5轮毂电机版本,请启动这个launch文件
    roslaunch rslidar_pointcloud xiaoqiang_lungu.launch
    #如果是小强xq4-pro普通电机版本,请启动这个launch文件
    roslaunch rslidar_pointcloud xiaoqiang_pro.launch
    
    #新开一个终端,启动pointcloud_to_laserscan节点
    roslaunch pointcloud_to_laserscan xiaoqiang_rslidar.launch
    

    正常的话,现在就可以获取10hz的laserscan类型话题数据了
    275e1b43-a092-48f6-a887-93430c335555-image.png

    4.在rviz中查看2d雷达数据

    roscd  pointcloud_to_laserscan/rviz/
    rviz -d  rsldiar.rviz
    
    #图中白线就是转换输出的2d雷达数据
    

    93f0c804-7960-4e14-a55e-03e682344b9e-image.png

    5.pointcloud_to_laserscan 中xiaoqiang_rslidar.launch文件参数简介

    pointcloud_to_laserscan假定输入的点云数据坐标系是这样分布的:前进方向为x,重力反方向是z轴,左边是y轴的右手系

    min_height 、max_height #这两个参数用来指定这段z轴高度范围内的输入点云将参与转换,范围外的不参与
    angle_min、angle_max #这两个参数用来指定这段yaw角度范围内的输入点云将参与转换,范围外的不参与
    angle_increment #输出的2d雷达数据的角分辨率,即相邻扫描点的角度增量
    scan_time #扫描时间,即话题的发布周期
    range_min、range_max #这两个参数用来指定输出数据的有效距离,即2d雷达的有效测量范围
    


  • 原来这个包这个有用,改下launch就能用



  • @xiaoqiang kinect1.0是否也可以用这个包将点云压缩为2D激光雷达?



  • @gejiaqi1117 可以,只要是点云都可以转



  • @weijiz 根据BluewhaleRobot改成这样:<param name=“output_frame_id” value=’/kinect_link",<remap from=“cloud in” to="/kinect/depth/points"/
    <remap from=“scan” to ="/scan"

    但是在rviz中运行freenect-xyz.launch 和这个包时,还是freenect-xyz的点云显示,不知道是不是哪里有问题,请大神帮忙看看,感谢!



  • 可否出一个基于kinect转激光雷达的版本



  • @gejiaqi1117 这种教程网上已经很多了,后续我们会在小强的freenect_stack包里面增加一个演示launch文件



  • @xiaoqiang 您好,我在xq4kinect1.0应用此包时,<remap from =“scan” to ="/scan’ />,检查到/scan ranges[inf,inf…],是什么原因呢?



  • @gejiaqi1117 参考这里https://community.bwbot.org/topic/765/使用depthimage_to_laserscan包将kinect深度图像转换成2d激光雷达话题



  • @雾琴水音 参考这里https://github.com/BluewhaleRobot/pointcloud_to_laserscan/blob/lunar-devel/launch/xiaoqiang_lungu_kinect.launch



  • @xiaoqiang 谢谢您


Log in to reply