From 558cb17fa06489fccae61c6b36c535ffac083e7f Mon Sep 17 00:00:00 2001 From: Maximilian Naumann Date: Wed, 22 May 2019 13:04:03 -0700 Subject: [PATCH 1/3] Fix acceleration message --- nav_msgs/msg/OdometryWithAcceleration.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav_msgs/msg/OdometryWithAcceleration.msg b/nav_msgs/msg/OdometryWithAcceleration.msg index c221ae80..5a47ba46 100644 --- a/nav_msgs/msg/OdometryWithAcceleration.msg +++ b/nav_msgs/msg/OdometryWithAcceleration.msg @@ -6,4 +6,4 @@ Header header string child_frame_id geometry_msgs/PoseWithCovariance pose geometry_msgs/TwistWithCovariance velocity -geometry_msgs/TwistWithCovariance acceleration +geometry_msgs/AccelWithCovariance accel From 7016864fe20297c0c75ea667f6413418ffdc8234 Mon Sep 17 00:00:00 2001 From: Maximilian Naumann Date: Wed, 22 May 2019 13:04:30 -0700 Subject: [PATCH 2/3] Keep the name twist for velocities --- nav_msgs/msg/Odometry.msg | 2 +- nav_msgs/msg/OdometryWithAcceleration.msg | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/nav_msgs/msg/Odometry.msg b/nav_msgs/msg/Odometry.msg index dc62bc85..a40ea9f0 100644 --- a/nav_msgs/msg/Odometry.msg +++ b/nav_msgs/msg/Odometry.msg @@ -4,4 +4,4 @@ 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 5a47ba46..02d82adb 100644 --- a/nav_msgs/msg/OdometryWithAcceleration.msg +++ b/nav_msgs/msg/OdometryWithAcceleration.msg @@ -5,5 +5,5 @@ Header header string child_frame_id geometry_msgs/PoseWithCovariance pose -geometry_msgs/TwistWithCovariance velocity +geometry_msgs/TwistWithCovariance twist geometry_msgs/AccelWithCovariance accel From 9c7cec6f4b341554a4dc6d983e548a78ba0216e6 Mon Sep 17 00:00:00 2001 From: Maximilian Naumann Date: Wed, 22 May 2019 13:05:29 -0700 Subject: [PATCH 3/3] Add documentation for treatment of incomplete information --- nav_msgs/msg/Odometry.msg | 13 ++++++++++++- nav_msgs/msg/OdometryWithAcceleration.msg | 11 +++++++++++ 2 files changed, 23 insertions(+), 1 deletion(-) diff --git a/nav_msgs/msg/Odometry.msg b/nav_msgs/msg/Odometry.msg index a40ea9f0..a7fee9b1 100644 --- a/nav_msgs/msg/Odometry.msg +++ b/nav_msgs/msg/Odometry.msg @@ -1,6 +1,17 @@ # 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 diff --git a/nav_msgs/msg/OdometryWithAcceleration.msg b/nav_msgs/msg/OdometryWithAcceleration.msg index 02d82adb..849b4aca 100644 --- a/nav_msgs/msg/OdometryWithAcceleration.msg +++ b/nav_msgs/msg/OdometryWithAcceleration.msg @@ -2,6 +2,17 @@ # 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