Odom 服务接口
获取里程计数据
ROS2 接口
简介
里程计服务接口用于订阅机器人的位置、方向、线速度、角速度等信息的leg_odom topic。该 topic 使用nav_msgs::msg::Odometry消息类型,包含机器人底盘所发布的里程计相关信息。
| Topic 名称 | Topic类型 | 角色 |
|---|---|---|
leg_odom | nav_msgs::msg::Odometry | 订阅方 |
消息结构
bash
std_msgs/Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist主要字段说明
| 字段名 | 说明 |
|---|---|
header.stamp | 时间戳,指示数据采集的时间。 |
header.frame_id | 坐标系ID,指示里程计pose数据所参考的坐标系。 |
child_frame_id | 表示里程计twist数据所参考的机器人坐标系。 |
pose.pose.position | 通过三维数组存储的位置信息,数组三个元素分别表示机身几何中心在世界坐标系下的x、y、z坐标值(m)。 |
pose.pose.orientation | 通过四维数组存储的方向四元数信息,用于描述机器人坐标系相对于odom坐标系的旋转状态。 |
twist.twist.linear | 机器人线速度,包括 x、y 和 z 分量。 |
twist.twist.angular | 机器人角速度,表示机身绕机器人坐标系z轴的旋转角速度(rad/s)。 |
回调函数实例
cpp
void odometryCallback(nav_msgs::msg::Odometry::SharedPtr odom_data) {
const auto& position = odom_data->pose.pose.position;
if (isOdomInvalid(Eigen::Vector3d{position.x, position.y, position.z})) {
SPDLOG_WARN("odometry data is invalid !!!");
return;
}
geometry_msgs::msg::TransformStamped transform;
// get current_pose_
transform.transform.rotation = odom_data->pose.pose.orientation;
transform.transform.translation.x = position.x;
transform.transform.translation.y = position.y;
transform.transform.translation.z = position.z;
transform.header = odom_data->header;
transform.child_frame_id = odom_data->child_frame_id;
tf_broadcaster_->sendTransform(transform);
// get current_vel_
current_vel_[0] = odom_data->twist.twist.linear.x;
current_vel_[1] = odom_data->twist.twist.linear.y;
current_vel_[2] = odom_data->twist.twist.linear.z;
current_vel_[3] = odom_data->twist.twist.angular.x;
current_vel_[4] = odom_data->twist.twist.angular.y;
current_vel_[5] = odom_data->twist.twist.angular.z;
}测试方法
- 订阅里程计消息:
bash
ros2 topic echo /leg_odom注意事项
- 获取里程计数据时,应先确保里程计 ROS2 节点已启动并正在发布
leg_odomtopic。