Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -17,16 +17,16 @@ namespace example_behaviors
/**
* @brief Segment an image using the SAM 2 model
*/
class SAM2Segmentation : public moveit_studio::behaviors::AsyncBehaviorBase
class ExampleSAM2Segmentation : public moveit_studio::behaviors::AsyncBehaviorBase
{
public:
/**
* @brief Constructor for the SAM2Segmentation behavior.
* @brief Constructor for the ExampleSAM2Segmentation behavior.
* @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.
* @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.
* @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.
*/
SAM2Segmentation(const std::string& name, const BT::NodeConfiguration& config,
ExampleSAM2Segmentation(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <string>

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <example_behaviors/sam2_segmentation.hpp>
#include <example_behaviors/example_sam2_segmentation.hpp>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <moveit_pro_ml/onnx_sam2.hpp>
#include <moveit_studio_behavior_interface/async_behavior_base.hpp>
Expand Down Expand Up @@ -59,7 +59,7 @@ namespace example_behaviors
mask_msg.y = 0;
}

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

BT::PortsList SAM2Segmentation::providedPorts()
BT::PortsList ExampleSAM2Segmentation::providedPorts()
{
return {
BT::InputPort<sensor_msgs::msg::Image>(kPortImage, kPortImageDefault,
Expand All @@ -83,7 +83,7 @@ namespace example_behaviors
};
}

tl::expected<bool, std::string> SAM2Segmentation::doWork()
tl::expected<bool, std::string> ExampleSAM2Segmentation::doWork()
{
const auto ports = moveit_studio::behaviors::getRequiredInputs(getInput<sensor_msgs::msg::Image>(kPortImage),
getInput<std::vector<
Expand Down Expand Up @@ -130,7 +130,7 @@ namespace example_behaviors
return true;
}

BT::KeyValueVector SAM2Segmentation::metadata()
BT::KeyValueVector ExampleSAM2Segmentation::metadata()
{
return {
{
Expand Down
2 changes: 2 additions & 0 deletions src/example_behaviors/src/register_behaviors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <example_behaviors/example_setup_mtc_place_from_pose.hpp>
#include <example_behaviors/example_ndt_registration.hpp>
#include <example_behaviors/example_ransac_registration.hpp>
#include <example_behaviors/example_sam2_segmentation.hpp>

#include <pluginlib/class_list_macros.hpp>

Expand All @@ -40,6 +41,7 @@ class ExampleBehaviorsLoader : public moveit_studio::behaviors::SharedResourcesN
shared_resources);
moveit_studio::behaviors::registerBehavior<ExampleNDTRegistration>(factory, "ExampleNDTRegistration", shared_resources);
moveit_studio::behaviors::registerBehavior<ExampleRANSACRegistration>(factory, "ExampleRANSACRegistration", shared_resources);
moveit_studio::behaviors::registerBehavior<ExampleSAM2Segmentation>(factory, "ExampleSAM2Segmentation", shared_resources);
}
};
} // namespace example_behaviors
Expand Down
2 changes: 1 addition & 1 deletion src/lab_sim/objectives/run_sam2_onnx.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
point_names="Point1;"
view_name="/wrist_camera/color"
/>
<Action ID="SAM2Segmentation" />
<Action ID="ExampleSAM2Segmentation" />
<Action ID="GetPointCloud" topic_name="/wrist_camera/points" />
<Action
ID="GetCameraInfo"
Expand Down
Loading