里程计消息nav_msgs/Odometry 结构如下
Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist
协方差解释:
As a robot moves around, the uncertainty on its pose in a world reference continues to grow larger and larger. Over time, the covariance would grow without bounds. Therefore it is not useful to publish the covariance on the pose itself, instead the sensor sources publish how the covariance changes over time, i.e. the covariance on the velocity. Note that using observations of the world (e.g. measuring the distance to a known wall) will reduce the uncertainty on the robot pose; this however is localization, not odometry.
来自robot_pose_ekf;
这里说的是,协方差表示的是协方差如何变化的!一个位姿的协方差是没有意义的,因为随着时间的累计,协方差将变的非常大。
这样的话,可以理解turtebot中,为什么发布的里程计协方差为一个常量,而不是随时间增大的量。
void Odometry::publishOdometry(const geometry_msgs::Quaternion &odom_quat,
const ecl::linear_algebra::Vector3d &pose_update_rates)
{
// Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature
nav_msgs::OdometryPtr odom(new nav_msgs::Odometry);
// Header
odom->header.stamp = ros::Time::now();
odom->header.frame_id = odom_frame;
odom->child_frame_id = base_frame;
// Position
odom->pose.pose.position.x = pose.x();
odom->pose.pose.position.y = pose.y();
odom->pose.pose.position.z = 0.0;
odom->pose.pose.orientation = odom_quat;
// Velocity
odom->twist.twist.linear.x = pose_update_rates[0];
odom->twist.twist.linear.y = pose_update_rates[1];
odom->twist.twist.angular.z = pose_update_rates[2];
// Pose covariance (required by robot_pose_ekf) TODO: publish realistic values
// Odometry yaw covariance must be much bigger than the covariance provided
// by the imu, as the later takes much better measures
odom->pose.covariance[0] = 0.1; // x的协方差
odom->pose.covariance[7] = 0.1; // y的协方差
odom->pose.covariance[35] = use_imu_heading ? 0.05 : 0.2; //theta的协方差
odom->pose.covariance[14] = 1e10; // set a non-zero covariance on unused theta x axis
odom->pose.covariance[21] = 1e10; // dimensions (z, pitch and roll); this theta y axis
odom->pose.covariance[28] = 1e10; // is a requirement of robot_pose_ekf theta z axis
odom_publisher.publish(odom);
}