UWB跟随服务接口
订阅UWB原始数据接口
简介
该接口用于订阅 ROS2 的 /uwb_data
topic,以获取uwb手环反馈坐标数据。
Topic 名称 | Topic 类型(自定义message) | 角色 |
---|---|---|
/uwb_data | uwb_sensor_msgs::msg::UwbDataWithTimestamp | 订阅方 |
消息结构
uwb_sensor_msgs::msg::UwbDataWithTimestamp
包括以下字段:
x_position
:表示tag相较于anchor的x轴方向坐标/cm。y_position
:表示tag相较于anchor的y轴方向坐标/cm。- distance:表示tag相较于anchor的二维欧式距离/cm。
- phase:表示tag相较于anchor的角度信息/度。
callback示例消息
cpp
void uwb_callback(
const uwb_sensor_msgs::msg::UwbDataWithTimestamp::SharedPtr msg) {
if(msg->distance ==0 && msg->phase ==0 )
{
uwb_updated_ = false;
}else
{
msg->distance = (msg->distance)*0.01;
RCLCPP_INFO(this->get_logger(),
"Received UWB data: dis: '%f m', phase: '%f deg'",
msg->distance, msg->phase);
}
}
测试方法
- 终端使用以下命令,实时打印uwb topic:/uwb_data数据:
bash
ros2 topic echo /uwb_data
- 终端使用一下命令,实时分析uwb数据的发布频率:
bash
ros2 topic hz /uwb_data
注意事项
若打印数据,显示error或者为空,主要原因在于自定义消息体不是ros2标准库,因此打印前需要source
bash
source install/setup.bash