|
| 1 | +#include <future> |
| 2 | +#include <memory> |
| 3 | +#include <string> |
| 4 | + |
| 5 | +#include <ament_index_cpp/get_package_share_directory.hpp> |
| 6 | +#include <example_behaviors/sam2_segmentation.hpp> |
| 7 | +#include <geometry_msgs/msg/point_stamped.hpp> |
| 8 | +#include <moveit_pro_ml/onnx_sam2.hpp> |
| 9 | +#include <moveit_studio_behavior_interface/async_behavior_base.hpp> |
| 10 | +#include <moveit_studio_behavior_interface/get_required_ports.hpp> |
| 11 | +#include <moveit_studio_vision_msgs/msg/mask2_d.hpp> |
| 12 | +#include <sensor_msgs/msg/image.hpp> |
| 13 | +#include <tl_expected/expected.hpp> |
| 14 | + |
| 15 | +namespace |
| 16 | +{ |
| 17 | + constexpr auto kPortImage = "image"; |
| 18 | + constexpr auto kPortImageDefault = "{image}"; |
| 19 | + constexpr auto kPortPoint = "pixel_coords"; |
| 20 | + constexpr auto kPortPointDefault = "{pixel_coords}"; |
| 21 | + constexpr auto kPortMasks = "masks2d"; |
| 22 | + constexpr auto kPortMasksDefault = "{masks2d}"; |
| 23 | + |
| 24 | + constexpr auto kImageInferenceWidth = 1024; |
| 25 | + constexpr auto kImageInferenceHeight = 1024; |
| 26 | +} // namespace |
| 27 | + |
| 28 | +namespace example_behaviors |
| 29 | +{ |
| 30 | + // Convert a ROS image message to the ONNX image format used by the SAM 2 model |
| 31 | + void set_onnx_image_from_ros_image(const sensor_msgs::msg::Image& image_msg, |
| 32 | + moveit_pro_ml::ONNXImage& onnx_image) |
| 33 | + { |
| 34 | + onnx_image.shape = {1, image_msg.height, image_msg.width, 3}; |
| 35 | + onnx_image.data.resize(image_msg.height * image_msg.width * 3); |
| 36 | + const int stride = image_msg.encoding != "rgb8" ? 3: 4; |
| 37 | + for (size_t i = 0; i < onnx_image.data.size(); i+=stride) |
| 38 | + { |
| 39 | + onnx_image.data[i] = static_cast<float>(image_msg.data[i]) / 255.0f; |
| 40 | + onnx_image.data[i+1] = static_cast<float>(image_msg.data[i+1]) / 255.0f; |
| 41 | + onnx_image.data[i+2] = static_cast<float>(image_msg.data[i+2]) / 255.0f; |
| 42 | + } |
| 43 | + } |
| 44 | + |
| 45 | + // Converts a single channel ONNX image mask to a ROS mask message. |
| 46 | + void set_ros_mask_from_onnx_mask(const moveit_pro_ml::ONNXImage& onnx_image, sensor_msgs::msg::Image& mask_image_msg, moveit_studio_vision_msgs::msg::Mask2D& mask_msg) |
| 47 | + { |
| 48 | + mask_image_msg.height = static_cast<uint32_t>(onnx_image.shape[0]); |
| 49 | + mask_image_msg.width = static_cast<uint32_t>(onnx_image.shape[1]); |
| 50 | + mask_image_msg.encoding = "mono8"; |
| 51 | + mask_image_msg.data.resize(mask_image_msg.height * mask_image_msg.width); |
| 52 | + mask_image_msg.step = mask_image_msg.width; |
| 53 | + for (size_t i = 0; i < onnx_image.data.size(); ++i) |
| 54 | + { |
| 55 | + mask_image_msg.data[i] = onnx_image.data[i] > 0.5 ? 255: 0; |
| 56 | + } |
| 57 | + mask_msg.pixels = mask_image_msg; |
| 58 | + mask_msg.x = 0; |
| 59 | + mask_msg.y = 0; |
| 60 | + } |
| 61 | + |
| 62 | + SAM2Segmentation::SAM2Segmentation(const std::string& name, const BT::NodeConfiguration& config, |
| 63 | + const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources) |
| 64 | + : moveit_studio::behaviors::AsyncBehaviorBase(name, config, shared_resources) |
| 65 | + { |
| 66 | + |
| 67 | + const std::filesystem::path package_path = ament_index_cpp::get_package_share_directory("example_behaviors"); |
| 68 | + const std::filesystem::path encoder_onnx_file = package_path / "models" / "sam2_hiera_large_encoder.onnx"; |
| 69 | + const std::filesystem::path decoder_onnx_file = package_path / "models" / "decoder.onnx"; |
| 70 | + sam2_ = std::make_unique<moveit_pro_ml::SAM2>(encoder_onnx_file, decoder_onnx_file); |
| 71 | + } |
| 72 | + |
| 73 | + BT::PortsList SAM2Segmentation::providedPorts() |
| 74 | + { |
| 75 | + return { |
| 76 | + BT::InputPort<sensor_msgs::msg::Image>(kPortImage, kPortImageDefault, |
| 77 | + "The Image to run segmentation on."), |
| 78 | + BT::InputPort<std::vector<geometry_msgs::msg::PointStamped>>(kPortPoint, kPortPointDefault, |
| 79 | + "The input points, as a vector of <code>geometry_msgs/PointStamped</code> messages to be used for segmentation."), |
| 80 | + |
| 81 | + BT::OutputPort<std::vector<moveit_studio_vision_msgs::msg::Mask2D>>(kPortMasks, kPortMasksDefault, |
| 82 | + "The masks contained in a vector of <code>moveit_studio_vision_msgs::msg::Mask2D</code> messages.") |
| 83 | + }; |
| 84 | + } |
| 85 | + |
| 86 | + tl::expected<bool, std::string> SAM2Segmentation::doWork() |
| 87 | + { |
| 88 | + const auto ports = moveit_studio::behaviors::getRequiredInputs(getInput<sensor_msgs::msg::Image>(kPortImage), |
| 89 | + getInput<std::vector< |
| 90 | + geometry_msgs::msg::PointStamped>>(kPortPoint)); |
| 91 | + |
| 92 | + // Check that all required input data ports were set. |
| 93 | + if (!ports.has_value()) |
| 94 | + { |
| 95 | + auto error_message = fmt::format("Failed to get required values from input data ports:\n{}", ports.error()); |
| 96 | + return tl::make_unexpected(error_message); |
| 97 | + } |
| 98 | + const auto& [image_msg, points_2d] = ports.value(); |
| 99 | + |
| 100 | + if (image_msg.encoding != "rgb8" && image_msg.encoding != "rgba8") |
| 101 | + { |
| 102 | + auto error_message = fmt::format("Invalid image message format. Expected `(rgb8, rgba8)` got :\n{}", image_msg.encoding); |
| 103 | + return tl::make_unexpected(error_message); |
| 104 | + } |
| 105 | + |
| 106 | + // Create ONNX formatted image tensor from ROS image |
| 107 | + set_onnx_image_from_ros_image(image_msg, onnx_image_); |
| 108 | + |
| 109 | + std::vector<moveit_pro_ml::PointPrompt> point_prompts; |
| 110 | + for (auto const& point : points_2d) |
| 111 | + { |
| 112 | + // Assume all points are the same label |
| 113 | + point_prompts.push_back({{kImageInferenceWidth*static_cast<float>(point.point.x), kImageInferenceHeight*static_cast<float>(point.point.y)}, {1.0f}}); |
| 114 | + } |
| 115 | + |
| 116 | + try |
| 117 | + { |
| 118 | + const auto masks = sam2_->predict(onnx_image_, point_prompts); |
| 119 | + |
| 120 | + mask_image_msg_.header = image_msg.header; |
| 121 | + set_ros_mask_from_onnx_mask(masks, mask_image_msg_, mask_msg_); |
| 122 | + |
| 123 | + setOutput<std::vector<moveit_studio_vision_msgs::msg::Mask2D>>(kPortMasks, {mask_msg_}); |
| 124 | + } |
| 125 | + catch (const std::invalid_argument& e) |
| 126 | + { |
| 127 | + return tl::make_unexpected(fmt::format("Invalid argument: {}", e.what())); |
| 128 | + } |
| 129 | + |
| 130 | + return true; |
| 131 | + } |
| 132 | + |
| 133 | + BT::KeyValueVector SAM2Segmentation::metadata() |
| 134 | + { |
| 135 | + return { |
| 136 | + { |
| 137 | + "description", |
| 138 | + "Segments a ROS image message using the provided points represented as a vector of <code>geometry_msgs/PointStamped</code> messages." |
| 139 | + } |
| 140 | + }; |
| 141 | + } |
| 142 | +} // namespace sam2_segmentation |
0 commit comments