-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Image segmenter output messages. (#5)
Image segmentation action and messages.
- Loading branch information
Showing
4 changed files
with
45 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
15 changes: 15 additions & 0 deletions
15
moveit_studio_msgs/moveit_studio_vision_msgs/action/GetMasks2D.action
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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
17
moveit_studio_msgs/moveit_studio_vision_msgs/msg/Mask2D.msg
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters