Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create new messages with all fields needed to define a velocity and transform it #240

Merged
merged 5 commits into from
Apr 10, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions geometry_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
)
Expand Down
8 changes: 8 additions & 0 deletions geometry_msgs/msg/VelocityStamped.msg
Original file line number Diff line number Diff line change
@@ -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