Skip to content

Commit 14e2bde

Browse files
committed
cleanup
Signed-off-by: Paul Gesel <[email protected]>
1 parent ac8d439 commit 14e2bde

File tree

3 files changed

+48
-20
lines changed

3 files changed

+48
-20
lines changed

src/example_behaviors/include/example_behaviors/sam2_segmentation.hpp

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,18 @@ class SAM2Segmentation : public moveit_studio::behaviors::AsyncBehaviorBase
4444

4545

4646
private:
47-
void set_onnx_image_from_ros_image(const sensor_msgs::msg::Image& image_msg, moveit_pro_ml::ONNXImage& onnx_image);
47+
/**
48+
* @brief Convert a ROS image message to the ONNX image format used by the SAM 2 model.
49+
* @param image_msg The ROS message to be converted
50+
* @param onnx_image The ONNX image
51+
*/
52+
void set_onnx_image_from_ros_image(const sensor_msgs::msg::Image& image_msg, moveit_pro_ml::ONNXImage& onnx_image);/**
53+
54+
/**
55+
* @brief Convert an ONNX image to a ROS image message.
56+
* @param onnx_image The ONNX image to be converted
57+
* @param image_msg The ROS message
58+
*/
4859
void set_ros_image_from_onnx_image(const moveit_pro_ml::ONNXImage& onnx_image, sensor_msgs::msg::Image& image_msg);
4960

5061
std::shared_ptr<moveit_pro_ml::SAM2> sam2_;

src/example_behaviors/src/sam2_segmentation.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -89,19 +89,19 @@ namespace example_behaviors
8989
}
9090
const auto& [image_msg, points_2d] = ports.value();
9191

92-
if (image_msg.encoding != "rgb8"|| image_msg.encoding != "rgba8")
92+
if (image_msg.encoding != "rgb8" && image_msg.encoding != "rgba8")
9393
{
9494
auto error_message = fmt::format("Invalid image message format. Expected `(rgb8, rgba8)` got :\n{}", image_msg.encoding);
9595
return tl::make_unexpected(error_message);
9696
}
9797

98-
// create ONNX formatted image tensor from ROS image
98+
// Create ONNX formatted image tensor from ROS image
9999
set_onnx_image_from_ros_image(image_msg, onnx_image_);
100100

101101
std::vector<moveit_pro_ml::PointPrompt> point_prompts;
102102
for (auto const& point : points_2d)
103103
{
104-
// assume all point are the same label
104+
// Assume all point are the same label
105105
point_prompts.push_back({{kImageInferenceWidth*static_cast<float>(point.point.x), kImageInferenceHeight*static_cast<float>(point.point.y)}, {1.0f}});
106106
}
107107

@@ -130,7 +130,7 @@ namespace example_behaviors
130130
return {
131131
{
132132
"description",
133-
"Segments a ROS image message using the click points provided as a vector of <code>geometry_msgs/PointStamped</code> messages."
133+
"Segments a ROS image message using the provided points represented as a vector of <code>geometry_msgs/PointStamped</code> messages."
134134
}
135135
};
136136
}
Lines changed: 32 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,24 +1,41 @@
1-
<?xml version="1.0" encoding="utf-8"?>
2-
<root BTCPP_format="4" main_tree_to_execute="Run SAM 2 ONNX">
1+
<?xml version="1.0" encoding="utf-8" ?>
2+
<root
3+
BTCPP_format="4"
4+
main_tree_to_execute="Segment Point Cloud from Clicked Point"
5+
>
36
<!--//////////-->
4-
<BehaviorTree ID="Run SAM 2 ONNX" _description="Captures a point cloud and and filters it to only include points of a segmented object. The user is prompted to select the object to be segment using clicked points." _favorite="true">
7+
<BehaviorTree
8+
ID="Segment Point Cloud from Clicked Point"
9+
_description="Captures a point cloud and requests the user to click an object in the image to be segmented. The point cloud is then filtered to only include the selected object."
10+
_favorite="true"
11+
>
512
<Control ID="Sequence">
6-
<Action ID="ClearSnapshot"/>
7-
<Action ID="GetImage" topic_name="/wrist_camera/color"/>
8-
<Action ID="GetPointsFromUser" point_prompts="Select a prompt point 1;Select a prompt point 2" point_names="Point1;Point2" view_name="/wrist_camera/color"/>
9-
<Action ID="SAM2Segmentation"/>
10-
<Action ID="GetPointCloud" topic_name="/wrist_camera/points"/>
11-
<Action ID="GetCameraInfo" topic_name="/wrist_camera/camera_info" message_out="{camera_info}" timeout_sec="5.000000"/>
12-
<Action ID="GetMasks3DFromMasks2D"/>
13+
<Action ID="ClearSnapshot" />
14+
<Action ID="GetImage" topic_name="/wrist_camera/color" />
15+
<Action
16+
ID="GetPointsFromUser"
17+
point_prompts="Select the object to be segmented;"
18+
point_names="Point1;"
19+
view_name="/wrist_camera/color"
20+
/>
21+
<Action ID="SAM2Segmentation" />
22+
<Action ID="GetPointCloud" topic_name="/wrist_camera/points" />
23+
<Action
24+
ID="GetCameraInfo"
25+
topic_name="/wrist_camera/camera_info"
26+
message_out="{camera_info}"
27+
timeout_sec="5.000000"
28+
/>
29+
<Action ID="GetMasks3DFromMasks2D" />
1330
<Decorator ID="ForEachMask3D" vector_in="{masks3d}" out="{mask3d}">
14-
<Action ID="GetPointCloudFromMask3D" point_cloud="{point_cloud}"/>
31+
<Action ID="GetPointCloudFromMask3D" point_cloud="{point_cloud}" />
1532
</Decorator>
16-
<Action ID="SendPointCloudToUI" point_cloud="{point_cloud_fragment}"/>
17-
<Action ID="PublishPointCloud" point_cloud="{point_cloud_fragment}"/>
18-
<Action ID="SwitchUIPrimaryView"/>
33+
<Action ID="SendPointCloudToUI" point_cloud="{point_cloud_fragment}" />
34+
<Action ID="PublishPointCloud" point_cloud="{point_cloud_fragment}" />
35+
<Action ID="SwitchUIPrimaryView" />
1936
</Control>
2037
</BehaviorTree>
2138
<TreeNodesModel>
22-
<SubTree ID="Run SAM 2 ONNX"/>
39+
<SubTree ID="Segment Point Cloud from Clicked Point" />
2340
</TreeNodesModel>
2441
</root>

0 commit comments

Comments
 (0)