moveit2
The MoveIt Motion Planning Framework for ROS 2.
cartesian_interpolator.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2013, Willow Garage, Inc.
6  * Copyright (c) 2019, PickNik Inc.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the Willow Garage nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /* Author: Ioan Sucan, Sachin Chitta, Acorn Pooley, Mario Prats, Dave Coleman */
38 
39 #include <memory>
41 #include <geometric_shapes/check_isometry.h>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 
45 namespace moveit
46 {
47 namespace core
48 {
53 static const std::size_t MIN_STEPS_FOR_JUMP_THRESH = 10;
54 
55 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_robot_state.cartesian_interpolator");
56 
57 CartesianInterpolator::Distance CartesianInterpolator::computeCartesianPath(
58  RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
59  const Eigen::Vector3d& translation, bool global_reference_frame, const MaxEEFStep& max_step,
60  const JumpThreshold& jump_threshold, const GroupStateValidityCallbackFn& validCallback,
62 {
63  const double distance = translation.norm();
64  // The target pose is obtained by adding the translation vector to the link's current pose
65  Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
66 
67  // the translation direction can be specified w.r.t. the local link frame (then rotate into global frame)
68  pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
69 
70  // call computeCartesianPath for the computed target pose in the global reference frame
71  return CartesianInterpolator::Distance(distance) * computeCartesianPath(start_state, group, traj, link, pose, true,
72  max_step, jump_threshold, validCallback,
73  options, cost_function);
74 }
75 
76 CartesianInterpolator::Percentage CartesianInterpolator::computeCartesianPath(
77  RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
78  const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
79  const JumpThreshold& jump_threshold, const GroupStateValidityCallbackFn& validCallback,
81  const Eigen::Isometry3d& link_offset)
82 {
83  // check unsanitized inputs for non-isometry
84  ASSERT_ISOMETRY(target)
85  ASSERT_ISOMETRY(link_offset)
86 
87  const std::vector<const JointModel*>& cjnt = group->getContinuousJointModels();
88  // make sure that continuous joints wrap
89  for (const JointModel* joint : cjnt)
90  start_state->enforceBounds(joint);
91 
92  // Cartesian pose we start from
93  Eigen::Isometry3d start_pose = start_state->getGlobalLinkTransform(link) * link_offset;
94  Eigen::Isometry3d offset = link_offset.inverse();
95 
96  // the target can be in the local reference frame (in which case we rotate it)
97  Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
98 
99  Eigen::Quaterniond start_quaternion(start_pose.linear());
100  Eigen::Quaterniond target_quaternion(rotated_target.linear());
101 
102  if (max_step.translation <= 0.0 && max_step.rotation <= 0.0)
103  {
104  RCLCPP_ERROR(LOGGER, "Invalid MaxEEFStep passed into computeCartesianPath. Both the MaxEEFStep.rotation and "
105  "MaxEEFStep.translation components must be non-negative and at least one component must be "
106  "greater than zero");
107  return 0.0;
108  }
109 
110  double rotation_distance = start_quaternion.angularDistance(target_quaternion);
111  double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
112 
113  // decide how many steps we will need for this trajectory
114  std::size_t translation_steps = 0;
115  if (max_step.translation > 0.0)
116  translation_steps = floor(translation_distance / max_step.translation);
117 
118  std::size_t rotation_steps = 0;
119  if (max_step.rotation > 0.0)
120  rotation_steps = floor(rotation_distance / max_step.rotation);
121 
122  // If we are testing for relative jumps, we always want at least MIN_STEPS_FOR_JUMP_THRESH steps
123  std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
124  if (jump_threshold.factor > 0 && steps < MIN_STEPS_FOR_JUMP_THRESH)
125  steps = MIN_STEPS_FOR_JUMP_THRESH;
126 
127  // To limit absolute joint-space jumps, we pass consistency limits to the IK solver
128  std::vector<double> consistency_limits;
129  if (jump_threshold.prismatic > 0 || jump_threshold.revolute > 0)
130  for (const JointModel* jm : group->getActiveJointModels())
131  {
132  double limit;
133  switch (jm->getType())
134  {
136  limit = jump_threshold.revolute;
137  break;
139  limit = jump_threshold.prismatic;
140  break;
141  default:
142  limit = 0.0;
143  }
144  if (limit == 0.0)
145  limit = jm->getMaximumExtent();
146  consistency_limits.push_back(limit);
147  }
148 
149  traj.clear();
150  traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
151 
152  double last_valid_percentage = 0.0;
153  for (std::size_t i = 1; i <= steps; ++i)
154  {
155  double percentage = (double)i / (double)steps;
156 
157  Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
158  pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
159 
160  // Explicitly use a single IK attempt only: We want a smooth trajectory.
161  // Random seeding (of additional attempts) would probably create IK jumps.
162  if (start_state->setFromIK(group, pose * offset, link->getName(), consistency_limits, 0.0, validCallback, options,
163  cost_function))
164  traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
165  else
166  break;
167 
168  last_valid_percentage = percentage;
169  }
170 
171  last_valid_percentage *= checkJointSpaceJump(group, traj, jump_threshold);
172 
173  return CartesianInterpolator::Percentage(last_valid_percentage);
174 }
175 
176 CartesianInterpolator::Percentage CartesianInterpolator::computeCartesianPath(
177  RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
178  const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame, const MaxEEFStep& max_step,
179  const JumpThreshold& jump_threshold, const GroupStateValidityCallbackFn& validCallback,
181  const Eigen::Isometry3d& link_offset)
182 {
183  double percentage_solved = 0.0;
184  for (std::size_t i = 0; i < waypoints.size(); ++i)
185  {
186  // Don't test joint space jumps for every waypoint, test them later on the whole trajectory.
187  static const JumpThreshold NO_JOINT_SPACE_JUMP_TEST;
188  std::vector<RobotStatePtr> waypoint_traj;
189  double wp_percentage_solved =
190  computeCartesianPath(start_state, group, waypoint_traj, link, waypoints[i], global_reference_frame, max_step,
191  NO_JOINT_SPACE_JUMP_TEST, validCallback, options, cost_function, link_offset);
192  if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
193  {
194  percentage_solved = (double)(i + 1) / (double)waypoints.size();
195  std::vector<RobotStatePtr>::iterator start = waypoint_traj.begin();
196  if (i > 0 && !waypoint_traj.empty())
197  std::advance(start, 1);
198  traj.insert(traj.end(), start, waypoint_traj.end());
199  }
200  else
201  {
202  percentage_solved += wp_percentage_solved / (double)waypoints.size();
203  std::vector<RobotStatePtr>::iterator start = waypoint_traj.begin();
204  if (i > 0 && !waypoint_traj.empty())
205  std::advance(start, 1);
206  traj.insert(traj.end(), start, waypoint_traj.end());
207  break;
208  }
209  }
210 
211  percentage_solved *= checkJointSpaceJump(group, traj, jump_threshold);
212 
213  return CartesianInterpolator::Percentage(percentage_solved);
214 }
215 
217  std::vector<RobotStatePtr>& traj,
218  const JumpThreshold& jump_threshold)
219 {
220  double percentage_solved = 1.0;
221  if (traj.size() <= 1)
222  return percentage_solved;
223 
224  if (jump_threshold.factor > 0.0)
225  percentage_solved *= checkRelativeJointSpaceJump(group, traj, jump_threshold.factor);
226 
227  if (jump_threshold.revolute > 0.0 || jump_threshold.prismatic > 0.0)
228  percentage_solved *= checkAbsoluteJointSpaceJump(group, traj, jump_threshold.revolute, jump_threshold.prismatic);
229 
230  return CartesianInterpolator::Percentage(percentage_solved);
231 }
232 
234  std::vector<RobotStatePtr>& traj,
235  double jump_threshold_factor)
236 {
237  if (traj.size() < MIN_STEPS_FOR_JUMP_THRESH)
238  {
239  RCLCPP_WARN(LOGGER,
240  "The computed trajectory is too short to detect jumps in joint-space "
241  "Need at least %zu steps, only got %zu. Try a lower max_step.",
242  MIN_STEPS_FOR_JUMP_THRESH, traj.size());
243  }
244 
245  std::vector<double> dist_vector;
246  dist_vector.reserve(traj.size() - 1);
247  double total_dist = 0.0;
248  for (std::size_t i = 1; i < traj.size(); ++i)
249  {
250  double dist_prev_point = traj[i]->distance(*traj[i - 1], group);
251  dist_vector.push_back(dist_prev_point);
252  total_dist += dist_prev_point;
253  }
254 
255  double percentage = 1.0;
256  // compute the average distance between the states we looked at
257  double thres = jump_threshold_factor * (total_dist / (double)dist_vector.size());
258  for (std::size_t i = 0; i < dist_vector.size(); ++i)
259  if (dist_vector[i] > thres)
260  {
261  RCLCPP_DEBUG(LOGGER, "Truncating Cartesian path due to detected jump in joint-space distance");
262  percentage = (double)(i + 1) / (double)(traj.size());
263  traj.resize(i + 1);
264  break;
265  }
266 
267  return CartesianInterpolator::Percentage(percentage);
268 }
269 
271  std::vector<RobotStatePtr>& traj,
272  double revolute_threshold,
273  double prismatic_threshold)
274 {
275  bool check_revolute = revolute_threshold > 0.0;
276  bool check_prismatic = prismatic_threshold > 0.0;
277 
278  double joint_threshold;
279  bool check_joint;
280  bool still_valid = true;
281  const std::vector<const JointModel*>& joints = group->getActiveJointModels();
282  for (std::size_t traj_ix = 0, ix_end = traj.size() - 1; traj_ix != ix_end; ++traj_ix)
283  {
284  for (auto& joint : joints)
285  {
286  switch (joint->getType())
287  {
289  check_joint = check_revolute;
290  joint_threshold = revolute_threshold;
291  break;
293  check_joint = check_prismatic;
294  joint_threshold = prismatic_threshold;
295  break;
296  default:
297  RCLCPP_WARN(LOGGER,
298  "Joint %s has not supported type %s. \n"
299  "checkAbsoluteJointSpaceJump only supports prismatic and revolute joints.",
300  joint->getName().c_str(), joint->getTypeName().c_str());
301  continue;
302  }
303  if (check_joint)
304  {
305  double distance = traj[traj_ix]->distance(*traj[traj_ix + 1], joint);
306  if (distance > joint_threshold)
307  {
308  RCLCPP_DEBUG(LOGGER, "Truncating Cartesian path due to detected jump of %.4f > %.4f in joint %s", distance,
309  joint_threshold, joint->getName().c_str());
310  still_valid = false;
311  break;
312  }
313  }
314  }
315 
316  if (!still_valid)
317  {
318  double percent_valid = (double)(traj_ix + 1) / (double)(traj.size());
319  traj.resize(traj_ix + 1);
320  return CartesianInterpolator::Percentage(percent_valid);
321  }
322  }
324 }
325 
326 } // end of namespace core
327 } // end of namespace moveit
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, moveit::core::JointModelGroup const *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
static Percentage checkAbsoluteJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, double revolute_jump_threshold, double prismatic_jump_threshold)
Tests for absolute joint space jumps of the trajectory traj.
static Distance computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
static Percentage checkRelativeJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, double jump_threshold_factor)
Tests for relative joint space jumps of the trajectory traj.
static Percentage checkJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const JumpThreshold &jump_threshold)
Tests joint space jumps of a trajectory.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition: robot_state.h:70
Main namespace for MoveIt.
Definition: exceptions.h:43
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
A set of options for the kinematics solver.
Struct for containing jump_threshold.