moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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, V Mohammed Ibrahim
38 *
39 */
40
42#include <realtime_tools/thread_priority.hpp>
44
45namespace moveit_servo
46{
47
48rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ServoNode::get_node_base_interface()
49{
50 return node_->get_node_base_interface();
51}
52
54{
55 stop_servo_ = true;
56 if (servo_loop_thread_.joinable())
57 servo_loop_thread_.join();
58}
59
60ServoNode::ServoNode(const rclcpp::NodeOptions& options)
61 : node_{ std::make_shared<rclcpp::Node>("servo_node", options) }
62 , stop_servo_{ false }
63 , servo_paused_{ false }
64 , new_joint_jog_msg_{ false }
65 , new_twist_msg_{ false }
66 , new_pose_msg_{ false }
67{
68 moveit::setNodeLoggerName(node_->get_name());
69
70 // Configure SCHED_FIFO and priority
71 if (realtime_tools::configure_sched_fifo(servo_params_.thread_priority))
72 {
73 RCLCPP_INFO_STREAM(node_->get_logger(), "Enabled SCHED_FIFO and higher thread priority.");
74 }
75 else
76 {
77 RCLCPP_WARN_STREAM(node_->get_logger(), "Could not enable FIFO RT scheduling policy. Continuing with the default.");
78 }
79
80 // Check if a realtime kernel is available
81 if (!realtime_tools::has_realtime_kernel())
82 {
83 RCLCPP_WARN_STREAM(node_->get_logger(), "Realtime kernel is recommended for better performance.");
84 }
85
86 std::shared_ptr<servo::ParamListener> servo_param_listener =
87 std::make_shared<servo::ParamListener>(node_, "moveit_servo");
88
89 // Create Servo instance
90 planning_scene_monitor_ = createPlanningSceneMonitor(node_, servo_param_listener->get_params());
91 servo_ = std::make_unique<Servo>(node_, servo_param_listener, planning_scene_monitor_);
92
93 servo_params_ = servo_->getParams();
94
95 // Create subscriber for jointjog
96 joint_jog_subscriber_ = node_->create_subscription<control_msgs::msg::JointJog>(
97 servo_params_.joint_command_in_topic, rclcpp::SystemDefaultsQoS(),
98 [this](const control_msgs::msg::JointJog::ConstSharedPtr& msg) { return jointJogCallback(msg); });
99
100 // Create subscriber for twist
101 twist_subscriber_ = node_->create_subscription<geometry_msgs::msg::TwistStamped>(
102 servo_params_.cartesian_command_in_topic, rclcpp::SystemDefaultsQoS(),
103 [this](const geometry_msgs::msg::TwistStamped::ConstSharedPtr& msg) { return twistCallback(msg); });
104
105 // Create subscriber for pose
106 pose_subscriber_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
107 servo_params_.pose_command_in_topic, rclcpp::SystemDefaultsQoS(),
108 [this](const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg) { return poseCallback(msg); });
109
110 if (servo_params_.command_out_type == "trajectory_msgs/JointTrajectory")
111 {
112 trajectory_publisher_ = node_->create_publisher<trajectory_msgs::msg::JointTrajectory>(
113 servo_params_.command_out_topic, rclcpp::SystemDefaultsQoS());
114 }
115 else if (servo_params_.command_out_type == "std_msgs/Float64MultiArray")
116 {
117 multi_array_publisher_ = node_->create_publisher<std_msgs::msg::Float64MultiArray>(servo_params_.command_out_topic,
118 rclcpp::SystemDefaultsQoS());
119 }
120 // Create status publisher
121 status_publisher_ =
122 node_->create_publisher<moveit_msgs::msg::ServoStatus>(servo_params_.status_topic, rclcpp::SystemDefaultsQoS());
123
124 // Create service to enable switching command type
125 switch_command_type_ = node_->create_service<moveit_msgs::srv::ServoCommandType>(
126 "~/switch_command_type", [this](const std::shared_ptr<moveit_msgs::srv::ServoCommandType::Request>& request,
127 const std::shared_ptr<moveit_msgs::srv::ServoCommandType::Response>& response) {
128 return switchCommandType(request, response);
129 });
130
131 // Create service to pause/unpause servoing
132 pause_servo_ = node_->create_service<std_srvs::srv::SetBool>(
133 "~/pause_servo", [this](const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
134 const std::shared_ptr<std_srvs::srv::SetBool::Response>& response) {
135 return pauseServo(request, response);
136 });
137
138 // Start the servoing loop
139 servo_loop_thread_ = std::thread(&ServoNode::servoLoop, this);
140}
141
142void ServoNode::pauseServo(const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
143 const std::shared_ptr<std_srvs::srv::SetBool::Response>& response)
144{
145 servo_paused_ = request->data;
146 response->success = (servo_paused_ == request->data);
147 if (servo_paused_)
148 {
149 servo_->setCollisionChecking(false);
150 response->message = "Servoing disabled";
151 }
152 else
153 {
154 // Reset the smoothing plugin with the robot's current state in case the robot moved between pausing and unpausing.
155 last_commanded_state_ = servo_->getCurrentRobotState(true /* block for current robot state */);
156 servo_->resetSmoothing(last_commanded_state_);
157
158 // clear out the command rolling window and reset last commanded state to be the current state
159 joint_cmd_rolling_window_.clear();
160
161 // reactivate collision checking
162 servo_->setCollisionChecking(true);
163 response->message = "Servoing enabled";
164 }
165}
166
167void ServoNode::switchCommandType(const std::shared_ptr<moveit_msgs::srv::ServoCommandType::Request>& request,
168 const std::shared_ptr<moveit_msgs::srv::ServoCommandType::Response>& response)
169{
170 const bool is_valid = (request->command_type >= static_cast<int8_t>(CommandType::MIN)) &&
171 (request->command_type <= static_cast<int8_t>(CommandType::MAX));
172 if (is_valid)
173 {
174 servo_->setCommandType(static_cast<CommandType>(request->command_type));
175 }
176 else
177 {
178 RCLCPP_WARN_STREAM(node_->get_logger(), "Unknown command type " << request->command_type << " requested");
179 }
180 response->success = (request->command_type == static_cast<int8_t>(servo_->getCommandType()));
181}
182
183void ServoNode::jointJogCallback(const control_msgs::msg::JointJog::ConstSharedPtr& msg)
184{
185 latest_joint_jog_ = *msg;
186 new_joint_jog_msg_ = true;
187}
188
189void ServoNode::twistCallback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr& msg)
190{
191 latest_twist_ = *msg;
192 new_twist_msg_ = true;
193}
194
195void ServoNode::poseCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg)
196{
197 latest_pose_ = *msg;
198 new_pose_msg_ = true;
199}
200
201std::optional<KinematicState> ServoNode::processJointJogCommand(const moveit::core::RobotStatePtr& robot_state)
202{
203 std::optional<KinematicState> next_joint_state = std::nullopt;
204 // Reject any other command types that had arrived simultaneously.
205 new_twist_msg_ = new_pose_msg_ = false;
206
207 const bool command_stale = (node_->now() - latest_joint_jog_.header.stamp) >=
208 rclcpp::Duration::from_seconds(servo_params_.incoming_command_timeout);
209 if (!command_stale)
210 {
211 JointJogCommand command{ latest_joint_jog_.joint_names, latest_joint_jog_.velocities };
212 next_joint_state = servo_->getNextJointState(robot_state, command);
213 }
214 else
215 {
216 auto result = servo_->smoothHalt(last_commanded_state_);
217 new_joint_jog_msg_ = !result.first;
218 if (new_joint_jog_msg_)
219 {
220 next_joint_state = result.second;
221 RCLCPP_DEBUG_STREAM(node_->get_logger(), "Joint jog command timed out. Halting to a stop.");
222 }
223 }
224
225 return next_joint_state;
226}
227
228std::optional<KinematicState> ServoNode::processTwistCommand(const moveit::core::RobotStatePtr& robot_state)
229{
230 std::optional<KinematicState> next_joint_state = std::nullopt;
231
232 // Mark latest twist command as processed.
233 // Reject any other command types that had arrived simultaneously.
234 new_joint_jog_msg_ = new_pose_msg_ = false;
235
236 const bool command_stale = (node_->now() - latest_twist_.header.stamp) >=
237 rclcpp::Duration::from_seconds(servo_params_.incoming_command_timeout);
238 if (!command_stale)
239 {
240 const Eigen::Vector<double, 6> velocities{ latest_twist_.twist.linear.x, latest_twist_.twist.linear.y,
241 latest_twist_.twist.linear.z, latest_twist_.twist.angular.x,
242 latest_twist_.twist.angular.y, latest_twist_.twist.angular.z };
243 const TwistCommand command{ latest_twist_.header.frame_id, velocities };
244 next_joint_state = servo_->getNextJointState(robot_state, command);
245 }
246 else
247 {
248 auto result = servo_->smoothHalt(last_commanded_state_);
249 new_twist_msg_ = !result.first;
250 if (new_twist_msg_)
251 {
252 next_joint_state = result.second;
253 RCLCPP_DEBUG_STREAM(node_->get_logger(), "Twist command timed out. Halting to a stop.");
254 }
255 }
256
257 return next_joint_state;
258}
259
260std::optional<KinematicState> ServoNode::processPoseCommand(const moveit::core::RobotStatePtr& robot_state)
261{
262 std::optional<KinematicState> next_joint_state = std::nullopt;
263
264 // Mark latest pose command as processed.
265 // Reject any other command types that had arrived simultaneously.
266 new_joint_jog_msg_ = new_twist_msg_ = false;
267
268 const bool command_stale = (node_->now() - latest_pose_.header.stamp) >=
269 rclcpp::Duration::from_seconds(servo_params_.incoming_command_timeout);
270 if (!command_stale)
271 {
272 const PoseCommand command = poseFromPoseStamped(latest_pose_);
273 next_joint_state = servo_->getNextJointState(robot_state, command);
274 }
275 else
276 {
277 auto result = servo_->smoothHalt(last_commanded_state_);
278 new_pose_msg_ = !result.first;
279 if (new_pose_msg_)
280 {
281 next_joint_state = result.second;
282 RCLCPP_DEBUG_STREAM(node_->get_logger(), "Pose command timed out. Halting to a stop.");
283 }
284 }
285
286 return next_joint_state;
287}
288
289void ServoNode::servoLoop()
290{
291 moveit_msgs::msg::ServoStatus status_msg;
292 std::optional<KinematicState> next_joint_state = std::nullopt;
293 rclcpp::WallRate servo_frequency(1 / servo_params_.publish_period);
294
295 // wait for first robot joint state update
296 const auto servo_node_start = node_->now();
297 while (planning_scene_monitor_->getLastUpdateTime().get_clock_type() != node_->get_clock()->get_clock_type() ||
298 servo_node_start > planning_scene_monitor_->getLastUpdateTime())
299 {
300 RCLCPP_INFO(node_->get_logger(), "Waiting to receive robot state update.");
301 rclcpp::sleep_for(std::chrono::seconds(1));
302 }
303 KinematicState current_state = servo_->getCurrentRobotState(true /* block for current robot state */);
304 last_commanded_state_ = current_state;
305 // Ensure the filter is up to date
306 servo_->resetSmoothing(current_state);
307
308 // Get the robot state and joint model group info.
309 moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
310 const moveit::core::JointModelGroup* joint_model_group =
311 robot_state->getJointModelGroup(servo_params_.move_group_name);
312
313 while (rclcpp::ok() && !stop_servo_)
314 {
315 // Skip processing if servoing is disabled.
316 if (servo_paused_)
317 {
318 servo_->resetSmoothing(current_state);
319 servo_frequency.sleep();
320 continue;
321 }
322
323 const bool use_trajectory = servo_params_.command_out_type == "trajectory_msgs/JointTrajectory";
324 const auto cur_time = node_->now();
325
326 if (use_trajectory && !joint_cmd_rolling_window_.empty() && joint_cmd_rolling_window_.back().time_stamp > cur_time)
327 {
328 current_state = joint_cmd_rolling_window_.back();
329 }
330 else
331 {
332 // if all joint_cmd_rolling_window_ is empty or all commands in it are outdated, use current robot state
333 joint_cmd_rolling_window_.clear();
334 current_state = servo_->getCurrentRobotState(false /* block for current robot state */);
335 current_state.velocities *= 0.0;
336 }
337
338 // update robot state values
339 robot_state->setJointGroupPositions(joint_model_group, current_state.positions);
340 robot_state->setJointGroupVelocities(joint_model_group, current_state.velocities);
341
342 next_joint_state = std::nullopt;
343 const CommandType expected_type = servo_->getCommandType();
344
345 if (expected_type == CommandType::JOINT_JOG && new_joint_jog_msg_)
346 {
347 next_joint_state = processJointJogCommand(robot_state);
348 }
349 else if (expected_type == CommandType::TWIST && new_twist_msg_)
350 {
351 next_joint_state = processTwistCommand(robot_state);
352 }
353 else if (expected_type == CommandType::POSE && new_pose_msg_)
354 {
355 next_joint_state = processPoseCommand(robot_state);
356 }
357 else if (new_joint_jog_msg_ || new_twist_msg_ || new_pose_msg_)
358 {
359 new_joint_jog_msg_ = new_twist_msg_ = new_pose_msg_ = false;
360 RCLCPP_WARN_STREAM(node_->get_logger(), "Command type has not been set, cannot accept input");
361 }
362
363 if (next_joint_state && (servo_->getStatus() != StatusCode::INVALID) &&
364 (servo_->getStatus() != StatusCode::HALT_FOR_COLLISION))
365 {
366 if (use_trajectory)
367 {
368 auto& next_joint_state_value = next_joint_state.value();
369 updateSlidingWindow(next_joint_state_value, joint_cmd_rolling_window_, servo_params_.max_expected_latency,
370 cur_time);
371 if (const auto msg = composeTrajectoryMessage(servo_params_, joint_cmd_rolling_window_))
372 {
373 trajectory_publisher_->publish(msg.value());
374 }
375 }
376 else
377 {
378 multi_array_publisher_->publish(composeMultiArrayMessage(servo_->getParams(), next_joint_state.value()));
379 }
380 last_commanded_state_ = next_joint_state.value();
381 }
382 else
383 {
384 // if no new command was created, use current robot state
385 updateSlidingWindow(current_state, joint_cmd_rolling_window_, servo_params_.max_expected_latency, cur_time);
386 }
387
388 status_msg.code = static_cast<int8_t>(servo_->getStatus());
389 status_msg.message = servo_->getStatusMessage();
390 status_publisher_->publish(status_msg);
391
392 servo_frequency.sleep();
393 }
394}
395
396} // namespace moveit_servo
397
398#include "rclcpp_components/register_node_macro.hpp"
399RCLCPP_COMPONENTS_REGISTER_NODE(moveit_servo::ServoNode)
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
ServoNode(const rclcpp::NodeOptions &options)
std::optional< trajectory_msgs::msg::JointTrajectory > composeTrajectoryMessage(const servo::Params &servo_params, const std::deque< KinematicState > &joint_cmd_rolling_window)
Create a trajectory message from a rolling window queue of joint state commands. Method optionally re...
Definition common.cpp:151
std_msgs::msg::Float64MultiArray composeMultiArrayMessage(const servo::Params &servo_params, const KinematicState &joint_state)
Create a Float64MultiArray message from given joint state.
Definition common.cpp:258
void updateSlidingWindow(KinematicState &next_joint_state, std::deque< KinematicState > &joint_cmd_rolling_window, double max_expected_latency, const rclcpp::Time &cur_time)
Adds a new joint state command to a queue containing commands over a time window. Also modifies the v...
Definition common.cpp:203
PoseCommand poseFromPoseStamped(const geometry_msgs::msg::PoseStamped &msg)
Convert a PoseStamped message to a Servo Pose.
Definition common.cpp:464
planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const servo::Params &servo_params)
Creates the planning scene monitor used by servo.
Definition common.cpp:480
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition logger.cpp:73