41#if __has_include(<realtime_tools/realtime_helpers.hpp>)
42#include <realtime_tools/realtime_helpers.hpp>
44#include <realtime_tools/thread_priority.hpp>
55 return node_->get_node_base_interface();
61 if (servo_loop_thread_.joinable())
62 servo_loop_thread_.join();
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 }
76 if (realtime_tools::configure_sched_fifo(servo_params_.thread_priority))
78 RCLCPP_INFO_STREAM(node_->get_logger(),
"Enabled SCHED_FIFO and higher thread priority.");
82 RCLCPP_WARN_STREAM(node_->get_logger(),
"Could not enable FIFO RT scheduling policy. Continuing with the default.");
86 if (!realtime_tools::has_realtime_kernel())
88 RCLCPP_WARN_STREAM(node_->get_logger(),
"Realtime kernel is recommended for better performance.");
91 std::shared_ptr<servo::ParamListener> servo_param_listener =
92 std::make_shared<servo::ParamListener>(node_,
"moveit_servo");
96 servo_ = std::make_unique<Servo>(node_, servo_param_listener, planning_scene_monitor_);
98 servo_params_ = servo_->getParams();
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); });
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); });
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); });
115 if (servo_params_.command_out_type ==
"trajectory_msgs/JointTrajectory")
117 trajectory_publisher_ = node_->create_publisher<trajectory_msgs::msg::JointTrajectory>(
118 servo_params_.command_out_topic, rclcpp::SystemDefaultsQoS());
120 else if (servo_params_.command_out_type ==
"std_msgs/Float64MultiArray")
122 multi_array_publisher_ = node_->create_publisher<std_msgs::msg::Float64MultiArray>(servo_params_.command_out_topic,
123 rclcpp::SystemDefaultsQoS());
127 node_->create_publisher<moveit_msgs::msg::ServoStatus>(servo_params_.status_topic, rclcpp::SystemDefaultsQoS());
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);
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);
144 servo_loop_thread_ = std::thread(&ServoNode::servoLoop,
this);
147void ServoNode::pauseServo(
const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
148 const std::shared_ptr<std_srvs::srv::SetBool::Response>& response)
150 servo_paused_ = request->data;
151 response->success = (servo_paused_ == request->data);
154 servo_->setCollisionChecking(
false);
155 response->message =
"Servoing disabled";
159 std::lock_guard<std::mutex> lock_guard(lock_);
161 last_commanded_state_ = servo_->getCurrentRobotState(
true );
162 servo_->resetSmoothing(last_commanded_state_);
165 joint_cmd_rolling_window_.clear();
168 servo_->setCollisionChecking(
true);
169 response->message =
"Servoing enabled";
173void ServoNode::switchCommandType(
const std::shared_ptr<moveit_msgs::srv::ServoCommandType::Request>& request,
174 const std::shared_ptr<moveit_msgs::srv::ServoCommandType::Response>& response)
176 const bool is_valid = (request->command_type >=
static_cast<int8_t
>(
CommandType::MIN)) &&
180 servo_->setCommandType(
static_cast<CommandType>(request->command_type));
184 RCLCPP_WARN_STREAM(node_->get_logger(),
"Unknown command type " << request->command_type <<
" requested");
186 response->success = (request->command_type ==
static_cast<int8_t
>(servo_->getCommandType()));
189void ServoNode::jointJogCallback(
const control_msgs::msg::JointJog::ConstSharedPtr& msg)
191 latest_joint_jog_ = *msg;
192 new_joint_jog_msg_ =
true;
195void ServoNode::twistCallback(
const geometry_msgs::msg::TwistStamped::ConstSharedPtr& msg)
197 latest_twist_ = *msg;
198 new_twist_msg_ =
true;
201void ServoNode::poseCallback(
const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg)
204 new_pose_msg_ =
true;
207std::optional<KinematicState> ServoNode::processJointJogCommand(
const moveit::core::RobotStatePtr& robot_state)
209 std::optional<KinematicState> next_joint_state = std::nullopt;
211 new_twist_msg_ = new_pose_msg_ =
false;
213 const bool command_stale = (node_->now() - latest_joint_jog_.header.stamp) >=
214 rclcpp::Duration::from_seconds(servo_params_.incoming_command_timeout);
217 JointJogCommand command{ latest_joint_jog_.joint_names, latest_joint_jog_.velocities };
218 next_joint_state = servo_->getNextJointState(robot_state, command);
222 auto result = servo_->smoothHalt(last_commanded_state_);
223 new_joint_jog_msg_ = !result.first;
224 if (new_joint_jog_msg_)
226 next_joint_state = result.second;
227 RCLCPP_DEBUG_STREAM(node_->get_logger(),
"Joint jog command timed out. Halting to a stop.");
231 return next_joint_state;
234std::optional<KinematicState> ServoNode::processTwistCommand(
const moveit::core::RobotStatePtr& robot_state)
236 std::optional<KinematicState> next_joint_state = std::nullopt;
240 new_joint_jog_msg_ = new_pose_msg_ =
false;
242 const bool command_stale = (node_->now() - latest_twist_.header.stamp) >=
243 rclcpp::Duration::from_seconds(servo_params_.incoming_command_timeout);
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);
254 auto result = servo_->smoothHalt(last_commanded_state_);
255 new_twist_msg_ = !result.first;
258 next_joint_state = result.second;
259 RCLCPP_DEBUG_STREAM(node_->get_logger(),
"Twist command timed out. Halting to a stop.");
263 return next_joint_state;
266std::optional<KinematicState> ServoNode::processPoseCommand(
const moveit::core::RobotStatePtr& robot_state)
268 std::optional<KinematicState> next_joint_state = std::nullopt;
272 new_joint_jog_msg_ = new_twist_msg_ =
false;
274 const bool command_stale = (node_->now() - latest_pose_.header.stamp) >=
275 rclcpp::Duration::from_seconds(servo_params_.incoming_command_timeout);
279 next_joint_state = servo_->getNextJointState(robot_state, command);
283 auto result = servo_->smoothHalt(last_commanded_state_);
284 new_pose_msg_ = !result.first;
287 next_joint_state = result.second;
288 RCLCPP_DEBUG_STREAM(node_->get_logger(),
"Pose command timed out. Halting to a stop.");
292 return next_joint_state;
295void ServoNode::servoLoop()
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);
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())
306 RCLCPP_INFO(node_->get_logger(),
"Waiting to receive robot state update.");
307 rclcpp::sleep_for(std::chrono::seconds(1));
309 KinematicState current_state = servo_->getCurrentRobotState(
true );
310 last_commanded_state_ = current_state;
312 servo_->resetSmoothing(current_state);
315 moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
317 robot_state->getJointModelGroup(servo_params_.move_group_name);
319 while (rclcpp::ok() && !stop_servo_)
324 servo_->resetSmoothing(current_state);
325 servo_frequency.sleep();
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();
333 if (use_trajectory && !joint_cmd_rolling_window_.empty() && joint_cmd_rolling_window_.back().time_stamp > cur_time)
335 current_state = joint_cmd_rolling_window_.back();
340 joint_cmd_rolling_window_.clear();
341 current_state = servo_->getCurrentRobotState(
false );
342 current_state.velocities *= 0.0;
346 robot_state->setJointGroupPositions(joint_model_group, current_state.positions);
347 robot_state->setJointGroupVelocities(joint_model_group, current_state.velocities);
349 next_joint_state = std::nullopt;
350 const CommandType expected_type = servo_->getCommandType();
354 next_joint_state = processJointJogCommand(robot_state);
358 next_joint_state = processTwistCommand(robot_state);
362 next_joint_state = processPoseCommand(robot_state);
364 else if (new_joint_jog_msg_ || new_twist_msg_ || new_pose_msg_)
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");
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,
380 trajectory_publisher_->publish(msg.value());
387 last_commanded_state_ = next_joint_state.value();
392 updateSlidingWindow(current_state, joint_cmd_rolling_window_, servo_params_.max_expected_latency, cur_time);
393 servo_->resetSmoothing(current_state);
396 status_msg.code =
static_cast<int8_t
>(servo_->getStatus());
397 status_msg.message = servo_->getStatusMessage();
398 status_publisher_->publish(status_msg);
400 servo_frequency.sleep();
406#include "rclcpp_components/register_node_macro.hpp"
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...
std_msgs::msg::Float64MultiArray composeMultiArrayMessage(const servo::Params &servo_params, const KinematicState &joint_state)
Create a Float64MultiArray message from given joint state.
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...
PoseCommand poseFromPoseStamped(const geometry_msgs::msg::PoseStamped &msg)
Convert a PoseStamped message to a Servo Pose.
planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const servo::Params &servo_params)
Creates the planning scene monitor used by servo.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.