diff --git a/geometry_msgs/CMakeLists.txt b/geometry_msgs/CMakeLists.txt index bad3b774..ad05ae89 100644 --- a/geometry_msgs/CMakeLists.txt +++ b/geometry_msgs/CMakeLists.txt @@ -25,6 +25,8 @@ add_message_files( PoseWithCovarianceStamped.msg Quaternion.msg QuaternionStamped.msg + Ray.msg + RayStamped.msg Transform.msg TransformStamped.msg Twist.msg diff --git a/geometry_msgs/msg/Ray.msg b/geometry_msgs/msg/Ray.msg new file mode 100644 index 00000000..3f3af4c2 --- /dev/null +++ b/geometry_msgs/msg/Ray.msg @@ -0,0 +1,3 @@ +# A representation of a ray in 3-space, composed of an origin and a direction +Point origin +Vector3 direction diff --git a/geometry_msgs/msg/RayStamped.msg b/geometry_msgs/msg/RayStamped.msg new file mode 100644 index 00000000..9b1bff53 --- /dev/null +++ b/geometry_msgs/msg/RayStamped.msg @@ -0,0 +1,3 @@ +# A Ray with reference coordinate frame and timestamp +Header header +Ray ray