#include "behaviortree_ros2/bt_service_node.hpp" #include "behaviortree_ros2/plugins.hpp" #include // #include #include "rbs_skill_interfaces/srv/get_pick_place_poses.hpp" // #include "rbs_mill_interfaces" // #include "rbs_mill_interfaces/srv/get_slot_grasping_pose.hpp" #include "rbs_mill_interfaces/srv/get_grasping_pose.hpp" #include #include #include #include // #include #include #include using GraspingService = rbs_mill_interfaces::srv::GetGraspingPose; using namespace BT; class GetGraspPose : public RosServiceNode { public: GetGraspPose(const std::string &name, const NodeConfig &conf, const RosNodeParams ¶ms) : RosServiceNode(name, conf, params) { RCLCPP_INFO(this->logger(), "Starting GetSlotGraspingPose"); } static PortsList providedPorts() { return providedBasicPorts( {InputPort("from_pose"), InputPort("relative_to"), OutputPort>("grasp"), OutputPort>("pregrasp"), OutputPort>("postgrasp")}); } bool setRequest(Request::SharedPtr &request) override { RCLCPP_INFO(this->logger(), "[%s] Starting send request for: [%s]", name().c_str(), this->service_name_.c_str()); if (!getInput("from_pose", request->pose_name)) { RCLCPP_ERROR(this->node_.lock()->get_logger(), "[%s] Failed to get slot_name from input port", name().c_str()); return false; } if (!getInput("relative_to", request->relative_to)) { RCLCPP_ERROR(this->node_.lock()->get_logger(), "[%s] Failed to get relative_to from input port", name().c_str()); return false; } request->action_type = "pick"; return true; } NodeStatus onResponseReceived(const Response::SharedPtr &response) override { if (!response->ok) { RCLCPP_ERROR(this->node_.lock()->get_logger(), "[%s] Response indicates failure.", name().c_str()); return NodeStatus::FAILURE; } RCLCPP_INFO(this->node_.lock()->get_logger(), "[%s] Response received successfully.", name().c_str()); auto grasp = std::make_shared(response->grasp_poses.pose); auto pregrasp = std::make_shared( response->grasp_poses.pre_pose); auto postgrasp = std::make_shared( response->grasp_poses.post_pose); if (!grasp || !pregrasp || !postgrasp) { RCLCPP_ERROR(this->logger(), "[%s] Response poses are empty", name().c_str()); return NodeStatus::FAILURE; } setOutput("grasp", grasp); setOutput("pregrasp", pregrasp); setOutput("postgrasp", postgrasp); return NodeStatus::SUCCESS; } // virtual NodeStatus onFailure(ServiceNodeErrorCode error) override {} }; CreateRosNodePlugin(GetGraspPose, "GetSlotGraspPoses");