鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    ros2中如何将单线雷达的2D:laser_scan数据转换成3D:pointcloud2类型数据

    已定时 已固定 已锁定 已移动
    ROS 2相关问题
    雷达 数据转换
    4
    10
    1.2k
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • senS
      Sen
      最后由 编辑

      各位大佬们,我想问的如题!

      小鱼小 2 条回复 最后回复 回复 引用 0
      • 14002765871
        庙堂不见江湖见
        最后由 编辑

        同样想问!!!求大佬解答!

        1 条回复 最后回复 回复 引用 0
        • 小鱼小
          小鱼 技术大佬 @sen
          最后由 编辑

          @sen 请看这个包:https://github.com/ros-perception/pointcloud_to_laserscan/tree/humble

          接下来说说怎么用

          安装

          首先是安装,直接下载安装或者apt直接的装都可以.推荐apt

          sudo apt install ros-humble-pointcloud-to-laserscan
          
          sudo apt install ros-humble-pointcloud-to-laserscan
          [sudo] fishros 的密码: 
          正在读取软件包列表... 完成
          正在分析软件包的依赖关系树... 完成
          正在读取状态信息... 完成                 
          下列软件包是自动安装的并且现在不需要了:
          .......
          使用'sudo apt autoremove'来卸载它(它们)。
          下列【新】软件包将被安装:
            ros-humble-pointcloud-to-laserscan
          升级了 0 个软件包,新安装了 1 个软件包,要卸载 0 个软件包,有 536 个软件包未被升级。
          需要下载 253 kB 的归档。
          解压缩后会消耗 1,434 kB 的额外空间。
          获取:1 http://mirrors.tuna.tsinghua.edu.cn/ros2/ubuntu jammy/main amd64 ros-humble-pointcloud-to-laserscan amd64 2.0.1-3jammy.20221108.191144 [253 kB]
          已下载 253 kB,耗时 2秒 (145 kB/s)                                 
          正在选中未选择的软件包 ros-humble-pointcloud-to-laserscan。
          进度:[ 100%] 
          

          使用

          这个包可以帮我们直接把雷达话题数据转换成点云话题数据发布出来,所以你啥都不用干,提供必要信息,直接运行这个节点就可以了

          随手新建一个launch文件,test_laserscan2pcl2.py,写入下面内容

          from launch import LaunchDescription
          from launch.actions import DeclareLaunchArgument
          from launch.actions import ExecuteProcess
          from launch.substitutions import LaunchConfiguration
          from launch_ros.actions import Node
          
          import yaml
          
          
          def generate_launch_description():
              return LaunchDescription([
                  DeclareLaunchArgument(
                      name='scanner', default_value='scanner',
                      description='Namespace for sample topics'
                  ),
                  ExecuteProcess(
                      cmd=[
                          'ros2', 'topic', 'pub', '-r', '10',
                          '--qos-profile', 'sensor_data',
                          [LaunchConfiguration(variable_name='scanner'), '/scan'],
                          'sensor_msgs/msg/LaserScan', yaml.dump({
                              'header': {'frame_id': 'scan'}, 'angle_min': -1.0,
                              'angle_max': 1.0, 'angle_increment': 0.1, 'range_max': 10.0,
                              'ranges': [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
                          })
                      ],
                      name='scan_publisher'
                  ),
                  Node(
                      package='tf2_ros',
                      executable='static_transform_publisher',
                      name='static_transform_publisher',
                      arguments=[
                          '--x', '0', '--y', '0', '--z', '0',
                          '--qx', '0', '--qy', '0', '--qz', '0', '--qw', '1',
                          '--frame-id', 'map', '--child-frame-id', 'scan'
                      ]
                  ),
                  Node(
                      package='pointcloud_to_laserscan',
                      executable='laserscan_to_pointcloud_node',
                      name='laserscan_to_pointcloud',
                      remappings=[('scan_in', [LaunchConfiguration(variable_name='scanner'), '/scan']),
                                  ('cloud', [LaunchConfiguration(variable_name='scanner'), '/cloud'])],
                      parameters=[{'target_frame': 'scan', 'transform_tolerance': 0.01}]
                  ),
              ])
          

          接着直接ros2 launch test_laserscan2pcl2.py ,接着我们就可以打开rviz2来看看这些数据,或者用ros2 topic list 或者echo出来了

          上一个rviz的图

          403665e8-de9f-4a1f-9a57-5b066c697b31-image.png

          新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

          5107211675 1 条回复 最后回复 回复 引用 0
          • 小鱼小
            小鱼 技术大佬 @sen
            最后由 编辑

            @sen 已回答,请查看上一条回复!

            新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

            senS 1 条回复 最后回复 回复 引用 0
            • senS
              Sen @小鱼
              最后由 编辑

              @小鱼 谢谢小鱼,想请问一下,带message_fliter的转换和不带的转换在数据上有什么差别,哪个更有优势一点呢?

              小鱼小 1 条回复 最后回复 回复 引用 0
              • 小鱼小
                小鱼 技术大佬 @sen
                最后由 编辑

                @sen message_fliter 主要是用于消息过滤和同步使用,如果想将雷达数据和点云数据在时间上对齐或者做其他操作,可以使用message_fliter

                新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                senS 1 条回复 最后回复 回复 引用 0
                • senS
                  Sen @小鱼
                  最后由 编辑

                  @小鱼 这个在时间上对齐是指,从第一帧转换数据往后,让点云数据的间隔和雷达数据的间隔相同吗?我对这方面了解比较少,问题可能比较笨,谢谢小鱼了

                  小鱼小 1 条回复 最后回复 回复 引用 0
                  • 小鱼小
                    小鱼 技术大佬 @sen
                    最后由 编辑

                    @sen 如果我没理解错是这样,让你接收的雷达点数据和点云数据时间上匹配,也就是同一刻的数据

                    新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                    senS 1 条回复 最后回复 回复 引用 0
                    • senS
                      Sen @小鱼
                      最后由 编辑

                      @小鱼 好的,谢谢小鱼

                      1 条回复 最后回复 回复 引用 0
                      • 5107211675
                        十一。 @小鱼
                        最后由 编辑

                        此回复已被删除!
                        1 条回复 最后回复 回复 引用 0
                        • 第一个帖子
                          最后一个帖子
                        皖ICP备16016415号-7
                        Powered by NodeBB | 鱼香ROS