- 8探头超声波 F40-16TR
# 1.0 编译
colcon build --symlink-install --packages-select ultra_sonic_radar_driver
# 2.0 运行
source install/setup.bash
ros2 launch ultra_sonic_radar_driver mc_radar_driver.launch.xml
# 3.0 激活
ros2 topic pub -1 /sensing/ultra_sonic_radar/activate_radar std_msgs/msg/Bool "{data: True}"
order: [0, 1, 2, 3, 4, 5, 6, 7] # order of detector
field_of_view_radian: [0.52, 0.52, 0.52, 0.52, 0.52, 0.52, 0.52, 0.52] # radians
min_range_m: [0.2, 0.2, 0.2, 0.2, 0.2, 0.2, 0.2, 0.2] # m
max_range_m: [2.0, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0] # m
Input | Data Type | Explanation |
---|---|---|
header | std_msgs/Header | header |
0号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_0 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标0 |
1号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_1 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标1 |
2号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_2 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标2 |
3号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_3 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标3 |
4号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_4 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标4 |
5号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_5 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标5 |
6号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_6 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标6 |
7号探头的数据 | /sensing/ultra_sonic_radar/ultra_sonic_radar_7 ( sensor_msgs::msg::Range ) |
对应配置文件order字段下标7 |
如果超声波安装位置没有正确,可以通过调整config.param.yaml
order字段,让对应位置的超声波探头传出的对应的话题上