moveit2
The MoveIt Motion Planning Framework for ROS 2.
servo_node.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019, Los Alamos National Security, LLC
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 /* Title : servo_node.cpp
35  * Project : moveit_servo
36  * Created : 12/31/2018
37  * Author : Andy Zelenak
38  */
39 
42 
43 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.servo_node");
44 
45 namespace moveit_servo
46 {
47 ServoNode::ServoNode(const rclcpp::NodeOptions& options)
48  : node_{ std::make_shared<rclcpp::Node>("servo_node", options) }
49 {
50  if (!options.use_intra_process_comms())
51  {
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");
55  }
56 
57  // Set up services for interacting with Servo
58  start_servo_service_ = node_->create_service<std_srvs::srv::Trigger>(
59  "~/start_servo",
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>(
63  "~/stop_servo",
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>(
67  "~/pause_servo",
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);
74  });
75 
76  // Can set robot_description name from parameters
77  std::string robot_description_name = "robot_description";
78  node_->get_parameter_or("robot_description_name", robot_description_name, robot_description_name);
79 
80  // Get the servo parameters
81  auto servo_parameters = moveit_servo::ServoParameters::makeServoParameters(node_);
82  if (servo_parameters == nullptr)
83  {
84  RCLCPP_ERROR(LOGGER, "Failed to load the servo parameters");
85  throw std::runtime_error("Failed to load the servo parameters");
86  }
87 
88  // Set up planning_scene_monitor
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);
96  planning_scene_monitor_->startPublishingPlanningScene(planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE,
97  std::string(node_->get_fully_qualified_name()) +
98  "/publish_planning_scene");
99  // If the planning scene monitor in servo is the primary one we provide /get_planning_scene service so RViz displays
100  // or secondary planning scene monitors can fetch the scene, otherwise we request the planning scene from the
101  // primary planning scene monitor (e.g. move_group)
102  if (servo_parameters->is_primary_planning_scene_monitor)
103  planning_scene_monitor_->providePlanningSceneService();
104  else
105  planning_scene_monitor_->requestPlanningSceneState();
106 
107  // Create Servo
108  servo_ = std::make_unique<moveit_servo::Servo>(node_, servo_parameters, planning_scene_monitor_);
109 }
110 
111 void ServoNode::startCB(const std::shared_ptr<std_srvs::srv::Trigger::Request>& /* unused */,
112  const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
113 {
114  servo_->start();
115  response->success = true;
116 }
117 
118 void ServoNode::stopCB(const std::shared_ptr<std_srvs::srv::Trigger::Request>& /* unused */,
119  const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
120 {
121  servo_->setPaused(true);
122  response->success = true;
123 }
124 
125 void ServoNode::pauseCB(const std::shared_ptr<std_srvs::srv::Trigger::Request>& /* unused */,
126  const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
127 {
128  servo_->setPaused(true);
129  response->success = true;
130 }
131 
132 void ServoNode::unpauseCB(const std::shared_ptr<std_srvs::srv::Trigger::Request>& /* unused */,
133  const std::shared_ptr<std_srvs::srv::Trigger::Response>& response)
134 {
135  servo_->setPaused(false);
136  response->success = true;
137 }
138 
139 } // namespace moveit_servo
140 
141 // Register the component with class_loader
142 #include <rclcpp_components/register_node_macro.hpp>
143 RCLCPP_COMPONENTS_REGISTER_NODE(moveit_servo::ServoNode)
ServoNode(const rclcpp::NodeOptions &options)
Definition: servo_node.cpp:47
const rclcpp::Logger LOGGER
Definition: async_test.h:31
static SharedConstPtr makeServoParameters(const rclcpp::Node::SharedPtr &node, const std::string &ns="moveit_servo", bool dynamic_parameters=true)