diff --git a/nav_msgs/msg/Odometry.msg b/nav_msgs/msg/Odometry.msg index dc62bc85..a7fee9b1 100644 --- a/nav_msgs/msg/Odometry.msg +++ b/nav_msgs/msg/Odometry.msg @@ -1,7 +1,18 @@ # This represents an estimate of a position and velocity in free space. # The pose in this message should be specified in the coordinate frame given by header.frame_id. -# The velocity in this message should be specified in the coordinate frame given by the child_frame_id +# The velocity in this message should be specified in the coordinate frame given by the child_frame_id. +# +# If the covariance of the measurement is known, it should be filled in (if all you know is the +# variance of each measurement, e.g. from a datasheet, just put those along the diagonal). +# A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the +# data a covariance will have to be assumed or gotten from some other source. +# +# If you have no estimate for one of the data elements, please set _the respective diagonal_ element +# of the associated covariance matrix to -1. +# If you are interpreting this message, please check for a value of -1 in the _diagonal_ elements +# of each covariance matrix, and disregard the associated estimates. + Header header string child_frame_id geometry_msgs/PoseWithCovariance pose -geometry_msgs/TwistWithCovariance twist # velocity but keeping name for backwards compatibility +geometry_msgs/TwistWithCovariance twist diff --git a/nav_msgs/msg/OdometryWithAcceleration.msg b/nav_msgs/msg/OdometryWithAcceleration.msg index c221ae80..849b4aca 100644 --- a/nav_msgs/msg/OdometryWithAcceleration.msg +++ b/nav_msgs/msg/OdometryWithAcceleration.msg @@ -2,8 +2,19 @@ # The pose in this message should be specified in the coordinate frame given by header.frame_id. # The velocity in this message should be specified in the coordinate frame given by the child_frame_id. # The acceleration in this message should be specified in the coordinate frame given by the child_frame_id. +# +# If the covariance of the measurement is known, it should be filled in (if all you know is the +# variance of each measurement, e.g. from a datasheet, just put those along the diagonal). +# A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the +# data a covariance will have to be assumed or gotten from some other source. +# +# If you have no estimate for one of the data elements, please set _the respective diagonal_ element +# of the associated covariance matrix to -1. +# If you are interpreting this message, please check for a value of -1 in the _diagonal_ elements +# of each covariance matrix, and disregard the associated estimates. + Header header string child_frame_id geometry_msgs/PoseWithCovariance pose -geometry_msgs/TwistWithCovariance velocity -geometry_msgs/TwistWithCovariance acceleration +geometry_msgs/TwistWithCovariance twist +geometry_msgs/AccelWithCovariance accel