Odom service interface
Get Odometer Data
Introduction
the odometer service interface is used to subscribe to the position, direction, linear velocity, angular velocity and other leg_odom
topic information of the robot. This topic uses nav_msgs::msg::Odometry
message type containing information about the odometer issued by the robot chassis.
Topic Name | Topic type | role |
---|---|---|
leg_odom | nav_msgs::msg::Odometry | subscriber |
Message Structure
bash
std_msgs/Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist
Main Field Description
header
: A standard ROS message header that contains a timestamp and coordinate system.
stamp
: Timestamp, indicating the time of data collection.frame_id
: Coordinate system ID, indicating the coordinate system referenced by the odometer pose data.child_frame_id
: Indicates the robot coordinate system referenced by the odometer twist data.
pose
: The pose information of the robot, usually including the position ( position ) and direction ( orientation ).
pose.pose.position
: Position information stored through a three-dimensional array. The three elements of the array respectively represent the x, y, and z coordinate values of the geometric center of the fuselage under the World coordinate system (m)pose.pose.orientation
: The direction quaternion information stored through the four-dimensional array is used to describe the rotation state
twist
: The linear velocity and angular velocity information of the robot, used to represent the motion state of the robot.
twist.twist.linear
: Robot linear velocity, including x, y, and z components.twist.twist.angular
: Robot angular velocity, which represents the rotational angular velocity of the fuselage around the z axis of the robot coordinate system (rad/s)
Callback Function Instance
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;
}
Test Method
- subscribe to odometer messages:
bash
ros2 topic echo /leg_odom
Precautions
- when obtaining odometer data, first ensure that the odometer ROS2 node has been started and is being released leg_odom topic.