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, Robert Haschke */
38 
39 #include <memory>
41 #include <geometric_shapes/check_isometry.h>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rcpputils/asserts.hpp>
45 #include <moveit/utils/logger.hpp>
46 
47 namespace moveit::core
48 {
49 
50 // Minimum amount of path waypoints recommended to reliably compute a joint-space increment average.
51 // If relative jump detection is selected and the path is shorter than `MIN_STEPS_FOR_JUMP_THRESH`, a warning message
52 // will be printed out.
53 static const std::size_t MIN_STEPS_FOR_JUMP_THRESH = 10;
54 
55 namespace
56 {
57 
58 rclcpp::Logger getLogger()
59 {
60  return moveit::getLogger("moveit.core.cartesian_interpolator");
61 }
62 
63 bool validateAndImproveInterval(const RobotState& start_state, const RobotState& end_state,
64  const Eigen::Isometry3d& start_pose, const Eigen::Isometry3d& end_pose,
65  std::vector<RobotStatePtr>& traj, double& percentage, const double width,
66  const JointModelGroup* group, const LinkModel* link,
67  const CartesianPrecision& precision, const GroupStateValidityCallbackFn& validCallback,
69  const kinematics::KinematicsBase::IKCostFn& cost_function,
70  const Eigen::Isometry3d& link_offset)
71 {
72  // compute pose at joint-space midpoint between start_state and end_state
73  RobotState mid_state(start_state.getRobotModel());
74  start_state.interpolate(end_state, 0.5, mid_state);
75  Eigen::Isometry3d fk_pose = mid_state.getGlobalLinkTransform(link) * link_offset;
76 
77  // compute pose at Cartesian-space midpoint between start_pose and end_pose
78  Eigen::Isometry3d mid_pose(Eigen::Quaterniond(start_pose.linear()).slerp(0.5, Eigen::Quaterniond(end_pose.linear())));
79  mid_pose.translation() = 0.5 * (start_pose.translation() + end_pose.translation());
80 
81  // if deviation between both poses, fk_pose and mid_pose is within precision, we are satisfied
82  double linear_distance = (mid_pose.translation() - fk_pose.translation()).norm();
83  double angular_distance = Eigen::Quaterniond(mid_pose.linear()).angularDistance(Eigen::Quaterniond(fk_pose.linear()));
84  if (linear_distance <= precision.translational && angular_distance <= precision.rotational)
85  {
86  traj.push_back(std::make_shared<moveit::core::RobotState>(end_state));
87  return true;
88  }
89 
90  if (width < precision.max_resolution)
91  return false; // failed to find linear interpolation within max_resolution
92 
93  // otherwise subdivide interval further, computing IK for mid_pose
94  if (!mid_state.setFromIK(group, mid_pose * link_offset.inverse(), link->getName(), 0.0, validCallback, options,
95  cost_function))
96  return false;
97 
98  // and recursively processing the two sub-intervals
99  const auto half_width = width / 2.0;
100  const auto old_percentage = percentage;
101  percentage = percentage - half_width;
102  if (!validateAndImproveInterval(start_state, mid_state, start_pose, mid_pose, traj, percentage, half_width, group,
103  link, precision, validCallback, options, cost_function, link_offset))
104  return false;
105 
106  percentage = old_percentage;
107  return validateAndImproveInterval(mid_state, end_state, mid_pose, end_pose, traj, percentage, half_width, group, link,
108  precision, validCallback, options, cost_function, link_offset);
109 }
110 
111 std::optional<int> hasRelativeJointSpaceJump(const std::vector<moveit::core::RobotStatePtr>& waypoints,
112  const moveit::core::JointModelGroup& group, double jump_threshold_factor)
113 {
114  if (waypoints.size() < MIN_STEPS_FOR_JUMP_THRESH)
115  {
116  RCLCPP_WARN(getLogger(),
117  "The computed path is too short to detect jumps in joint-space. "
118  "Need at least %zu steps, only got %zu. Try a lower max_step.",
119  MIN_STEPS_FOR_JUMP_THRESH, waypoints.size());
120  }
121 
122  std::vector<double> dist_vector;
123  dist_vector.reserve(waypoints.size() - 1);
124  double total_dist = 0.0;
125  for (std::size_t i = 1; i < waypoints.size(); ++i)
126  {
127  const double dist_prev_point = waypoints[i]->distance(*waypoints[i - 1], &group);
128  dist_vector.push_back(dist_prev_point);
129  total_dist += dist_prev_point;
130  }
131 
132  // compute the average distance between the states we looked at.
133  double thres = jump_threshold_factor * (total_dist / static_cast<double>(dist_vector.size()));
134  for (std::size_t i = 0; i < dist_vector.size(); ++i)
135  {
136  if (dist_vector[i] > thres)
137  {
138  return i + 1;
139  }
140  }
141 
142  return std::nullopt;
143 }
144 
145 std::optional<int> hasAbsoluteJointSpaceJump(const std::vector<moveit::core::RobotStatePtr>& waypoints,
146  const moveit::core::JointModelGroup& group, double revolute_threshold,
147  double prismatic_threshold)
148 {
149  const bool check_revolute = revolute_threshold > 0.0;
150  const bool check_prismatic = prismatic_threshold > 0.0;
151 
152  const std::vector<const moveit::core::JointModel*>& joints = group.getActiveJointModels();
153  for (std::size_t i = 1; i < waypoints.size(); ++i)
154  {
155  for (const auto& joint : joints)
156  {
157  const double distance = waypoints[i]->distance(*waypoints[i - 1], joint);
158  switch (joint->getType())
159  {
161  if (check_revolute && distance > revolute_threshold)
162  {
163  return i;
164  }
165  break;
167  if (check_prismatic && distance > prismatic_threshold)
168  {
169  return i;
170  }
171  break;
172  default:
173  RCLCPP_WARN(getLogger(),
174  "Joint %s has not supported type %s. \n"
175  "hasAbsoluteJointSpaceJump only supports prismatic and revolute joints. Skipping joint jump "
176  "check for this joint.",
177  joint->getName().c_str(), joint->getTypeName().c_str());
178  continue;
179  }
180  }
181  }
182 
183  return std::nullopt;
184 }
185 } // namespace
186 
187 CartesianInterpolator::Distance CartesianInterpolator::computeCartesianPath(
188  const RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
189  const LinkModel* link, const Eigen::Vector3d& translation, bool global_reference_frame, const MaxEEFStep& max_step,
190  const CartesianPrecision& precision, const GroupStateValidityCallbackFn& validCallback,
192 {
193  const double distance = translation.norm();
194  // The target pose is obtained by adding the translation vector to the link's current pose
195  Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
196 
197  // the translation direction can be specified w.r.t. the local link frame (then rotate into global frame)
198  pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
199 
200  // call computeCartesianPath for the computed target pose in the global reference frame
201  return CartesianInterpolator::Distance(distance) * computeCartesianPath(start_state, group, traj, link, pose, true,
202  max_step, precision, validCallback, options,
203  cost_function);
204 }
205 
207  const RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
208  const LinkModel* link, const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
209  const CartesianPrecision& precision, const GroupStateValidityCallbackFn& validCallback,
211  const Eigen::Isometry3d& link_offset)
212 {
213  // check unsanitized inputs for non-isometry
214  ASSERT_ISOMETRY(target)
215  ASSERT_ISOMETRY(link_offset)
216 
217  RobotState state(*start_state);
218 
219  const std::vector<const JointModel*>& cjnt = group->getContinuousJointModels();
220  // make sure that continuous joints wrap
221  for (const JointModel* joint : cjnt)
222  state.enforceBounds(joint);
223 
224  // Cartesian pose we start from
225  Eigen::Isometry3d start_pose = state.getGlobalLinkTransform(link) * link_offset;
226  Eigen::Isometry3d inv_offset = link_offset.inverse();
227 
228  // the target can be in the local reference frame (in which case we rotate it)
229  Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
230 
231  Eigen::Quaterniond start_quaternion(start_pose.linear());
232  Eigen::Quaterniond target_quaternion(rotated_target.linear());
233 
234  double rotation_distance = start_quaternion.angularDistance(target_quaternion);
235  double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
236 
237  // decide how many steps we will need for this trajectory
238  std::size_t translation_steps = 0;
239  if (max_step.translation > 0.0)
240  translation_steps = floor(translation_distance / max_step.translation);
241 
242  std::size_t rotation_steps = 0;
243  if (max_step.rotation > 0.0)
244  rotation_steps = floor(rotation_distance / max_step.rotation);
245  std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
246 
247  traj.clear();
248  traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
249 
250  double last_valid_percentage = 0.0;
251  Eigen::Isometry3d prev_pose = start_pose;
252  RobotState prev_state(state);
253  for (std::size_t i = 1; i <= steps; ++i)
254  {
255  double percentage = static_cast<double>(i) / static_cast<double>(steps);
256 
257  Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
258  pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
259 
260  if (!state.setFromIK(group, pose * inv_offset, link->getName(), 0.0, validCallback, options, cost_function) ||
261  !validateAndImproveInterval(prev_state, state, prev_pose, pose, traj, percentage,
262  1.0 / static_cast<double>(steps), group, link, precision, validCallback, options,
263  cost_function, link_offset))
264  break;
265 
266  prev_pose = pose;
267  prev_state = state;
268  last_valid_percentage = percentage;
269  }
270 
271  return last_valid_percentage;
272 }
273 
275  const RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
276  const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
277  const MaxEEFStep& max_step, const CartesianPrecision& precision, const GroupStateValidityCallbackFn& validCallback,
279  const Eigen::Isometry3d& link_offset)
280 {
281  double percentage_solved = 0.0;
282  for (std::size_t i = 0; i < waypoints.size(); ++i)
283  {
284  std::vector<RobotStatePtr> waypoint_traj;
285  double wp_percentage_solved =
286  computeCartesianPath(start_state, group, waypoint_traj, link, waypoints[i], global_reference_frame, max_step,
287  precision, validCallback, options, cost_function, link_offset);
288 
289  std::vector<RobotStatePtr>::iterator start = waypoint_traj.begin();
290  if (i > 0 && !waypoint_traj.empty())
291  std::advance(start, 1);
292  traj.insert(traj.end(), start, waypoint_traj.end());
293 
294  if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
295  {
296  percentage_solved = static_cast<double>(i + 1) / static_cast<double>(waypoints.size());
297  }
298  else
299  {
300  percentage_solved += wp_percentage_solved / static_cast<double>(waypoints.size());
301  break;
302  }
303  start_state = traj.back().get();
304  }
305 
306  return percentage_solved;
307 }
308 
310 {
311  return JumpThreshold();
312 }
313 
314 JumpThreshold JumpThreshold::relative(double relative_factor)
315 {
316  rcpputils::require_true(relative_factor > 1.0);
317 
318  JumpThreshold threshold;
319  threshold.relative_factor = relative_factor;
320  return threshold;
321 }
322 
323 JumpThreshold JumpThreshold::absolute(double revolute, double prismatic)
324 {
325  rcpputils::require_true(revolute > 0.0);
326  rcpputils::require_true(prismatic > 0.0);
327 
328  JumpThreshold threshold;
329  threshold.revolute = revolute;
330  threshold.prismatic = prismatic;
331  return threshold;
332 }
333 
334 JumpThreshold::JumpThreshold(double relative_factor)
335 {
336  this->relative_factor = relative_factor;
337 }
338 JumpThreshold::JumpThreshold(double revolute, double prismatic)
339 {
340  this->revolute = revolute;
341  this->prismatic = prismatic;
342 }
343 
345  RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& path, const LinkModel* link,
346  const Eigen::Vector3d& translation, bool global_reference_frame, const MaxEEFStep& max_step,
347  const JumpThreshold& jump_threshold, const GroupStateValidityCallbackFn& validCallback,
349 {
350  const double distance = translation.norm();
351  // The target pose is obtained by adding the translation vector to the link's current pose
352  Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
353 
354  // the translation direction can be specified w.r.t. the local link frame (then rotate into global frame)
355  pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
356 
357 #pragma GCC diagnostic push
358 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
359  // call computeCartesianPath for the computed target pose in the global reference frame
360  return CartesianInterpolator::Distance(distance) * computeCartesianPath(start_state, group, path, link, pose, true,
361  max_step, jump_threshold, validCallback,
362  options, cost_function);
363 #pragma GCC diagnostic pop
364 }
365 
367  RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& path, const LinkModel* link,
368  const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
369  const JumpThreshold& jump_threshold, const GroupStateValidityCallbackFn& validCallback,
371  const Eigen::Isometry3d& link_offset)
372 {
373  // check unsanitized inputs for non-isometry
374  ASSERT_ISOMETRY(target)
375  ASSERT_ISOMETRY(link_offset)
376 
377  const std::vector<const JointModel*>& cjnt = group->getContinuousJointModels();
378  // make sure that continuous joints wrap
379  for (const JointModel* joint : cjnt)
380  start_state->enforceBounds(joint);
381 
382  // Cartesian pose we start from
383  Eigen::Isometry3d start_pose = start_state->getGlobalLinkTransform(link) * link_offset;
384  Eigen::Isometry3d offset = link_offset.inverse();
385 
386  // the target can be in the local reference frame (in which case we rotate it)
387  Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
388 
389  Eigen::Quaterniond start_quaternion(start_pose.linear());
390  Eigen::Quaterniond target_quaternion(rotated_target.linear());
391 
392  if (max_step.translation <= 0.0 && max_step.rotation <= 0.0)
393  {
394  RCLCPP_ERROR(getLogger(),
395  "Invalid MaxEEFStep passed into computeCartesianPath. Both the MaxEEFStep.rotation and "
396  "MaxEEFStep.translation components must be non-negative and at least one component must be "
397  "greater than zero");
398  return 0.0;
399  }
400 
401  double rotation_distance = start_quaternion.angularDistance(target_quaternion);
402  double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
403 
404  // decide how many steps we will need for this path
405  std::size_t translation_steps = 0;
406  if (max_step.translation > 0.0)
407  translation_steps = floor(translation_distance / max_step.translation);
408 
409  std::size_t rotation_steps = 0;
410  if (max_step.rotation > 0.0)
411  rotation_steps = floor(rotation_distance / max_step.rotation);
412 
413  // If we are testing for relative jumps, we always want at least MIN_STEPS_FOR_JUMP_THRESH steps
414  std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
415  if (jump_threshold.relative_factor > 0 && steps < MIN_STEPS_FOR_JUMP_THRESH)
416  steps = MIN_STEPS_FOR_JUMP_THRESH;
417 
418  // To limit absolute joint-space jumps, we pass consistency limits to the IK solver
419  std::vector<double> consistency_limits;
420  if (jump_threshold.prismatic > 0 || jump_threshold.revolute > 0)
421  {
422  for (const JointModel* jm : group->getActiveJointModels())
423  {
424  double limit;
425  switch (jm->getType())
426  {
428  limit = jump_threshold.revolute;
429  break;
431  limit = jump_threshold.prismatic;
432  break;
433  default:
434  limit = 0.0;
435  }
436  if (limit == 0.0)
437  limit = jm->getMaximumExtent();
438  consistency_limits.push_back(limit);
439  }
440  }
441 
442  path.clear();
443  path.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
444 
445  double last_valid_percentage = 0.0;
446  for (std::size_t i = 1; i <= steps; ++i)
447  {
448  double percentage = static_cast<double>(i) / static_cast<double>(steps);
449 
450  Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
451  pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
452 
453  // Explicitly use a single IK attempt only (by setting a timeout of 0.0), using the current state as the seed.
454  // Random seeding (of additional attempts) would create large joint-space jumps.
455  if (start_state->setFromIK(group, pose * offset, link->getName(), consistency_limits, 0.0, validCallback, options,
456  cost_function))
457  {
458  path.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
459  }
460  else
461  {
462  break;
463  }
464 
465  last_valid_percentage = percentage;
466  }
467 
468  last_valid_percentage *= checkJointSpaceJump(group, path, jump_threshold);
469 
470  return CartesianInterpolator::Percentage(last_valid_percentage);
471 }
472 
473 CartesianInterpolator::Percentage CartesianInterpolator::computeCartesianPath(
474  RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& path, const LinkModel* link,
475  const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame, const MaxEEFStep& max_step,
476  const JumpThreshold& jump_threshold, const GroupStateValidityCallbackFn& validCallback,
478  const Eigen::Isometry3d& link_offset)
479 {
480  double percentage_solved = 0.0;
481  for (std::size_t i = 0; i < waypoints.size(); ++i)
482  {
483  // Don't test joint space jumps for every waypoint, test them later on the whole path.
484  static const JumpThreshold NO_JOINT_SPACE_JUMP_TEST = JumpThreshold::disabled();
485  std::vector<RobotStatePtr> waypoint_path;
486 #pragma GCC diagnostic push
487 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
488  double wp_percentage_solved =
489  computeCartesianPath(start_state, group, waypoint_path, link, waypoints[i], global_reference_frame, max_step,
490  NO_JOINT_SPACE_JUMP_TEST, validCallback, options, cost_function, link_offset);
491 #pragma GCC diagnostic pop
492 
493  std::vector<RobotStatePtr>::iterator start = waypoint_path.begin();
494  if (i > 0 && !waypoint_path.empty())
495  std::advance(start, 1);
496  path.insert(path.end(), start, waypoint_path.end());
497 
498  if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
499  {
500  percentage_solved = static_cast<double>((i + 1)) / static_cast<double>(waypoints.size());
501  }
502  else
503  {
504  percentage_solved += wp_percentage_solved / static_cast<double>(waypoints.size());
505  break;
506  }
507  }
508 
509  percentage_solved *= checkJointSpaceJump(group, path, jump_threshold);
510 
511  return CartesianInterpolator::Percentage(percentage_solved);
512 }
513 
515  std::vector<RobotStatePtr>& path,
516  const JumpThreshold& jump_threshold)
517 {
518  std::optional<int> jump_index = hasJointSpaceJump(path, *group, jump_threshold);
519 
520  double percentage_solved = 1.0;
521  if (jump_index.has_value())
522  {
523  percentage_solved = static_cast<double>(*jump_index) / static_cast<double>(path.size());
524  // Truncate the path at the index right before the jump.
525  path.resize(jump_index.value());
526  }
527 
528  return CartesianInterpolator::Percentage(percentage_solved);
529 }
530 
531 std::optional<int> hasJointSpaceJump(const std::vector<moveit::core::RobotStatePtr>& waypoints,
532  const moveit::core::JointModelGroup& group,
533  const moveit::core::JumpThreshold& jump_threshold)
534 {
535  if (waypoints.size() <= 1)
536  {
537  return std::nullopt;
538  }
539 
540  if (jump_threshold.relative_factor > 0.0)
541  {
542  return hasRelativeJointSpaceJump(waypoints, group, jump_threshold.relative_factor);
543  }
544 
545  if (jump_threshold.revolute > 0.0 || jump_threshold.prismatic > 0.0)
546  {
547  return hasAbsoluteJointSpaceJump(waypoints, group, jump_threshold.revolute, jump_threshold.prismatic);
548  }
549 
550  return std::nullopt;
551 }
552 
553 } // end of namespace moveit::core
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, const moveit::core::JointModelGroup *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
static Distance computeCartesianPath(const 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 CartesianPrecision &precision, 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 checkJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &path, const JumpThreshold &jump_threshold)
Checks if a path has a joint-space jump, and truncates the path at the jump.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints used in this group (may include mimic joints).
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.hpp:72
const std::string & getName() const
The name of this link.
Definition: link_model.hpp:86
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.hpp:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.hpp:89
Core components of MoveIt.
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.hpp:70
std::optional< int > hasJointSpaceJump(const std::vector< moveit::core::RobotStatePtr > &waypoints, const moveit::core::JointModelGroup &group, const moveit::core::JumpThreshold &jump_threshold)
Checks if a joint-space path has a jump larger than the given threshold.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.hpp:59
A set of options for the kinematics solver.
Struct with options for defining joint-space jump thresholds.
static JumpThreshold relative(double relative_factor)
Detect joint-space jumps relative to the average joint-space displacement along the path.
static JumpThreshold absolute(double revolute, double prismatic)
Detect joint-space jumps greater than the given absolute thresholds.
static JumpThreshold disabled()
Do not define any jump threshold, i.e., disable joint-space jump detection.
Struct for containing max_step for computeCartesianPath.