From 021097cd8e1b743387a4fb8574854482a41a17d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 2 Apr 2024 11:09:45 +0200 Subject: [PATCH] Added feedback MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero Update geometry_msgs/msg/VelocityStamped.msg Co-authored-by: Addisu Z. Taddese Signed-off-by: Alejandro Hernández Cordero Update geometry_msgs/msg/VelocityStamped.msg Co-authored-by: Addisu Z. Taddese Signed-off-by: Alejandro Hernández Cordero --- geometry_msgs/msg/VelocityStamped.msg | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/geometry_msgs/msg/VelocityStamped.msg b/geometry_msgs/msg/VelocityStamped.msg index 2542e8ad..ff61c6ea 100644 --- a/geometry_msgs/msg/VelocityStamped.msg +++ b/geometry_msgs/msg/VelocityStamped.msg @@ -1,11 +1,8 @@ -# This expresses the timestamped velocity of a frame 'body_frame_id' in the reference frame 'header.frame_id' expressed from arbitrary observation pose 'observation_pose'. -# The message is often used in simplified versions where: -# - observation pose is not defined, i.e., it is assumed that the observation pose is the origin of the 'header.frame_id'; -# - if the observation pose is an established frame, you may set its frame_id only in the pose (since the relative pose to that frame is Identity); -# - 'body_frame_id' and 'header.frame_id' are identical, i.e., the velocity is observed and defined in the local coordinates system of the body -# which is the usual use-case in mobile robotics. +# This expresses the timestamped velocity vector of a frame 'body_frame_id' in the reference frame 'reference_frame_id' expressed from arbitrary observation frame 'header.frame_id'. +# - If the 'body_frame_id' and 'header.frame_id' are identical, the velocity is observed and defined in the local coordinates system of the body +# which is the usual use-case in mobile robotics and is also known as a body twist. std_msgs/Header header string body_frame_id -PoseStamped observation_pose +string reference_frame_id Twist velocity