moveit2
The MoveIt Motion Planning Framework for ROS 2.
servo_calcs.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : servo_calcs.h
3  * Project : moveit_servo
4  * Created : 1/11/2019
5  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
6  *
7  * BSD 3-Clause License
8  *
9  * Copyright (c) 2019, Los Alamos National Security, LLC
10  * All rights reserved.
11  *
12  * Redistribution and use in source and binary forms, with or without
13  * modification, are permitted provided that the following conditions are met:
14  *
15  * * Redistributions of source code must retain the above copyright notice, this
16  * list of conditions and the following disclaimer.
17  *
18  * * Redistributions in binary form must reproduce the above copyright notice,
19  * this list of conditions and the following disclaimer in the documentation
20  * and/or other materials provided with the distribution.
21  *
22  * * Neither the name of the copyright holder nor the names of its
23  * contributors may be used to endorse or promote products derived from
24  * this software without specific prior written permission.
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
27  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
28  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
29  * ARE
30  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
31  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
32  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
33  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
34  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
35  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
36  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
37  *******************************************************************************/
38 
39 #pragma once
40 
41 // C++
42 #include <condition_variable>
43 #include <mutex>
44 #include <thread>
45 #include <atomic>
46 
47 // ROS
48 #include <control_msgs/msg/joint_jog.hpp>
49 #include <geometry_msgs/msg/twist_stamped.hpp>
52 #include <moveit_msgs/srv/change_drift_dimensions.hpp>
53 #include <moveit_msgs/srv/change_control_dimensions.hpp>
54 #include <pluginlib/class_loader.hpp>
55 #include <rclcpp/rclcpp.hpp>
56 #include <sensor_msgs/msg/joint_state.hpp>
57 #include <std_msgs/msg/float64.hpp>
58 #include <std_msgs/msg/float64_multi_array.hpp>
59 #include <std_msgs/msg/int8.hpp>
60 #include <std_srvs/srv/empty.hpp>
61 #include <trajectory_msgs/msg/joint_trajectory.hpp>
62 
63 // moveit_core
65 
66 // moveit_servo
70 
71 namespace moveit_servo
72 {
73 enum class ServoType
74 {
77 };
78 
80 {
81 public:
82  ServoCalcs(const rclcpp::Node::SharedPtr& node,
83  const std::shared_ptr<const moveit_servo::ServoParameters>& parameters,
84  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
85 
86  ~ServoCalcs();
87 
89  void start();
90 
98  bool getCommandFrameTransform(Eigen::Isometry3d& transform);
99  bool getCommandFrameTransform(geometry_msgs::msg::TransformStamped& transform);
100 
108  bool getEEFrameTransform(Eigen::Isometry3d& transform);
109  bool getEEFrameTransform(geometry_msgs::msg::TransformStamped& transform);
110 
112  void setPaused(bool paused);
113 
114 protected:
116  void mainCalcLoop();
117 
120 
122  void stop();
123 
125  bool cartesianServoCalcs(geometry_msgs::msg::TwistStamped& cmd,
126  trajectory_msgs::msg::JointTrajectory& joint_trajectory);
127 
129  bool jointServoCalcs(const control_msgs::msg::JointJog& cmd, trajectory_msgs::msg::JointTrajectory& joint_trajectory);
130 
132  void updateJoints();
133 
139  bool checkValidCommand(const control_msgs::msg::JointJog& cmd);
140 
146  bool checkValidCommand(const geometry_msgs::msg::TwistStamped& cmd);
147 
152  Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::msg::TwistStamped& command);
153 
158  Eigen::VectorXd scaleJointCommand(const control_msgs::msg::JointJog& command);
159 
162  void filteredHalt(trajectory_msgs::msg::JointTrajectory& joint_trajectory);
163 
167  void suddenHalt(sensor_msgs::msg::JointState& joint_state,
168  const std::vector<const moveit::core::JointModel*>& joints_to_halt) const;
169 
173  std::vector<const moveit::core::JointModel*> enforcePositionLimits(sensor_msgs::msg::JointState& joint_state) const;
174 
176  void composeJointTrajMessage(const sensor_msgs::msg::JointState& joint_state,
177  trajectory_msgs::msg::JointTrajectory& joint_trajectory);
178 
180  void resetLowPassFilters(const sensor_msgs::msg::JointState& joint_state);
181 
188  bool internalServoUpdate(Eigen::ArrayXd& delta_theta, trajectory_msgs::msg::JointTrajectory& joint_trajectory,
189  const ServoType servo_type);
190 
198  bool applyJointUpdate(const Eigen::ArrayXd& delta_theta, sensor_msgs::msg::JointState& joint_state);
199 
203  void insertRedundantPointsIntoTrajectory(trajectory_msgs::msg::JointTrajectory& joint_trajectory, int count) const;
204 
212  void removeDimension(Eigen::MatrixXd& matrix, Eigen::VectorXd& delta_x, unsigned int row_to_remove) const;
213 
220  void removeDriftDimensions(Eigen::MatrixXd& matrix, Eigen::VectorXd& delta_x);
221 
227  void enforceControlDimensions(geometry_msgs::msg::TwistStamped& command);
228 
229  /* \brief Callback for joint subsription */
230  void jointStateCB(const sensor_msgs::msg::JointState::SharedPtr msg);
231 
232  /* \brief Command callbacks */
233  void twistStampedCB(const geometry_msgs::msg::TwistStamped::ConstSharedPtr& msg);
234  void jointCmdCB(const control_msgs::msg::JointJog::ConstSharedPtr& msg);
235  void collisionVelocityScaleCB(const std_msgs::msg::Float64::ConstSharedPtr& msg);
236 
245  void changeDriftDimensions(const std::shared_ptr<moveit_msgs::srv::ChangeDriftDimensions::Request>& req,
246  const std::shared_ptr<moveit_msgs::srv::ChangeDriftDimensions::Response>& res);
247 
249  // Service callback for changing servoing dimensions
250  void changeControlDimensions(const std::shared_ptr<moveit_msgs::srv::ChangeControlDimensions::Request>& req,
251  const std::shared_ptr<moveit_msgs::srv::ChangeControlDimensions::Response>& res);
252 
254  bool resetServoStatus(const std::shared_ptr<std_srvs::srv::Empty::Request>& req,
255  const std::shared_ptr<std_srvs::srv::Empty::Response>& res);
256 
257  // Pointer to the ROS node
258  std::shared_ptr<rclcpp::Node> node_;
259 
260  // Parameters from yaml
261  const std::shared_ptr<const moveit_servo::ServoParameters> parameters_;
262 
263  // Pointer to the collision environment
264  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
265 
266  // Track the number of cycles during which motion has not occurred.
267  // Will avoid re-publishing zero velocities endlessly.
269 
270  // Flag for staying inactive while there are no incoming commands
272 
273  // Flag saying if the filters were updated during the timer callback
274  bool updated_filters_ = false;
275 
276  // Nonzero status flags
279  bool have_nonzero_command_ = false;
280 
281  // Incoming command messages
282  geometry_msgs::msg::TwistStamped twist_stamped_cmd_;
283  control_msgs::msg::JointJog joint_servo_cmd_;
284 
286 
287  moveit::core::RobotStatePtr current_state_;
288 
289  // (mutex protected below)
290  // internal_joint_state_ is used in servo calculations. It shouldn't be relied on to be accurate.
291  // original_joint_state_ is the same as incoming_joint_state_ except it only contains the joints the servo node acts
292  // on.
293  sensor_msgs::msg::JointState internal_joint_state_, original_joint_state_;
294  std::map<std::string, std::size_t> joint_state_name_map_;
295 
296  // Smoothing algorithm (loads a plugin)
297  std::shared_ptr<online_signal_smoothing::SmoothingBaseClass> smoother_;
298 
299  trajectory_msgs::msg::JointTrajectory::SharedPtr last_sent_command_;
300 
301  // ROS
302  rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_;
303  rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr twist_stamped_sub_;
304  rclcpp::Subscription<control_msgs::msg::JointJog>::SharedPtr joint_cmd_sub_;
305  rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr collision_velocity_scale_sub_;
306  rclcpp::Publisher<std_msgs::msg::Int8>::SharedPtr status_pub_;
307  rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr trajectory_outgoing_cmd_pub_;
308  rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr multiarray_outgoing_cmd_pub_;
309  rclcpp::Service<moveit_msgs::srv::ChangeControlDimensions>::SharedPtr control_dimensions_server_;
310  rclcpp::Service<moveit_msgs::srv::ChangeDriftDimensions>::SharedPtr drift_dimensions_server_;
311  rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_servo_status_;
312 
313  // Main tracking / result publisher loop
314  std::thread thread_;
316  std::atomic<bool> done_stopping_;
317 
318  // Status
320  std::atomic<bool> paused_;
323  bool ok_to_publish_ = false;
325 
326  // Use ArrayXd type to enable more coefficient-wise operations
327  Eigen::ArrayXd delta_theta_;
328 
330 
331  unsigned int num_joints_;
332 
333  // True -> allow drift in this dimension. In the command frame. [x, y, z, roll, pitch, yaw]
334  std::array<bool, 6> drift_dimensions_ = { { false, false, false, false, false, false } };
335 
336  // The dimensions to control. In the command frame. [x, y, z, roll, pitch, yaw]
337  std::array<bool, 6> control_dimensions_ = { { true, true, true, true, true, true } };
338 
339  // main_loop_mutex_ is used to protect the input state and dynamic parameters
340  mutable std::mutex main_loop_mutex_;
341  Eigen::Isometry3d tf_moveit_to_robot_cmd_frame_;
342  Eigen::Isometry3d tf_moveit_to_ee_frame_;
343  geometry_msgs::msg::TwistStamped::ConstSharedPtr latest_twist_stamped_;
344  control_msgs::msg::JointJog::ConstSharedPtr latest_joint_cmd_;
345  rclcpp::Time latest_twist_command_stamp_ = rclcpp::Time(0., RCL_ROS_TIME);
346  rclcpp::Time latest_joint_command_stamp_ = rclcpp::Time(0., RCL_ROS_TIME);
349 
350  // input condition variable used for low latency mode
351  std::condition_variable input_cv_;
352  bool new_input_cmd_ = false;
353 
354  // dynamic parameters
356  rcl_interfaces::msg::SetParametersResult robotLinkCommandFrameCallback(const rclcpp::Parameter& parameter);
357 
358  // Load a smoothing plugin
359  pluginlib::ClassLoader<online_signal_smoothing::SmoothingBaseClass> smoothing_loader_;
360 
361  kinematics::KinematicsBaseConstPtr ik_solver_;
362  Eigen::Isometry3d ik_base_to_tip_frame_;
363  bool use_inv_jacobian_ = false;
364 };
365 } // namespace moveit_servo
const std::shared_ptr< const moveit_servo::ServoParameters > parameters_
Definition: servo_calcs.h:261
std::atomic< bool > paused_
Definition: servo_calcs.h:320
unsigned int num_joints_
Definition: servo_calcs.h:331
void removeDimension(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x, unsigned int row_to_remove) const
rclcpp::Publisher< std_msgs::msg::Int8 >::SharedPtr status_pub_
Definition: servo_calcs.h:306
Eigen::Isometry3d tf_moveit_to_ee_frame_
Definition: servo_calcs.h:342
std::array< bool, 6 > control_dimensions_
Definition: servo_calcs.h:337
std::array< bool, 6 > drift_dimensions_
Definition: servo_calcs.h:334
void changeDriftDimensions(const std::shared_ptr< moveit_msgs::srv::ChangeDriftDimensions::Request > &req, const std::shared_ptr< moveit_msgs::srv::ChangeDriftDimensions::Response > &res)
moveit::core::RobotStatePtr current_state_
Definition: servo_calcs.h:287
void resetLowPassFilters(const sensor_msgs::msg::JointState &joint_state)
Set the filters to the specified values.
sensor_msgs::msg::JointState original_joint_state_
Definition: servo_calcs.h:293
void updateJoints()
Parse the incoming joint msg for the joints of our MoveGroup.
control_msgs::msg::JointJog joint_servo_cmd_
Definition: servo_calcs.h:283
void insertRedundantPointsIntoTrajectory(trajectory_msgs::msg::JointTrajectory &joint_trajectory, int count) const
Gazebo simulations have very strict message timestamp requirements. Satisfy Gazebo by stuffing multip...
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
rclcpp::Service< moveit_msgs::srv::ChangeControlDimensions >::SharedPtr control_dimensions_server_
Definition: servo_calcs.h:309
Eigen::Isometry3d tf_moveit_to_robot_cmd_frame_
Definition: servo_calcs.h:341
rclcpp::Service< moveit_msgs::srv::ChangeDriftDimensions >::SharedPtr drift_dimensions_server_
Definition: servo_calcs.h:310
std::string robot_link_command_frame_
Definition: servo_calcs.h:355
const int gazebo_redundant_message_count_
Definition: servo_calcs.h:329
rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr multiarray_outgoing_cmd_pub_
Definition: servo_calcs.h:308
std::map< std::string, std::size_t > joint_state_name_map_
Definition: servo_calcs.h:294
bool jointServoCalcs(const control_msgs::msg::JointJog &cmd, trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Do servoing calculations for direct commands to a joint.
void stop()
Stop the currently running thread.
bool cartesianServoCalcs(geometry_msgs::msg::TwistStamped &cmd, trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Do servoing calculations for Cartesian twist commands.
pluginlib::ClassLoader< online_signal_smoothing::SmoothingBaseClass > smoothing_loader_
Definition: servo_calcs.h:359
rclcpp::Service< std_srvs::srv::Empty >::SharedPtr reset_servo_status_
Definition: servo_calcs.h:311
rclcpp::Subscription< geometry_msgs::msg::TwistStamped >::SharedPtr twist_stamped_sub_
Definition: servo_calcs.h:303
void jointStateCB(const sensor_msgs::msg::JointState::SharedPtr msg)
control_msgs::msg::JointJog::ConstSharedPtr latest_joint_cmd_
Definition: servo_calcs.h:344
rclcpp::Subscription< sensor_msgs::msg::JointState >::SharedPtr joint_state_sub_
Definition: servo_calcs.h:302
geometry_msgs::msg::TwistStamped::ConstSharedPtr latest_twist_stamped_
Definition: servo_calcs.h:343
geometry_msgs::msg::TwistStamped twist_stamped_cmd_
Definition: servo_calcs.h:282
rclcpp::Subscription< control_msgs::msg::JointJog >::SharedPtr joint_cmd_sub_
Definition: servo_calcs.h:304
std::condition_variable input_cv_
Definition: servo_calcs.h:351
Eigen::ArrayXd delta_theta_
Definition: servo_calcs.h:327
sensor_msgs::msg::JointState internal_joint_state_
Definition: servo_calcs.h:293
rclcpp::Subscription< std_msgs::msg::Float64 >::SharedPtr collision_velocity_scale_sub_
Definition: servo_calcs.h:305
void changeControlDimensions(const std::shared_ptr< moveit_msgs::srv::ChangeControlDimensions::Request > &req, const std::shared_ptr< moveit_msgs::srv::ChangeControlDimensions::Response > &res)
Start the main calculation timer.
bool getEEFrameTransform(Eigen::Isometry3d &transform)
void collisionVelocityScaleCB(const std_msgs::msg::Float64::ConstSharedPtr &msg)
void twistStampedCB(const geometry_msgs::msg::TwistStamped::ConstSharedPtr &msg)
Eigen::VectorXd scaleJointCommand(const control_msgs::msg::JointJog &command)
If incoming velocity commands are from a unitless joystick, scale them to physical units....
bool internalServoUpdate(Eigen::ArrayXd &delta_theta, trajectory_msgs::msg::JointTrajectory &joint_trajectory, const ServoType servo_type)
Handles all aspects of the servoing after the desired joint commands are established Joint and Cartes...
rclcpp::Time latest_joint_command_stamp_
Definition: servo_calcs.h:346
rcl_interfaces::msg::SetParametersResult robotLinkCommandFrameCallback(const rclcpp::Parameter &parameter)
void mainCalcLoop()
Run the main calculation loop.
void calculateSingleIteration()
Do calculations for a single iteration. Publish one outgoing command.
void jointCmdCB(const control_msgs::msg::JointJog::ConstSharedPtr &msg)
rclcpp::Time latest_twist_command_stamp_
Definition: servo_calcs.h:345
const moveit::core::JointModelGroup * joint_model_group_
Definition: servo_calcs.h:285
rclcpp::Publisher< trajectory_msgs::msg::JointTrajectory >::SharedPtr trajectory_outgoing_cmd_pub_
Definition: servo_calcs.h:307
trajectory_msgs::msg::JointTrajectory::SharedPtr last_sent_command_
Definition: servo_calcs.h:299
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: servo_calcs.h:264
bool checkValidCommand(const control_msgs::msg::JointJog &cmd)
void composeJointTrajMessage(const sensor_msgs::msg::JointState &joint_state, trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Compose the outgoing JointTrajectory message.
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
void suddenHalt(sensor_msgs::msg::JointState &joint_state, const std::vector< const moveit::core::JointModel * > &joints_to_halt) const
Suddenly halt for a joint limit or other critical issue. Is handled differently for position vs....
std::shared_ptr< online_signal_smoothing::SmoothingBaseClass > smoother_
Definition: servo_calcs.h:297
void filteredHalt(trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Come to a halt in a smooth way. Apply a smoothing plugin, if one is configured.
void start()
Start the timer where we do work and publish outputs.
Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::msg::TwistStamped &command)
If incoming velocity commands are from a unitless joystick, scale them to physical units....
Eigen::Isometry3d ik_base_to_tip_frame_
Definition: servo_calcs.h:362
void enforceControlDimensions(geometry_msgs::msg::TwistStamped &command)
void removeDriftDimensions(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x)
bool resetServoStatus(const std::shared_ptr< std_srvs::srv::Empty::Request > &req, const std::shared_ptr< std_srvs::srv::Empty::Response > &res)
Service callback to reset Servo status, e.g. so the arm can move again after a collision.
std::shared_ptr< rclcpp::Node > node_
Definition: servo_calcs.h:258
kinematics::KinematicsBaseConstPtr ik_solver_
Definition: servo_calcs.h:361
bool applyJointUpdate(const Eigen::ArrayXd &delta_theta, sensor_msgs::msg::JointState &joint_state)
Joint-wise update of a sensor_msgs::msg::JointState with given delta's Also filters and calculates th...
ServoCalcs(const rclcpp::Node::SharedPtr &node, const std::shared_ptr< const moveit_servo::ServoParameters > &parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Definition: servo_calcs.cpp:65
std::atomic< bool > done_stopping_
Definition: servo_calcs.h:316
std::vector< const moveit::core::JointModel * > enforcePositionLimits(sensor_msgs::msg::JointState &joint_state) const
Avoid overshooting joint limits.