diff --git a/geometry_msgs/CMakeLists.txt b/geometry_msgs/CMakeLists.txt index 9d5df7ab..89e4e177 100644 --- a/geometry_msgs/CMakeLists.txt +++ b/geometry_msgs/CMakeLists.txt @@ -25,6 +25,8 @@ set(msg_files "msg/Point32.msg" "msg/PointStamped.msg" "msg/Polygon.msg" + "msg/PolygonInstance.msg" + "msg/PolygonInstanceStamped.msg" "msg/PolygonStamped.msg" "msg/Pose.msg" "msg/Pose2D.msg" diff --git a/geometry_msgs/msg/PolygonInstance.msg b/geometry_msgs/msg/PolygonInstance.msg new file mode 100644 index 00000000..cb823162 --- /dev/null +++ b/geometry_msgs/msg/PolygonInstance.msg @@ -0,0 +1,5 @@ +# A specification of a polygon where the first and last points are assumed to be connected +# It includes a unique identification field for disambiguating multiple instances + +geometry_msgs/Polygon polygon +int64 id \ No newline at end of file diff --git a/geometry_msgs/msg/PolygonInstanceStamped.msg b/geometry_msgs/msg/PolygonInstanceStamped.msg new file mode 100644 index 00000000..33bc2d55 --- /dev/null +++ b/geometry_msgs/msg/PolygonInstanceStamped.msg @@ -0,0 +1,5 @@ +# This represents a Polygon with reference coordinate frame and timestamp +# It includes a unique identification field for disambiguating multiple instances + +std_msgs/Header header +geometry_msgs/PolygonInstance polygon \ No newline at end of file