From a69729c042a0fac377d78b1165658f2601c34837 Mon Sep 17 00:00:00 2001 From: Adam Allevato Date: Sun, 20 Dec 2020 17:07:58 -0600 Subject: [PATCH 1/2] Clarify bbox size comment --- msg/BoundingBox2D.msg | 5 +++-- msg/BoundingBox3D.msg | 5 +++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/msg/BoundingBox2D.msg b/msg/BoundingBox2D.msg index e42f54d..2222a08 100644 --- a/msg/BoundingBox2D.msg +++ b/msg/BoundingBox2D.msg @@ -7,7 +7,8 @@ # The 2D position (in pixels) and orientation of the bounding box center. geometry_msgs/Pose2D center -# The size (in pixels) of the bounding box surrounding the object relative -# to the pose of its center. +# The total size (in pixels) of the bounding box surrounding the +# object. The X and Y axes are relative to the center pose +# (including rotation). float64 size_x float64 size_y diff --git a/msg/BoundingBox3D.msg b/msg/BoundingBox3D.msg index 00713ad..faf9a1a 100644 --- a/msg/BoundingBox3D.msg +++ b/msg/BoundingBox3D.msg @@ -5,6 +5,7 @@ # The 3D position and orientation of the bounding box center geometry_msgs/Pose center -# The size of the bounding box, in meters, surrounding the object's center -# pose. +# The total size (in meters) of the bounding box surrounding the +# object. The X and Y axes are relative to the center pose +# (including orientation). geometry_msgs/Vector3 size From 8f289b009073c4f78d7be888d9465d4facb724a4 Mon Sep 17 00:00:00 2001 From: Adam Allevato Date: Mon, 4 Jan 2021 22:41:44 -0600 Subject: [PATCH 2/2] Revert confusing comment about bbox orientation --- msg/BoundingBox2D.msg | 5 ++--- msg/BoundingBox3D.msg | 5 ++--- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/msg/BoundingBox2D.msg b/msg/BoundingBox2D.msg index 2222a08..85a306d 100644 --- a/msg/BoundingBox2D.msg +++ b/msg/BoundingBox2D.msg @@ -7,8 +7,7 @@ # The 2D position (in pixels) and orientation of the bounding box center. geometry_msgs/Pose2D center -# The total size (in pixels) of the bounding box surrounding the -# object. The X and Y axes are relative to the center pose -# (including rotation). +# The total size (in pixels) of the bounding box surrounding the object relative +# to the pose of its center. float64 size_x float64 size_y diff --git a/msg/BoundingBox3D.msg b/msg/BoundingBox3D.msg index faf9a1a..cb8f49d 100644 --- a/msg/BoundingBox3D.msg +++ b/msg/BoundingBox3D.msg @@ -5,7 +5,6 @@ # The 3D position and orientation of the bounding box center geometry_msgs/Pose center -# The total size (in meters) of the bounding box surrounding the -# object. The X and Y axes are relative to the center pose -# (including orientation). +# The total size of the bounding box, in meters, surrounding the object's center +# pose. geometry_msgs/Vector3 size