diff --git a/nav_msgs/msg/Odometry.msg b/nav_msgs/msg/Odometry.msg index 73578ed8..dc62bc85 100644 --- a/nav_msgs/msg/Odometry.msg +++ b/nav_msgs/msg/Odometry.msg @@ -1,7 +1,7 @@ # 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 twist 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 Header header string child_frame_id geometry_msgs/PoseWithCovariance pose -geometry_msgs/TwistWithCovariance twist +geometry_msgs/TwistWithCovariance twist # velocity but keeping name for backwards compatibility diff --git a/nav_msgs/msg/OdometryWithAcceleration.msg b/nav_msgs/msg/OdometryWithAcceleration.msg new file mode 100644 index 00000000..c221ae80 --- /dev/null +++ b/nav_msgs/msg/OdometryWithAcceleration.msg @@ -0,0 +1,9 @@ +# This represents an estimate of a position, velocity, and acceleration 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 acceleration in this message should be specified in the coordinate frame given by the child_frame_id. +Header header +string child_frame_id +geometry_msgs/PoseWithCovariance pose +geometry_msgs/TwistWithCovariance velocity +geometry_msgs/TwistWithCovariance acceleration