servo_calcs.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_calcs.cpp
35  * Project : moveit_servo
36  * Created : 1/11/2019
37  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
38  */
39 
40 #include <cassert>
41 
42 #include <std_msgs/Bool.h>
43 #include <std_msgs/Float64MultiArray.h>
44 
47 
48 static const std::string LOGNAME = "servo_calcs";
49 constexpr size_t ROS_LOG_THROTTLE_PERIOD = 30; // Seconds to throttle logs inside loops
50 
51 namespace moveit_servo
52 {
53 namespace
54 {
55 // Helper function for detecting zeroed message
56 bool isNonZero(const geometry_msgs::TwistStamped& msg)
57 {
58  return msg.twist.linear.x != 0.0 || msg.twist.linear.y != 0.0 || msg.twist.linear.z != 0.0 ||
59  msg.twist.angular.x != 0.0 || msg.twist.angular.y != 0.0 || msg.twist.angular.z != 0.0;
60 }
61 
62 // Helper function for detecting zeroed message
63 bool isNonZero(const control_msgs::JointJog& msg)
64 {
65  bool all_zeros = true;
66  for (double delta : msg.velocities)
67  {
68  all_zeros &= (delta == 0.0);
69  };
70  return !all_zeros;
71 }
72 
73 // Helper function for converting Eigen::Isometry3d to geometry_msgs/TransformStamped
74 geometry_msgs::TransformStamped convertIsometryToTransform(const Eigen::Isometry3d& eigen_tf,
75  const std::string& parent_frame,
76  const std::string& child_frame)
77 {
78  geometry_msgs::TransformStamped output = tf2::eigenToTransform(eigen_tf);
79  output.header.frame_id = parent_frame;
80  output.child_frame_id = child_frame;
81 
82  return output;
83 }
84 } // namespace
85 
86 // Constructor for the class that handles servoing calculations
88  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor)
89  : nh_(nh)
90  , parameters_(parameters)
91  , planning_scene_monitor_(planning_scene_monitor)
92  , stop_requested_(true)
93  , paused_(false)
94 {
95  // MoveIt Setup
96  current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
98  prev_joint_velocity_ = Eigen::ArrayXd::Zero(joint_model_group_->getActiveJointModels().size());
99 
100  // Subscribe to command topics
104 
105  // ROS Server for allowing drift in some dimensions
108 
109  // ROS Server for changing the control dimensions
112 
113  // ROS Server to reset the status, e.g. so the arm can move again after a collision
116 
117  // Publish and Subscribe to internal namespace topics
118  ros::NodeHandle internal_nh(nh_, "internal");
120  internal_nh.subscribe("collision_velocity_scale", ROS_QUEUE_SIZE, &ServoCalcs::collisionVelocityScaleCB, this);
121  worst_case_stop_time_pub_ = internal_nh.advertise<std_msgs::Float64>("worst_case_stop_time", ROS_QUEUE_SIZE);
122 
123  // Publish freshly-calculated joints to the robot.
124  // Put the outgoing msg in the right format (trajectory_msgs/JointTrajectory or std_msgs/Float64MultiArray).
125  if (parameters_.command_out_type == "trajectory_msgs/JointTrajectory")
126  outgoing_cmd_pub_ = nh_.advertise<trajectory_msgs::JointTrajectory>(parameters_.command_out_topic, ROS_QUEUE_SIZE);
127  else if (parameters_.command_out_type == "std_msgs/Float64MultiArray")
129 
130  // Publish status
132 
134  num_joints_ = internal_joint_state_.name.size();
135  internal_joint_state_.position.resize(num_joints_);
136  internal_joint_state_.velocity.resize(num_joints_);
137 
138  // A map for the indices of incoming joint commands
139  for (std::size_t i = 0; i < num_joints_; ++i)
140  {
142  }
143 
144  // Low-pass filters for the joint positions
145  for (size_t i = 0; i < num_joints_; ++i)
146  {
148  }
149 
150  // A matrix of all zeros is used to check whether matrices have been initialized
151  Eigen::Matrix3d empty_matrix;
152  empty_matrix.setZero();
153  tf_moveit_to_ee_frame_ = empty_matrix;
154  tf_moveit_to_robot_cmd_frame_ = empty_matrix;
155 }
156 
158 {
159  stop();
160 }
161 
163 {
164  // Stop the thread if we are currently running
165  stop();
166 
167  // We will update last_sent_command_ every time we start servo
168  auto initial_joint_trajectory = moveit::util::make_shared_from_pool<trajectory_msgs::JointTrajectory>();
169 
170  // When a joint_trajectory_controller receives a new command, a stamp of 0 indicates "begin immediately"
171  // See http://wiki.ros.org/joint_trajectory_controller#Trajectory_replacement
172  initial_joint_trajectory->header.stamp = ros::Time(0);
173  initial_joint_trajectory->header.frame_id = parameters_.planning_frame;
174  initial_joint_trajectory->joint_names = internal_joint_state_.name;
175  trajectory_msgs::JointTrajectoryPoint point;
176  point.time_from_start = ros::Duration(parameters_.publish_period);
177 
179  planning_scene_monitor_->getStateMonitor()->getCurrentState()->copyJointGroupPositions(joint_model_group_,
180  point.positions);
182  {
183  std::vector<double> velocity(num_joints_);
184  point.velocities = velocity;
185  }
187  {
188  // I do not know of a robot that takes acceleration commands.
189  // However, some controllers check that this data is non-empty.
190  // Send all zeros, for now.
191  point.accelerations.resize(num_joints_);
192  }
193  initial_joint_trajectory->points.push_back(point);
194  last_sent_command_ = initial_joint_trajectory;
195 
196  current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
197  tf_moveit_to_ee_frame_ = current_state_->getGlobalLinkTransform(parameters_.planning_frame).inverse() *
198  current_state_->getGlobalLinkTransform(parameters_.ee_frame_name);
199  tf_moveit_to_robot_cmd_frame_ = current_state_->getGlobalLinkTransform(parameters_.planning_frame).inverse() *
200  current_state_->getGlobalLinkTransform(parameters_.robot_link_command_frame);
201 
202  stop_requested_ = false;
203  thread_ = std::thread([this] { mainCalcLoop(); });
204  new_input_cmd_ = false;
205 }
206 
208 {
209  // Request stop
210  stop_requested_ = true;
211 
212  // Notify condition variable in case the thread is blocked on it
213  {
214  // scope so the mutex is unlocked after so the thread can continue
215  // and therefore be joinable
216  const std::lock_guard<std::mutex> lock(input_mutex_);
217  new_input_cmd_ = false;
218  input_cv_.notify_all();
219  }
220 
221  // Join the thread
222  if (thread_.joinable())
223  {
224  thread_.join();
225  }
226 }
227 
229 {
231 
232  while (ros::ok() && !stop_requested_)
233  {
234  // lock the input state mutex
235  std::unique_lock<std::mutex> input_lock(input_mutex_);
236 
237  // low latency mode -- begin calculations as soon as a new command is received.
239  {
240  input_cv_.wait(input_lock, [this] { return (new_input_cmd_ || stop_requested_); });
241  }
242 
243  // reset new_input_cmd_ flag
244  new_input_cmd_ = false;
245 
246  // run servo calcs
247  const auto start_time = ros::Time::now();
249  const auto run_duration = ros::Time::now() - start_time;
250 
251  // Log warning when the run duration was longer than the period
252  if (run_duration.toSec() > parameters_.publish_period)
253  {
255  "run_duration: " << run_duration.toSec() << " (" << parameters_.publish_period
256  << ")");
257  }
258 
259  // normal mode, unlock input mutex and wait for the period of the loop
261  {
262  input_lock.unlock();
263  rate.sleep();
264  }
265  }
266 }
267 
269 {
270  // Publish status each loop iteration
271  auto status_msg = moveit::util::make_shared_from_pool<std_msgs::Int8>();
272  status_msg->data = static_cast<int8_t>(status_);
273  status_pub_.publish(status_msg);
274 
275  // Always update the joints and end-effector transform for 2 reasons:
276  // 1) in case the getCommandFrameTransform() method is being used
277  // 2) so the low-pass filters are up to date and don't cause a jump
278  updateJoints();
279 
280  // Update from latest state
281  current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
282 
285  if (latest_joint_cmd_)
287 
288  // Check for stale cmds
293 
296 
297  // Get the transform from MoveIt planning frame to servoing command frame
298  // Calculate this transform to ensure it is available via C++ API
299  // We solve (planning_frame -> base -> robot_link_command_frame)
300  // by computing (base->planning_frame)^-1 * (base->robot_link_command_frame)
301  tf_moveit_to_robot_cmd_frame_ = current_state_->getGlobalLinkTransform(parameters_.planning_frame).inverse() *
302  current_state_->getGlobalLinkTransform(parameters_.robot_link_command_frame);
303 
304  // Calculate the transform from MoveIt planning frame to End Effector frame
305  // Calculate this transform to ensure it is available via C++ API
306  tf_moveit_to_ee_frame_ = current_state_->getGlobalLinkTransform(parameters_.planning_frame).inverse() *
307  current_state_->getGlobalLinkTransform(parameters_.ee_frame_name);
308 
310 
311  // Don't end this function without updating the filters
312  updated_filters_ = false;
313 
314  // If paused or while waiting for initial servo commands, just keep the low-pass filters up to date with current
315  // joints so a jump doesn't occur when restarting
317  {
319 
320  // Check if there are any new commands with valid timestamp
322  twist_stamped_cmd_.header.stamp == ros::Time(0.) && joint_servo_cmd_.header.stamp == ros::Time(0.);
323 
324  // Early exit
325  return;
326  }
327 
328  // If not waiting for initial command, and not paused.
329  // Do servoing calculations only if the robot should move, for efficiency
330  // Create new outgoing joint trajectory command message
331  auto joint_trajectory = moveit::util::make_shared_from_pool<trajectory_msgs::JointTrajectory>();
332 
333  // Prioritize cartesian servoing above joint servoing
334  // Only run commands if not stale and nonzero
336  {
337  if (!cartesianServoCalcs(twist_stamped_cmd_, *joint_trajectory))
338  {
340  return;
341  }
342  }
344  {
345  if (!jointServoCalcs(joint_servo_cmd_, *joint_trajectory))
346  {
348  return;
349  }
350  }
351  else
352  {
353  // Joint trajectory is not populated with anything, so set it to the last positions and 0 velocity
354  *joint_trajectory = *last_sent_command_;
355  for (auto& point : joint_trajectory->points)
356  {
357  current_state_->copyJointGroupPositions(joint_model_group_, point.positions);
358  point.velocities.assign(point.velocities.size(), 0);
359  point.accelerations.assign(point.accelerations.size(), 0);
360  }
361  }
362 
363  // Print a warning to the user if both are stale
365  {
367  "Stale command. "
368  "Try a larger 'incoming_command_timeout' parameter?");
369  }
370 
371  // If we should halt
373  {
374  suddenHalt(*joint_trajectory);
377  }
378 
379  // Skip the servoing publication if all inputs have been zero for several cycles in a row.
380  // num_outgoing_halt_msgs_to_publish == 0 signifies that we should keep republishing forever.
383  {
384  ok_to_publish_ = false;
385  ROS_DEBUG_STREAM_THROTTLE_NAMED(ROS_LOG_THROTTLE_PERIOD, LOGNAME, "All-zero command. Doing nothing.");
386  }
387  else
388  {
389  ok_to_publish_ = true;
390  }
391 
392  // Store last zero-velocity message flag to prevent superfluous warnings.
393  // Cartesian and joint commands must both be zero.
395  {
396  // Avoid overflow
397  if (zero_velocity_count_ < std::numeric_limits<int>::max())
399  }
400  else
401  {
403  }
404 
405  if (ok_to_publish_ && !paused_)
406  {
407  // Put the outgoing msg in the right format
408  // (trajectory_msgs/JointTrajectory or std_msgs/Float64MultiArray).
409  if (parameters_.command_out_type == "trajectory_msgs/JointTrajectory")
410  {
411  // When a joint_trajectory_controller receives a new command, a stamp of 0 indicates "begin immediately"
412  // See http://wiki.ros.org/joint_trajectory_controller#Trajectory_replacement
413  joint_trajectory->header.stamp = ros::Time(0);
414  outgoing_cmd_pub_.publish(joint_trajectory);
415  }
416  else if (parameters_.command_out_type == "std_msgs/Float64MultiArray")
417  {
418  auto joints = moveit::util::make_shared_from_pool<std_msgs::Float64MultiArray>();
419  if (parameters_.publish_joint_positions && !joint_trajectory->points.empty())
420  joints->data = joint_trajectory->points[0].positions;
421  else if (parameters_.publish_joint_velocities && !joint_trajectory->points.empty())
422  joints->data = joint_trajectory->points[0].velocities;
423  outgoing_cmd_pub_.publish(joints);
424  }
425 
426  last_sent_command_ = joint_trajectory;
427  }
428 
429  // Update the filters if we haven't yet
430  if (!updated_filters_)
432 }
433 // Perform the servoing calculations
434 bool ServoCalcs::cartesianServoCalcs(geometry_msgs::TwistStamped& cmd,
435  trajectory_msgs::JointTrajectory& joint_trajectory)
436 {
437  // Check for nan's in the incoming command
438  if (std::isnan(cmd.twist.linear.x) || std::isnan(cmd.twist.linear.y) || std::isnan(cmd.twist.linear.z) ||
439  std::isnan(cmd.twist.angular.x) || std::isnan(cmd.twist.angular.y) || std::isnan(cmd.twist.angular.z))
440  {
442  "nan in incoming command. Skipping this datapoint.");
443  return false;
444  }
445 
446  // If incoming commands should be in the range [-1:1], check for |delta|>1
447  if (parameters_.command_in_type == "unitless")
448  {
449  if ((fabs(cmd.twist.linear.x) > 1) || (fabs(cmd.twist.linear.y) > 1) || (fabs(cmd.twist.linear.z) > 1) ||
450  (fabs(cmd.twist.angular.x) > 1) || (fabs(cmd.twist.angular.y) > 1) || (fabs(cmd.twist.angular.z) > 1))
451  {
453  "Component of incoming command is >1. Skipping this datapoint.");
454  return false;
455  }
456  }
457 
458  // Set uncontrolled dimensions to 0 in command frame
459  if (!control_dimensions_[0])
460  cmd.twist.linear.x = 0;
461  if (!control_dimensions_[1])
462  cmd.twist.linear.y = 0;
463  if (!control_dimensions_[2])
464  cmd.twist.linear.z = 0;
465  if (!control_dimensions_[3])
466  cmd.twist.angular.x = 0;
467  if (!control_dimensions_[4])
468  cmd.twist.angular.y = 0;
469  if (!control_dimensions_[5])
470  cmd.twist.angular.z = 0;
471 
472  // Transform the command to the MoveGroup planning frame
473  if (cmd.header.frame_id != parameters_.planning_frame)
474  {
475  Eigen::Vector3d translation_vector(cmd.twist.linear.x, cmd.twist.linear.y, cmd.twist.linear.z);
476  Eigen::Vector3d angular_vector(cmd.twist.angular.x, cmd.twist.angular.y, cmd.twist.angular.z);
477 
478  // If the incoming frame is empty or is the command frame, we use the previously calculated tf
479  if (cmd.header.frame_id.empty() || cmd.header.frame_id == parameters_.robot_link_command_frame)
480  {
481  translation_vector = tf_moveit_to_robot_cmd_frame_.linear() * translation_vector;
482  angular_vector = tf_moveit_to_robot_cmd_frame_.linear() * angular_vector;
483  }
484  else if (cmd.header.frame_id == parameters_.ee_frame_name)
485  {
486  // If the frame is the EE frame, we already have that transform as well
487  translation_vector = tf_moveit_to_ee_frame_.linear() * translation_vector;
488  angular_vector = tf_moveit_to_ee_frame_.linear() * angular_vector;
489  }
490  else
491  {
492  // We solve (planning_frame -> base -> cmd.header.frame_id)
493  // by computing (base->planning_frame)^-1 * (base->cmd.header.frame_id)
494  const auto tf_moveit_to_incoming_cmd_frame =
495  current_state_->getGlobalLinkTransform(parameters_.planning_frame).inverse() *
496  current_state_->getGlobalLinkTransform(cmd.header.frame_id);
497 
498  translation_vector = tf_moveit_to_incoming_cmd_frame.linear() * translation_vector;
499  angular_vector = tf_moveit_to_incoming_cmd_frame.linear() * angular_vector;
500  }
501 
502  // Put these components back into a TwistStamped
503  cmd.header.frame_id = parameters_.planning_frame;
504  cmd.twist.linear.x = translation_vector(0);
505  cmd.twist.linear.y = translation_vector(1);
506  cmd.twist.linear.z = translation_vector(2);
507  cmd.twist.angular.x = angular_vector(0);
508  cmd.twist.angular.y = angular_vector(1);
509  cmd.twist.angular.z = angular_vector(2);
510  }
511 
512  Eigen::VectorXd delta_x = scaleCartesianCommand(cmd);
513 
514  // Convert from cartesian commands to joint commands
515  Eigen::MatrixXd jacobian = current_state_->getJacobian(joint_model_group_);
516 
517  // May allow some dimensions to drift, based on drift_dimensions
518  // i.e. take advantage of task redundancy.
519  // Remove the Jacobian rows corresponding to True in the vector drift_dimensions
520  // Work backwards through the 6-vector so indices don't get out of order
521  for (auto dimension = jacobian.rows() - 1; dimension >= 0; --dimension)
522  {
523  if (drift_dimensions_[dimension] && jacobian.rows() > 1)
524  {
525  removeDimension(jacobian, delta_x, dimension);
526  }
527  }
528 
529  Eigen::JacobiSVD<Eigen::MatrixXd> svd =
530  Eigen::JacobiSVD<Eigen::MatrixXd>(jacobian, Eigen::ComputeThinU | Eigen::ComputeThinV);
531  Eigen::MatrixXd matrix_s = svd.singularValues().asDiagonal();
532  Eigen::MatrixXd pseudo_inverse = svd.matrixV() * matrix_s.inverse() * svd.matrixU().transpose();
533 
534  delta_theta_ = pseudo_inverse * delta_x;
535 
537 
538  // If close to a collision or a singularity, decelerate
540 
542 
543  return convertDeltasToOutgoingCmd(joint_trajectory);
544 }
545 
546 bool ServoCalcs::jointServoCalcs(const control_msgs::JointJog& cmd, trajectory_msgs::JointTrajectory& joint_trajectory)
547 {
548  // Check for nan's
549  for (double velocity : cmd.velocities)
550  {
551  if (std::isnan(velocity))
552  {
554  "nan in incoming command. Skipping this datapoint.");
555  return false;
556  }
557  }
558 
559  // Apply user-defined scaling
561 
563 
564  // If close to a collision, decelerate
565  applyVelocityScaling(delta_theta_, 1.0 /* scaling for singularities -- ignore for joint motions */);
566 
568 
569  return convertDeltasToOutgoingCmd(joint_trajectory);
570 }
571 
572 bool ServoCalcs::convertDeltasToOutgoingCmd(trajectory_msgs::JointTrajectory& joint_trajectory)
573 {
576  return false;
577 
579 
580  // Calculate joint velocities here so that positions are filtered and SRDF bounds still get checked
582 
584 
586  {
587  suddenHalt(joint_trajectory);
589  }
590 
591  // done with calculations
593  {
595  }
596 
597  return true;
598 }
599 
600 // Spam several redundant points into the trajectory. The first few may be skipped if the
601 // time stamp is in the past when it reaches the client. Needed for gazebo simulation.
602 void ServoCalcs::insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory& joint_trajectory, int count) const
603 {
604  joint_trajectory.points.resize(count);
605  auto point = joint_trajectory.points[0];
606  // Start from 2nd point (i = 1) because we already have the first point.
607  // The timestamps are shifted up one period since first point is at 1 * publish_period, not 0.
608  for (int i = 1; i < count; ++i)
609  {
610  point.time_from_start = ros::Duration((i + 1) * parameters_.publish_period);
611  joint_trajectory.points[i] = point;
612  }
613 }
614 
615 void ServoCalcs::lowPassFilterPositions(sensor_msgs::JointState& joint_state)
616 {
617  for (size_t i = 0; i < position_filters_.size(); ++i)
618  {
619  joint_state.position[i] = position_filters_[i].filter(joint_state.position[i]);
620  }
621 
622  updated_filters_ = true;
623 }
624 
625 void ServoCalcs::resetLowPassFilters(const sensor_msgs::JointState& joint_state)
626 {
627  for (std::size_t i = 0; i < position_filters_.size(); ++i)
628  {
629  position_filters_[i].reset(joint_state.position[i]);
630  }
631 
632  updated_filters_ = true;
633 }
634 
635 void ServoCalcs::calculateJointVelocities(sensor_msgs::JointState& joint_state, const Eigen::ArrayXd& delta_theta)
636 {
637  for (int i = 0; i < delta_theta.size(); ++i)
638  {
639  joint_state.velocity[i] = delta_theta[i] / parameters_.publish_period;
640  }
641 }
642 
643 void ServoCalcs::composeJointTrajMessage(const sensor_msgs::JointState& joint_state,
644  trajectory_msgs::JointTrajectory& joint_trajectory) const
645 {
646  // When a joint_trajectory_controller receives a new command, a stamp of 0 indicates "begin immediately"
647  // See http://wiki.ros.org/joint_trajectory_controller#Trajectory_replacement
648  joint_trajectory.header.stamp = ros::Time(0);
649  joint_trajectory.header.frame_id = parameters_.planning_frame;
650  joint_trajectory.joint_names = joint_state.name;
651 
652  trajectory_msgs::JointTrajectoryPoint point;
653  point.time_from_start = ros::Duration(parameters_.publish_period);
655  point.positions = joint_state.position;
657  point.velocities = joint_state.velocity;
659  {
660  // I do not know of a robot that takes acceleration commands.
661  // However, some controllers check that this data is non-empty.
662  // Send all zeros, for now.
663  std::vector<double> acceleration(num_joints_);
664  point.accelerations = acceleration;
665  }
666  joint_trajectory.points.push_back(point);
667 }
668 
669 // Apply velocity scaling for proximity of collisions and singularities.
670 void ServoCalcs::applyVelocityScaling(Eigen::ArrayXd& delta_theta, double singularity_scale)
671 {
672  double collision_scale = collision_velocity_scale_;
673 
674  if (collision_scale > 0 && collision_scale < 1)
675  {
678  }
679  else if (collision_scale == 0)
680  {
682  }
683 
684  delta_theta = collision_scale * singularity_scale * delta_theta;
685 
687  {
688  ROS_WARN_STREAM_THROTTLE_NAMED(3, LOGNAME, "Halting for collision!");
689  delta_theta_.setZero();
690  }
691 }
692 
693 // Possibly calculate a velocity scaling factor, due to proximity of singularity and direction of motion
694 double ServoCalcs::velocityScalingFactorForSingularity(const Eigen::VectorXd& commanded_velocity,
695  const Eigen::JacobiSVD<Eigen::MatrixXd>& svd,
696  const Eigen::MatrixXd& pseudo_inverse)
697 {
698  double velocity_scale = 1;
699  std::size_t num_dimensions = commanded_velocity.size();
700 
701  // Find the direction away from nearest singularity.
702  // The last column of U from the SVD of the Jacobian points directly toward or away from the singularity.
703  // The sign can flip at any time, so we have to do some extra checking.
704  // Look ahead to see if the Jacobian's condition will decrease.
705  Eigen::VectorXd vector_toward_singularity = svd.matrixU().col(num_dimensions - 1);
706 
707  double ini_condition = svd.singularValues()(0) / svd.singularValues()(svd.singularValues().size() - 1);
708 
709  // This singular vector tends to flip direction unpredictably. See R. Bro,
710  // "Resolving the Sign Ambiguity in the Singular Value Decomposition".
711  // Look ahead to see if the Jacobian's condition will decrease in this
712  // direction. Start with a scaled version of the singular vector
713  Eigen::VectorXd delta_x(num_dimensions);
714  double scale = 100;
715  delta_x = vector_toward_singularity / scale;
716 
717  // Calculate a small change in joints
718  Eigen::VectorXd new_theta;
719  current_state_->copyJointGroupPositions(joint_model_group_, new_theta);
720  new_theta += pseudo_inverse * delta_x;
721  current_state_->setJointGroupPositions(joint_model_group_, new_theta);
722  Eigen::MatrixXd new_jacobian = current_state_->getJacobian(joint_model_group_);
723 
724  Eigen::JacobiSVD<Eigen::MatrixXd> new_svd(new_jacobian);
725  double new_condition = new_svd.singularValues()(0) / new_svd.singularValues()(new_svd.singularValues().size() - 1);
726  // If new_condition < ini_condition, the singular vector points away from the singularity. If so, flip its direction.
727  if (new_condition < ini_condition)
728  {
729  vector_toward_singularity *= -1;
730  }
731 
732  // If this dot product is positive, we're moving toward singularity ==> decelerate
733  double dot = vector_toward_singularity.dot(commanded_velocity);
734  if (dot > 0)
735  {
736  // Ramp velocity down linearly when the Jacobian condition is between lower_singularity_threshold and
737  // hard_stop_singularity_threshold, and we're moving towards the singularity
738  if ((ini_condition > parameters_.lower_singularity_threshold) &&
740  {
741  velocity_scale = 1. - (ini_condition - parameters_.lower_singularity_threshold) /
745  }
746 
747  // Very close to singularity, so halt.
748  else if (ini_condition > parameters_.hard_stop_singularity_threshold)
749  {
750  velocity_scale = 0;
753  }
754  }
755 
756  return velocity_scale;
757 }
758 
759 void ServoCalcs::enforceVelLimits(Eigen::ArrayXd& delta_theta)
760 {
761  // Convert to joint angle velocities for checking and applying joint specific velocity limits.
762  Eigen::ArrayXd velocity = delta_theta / parameters_.publish_period;
763 
764  std::size_t joint_delta_index{ 0 };
765  double velocity_scaling_factor{ 1.0 };
767  {
768  const auto& bounds = joint->getVariableBounds(joint->getName());
769  if (bounds.velocity_bounded_ && velocity(joint_delta_index) != 0.0)
770  {
771  const double unbounded_velocity = velocity(joint_delta_index);
772  // Clamp each joint velocity to a joint specific [min_velocity, max_velocity] range.
773  const auto bounded_velocity = std::min(std::max(unbounded_velocity, bounds.min_velocity_), bounds.max_velocity_);
774  velocity_scaling_factor = std::min(velocity_scaling_factor, bounded_velocity / unbounded_velocity);
775  }
776  ++joint_delta_index;
777  }
778 
779  // Convert back to joint angle increments.
780  delta_theta = velocity_scaling_factor * velocity * parameters_.publish_period;
781 }
782 
783 bool ServoCalcs::enforcePositionLimits(sensor_msgs::JointState& joint_state)
784 {
785  bool halting = false;
786 
787  for (auto joint : joint_model_group_->getActiveJointModels())
788  {
789  // Halt if we're past a joint margin and joint velocity is moving even farther past
790  double joint_angle = 0;
791  for (std::size_t c = 0; c < original_joint_state_.name.size(); ++c)
792  {
793  if (original_joint_state_.name[c] == joint->getName())
794  {
795  joint_angle = original_joint_state_.position.at(c);
796  break;
797  }
798  }
799  if (!current_state_->satisfiesPositionBounds(joint, -parameters_.joint_limit_margin))
800  {
801  const std::vector<moveit_msgs::JointLimits>& limits = joint->getVariableBoundsMsg();
802 
803  // Joint limits are not defined for some joints. Skip them.
804  if (!limits.empty())
805  {
806  // Check if pending velocity command is moving in the right direction
807  auto joint_itr = std::find(joint_state.name.begin(), joint_state.name.end(), joint->getName());
808  auto joint_idx = std::distance(joint_state.name.begin(), joint_itr);
809 
810  if ((joint_state.velocity.at(joint_idx) < 0 &&
811  (joint_angle < (limits[0].min_position + parameters_.joint_limit_margin))) ||
812  (joint_state.velocity.at(joint_idx) > 0 &&
813  (joint_angle > (limits[0].max_position - parameters_.joint_limit_margin))))
814  {
816  ros::this_node::getName() << " " << joint->getName()
817  << " close to a "
818  " position limit. Halting.");
819  halting = true;
820  }
821  }
822  }
823  }
824  return !halting;
825 }
826 
827 // Suddenly halt for a joint limit or other critical issue.
828 // Is handled differently for position vs. velocity control.
829 void ServoCalcs::suddenHalt(trajectory_msgs::JointTrajectory& joint_trajectory)
830 {
831  // Prepare the joint trajectory message to stop the robot
832  joint_trajectory.points.clear();
833  joint_trajectory.points.emplace_back();
834  trajectory_msgs::JointTrajectoryPoint& point = joint_trajectory.points.front();
835 
836  // When sending out trajectory_msgs/JointTrajectory type messages, the "trajectory" is just a single point.
837  // That point cannot have the same timestamp as the start of trajectory execution since that would mean the
838  // arm has to reach the first trajectory point the moment execution begins. To prevent errors about points
839  // being 0 seconds in the past, the smallest supported timestep is added as time from start to the trajectory point.
840  point.time_from_start.fromNSec(1);
841 
843  point.positions.resize(num_joints_);
845  point.velocities.resize(num_joints_);
846 
847  // Assert the following loop is safe to execute
848  assert(original_joint_state_.position.size() >= num_joints_);
849 
850  // Set the positions and velocities vectors
851  for (std::size_t i = 0; i < num_joints_; ++i)
852  {
853  // For position-controlled robots, can reset the joints to a known, good state
855  point.positions[i] = original_joint_state_.position[i];
856 
857  // For velocity-controlled robots, stop
859  point.velocities[i] = 0;
860  }
861 }
862 
863 // Parse the incoming joint msg for the joints of our MoveGroup
865 {
866  // Get the latest joint group positions
867  current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
868  current_state_->copyJointGroupPositions(joint_model_group_, internal_joint_state_.position);
869  current_state_->copyJointGroupVelocities(joint_model_group_, internal_joint_state_.velocity);
870 
871  // Cache the original joints in case they need to be reset
873 
874  // Calculate worst case joint stop time, for collision checking
875  std::string joint_name = "";
876  moveit::core::JointModel::Bounds kinematic_bounds;
877  double accel_limit = 0;
878  double joint_velocity = 0;
879  double worst_case_stop_time = 0;
880  for (size_t jt_state_idx = 0; jt_state_idx < internal_joint_state_.velocity.size(); ++jt_state_idx)
881  {
882  joint_name = internal_joint_state_.name[jt_state_idx];
883 
884  // Get acceleration limit for this joint
885  for (auto joint_model : joint_model_group_->getActiveJointModels())
886  {
887  if (joint_model->getName() == joint_name)
888  {
889  kinematic_bounds = joint_model->getVariableBounds();
890  // Some joints do not have acceleration limits
891  if (kinematic_bounds[0].acceleration_bounded_)
892  {
893  // Be conservative when calculating overall acceleration limit from min and max limits
894  accel_limit =
895  std::min(fabs(kinematic_bounds[0].min_acceleration_), fabs(kinematic_bounds[0].max_acceleration_));
896  }
897  else
898  {
900  "An acceleration limit is not defined for this joint; minimum stop distance "
901  "should not be used for collision checking");
902  }
903  break;
904  }
905  }
906 
907  // Get the current joint velocity
908  joint_velocity = internal_joint_state_.velocity[jt_state_idx];
909 
910  // Calculate worst case stop time
911  worst_case_stop_time = std::max(worst_case_stop_time, fabs(joint_velocity / accel_limit));
912  }
913 
914  // publish message
915  {
916  auto msg = moveit::util::make_shared_from_pool<std_msgs::Float64>();
917  msg->data = worst_case_stop_time;
919  }
920 }
921 
922 // Scale the incoming servo command
923 Eigen::VectorXd ServoCalcs::scaleCartesianCommand(const geometry_msgs::TwistStamped& command) const
924 {
925  Eigen::VectorXd result(6);
926 
927  // Apply user-defined scaling if inputs are unitless [-1:1]
928  if (parameters_.command_in_type == "unitless")
929  {
930  result[0] = parameters_.linear_scale * parameters_.publish_period * command.twist.linear.x;
931  result[1] = parameters_.linear_scale * parameters_.publish_period * command.twist.linear.y;
932  result[2] = parameters_.linear_scale * parameters_.publish_period * command.twist.linear.z;
933  result[3] = parameters_.rotational_scale * parameters_.publish_period * command.twist.angular.x;
934  result[4] = parameters_.rotational_scale * parameters_.publish_period * command.twist.angular.y;
935  result[5] = parameters_.rotational_scale * parameters_.publish_period * command.twist.angular.z;
936  }
937  // Otherwise, commands are in m/s and rad/s
938  else if (parameters_.command_in_type == "speed_units")
939  {
940  result[0] = command.twist.linear.x * parameters_.publish_period;
941  result[1] = command.twist.linear.y * parameters_.publish_period;
942  result[2] = command.twist.linear.z * parameters_.publish_period;
943  result[3] = command.twist.angular.x * parameters_.publish_period;
944  result[4] = command.twist.angular.y * parameters_.publish_period;
945  result[5] = command.twist.angular.z * parameters_.publish_period;
946  }
947  else
948  ROS_ERROR_STREAM_THROTTLE_NAMED(ROS_LOG_THROTTLE_PERIOD, LOGNAME, "Unexpected command_in_type");
949 
950  return result;
951 }
952 
953 Eigen::VectorXd ServoCalcs::scaleJointCommand(const control_msgs::JointJog& command) const
954 {
955  Eigen::VectorXd result(num_joints_);
956  result.setZero();
957 
958  std::size_t c;
959  for (std::size_t m = 0; m < command.joint_names.size(); ++m)
960  {
961  try
962  {
963  c = joint_state_name_map_.at(command.joint_names[m]);
964  }
965  catch (const std::out_of_range& e)
966  {
967  ROS_WARN_STREAM_THROTTLE_NAMED(ROS_LOG_THROTTLE_PERIOD, LOGNAME, "Ignoring joint " << command.joint_names[m]);
968  continue;
969  }
970  // Apply user-defined scaling if inputs are unitless [-1:1]
971  if (parameters_.command_in_type == "unitless")
972  result[c] = command.velocities[m] * parameters_.joint_scale * parameters_.publish_period;
973  // Otherwise, commands are in m/s and rad/s
974  else if (parameters_.command_in_type == "speed_units")
975  result[c] = command.velocities[m] * parameters_.publish_period;
976  else
977  ROS_ERROR_STREAM_THROTTLE_NAMED(ROS_LOG_THROTTLE_PERIOD, LOGNAME, "Unexpected command_in_type, check yaml file.");
978  }
979 
980  return result;
981 }
982 
983 // Add the deltas to each joint
984 bool ServoCalcs::addJointIncrements(sensor_msgs::JointState& output, const Eigen::VectorXd& increments) const
985 {
986  for (std::size_t i = 0, size = static_cast<std::size_t>(increments.size()); i < size; ++i)
987  {
988  try
989  {
990  output.position[i] += increments[i];
991  }
992  catch (const std::out_of_range& e)
993  {
995  ros::this_node::getName() << " Lengths of output and "
996  "increments do not match.");
997  return false;
998  }
999  }
1000 
1001  return true;
1002 }
1003 
1004 void ServoCalcs::removeDimension(Eigen::MatrixXd& jacobian, Eigen::VectorXd& delta_x, unsigned int row_to_remove)
1005 {
1006  unsigned int num_rows = jacobian.rows() - 1;
1007  unsigned int num_cols = jacobian.cols();
1008 
1009  if (row_to_remove < num_rows)
1010  {
1011  jacobian.block(row_to_remove, 0, num_rows - row_to_remove, num_cols) =
1012  jacobian.block(row_to_remove + 1, 0, num_rows - row_to_remove, num_cols);
1013  delta_x.segment(row_to_remove, num_rows - row_to_remove) =
1014  delta_x.segment(row_to_remove + 1, num_rows - row_to_remove);
1015  }
1016  jacobian.conservativeResize(num_rows, num_cols);
1017  delta_x.conservativeResize(num_rows);
1018 }
1019 
1020 bool ServoCalcs::getCommandFrameTransform(Eigen::Isometry3d& transform)
1021 {
1022  const std::lock_guard<std::mutex> lock(input_mutex_);
1024 
1025  // All zeros means the transform wasn't initialized, so return false
1026  return !transform.matrix().isZero(0);
1027 }
1028 
1029 bool ServoCalcs::getCommandFrameTransform(geometry_msgs::TransformStamped& transform)
1030 {
1031  const std::lock_guard<std::mutex> lock(input_mutex_);
1032  // All zeros means the transform wasn't initialized, so return false
1033  if (tf_moveit_to_robot_cmd_frame_.matrix().isZero(0))
1034  {
1035  return false;
1036  }
1037 
1038  transform = convertIsometryToTransform(tf_moveit_to_robot_cmd_frame_, parameters_.planning_frame,
1040  return true;
1041 }
1042 
1043 bool ServoCalcs::getEEFrameTransform(Eigen::Isometry3d& transform)
1044 {
1045  const std::lock_guard<std::mutex> lock(input_mutex_);
1047 
1048  // All zeros means the transform wasn't initialized, so return false
1049  return !transform.matrix().isZero(0);
1050 }
1051 
1052 bool ServoCalcs::getEEFrameTransform(geometry_msgs::TransformStamped& transform)
1053 {
1054  const std::lock_guard<std::mutex> lock(input_mutex_);
1055  // All zeros means the transform wasn't initialized, so return false
1056  if (tf_moveit_to_ee_frame_.matrix().isZero(0))
1057  {
1058  return false;
1059  }
1060 
1062  return true;
1063 }
1064 
1065 void ServoCalcs::twistStampedCB(const geometry_msgs::TwistStampedConstPtr& msg)
1066 {
1067  const std::lock_guard<std::mutex> lock(input_mutex_);
1068  latest_twist_stamped_ = msg;
1070 
1071  if (msg->header.stamp != ros::Time(0.))
1072  latest_twist_command_stamp_ = msg->header.stamp;
1073 
1074  // notify that we have a new input
1075  new_input_cmd_ = true;
1076  input_cv_.notify_all();
1077 }
1078 
1079 void ServoCalcs::jointCmdCB(const control_msgs::JointJogConstPtr& msg)
1080 {
1081  const std::lock_guard<std::mutex> lock(input_mutex_);
1082  latest_joint_cmd_ = msg;
1084 
1085  if (msg->header.stamp != ros::Time(0.))
1086  latest_joint_command_stamp_ = msg->header.stamp;
1087 
1088  // notify that we have a new input
1089  new_input_cmd_ = true;
1090  input_cv_.notify_all();
1091 }
1092 
1093 void ServoCalcs::collisionVelocityScaleCB(const std_msgs::Float64ConstPtr& msg)
1094 {
1095  collision_velocity_scale_ = msg->data;
1096 }
1097 
1098 bool ServoCalcs::changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request& req,
1099  moveit_msgs::ChangeDriftDimensions::Response& res)
1100 {
1101  drift_dimensions_[0] = req.drift_x_translation;
1102  drift_dimensions_[1] = req.drift_y_translation;
1103  drift_dimensions_[2] = req.drift_z_translation;
1104  drift_dimensions_[3] = req.drift_x_rotation;
1105  drift_dimensions_[4] = req.drift_y_rotation;
1106  drift_dimensions_[5] = req.drift_z_rotation;
1107 
1108  res.success = true;
1109  return true;
1110 }
1111 
1112 bool ServoCalcs::changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request& req,
1113  moveit_msgs::ChangeControlDimensions::Response& res)
1114 {
1115  control_dimensions_[0] = req.control_x_translation;
1116  control_dimensions_[1] = req.control_y_translation;
1117  control_dimensions_[2] = req.control_z_translation;
1118  control_dimensions_[3] = req.control_x_rotation;
1119  control_dimensions_[4] = req.control_y_rotation;
1120  control_dimensions_[5] = req.control_z_rotation;
1121 
1122  res.success = true;
1123  return true;
1124 }
1125 
1126 bool ServoCalcs::resetServoStatus(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
1127 {
1129  return true;
1130 }
1131 
1132 void ServoCalcs::setPaused(bool paused)
1133 {
1134  paused_ = paused;
1135 }
1136 
1137 void ServoCalcs::changeRobotLinkCommandFrame(const std::string& new_command_frame)
1138 {
1139  parameters_.robot_link_command_frame = new_command_frame;
1140 }
1141 
1142 } // namespace moveit_servo
ROS_WARN_STREAM_THROTTLE_NAMED
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
moveit_servo::ServoCalcs::stop_requested_
bool stop_requested_
Definition: servo_calcs.h:354
moveit_servo::ServoCalcs::collision_velocity_scale_sub_
ros::Subscriber collision_velocity_scale_sub_
Definition: servo_calcs.h:344
planning_scene_monitor
moveit_servo::ServoCalcs::changeRobotLinkCommandFrame
void changeRobotLinkCommandFrame(const std::string &new_command_frame)
Change the controlled link. Often, this is the end effector This must be a link on the robot since Mo...
Definition: servo_calcs.cpp:1137
moveit::core::JointModelGroup::getActiveJointModels
const std::vector< const JointModel * > & getActiveJointModels() const
moveit_servo::ServoCalcs::latest_joint_cmd_
control_msgs::JointJogConstPtr latest_joint_cmd_
Definition: servo_calcs.h:383
moveit_servo::ServoCalcs::jointCmdCB
void jointCmdCB(const control_msgs::JointJogConstPtr &msg)
Definition: servo_calcs.cpp:1079
moveit_servo::ServoCalcs::ok_to_publish_
bool ok_to_publish_
Definition: servo_calcs.h:361
moveit_servo::ServoCalcs::internal_joint_state_
sensor_msgs::JointState internal_joint_state_
Definition: servo_calcs.h:333
moveit_servo::ServoCalcs::joint_state_name_map_
std::map< std::string, std::size_t > joint_state_name_map_
Definition: servo_calcs.h:334
moveit_servo::ServoCalcs::collisionVelocityScaleCB
void collisionVelocityScaleCB(const std_msgs::Float64ConstPtr &msg)
Definition: servo_calcs.cpp:1093
moveit_servo::StatusCode::DECELERATE_FOR_COLLISION
@ DECELERATE_FOR_COLLISION
moveit_servo::ServoParameters::use_gazebo
bool use_gazebo
Definition: servo_parameters.h:106
moveit_servo::ServoCalcs::wait_for_servo_commands_
bool wait_for_servo_commands_
Definition: servo_calcs.h:310
moveit::core::JointModelGroup::getActiveJointModelNames
const std::vector< std::string > & getActiveJointModelNames() const
moveit_servo::ROS_QUEUE_SIZE
constexpr size_t ROS_QUEUE_SIZE
Definition: servo_parameters.h:80
moveit_servo::ServoCalcs::stop
void stop()
Stop the currently running thread.
Definition: servo_calcs.cpp:207
moveit_servo::ServoCalcs::addJointIncrements
bool addJointIncrements(sensor_msgs::JointState &output, const Eigen::VectorXd &increments) const
Definition: servo_calcs.cpp:984
moveit_servo::ServoCalcs::joint_cmd_sub_
ros::Subscriber joint_cmd_sub_
Definition: servo_calcs.h:343
command
ROSLIB_DECL std::string command(const std::string &cmd)
moveit_servo::ServoCalcs::calculateJointVelocities
void calculateJointVelocities(sensor_msgs::JointState &joint_state, const Eigen::ArrayXd &delta_theta)
Convert an incremental position command to joint velocity message.
Definition: servo_calcs.cpp:635
moveit_servo::ServoCalcs::status_pub_
ros::Publisher status_pub_
Definition: servo_calcs.h:345
moveit_servo::ServoCalcs::control_dimensions_server_
ros::ServiceServer control_dimensions_server_
Definition: servo_calcs.h:349
ROS_LOG_THROTTLE_PERIOD
constexpr size_t ROS_LOG_THROTTLE_PERIOD
Definition: servo_calcs.cpp:49
LOGNAME
static const std::string LOGNAME
Definition: servo_calcs.cpp:48
moveit_servo::ServoCalcs::tf_moveit_to_ee_frame_
Eigen::Isometry3d tf_moveit_to_ee_frame_
Definition: servo_calcs.h:381
moveit_servo::ServoCalcs::twistStampedCB
void twistStampedCB(const geometry_msgs::TwistStampedConstPtr &msg)
Definition: servo_calcs.cpp:1065
moveit_servo::StatusCode::JOINT_BOUND
@ JOINT_BOUND
moveit_servo::ServoCalcs::updated_filters_
bool updated_filters_
Definition: servo_calcs.h:313
moveit_servo::ServoCalcs::cartesianServoCalcs
bool cartesianServoCalcs(geometry_msgs::TwistStamped &cmd, trajectory_msgs::JointTrajectory &joint_trajectory)
Do servoing calculations for Cartesian twist commands.
Definition: servo_calcs.cpp:434
moveit_servo::ServoParameters::incoming_command_timeout
double incoming_command_timeout
Definition: servo_parameters.h:103
moveit_servo::ServoCalcs::drift_dimensions_
std::array< bool, 6 > drift_dimensions_
Definition: servo_calcs.h:373
moveit_servo::ServoCalcs::have_nonzero_command_
bool have_nonzero_command_
Definition: servo_calcs.h:318
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
moveit_servo::ServoParameters::linear_scale
double linear_scale
Definition: servo_parameters.h:96
moveit_servo::ServoCalcs::ServoCalcs
ServoCalcs(ros::NodeHandle &nh, ServoParameters &parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Definition: servo_calcs.cpp:87
moveit_servo::ServoCalcs::zero_velocity_count_
int zero_velocity_count_
Definition: servo_calcs.h:307
moveit_servo::ServoParameters::joint_command_in_topic
std::string joint_command_in_topic
Definition: servo_parameters.h:93
moveit_servo::ServoParameters::num_outgoing_halt_msgs_to_publish
int num_outgoing_halt_msgs_to_publish
Definition: servo_parameters.h:105
moveit_servo::ServoCalcs::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: servo_calcs.h:303
ROS_DEBUG_STREAM_THROTTLE_NAMED
#define ROS_DEBUG_STREAM_THROTTLE_NAMED(period, name, args)
moveit_servo::ServoParameters::move_group_name
std::string move_group_name
Definition: servo_parameters.h:85
moveit_servo::ServoCalcs::new_input_cmd_
bool new_input_cmd_
Definition: servo_calcs.h:391
moveit_servo::ServoCalcs::suddenHalt
void suddenHalt(trajectory_msgs::JointTrajectory &joint_trajectory)
Suddenly halt for a joint limit or other critical issue. Is handled differently for position vs....
Definition: servo_calcs.cpp:829
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
moveit_servo::ServoParameters::command_out_type
std::string command_out_type
Definition: servo_parameters.h:95
moveit_servo::ServoCalcs::composeJointTrajMessage
void composeJointTrajMessage(const sensor_msgs::JointState &joint_state, trajectory_msgs::JointTrajectory &joint_trajectory) const
Compose the outgoing JointTrajectory message.
Definition: servo_calcs.cpp:643
moveit_servo::ServoCalcs::collision_velocity_scale_
double collision_velocity_scale_
Definition: servo_calcs.h:362
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
make_shared_from_pool.h
moveit_servo::ServoCalcs::input_mutex_
std::mutex input_mutex_
Definition: servo_calcs.h:379
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
moveit_servo::ServoCalcs::num_joints_
uint num_joints_
Definition: servo_calcs.h:370
moveit_servo::ServoParameters::status_topic
std::string status_topic
Definition: servo_parameters.h:92
ros::ok
ROSCPP_DECL bool ok()
moveit_servo::ServoCalcs::getCommandFrameTransform
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
Definition: servo_calcs.cpp:1020
moveit_servo::ServoParameters::planning_frame
std::string planning_frame
Definition: servo_parameters.h:90
moveit_servo::ServoParameters::joint_scale
double joint_scale
Definition: servo_parameters.h:98
tf2::eigenToTransform
geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d &T)
moveit_servo::ServoCalcs::removeDimension
void removeDimension(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x, unsigned int row_to_remove)
Definition: servo_calcs.cpp:1004
moveit_servo::ServoCalcs::latest_joint_command_stamp_
ros::Time latest_joint_command_stamp_
Definition: servo_calcs.h:385
moveit_servo::ServoCalcs::nh_
ros::NodeHandle nh_
Definition: servo_calcs.h:297
moveit_servo::ServoCalcs::original_joint_state_
sensor_msgs::JointState original_joint_state_
Definition: servo_calcs.h:333
dot
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
res
res
moveit_servo::ServoCalcs::convertDeltasToOutgoingCmd
bool convertDeltasToOutgoingCmd(trajectory_msgs::JointTrajectory &joint_trajectory)
Convert joint deltas to an outgoing JointTrajectory command. This happens for joint commands and Cart...
Definition: servo_calcs.cpp:572
moveit_servo::ServoCalcs::position_filters_
std::vector< LowPassFilter > position_filters_
Definition: servo_calcs.h:336
moveit_servo::StatusCode::HALT_FOR_SINGULARITY
@ HALT_FOR_SINGULARITY
moveit_servo::ServoParameters
Definition: servo_parameters.h:83
moveit_servo::ServoParameters::joint_limit_margin
double joint_limit_margin
Definition: servo_parameters.h:104
moveit::core::JointModel::Bounds
std::vector< VariableBounds > Bounds
c
c
moveit_servo::ServoCalcs::current_state_
moveit::core::RobotStatePtr current_state_
Definition: servo_calcs.h:326
moveit_servo::ServoCalcs::worst_case_stop_time_pub_
ros::Publisher worst_case_stop_time_pub_
Definition: servo_calcs.h:346
moveit_servo::ServoCalcs::latest_nonzero_twist_stamped_
bool latest_nonzero_twist_stamped_
Definition: servo_calcs.h:386
moveit_servo::ServoParameters::rotational_scale
double rotational_scale
Definition: servo_parameters.h:97
moveit_servo::ServoParameters::ee_frame_name
std::string ee_frame_name
Definition: servo_parameters.h:91
moveit_servo
Definition: collision_check.h:50
moveit_servo::ServoCalcs::updateJoints
void updateJoints()
Parse the incoming joint msg for the joints of our MoveGroup.
Definition: servo_calcs.cpp:864
moveit_servo::ServoParameters::low_latency_mode
bool low_latency_mode
Definition: servo_parameters.h:110
moveit_servo::ServoCalcs::lowPassFilterPositions
void lowPassFilterPositions(sensor_msgs::JointState &joint_state)
Smooth position commands with a lowpass filter.
Definition: servo_calcs.cpp:615
moveit_servo::ServoCalcs::delta_theta_
Eigen::ArrayXd delta_theta_
Definition: servo_calcs.h:365
moveit_servo::ServoCalcs::joint_command_is_stale_
bool joint_command_is_stale_
Definition: servo_calcs.h:360
moveit_servo::ServoCalcs::latest_twist_stamped_
geometry_msgs::TwistStampedConstPtr latest_twist_stamped_
Definition: servo_calcs.h:382
moveit_servo::ServoCalcs::parameters_
ServoParameters & parameters_
Definition: servo_calcs.h:300
moveit_servo::ServoCalcs::changeDriftDimensions
bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
Definition: servo_calcs.cpp:1098
moveit_servo::ServoParameters::cartesian_command_in_topic
std::string cartesian_command_in_topic
Definition: servo_parameters.h:87
moveit_servo::ServoCalcs::~ServoCalcs
~ServoCalcs()
Definition: servo_calcs.cpp:157
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
moveit_servo::ServoCalcs::paused_
std::atomic< bool > paused_
Definition: servo_calcs.h:358
moveit_servo::ServoCalcs::changeControlDimensions
bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
Service callback for changing servoing dimensions (e.g. ignore rotation about X)
Definition: servo_calcs.cpp:1112
moveit_servo::ServoCalcs::gazebo_redundant_message_count_
const int gazebo_redundant_message_count_
Definition: servo_calcs.h:368
moveit_servo::ServoCalcs::getEEFrameTransform
bool getEEFrameTransform(Eigen::Isometry3d &transform)
Definition: servo_calcs.cpp:1043
moveit_servo::ServoCalcs::reset_servo_status_
ros::ServiceServer reset_servo_status_
Definition: servo_calcs.h:350
moveit_servo::StatusCode::DECELERATE_FOR_SINGULARITY
@ DECELERATE_FOR_SINGULARITY
moveit_servo::ServoCalcs::setPaused
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
Definition: servo_calcs.cpp:1132
ros::Rate::sleep
bool sleep()
moveit_servo::SERVO_STATUS_CODE_MAP
const std::unordered_map< StatusCode, std::string > SERVO_STATUS_CODE_MAP({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_SINGULARITY, "Close to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } })
moveit_servo::ServoCalcs::drift_dimensions_server_
ros::ServiceServer drift_dimensions_server_
Definition: servo_calcs.h:348
moveit_servo::ServoParameters::lower_singularity_threshold
double lower_singularity_threshold
Definition: servo_parameters.h:99
moveit_servo::ServoCalcs::resetLowPassFilters
void resetLowPassFilters(const sensor_msgs::JointState &joint_state)
Set the filters to the specified values.
Definition: servo_calcs.cpp:625
point
std::chrono::system_clock::time_point point
ROS_ERROR_STREAM_THROTTLE_NAMED
#define ROS_ERROR_STREAM_THROTTLE_NAMED(period, name, args)
moveit_servo::ServoCalcs::resetServoStatus
bool resetServoStatus(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Service callback to reset Servo status, e.g. so the arm can move again after a collision.
Definition: servo_calcs.cpp:1126
moveit_servo::ServoCalcs::enforceVelLimits
void enforceVelLimits(Eigen::ArrayXd &delta_theta)
Scale the delta theta to match joint velocity/acceleration limits.
Definition: servo_calcs.cpp:759
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
moveit_servo::ServoCalcs::have_nonzero_joint_command_
bool have_nonzero_joint_command_
Definition: servo_calcs.h:317
moveit_servo::ServoParameters::hard_stop_singularity_threshold
double hard_stop_singularity_threshold
Definition: servo_parameters.h:100
servo_calcs.h
m
m
moveit_servo::ServoCalcs::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: servo_calcs.h:324
moveit_servo::ServoCalcs::insertRedundantPointsIntoTrajectory
void insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory &joint_trajectory, int count) const
Gazebo simulations have very strict message timestamp requirements. Satisfy Gazebo by stuffing multip...
Definition: servo_calcs.cpp:602
moveit_servo::ServoCalcs::velocityScalingFactorForSingularity
double velocityScalingFactorForSingularity(const Eigen::VectorXd &commanded_velocity, const Eigen::JacobiSVD< Eigen::MatrixXd > &svd, const Eigen::MatrixXd &pseudo_inverse)
Possibly calculate a velocity scaling factor, due to proximity of singularity and direction of motion...
Definition: servo_calcs.cpp:694
ros::names::append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
moveit_servo::ServoCalcs::enforcePositionLimits
bool enforcePositionLimits(sensor_msgs::JointState &joint_state)
Avoid overshooting joint limits.
Definition: servo_calcs.cpp:783
ros::Time
moveit_servo::ServoCalcs::have_nonzero_twist_stamped_
bool have_nonzero_twist_stamped_
Definition: servo_calcs.h:316
moveit_servo::ServoCalcs::input_cv_
std::condition_variable input_cv_
Definition: servo_calcs.h:390
moveit_servo::ServoCalcs::thread_
std::thread thread_
Definition: servo_calcs.h:353
moveit_servo::ServoCalcs::outgoing_cmd_pub_
ros::Publisher outgoing_cmd_pub_
Definition: servo_calcs.h:347
moveit_servo::ServoParameters::publish_joint_positions
bool publish_joint_positions
Definition: servo_parameters.h:107
moveit_servo::ServoParameters::robot_link_command_frame
std::string robot_link_command_frame
Definition: servo_parameters.h:88
moveit_servo::StatusCode::HALT_FOR_COLLISION
@ HALT_FOR_COLLISION
moveit_servo::ServoCalcs::last_sent_command_
trajectory_msgs::JointTrajectoryConstPtr last_sent_command_
Definition: servo_calcs.h:338
moveit_servo::ServoCalcs::applyVelocityScaling
void applyVelocityScaling(Eigen::ArrayXd &delta_theta, double singularity_scale)
Definition: servo_calcs.cpp:670
ros::Rate
moveit_servo::ServoCalcs::latest_twist_command_stamp_
ros::Time latest_twist_command_stamp_
Definition: servo_calcs.h:384
moveit_servo::ServoCalcs::scaleJointCommand
Eigen::VectorXd scaleJointCommand(const control_msgs::JointJog &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units....
Definition: servo_calcs.cpp:953
moveit_servo::ServoParameters::publish_period
double publish_period
Definition: servo_parameters.h:102
moveit_servo::ServoCalcs::start
void start()
Start the timer where we do work and publish outputs.
Definition: servo_calcs.cpp:162
moveit_servo::ServoCalcs::prev_joint_velocity_
Eigen::ArrayXd prev_joint_velocity_
Definition: servo_calcs.h:366
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
moveit_servo::ServoCalcs::scaleCartesianCommand
Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::TwistStamped &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units....
Definition: servo_calcs.cpp:923
moveit_servo::ServoCalcs::mainCalcLoop
void mainCalcLoop()
Run the main calculation loop.
Definition: servo_calcs.cpp:228
moveit_servo::ServoParameters::command_in_type
std::string command_in_type
Definition: servo_parameters.h:94
cmd
string cmd
moveit_servo::ServoParameters::command_out_topic
std::string command_out_topic
Definition: servo_parameters.h:89
moveit_servo::ServoCalcs::calculateSingleIteration
void calculateSingleIteration()
Do calculations for a single iteration. Publish one outgoing command.
Definition: servo_calcs.cpp:268
moveit_servo::ServoCalcs::latest_nonzero_joint_cmd_
bool latest_nonzero_joint_cmd_
Definition: servo_calcs.h:387
moveit_servo::ServoCalcs::tf_moveit_to_robot_cmd_frame_
Eigen::Isometry3d tf_moveit_to_robot_cmd_frame_
Definition: servo_calcs.h:380
moveit_servo::ServoCalcs::jointServoCalcs
bool jointServoCalcs(const control_msgs::JointJog &cmd, trajectory_msgs::JointTrajectory &joint_trajectory)
Do servoing calculations for direct commands to a joint.
Definition: servo_calcs.cpp:546
ros::Duration
moveit_servo::ServoParameters::publish_joint_velocities
bool publish_joint_velocities
Definition: servo_parameters.h:108
moveit_servo::ServoCalcs::twist_stamped_cmd_
geometry_msgs::TwistStamped twist_stamped_cmd_
Definition: servo_calcs.h:321
moveit_servo::ServoParameters::low_pass_filter_coeff
double low_pass_filter_coeff
Definition: servo_parameters.h:101
moveit_servo::ServoCalcs::joint_servo_cmd_
control_msgs::JointJog joint_servo_cmd_
Definition: servo_calcs.h:322
moveit_servo::ServoCalcs::twist_stamped_sub_
ros::Subscriber twist_stamped_sub_
Definition: servo_calcs.h:342
moveit_servo::ServoCalcs::twist_command_is_stale_
bool twist_command_is_stale_
Definition: servo_calcs.h:359
moveit::core::JointModel
moveit_servo::StatusCode::NO_WARNING
@ NO_WARNING
ros::NodeHandle
moveit_servo::ServoParameters::publish_joint_accelerations
bool publish_joint_accelerations
Definition: servo_parameters.h:109
moveit_servo::ServoCalcs::status_
StatusCode status_
Definition: servo_calcs.h:357
ros::Time::now
static Time now()
moveit_servo::ServoCalcs::control_dimensions_
std::array< bool, 6 > control_dimensions_
Definition: servo_calcs.h:376
int8_t
int8_t


moveit_servo
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:56