From 4926528e14bf73412187af9522295be42e7b9306 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 10 Apr 2024 09:58:14 +0200 Subject: [PATCH] Create new messages with all fields needed to define a velocity and transform it (#240) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero Co-authored-by: Dr. Denis Co-authored-by: Addisu Z. Taddese Co-authored-by: Tully Foote (cherry picked from commit 74137fc6971ac7d6420248b4394cca977fb5a887) --- geometry_msgs/CMakeLists.txt | 1 + geometry_msgs/msg/VelocityStamped.msg | 8 ++++++++ 2 files changed, 9 insertions(+) create mode 100644 geometry_msgs/msg/VelocityStamped.msg diff --git a/geometry_msgs/CMakeLists.txt b/geometry_msgs/CMakeLists.txt index df9a8d6d..e3653c6e 100644 --- a/geometry_msgs/CMakeLists.txt +++ b/geometry_msgs/CMakeLists.txt @@ -43,6 +43,7 @@ set(msg_files "msg/TwistWithCovarianceStamped.msg" "msg/Vector3.msg" "msg/Vector3Stamped.msg" + "msg/VelocityStamped.msg" "msg/Wrench.msg" "msg/WrenchStamped.msg" ) diff --git a/geometry_msgs/msg/VelocityStamped.msg b/geometry_msgs/msg/VelocityStamped.msg new file mode 100644 index 00000000..ff61c6ea --- /dev/null +++ b/geometry_msgs/msg/VelocityStamped.msg @@ -0,0 +1,8 @@ +# 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 +string reference_frame_id +Twist velocity