Skip to content

Odom Service Interface


Odometry Data Retrieval Interface

ROS 2 Interface

Overview

This interface is used to subscribe to the robot's odometry data, including position, orientation, linear velocity, and angular velocity, via the /leg_odom topic. The topic uses the nav_msgs::msg::Odometry message type, which contains odometry information published by the robot's chassis.

Topic NameMessage TypeRole
leg_odomnav_msgs::msg::OdometrySubscriber

Message Structure

bash
std_msgs/Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist

Key Field Descriptions

Field NameDescription
header.stampTimestamp indicating the data acquisition time.
header.frame_idFrame of reference for the pose data.
child_frame_idFrame of reference for the twist (velocity) data, typically the robot's base frame.
pose.pose.position3D position of the robot's geometric center in the world frame (x, y, z in meters).
pose.pose.orientationOrientation represented as a quaternion (x, y, z, w), describing the robot's rotation relative to the odometry frame.
twist.twist.linearLinear velocity along x, y, and z axes.
twist.twist.angularAngular velocity (e.g., yaw rate around the z-axis, in rad/s).

Callback Example

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;
}

Testing Method

  • To view odometry messages in real time, run:
bash
ros2 topic echo /leg_odom

Precautions

  • Before retrieving odometry data, ensure that the ROS 2 node responsible for publishing the /leg_odom topic has been properly launched and is running.