Skip to content

Commit

Permalink
Image segmenter output messages. (#5)
Browse files Browse the repository at this point in the history
Image segmentation action and messages.
  • Loading branch information
uavster authored Sep 5, 2023
1 parent 1473f69 commit e499daa
Show file tree
Hide file tree
Showing 4 changed files with 45 additions and 1 deletion.
12 changes: 11 additions & 1 deletion moveit_studio_msgs/moveit_studio_vision_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,23 +9,33 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(moveit_studio_sdk_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(shape_msgs REQUIRED)
find_package(std_msgs REQUIRED)

set(msg_files
"msg/GraspableFace.msg"
"msg/GraspableObject.msg"
"msg/Mask2D.msg"
"msg/ObjectDetection.msg"
"msg/ObjectDetectionArray.msg"
"msg/PointCloudPCD.msg"
)

set(action_files
"action/GetMasks2D.action"
)

rosidl_generate_interfaces(${PROJECT_NAME}
${msg_files}
${msg_files}
${action_files}
DEPENDENCIES
builtin_interfaces
geometry_msgs
moveit_studio_sdk_msgs
sensor_msgs
shape_msgs
std_msgs
)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# Goal

# Image to segment.
sensor_msgs/Image image

# Segmentation parameters. They are stored as key-value pairs because they are
# specific to the segmentation model being run by the action server.
moveit_studio_sdk_msgs/BehaviorParameter[] parameters

---
# Result
moveit_studio_vision_msgs/Mask2D[] masks

---
# Feedback
17 changes: 17 additions & 0 deletions moveit_studio_msgs/moveit_studio_vision_msgs/msg/Mask2D.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# Message containing a 2D mask.
#
# This message may be used to represent an instance or semantic mask in the
# output message of an image segmenter.

# The position of the top-left corner of the mask within the segmented image.
# (0, 0) is the top-left corner of the segmented image.
# The segmented image should be referenced in the containing image segmenter
# message.
int32 x
int32 y

# A single plane image with the mask pixels.
# The image pixels can be encoded as:
# - Integer: only non-zero pixels belong to the mask.
# - Floating point: each pixel has a probability of belonging to the mask.
sensor_msgs/Image pixels
2 changes: 2 additions & 0 deletions moveit_studio_msgs/moveit_studio_vision_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@

<depend>builtin_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>moveit_studio_sdk_msgs</depend>
<depend>sensor_msgs</depend>
<depend>shape_msgs</depend>
<depend>std_msgs</depend>

Expand Down

0 comments on commit e499daa

Please sign in to comment.