From 77883ca064c1706766662a8f19e401a9e9b1c76d Mon Sep 17 00:00:00 2001 From: Chance Cardona Date: Tue, 31 Oct 2023 21:24:21 -0600 Subject: [PATCH] PR comment updates --- .../moveit_studio_vision_msgs/msg/GraspableObject.msg | 6 +++--- .../moveit_studio_vision_msgs/msg/ObjectSubframe.msg | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/msg/GraspableObject.msg b/moveit_studio_msgs/moveit_studio_vision_msgs/msg/GraspableObject.msg index edb2ee5..8881f2b 100644 --- a/moveit_studio_msgs/moveit_studio_vision_msgs/msg/GraspableObject.msg +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/msg/GraspableObject.msg @@ -9,7 +9,7 @@ std_msgs/Header header string id # The pose of the object relative to the frame specified in the header. This is -# used to create the transform to the object, from which all subframes are relative to. +# used to create the transform to the object, from which all subframe poses are relative to. geometry_msgs/Pose pose # A solid primitive which represents the maximum extent of the object. @@ -20,13 +20,13 @@ shape_msgs/SolidPrimitive bounding_volume moveit_studio_vision_msgs/GraspableFace[] surfaces # Primitives. A vector of solid geometric primitives which describe the shape of the object. -# The primitive_poses must be the same length, where each pose is relative to the transform.child_id shape_msgs/SolidPrimitive[] primitives +# The primitive_poses must be the same length as primitives, where each pose is relative to the objects pose. geometry_msgs/Pose[] primitive_poses # Meshes. A vector of meshes which describe the shape of the object. -# The mesh_poses must be the same length, where each pose is relative to the transform.child_id shape_msgs/Mesh[] meshes +# The mesh_poses must be the same length as meshes, where each pose is relative to the objects pose. geometry_msgs/Pose[] mesh_poses # Subframes. These correspond to affordances and their poses (relative to the object's pose). diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/msg/ObjectSubframe.msg b/moveit_studio_msgs/moveit_studio_vision_msgs/msg/ObjectSubframe.msg index 481598a..c99a41b 100644 --- a/moveit_studio_msgs/moveit_studio_vision_msgs/msg/ObjectSubframe.msg +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/msg/ObjectSubframe.msg @@ -1,5 +1,5 @@ # Subframe of an Object. This is intended to hold information about features of an object, -# and includes an ID of the feature, its pose, any describing geometry relative to this pose, and affordances. +# and includes an ID of the feature along with its pose. This is what should hold an affordance and any needed primitives for it. # ID of the subframe string id