Skip to content

Commit 1f0f61b

Browse files
authored
Sam naming (#38)
1 parent a657adf commit 1f0f61b

File tree

4 files changed

+11
-9
lines changed

4 files changed

+11
-9
lines changed

src/example_behaviors/include/example_behaviors/sam2_segmentation.hpp renamed to src/example_behaviors/include/example_behaviors/example_sam2_segmentation.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -17,16 +17,16 @@ namespace example_behaviors
1717
/**
1818
* @brief Segment an image using the SAM 2 model
1919
*/
20-
class SAM2Segmentation : public moveit_studio::behaviors::AsyncBehaviorBase
20+
class ExampleSAM2Segmentation : public moveit_studio::behaviors::AsyncBehaviorBase
2121
{
2222
public:
2323
/**
24-
* @brief Constructor for the SAM2Segmentation behavior.
24+
* @brief Constructor for the ExampleSAM2Segmentation behavior.
2525
* @param name The name of a particular instance of this Behavior. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree.
2626
* @param config This contains runtime configuration info for this Behavior, such as the mapping between the Behavior's data ports on the behavior tree's blackboard. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree.
2727
* @details An important limitation is that the members of the base Behavior class are not instantiated until after the initialize() function is called, so these classes should not be used within the constructor.
2828
*/
29-
SAM2Segmentation(const std::string& name, const BT::NodeConfiguration& config,
29+
ExampleSAM2Segmentation(const std::string& name, const BT::NodeConfiguration& config,
3030
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);
3131

3232
/**

src/example_behaviors/src/sam2_segmentation.cpp renamed to src/example_behaviors/src/example_sam2_segmentation.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
#include <string>
44

55
#include <ament_index_cpp/get_package_share_directory.hpp>
6-
#include <example_behaviors/sam2_segmentation.hpp>
6+
#include <example_behaviors/example_sam2_segmentation.hpp>
77
#include <geometry_msgs/msg/point_stamped.hpp>
88
#include <moveit_pro_ml/onnx_sam2.hpp>
99
#include <moveit_studio_behavior_interface/async_behavior_base.hpp>
@@ -59,7 +59,7 @@ namespace example_behaviors
5959
mask_msg.y = 0;
6060
}
6161

62-
SAM2Segmentation::SAM2Segmentation(const std::string& name, const BT::NodeConfiguration& config,
62+
ExampleSAM2Segmentation::ExampleSAM2Segmentation(const std::string& name, const BT::NodeConfiguration& config,
6363
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources)
6464
: moveit_studio::behaviors::AsyncBehaviorBase(name, config, shared_resources)
6565
{
@@ -70,7 +70,7 @@ namespace example_behaviors
7070
sam2_ = std::make_unique<moveit_pro_ml::SAM2>(encoder_onnx_file, decoder_onnx_file);
7171
}
7272

73-
BT::PortsList SAM2Segmentation::providedPorts()
73+
BT::PortsList ExampleSAM2Segmentation::providedPorts()
7474
{
7575
return {
7676
BT::InputPort<sensor_msgs::msg::Image>(kPortImage, kPortImageDefault,
@@ -83,7 +83,7 @@ namespace example_behaviors
8383
};
8484
}
8585

86-
tl::expected<bool, std::string> SAM2Segmentation::doWork()
86+
tl::expected<bool, std::string> ExampleSAM2Segmentation::doWork()
8787
{
8888
const auto ports = moveit_studio::behaviors::getRequiredInputs(getInput<sensor_msgs::msg::Image>(kPortImage),
8989
getInput<std::vector<
@@ -130,7 +130,7 @@ namespace example_behaviors
130130
return true;
131131
}
132132

133-
BT::KeyValueVector SAM2Segmentation::metadata()
133+
BT::KeyValueVector ExampleSAM2Segmentation::metadata()
134134
{
135135
return {
136136
{

src/example_behaviors/src/register_behaviors.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
#include <example_behaviors/example_setup_mtc_place_from_pose.hpp>
1515
#include <example_behaviors/example_ndt_registration.hpp>
1616
#include <example_behaviors/example_ransac_registration.hpp>
17+
#include <example_behaviors/example_sam2_segmentation.hpp>
1718

1819
#include <pluginlib/class_list_macros.hpp>
1920

@@ -40,6 +41,7 @@ class ExampleBehaviorsLoader : public moveit_studio::behaviors::SharedResourcesN
4041
shared_resources);
4142
moveit_studio::behaviors::registerBehavior<ExampleNDTRegistration>(factory, "ExampleNDTRegistration", shared_resources);
4243
moveit_studio::behaviors::registerBehavior<ExampleRANSACRegistration>(factory, "ExampleRANSACRegistration", shared_resources);
44+
moveit_studio::behaviors::registerBehavior<ExampleSAM2Segmentation>(factory, "ExampleSAM2Segmentation", shared_resources);
4345
}
4446
};
4547
} // namespace example_behaviors

src/lab_sim/objectives/run_sam2_onnx.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
point_names="Point1;"
1919
view_name="/wrist_camera/color"
2020
/>
21-
<Action ID="SAM2Segmentation" />
21+
<Action ID="ExampleSAM2Segmentation" />
2222
<Action ID="GetPointCloud" topic_name="/wrist_camera/points" />
2323
<Action
2424
ID="GetCameraInfo"

0 commit comments

Comments
 (0)