43 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_servo.servo_node");
48 : node_{ std::make_shared<
rclcpp::Node>(
"servo_node",
options) }
50 if (!
options.use_intra_process_comms())
52 RCLCPP_WARN_STREAM(LOGGER,
"Intra-process communication is disabled, consider enabling it by adding: "
53 "\nextra_arguments=[{'use_intra_process_comms' : True}]\nto the Servo composable node "
54 "in the launch file");
58 start_servo_service_ = node_->create_service<std_srvs::srv::Trigger>(
60 [
this](
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
61 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response) {
return startCB(request, response); });
62 stop_servo_service_ = node_->create_service<std_srvs::srv::Trigger>(
64 [
this](
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
65 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response) {
return stopCB(request, response); });
66 pause_servo_service_ = node_->create_service<std_srvs::srv::Trigger>(
68 [
this](
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
69 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response) {
return pauseCB(request, response); });
70 unpause_servo_service_ = node_->create_service<std_srvs::srv::Trigger>(
71 "~/unpause_servo", [
this](
const std::shared_ptr<std_srvs::srv::Trigger::Request>& request,
72 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response) {
73 return unpauseCB(request, response);
77 std::string robot_description_name =
"robot_description";
78 node_->get_parameter_or(
"robot_description_name", robot_description_name, robot_description_name);
82 if (servo_parameters ==
nullptr)
84 RCLCPP_ERROR(LOGGER,
"Failed to load the servo parameters");
85 throw std::runtime_error(
"Failed to load the servo parameters");
89 planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
90 node_, robot_description_name,
"planning_scene_monitor");
91 planning_scene_monitor_->startStateMonitor(servo_parameters->joint_topic);
92 planning_scene_monitor_->startSceneMonitor(servo_parameters->monitored_planning_scene_topic);
93 planning_scene_monitor_->startWorldGeometryMonitor();
94 planning_scene_monitor_->setPlanningScenePublishingFrequency(25);
95 planning_scene_monitor_->getStateMonitor()->enableCopyDynamics(
true);
97 std::string(node_->get_fully_qualified_name()) +
98 "/publish_planning_scene");
102 if (servo_parameters->is_primary_planning_scene_monitor)
103 planning_scene_monitor_->providePlanningSceneService();
105 planning_scene_monitor_->requestPlanningSceneState();
108 servo_ = std::make_unique<moveit_servo::Servo>(node_, servo_parameters, planning_scene_monitor_);
111 void ServoNode::startCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& ,
112 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
115 response->success =
true;
118 void ServoNode::stopCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& ,
119 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
121 servo_->setPaused(
true);
122 response->success =
true;
125 void ServoNode::pauseCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& ,
126 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
128 servo_->setPaused(
true);
129 response->success =
true;
132 void ServoNode::unpauseCB(
const std::shared_ptr<std_srvs::srv::Trigger::Request>& ,
133 const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
135 servo_->setPaused(
false);
136 response->success =
true;
142 #include <rclcpp_components/register_node_macro.hpp>
ServoNode(const rclcpp::NodeOptions &options)
@ UPDATE_SCENE
The entire scene was updated.
const rclcpp::Logger LOGGER
static SharedConstPtr makeServoParameters(const rclcpp::Node::SharedPtr &node, const std::string &ns="moveit_servo", bool dynamic_parameters=true)