Skip to content

Commit

Permalink
Add ShapeCompletion Action (#52)
Browse files Browse the repository at this point in the history
  • Loading branch information
chancecardona authored Jun 10, 2024
1 parent a7ae0a4 commit a7d6dc1
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ set(msg_files

set(action_files
"action/GetMasks2D.action"
"action/ShapeCompletion.action"
)

rosidl_generate_interfaces(${PROJECT_NAME}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
# Goal

# 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

---
# Feedback
4 changes: 2 additions & 2 deletions moveit_studio_msgs/moveit_studio_vision_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
<name>moveit_studio_vision_msgs</name>
<version>3.0.0</version>
<description>Messages, services, and actions used by MoveIt Pro vision capabilities.</description>
<author email="sebastian.castro@picknik.ai">Sebastian Castro</author>
<maintainer email="sebastian.castro@picknik.ai">Sebastian Castro</maintainer>
<author email="support@picknik.ai">MoveIt Pro maintainer</author>
<maintainer email="support@picknik.ai">MoveIt Pro maintainer</maintainer>

<license>BSD-3-Clause</license>

Expand Down

0 comments on commit a7d6dc1

Please sign in to comment.