Skip to content

Commit 74137fc

Browse files
ahcordedestoglazeeytfoote
authored
Create new messages with all fields needed to define a velocity and transform it (#240)
Signed-off-by: Alejandro Hernández Cordero <[email protected]> Co-authored-by: Dr. Denis <[email protected]> Co-authored-by: Addisu Z. Taddese <[email protected]> Co-authored-by: Tully Foote <[email protected]>
1 parent 5b82231 commit 74137fc

File tree

2 files changed

+9
-0
lines changed

2 files changed

+9
-0
lines changed

geometry_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ set(msg_files
4545
"msg/TwistWithCovarianceStamped.msg"
4646
"msg/Vector3.msg"
4747
"msg/Vector3Stamped.msg"
48+
"msg/VelocityStamped.msg"
4849
"msg/Wrench.msg"
4950
"msg/WrenchStamped.msg"
5051
)
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
# 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'.
2+
# - 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
3+
# which is the usual use-case in mobile robotics and is also known as a body twist.
4+
5+
std_msgs/Header header
6+
string body_frame_id
7+
string reference_frame_id
8+
Twist velocity

0 commit comments

Comments
 (0)