From 104e644e21018b43c5b9ea4a39c9b5671a7405cf Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 18 Jan 2024 20:06:44 +0000 Subject: [PATCH] adding IDs to geometry_msgs/Polygon, PolygonStamped (#232) * adding PolygonInstance msgs Signed-off-by: Steve Macenski Co-authored-by: Michael Carroll Co-authored-by: Chris Lalancette --- geometry_msgs/CMakeLists.txt | 2 ++ geometry_msgs/README.md | 2 ++ geometry_msgs/msg/PolygonInstance.msg | 5 +++++ geometry_msgs/msg/PolygonInstanceStamped.msg | 5 +++++ 4 files changed, 14 insertions(+) create mode 100644 geometry_msgs/msg/PolygonInstance.msg create mode 100644 geometry_msgs/msg/PolygonInstanceStamped.msg diff --git a/geometry_msgs/CMakeLists.txt b/geometry_msgs/CMakeLists.txt index df9a8d6d..5b6f31c2 100644 --- a/geometry_msgs/CMakeLists.txt +++ b/geometry_msgs/CMakeLists.txt @@ -26,6 +26,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/README.md b/geometry_msgs/README.md index 34a95139..2cad7e12 100644 --- a/geometry_msgs/README.md +++ b/geometry_msgs/README.md @@ -15,6 +15,8 @@ For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros * [Point](msg/Point.msg): The position of a 3-dimensional point in free space. * [PointStamped](msg/PointStamped.msg): Point with reference coordinate frame and timestamp. * [Polygon](msg/Polygon.msg): A specification of a polygon where the first and last points are assumed to be connected. +* [PolygonInstance](msg/PolygonInstance.msg): A specification of a polygon where the first and last points are assumed to be connected. Contains an identification field for disambiguation of multiple instances. +* [PolygonInstanceStamped](msg/PolygonInstanceStamped.msg): A Polygon with reference coordinate frame and timestamp. Contains an identification field for disambiguation of multiple instances. * [PolygonStamped](msg/PolygonStamped.msg): A Polygon with reference coordinate frame and timestamp. * [Pose2D](msg/Pose2D.msg): **Deprecated as of Foxy and will potentially be removed in any following release.** * [PoseArray](msg/PoseArray.msg): An array of poses with a header for global reference. diff --git a/geometry_msgs/msg/PolygonInstance.msg b/geometry_msgs/msg/PolygonInstance.msg new file mode 100644 index 00000000..61d6af5b --- /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 diff --git a/geometry_msgs/msg/PolygonInstanceStamped.msg b/geometry_msgs/msg/PolygonInstanceStamped.msg new file mode 100644 index 00000000..cefda8de --- /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