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