44 #include <std_srvs/srv/trigger.hpp>
56 return node_->get_node_base_interface();
60 std::shared_ptr<rclcpp::Node> node_;
61 std::unique_ptr<moveit_servo::Servo> servo_;
62 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
63 std::shared_ptr<planning_scene_monitor::PlanningSceneMonitor> planning_scene_monitor_;
66 void startCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
67 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response);
68 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr start_servo_service_;
73 void stopCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
74 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response);
75 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr stop_servo_service_;
78 void pauseCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
79 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response);
80 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr pause_servo_service_;
83 void unpauseCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
84 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response);
85 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr unpause_servo_service_;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
ServoNode(const rclcpp::NodeOptions &options)