紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
求助pointcloud_to_laserscan转换后rviz无法显示问题
-
使用的速腾16线激光雷达,需使用pointcloud_to_laserscan转换为/scan用作cartographer 2D建图测试,但在运行相关节点并订阅/scan消息后,/scan消息有输出,rviz2中按topic添加/LaserScan无可视化输出,请问如何解决?谢谢
其中转换launch文件pointcloud_to_laserscan.launch.py如下:
from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): return LaunchDescription([ Node( package='pointcloud_to_laserscan', executable='pointcloud_to_laserscan_node', remappings=[('cloud_in', 'rslidar_points'), ('scan', 'scan')], parameters=[{ 'target_frame': 'cloud', 'transform_tolerance': 0.01, 'min_height': 0.0, 'max_height': 1.0, 'angle_min': -3.1415926, # -M_PI/2 'angle_max': 3.1415926, # M_PI/2 'angle_increment': 0.0087, # M_PI/360.0 'scan_time': 0.1, 'range_min': 0.2, 'range_max': 100.0, 'use_inf': True, 'inf_epsilon': 1.0 }], name='pointcloud_to_laserscan' ) ])
point2scan节点信息如下:
$ ros2 node info /pointcloud_to_laserscan /pointcloud_to_laserscan Subscribers: /parameter_events: rcl_interfaces/msg/ParameterEvent Publishers: /parameter_events: rcl_interfaces/msg/ParameterEvent /rosout: rcl_interfaces/msg/Log /scan: sensor_msgs/msg/LaserScan Service Servers: /pointcloud_to_laserscan/describe_parameters: rcl_interfaces/srv/DescribeParameters /pointcloud_to_laserscan/get_parameter_types: rcl_interfaces/srv/GetParameterTypes /pointcloud_to_laserscan/get_parameters: rcl_interfaces/srv/GetParameters /pointcloud_to_laserscan/list_parameters: rcl_interfaces/srv/ListParameters /pointcloud_to_laserscan/set_parameters: rcl_interfaces/srv/SetParameters /pointcloud_to_laserscan/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically Service Clients: Action Servers: Action Clients:
雷达节点信息如下:
$ ros2 node info /rslidar_sdk/rslidar_points_destination_0 /rslidar_sdk/rslidar_points_destination_0 Subscribers: /parameter_events: rcl_interfaces/msg/ParameterEvent Publishers: /parameter_events: rcl_interfaces/msg/ParameterEvent /rosout: rcl_interfaces/msg/Log /rslidar_points: sensor_msgs/msg/PointCloud2 Service Servers: /rslidar_sdk/rslidar_points_destination_0/describe_parameters: rcl_interfaces/srv/DescribeParameters /rslidar_sdk/rslidar_points_destination_0/get_parameter_types: rcl_interfaces/srv/GetParameterTypes /rslidar_sdk/rslidar_points_destination_0/get_parameters: rcl_interfaces/srv/GetParameters /rslidar_sdk/rslidar_points_destination_0/list_parameters: rcl_interfaces/srv/ListParameters /rslidar_sdk/rslidar_points_destination_0/set_parameters: rcl_interfaces/srv/SetParameters /rslidar_sdk/rslidar_points_destination_0/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically Service Clients: Action Servers: Action Clients:
rviz界面如下:
请提出任何修改意见,谢谢!
-
-
我找到了问题所在,是QoS的问题,特此记录。
详细信息参考LaserScan showing [0] points from [0] messages -
-
麻烦问一下这个会影响后续用来建图吗,我现在也是pointcloud转laserscan之后,在rviz里调整策略为best effort后可以看到单线激光数据,但是发现用来跑cartographer好像有点问题,不知道是不是和这个有关
-
@654799839 我使用的过程中没有影响后续的cartographer建图和定位,可以在启动cartographer后用rqt_graph看下.