From 83587a1a65bd53cc58e6d0ba12862ca4e977195f Mon Sep 17 00:00:00 2001 From: Chance Cardona Date: Tue, 28 May 2024 17:29:19 -0600 Subject: [PATCH 1/4] added ShapeCompletion action definition --- .../action/ShapeCompletion.action | 12 ++++++++++++ .../moveit_studio_vision_msgs/package.xml | 4 ++-- 2 files changed, 14 insertions(+), 2 deletions(-) create mode 100644 moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action new file mode 100644 index 0000000..fa15251 --- /dev/null +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action @@ -0,0 +1,12 @@ +# Goal + +# Point cloud to complete +sensor_msgs/PointCloud2 partial_pointcloud +#vs moveit_studio_vision_msgs/PointCloudPCD ? + +--- +# Result +sensor_msgs/PointCloud2 completed_pointcloud + +--- +# Feedback diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/package.xml b/moveit_studio_msgs/moveit_studio_vision_msgs/package.xml index 1602deb..56fa68e 100644 --- a/moveit_studio_msgs/moveit_studio_vision_msgs/package.xml +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/package.xml @@ -2,8 +2,8 @@ moveit_studio_vision_msgs 3.0.0 Messages, services, and actions used by MoveIt Pro vision capabilities. - Sebastian Castro - Sebastian Castro + MoveIt Pro maintainer + MoveIt Pro maintainer BSD-3-Clause From 7d64165fa7927364f8c2d8818fdd904a2cd40597 Mon Sep 17 00:00:00 2001 From: Chance Cardona Date: Thu, 30 May 2024 12:23:28 -0600 Subject: [PATCH 2/4] Add to cmakelists and remove comment --- moveit_studio_msgs/moveit_studio_vision_msgs/CMakeLists.txt | 1 + .../moveit_studio_vision_msgs/action/ShapeCompletion.action | 3 +-- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/CMakeLists.txt b/moveit_studio_msgs/moveit_studio_vision_msgs/CMakeLists.txt index 2c40360..059aaf4 100644 --- a/moveit_studio_msgs/moveit_studio_vision_msgs/CMakeLists.txt +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/CMakeLists.txt @@ -30,6 +30,7 @@ set(msg_files set(action_files "action/GetMasks2D.action" + "action/ShapeCompletion.action" ) rosidl_generate_interfaces(${PROJECT_NAME} diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action index fa15251..7719d84 100644 --- a/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action @@ -2,11 +2,10 @@ # Point cloud to complete sensor_msgs/PointCloud2 partial_pointcloud -#vs moveit_studio_vision_msgs/PointCloudPCD ? --- # Result -sensor_msgs/PointCloud2 completed_pointcloud +sensor_msgs/PointCloud2 complete_pointcloud --- # Feedback From 9a89bf6ec95fb1889087da20be560f4159a33599 Mon Sep 17 00:00:00 2001 From: Chance Cardona Date: Thu, 30 May 2024 12:26:15 -0600 Subject: [PATCH 3/4] precommit --- .../moveit_studio_vision_msgs/action/ShapeCompletion.action | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action index 7719d84..24d4103 100644 --- a/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action @@ -3,7 +3,7 @@ # Point cloud to complete sensor_msgs/PointCloud2 partial_pointcloud ---- +--- # Result sensor_msgs/PointCloud2 complete_pointcloud From 7486c7484b8f9f594a19e23a742d6258fe3af111 Mon Sep 17 00:00:00 2001 From: Chance Cardona Date: Mon, 3 Jun 2024 15:26:44 -0600 Subject: [PATCH 4/4] Added model parameters to action --- .../moveit_studio_vision_msgs/action/ShapeCompletion.action | 3 +++ 1 file changed, 3 insertions(+) diff --git a/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action index 24d4103..6fa7323 100644 --- a/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action +++ b/moveit_studio_msgs/moveit_studio_vision_msgs/action/ShapeCompletion.action @@ -3,6 +3,9 @@ # Point cloud to complete sensor_msgs/PointCloud2 partial_pointcloud +# Model parameters. Stored as key-value pairs as they can be specific to the model selected. +moveit_studio_sdk_msgs/BehaviorParameter[] parameters + --- # Result sensor_msgs/PointCloud2 complete_pointcloud