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 LLC.
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>
42 
43 namespace moveit
44 {
45 namespace core
46 {
51 static const std::size_t MIN_STEPS_FOR_JUMP_THRESH = 10;
52 
53 const std::string LOGNAME = "cartesian_interpolator";
54 
55 bool validateAndImproveInterval(const RobotState& start_state, const RobotState& end_state,
56  const Eigen::Isometry3d& start_pose, const Eigen::Isometry3d& end_pose,
57  std::vector<RobotStatePtr>& traj, double& percentage, const double width,
58  const JointModelGroup* group, const LinkModel* link,
59  const CartesianPrecision& precision, const GroupStateValidityCallbackFn& validCallback,
60  const kinematics::KinematicsQueryOptions& options, const Eigen::Isometry3d& link_offset)
61 {
62  // compute pose at joint-space midpoint between start_state and end_state
63  RobotState mid_state(start_state.getRobotModel());
64  start_state.interpolate(end_state, 0.5, mid_state);
65  Eigen::Isometry3d fk_pose = mid_state.getGlobalLinkTransform(link) * link_offset;
66 
67  // compute pose at Cartesian-space midpoint between start_pose and end_pose
68  Eigen::Isometry3d mid_pose(Eigen::Quaterniond(start_pose.linear()).slerp(0.5, Eigen::Quaterniond(end_pose.linear())));
69  mid_pose.translation() = 0.5 * (start_pose.translation() + end_pose.translation());
70 
71  // if deviation between both poses, fk_pose and mid_pose is within precision, we are satisfied
72  double linear_distance = (mid_pose.translation() - fk_pose.translation()).norm();
73  double angular_distance = Eigen::Quaterniond(mid_pose.linear()).angularDistance(Eigen::Quaterniond(fk_pose.linear()));
74  if (linear_distance <= precision.translational && angular_distance <= precision.rotational)
75  {
76  traj.push_back(std::make_shared<moveit::core::RobotState>(end_state));
77  return true;
78  }
79 
80  if (width < precision.max_resolution)
81  return false; // failed to find linear interpolation within max_resolution
82 
83  // otherwise subdivide interval further, computing IK for mid_pose
84  if (!mid_state.setFromIK(group, mid_pose * link_offset.inverse(), link->getName(), 0.0, validCallback, options))
85  return false;
86 
87  // and recursively processing the two sub-intervals
88  const auto half_width = width / 2.0;
89  const auto old_percentage = percentage;
90  percentage = percentage - half_width;
91  if (!validateAndImproveInterval(start_state, mid_state, start_pose, mid_pose, traj, percentage, half_width, group,
92  link, precision, validCallback, options, link_offset))
93  return false;
94 
95  percentage = old_percentage;
96  return validateAndImproveInterval(mid_state, end_state, mid_pose, end_pose, traj, percentage, half_width, group, link,
97  precision, validCallback, options, link_offset);
98 }
99 
100 double CartesianInterpolator::computeCartesianPath(const RobotState* start_state, const JointModelGroup* group,
101  std::vector<RobotStatePtr>& traj, const LinkModel* link,
102  const Eigen::Vector3d& translation, bool global_reference_frame,
103  const MaxEEFStep& max_step, const CartesianPrecision& precision,
104  const GroupStateValidityCallbackFn& validCallback,
105  const kinematics::KinematicsQueryOptions& options)
106 {
107  const double distance = translation.norm();
108  // The target pose is obtained by adding the translation vector to the link's current pose
109  Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
110 
111  // the translation direction can be specified w.r.t. the local link frame (then rotate into global frame)
112  pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
113 
114  // call computeCartesianPath for the computed target pose in the global reference frame
115  return distance *
116  computeCartesianPath(start_state, group, traj, link, pose, true, max_step, precision, validCallback, options);
117 }
118 
120  std::vector<RobotStatePtr>& traj, const LinkModel* link,
121  const Eigen::Isometry3d& target, bool global_reference_frame,
122  const MaxEEFStep& max_step, const CartesianPrecision& precision,
123  const GroupStateValidityCallbackFn& validCallback,
124  const kinematics::KinematicsQueryOptions& options,
125  const Eigen::Isometry3d& link_offset)
126 {
127  // check unsanitized inputs for non-isometry
128  ASSERT_ISOMETRY(target)
129  ASSERT_ISOMETRY(link_offset)
130 
131  RobotState state(*start_state);
132 
133  const std::vector<const JointModel*>& cjnt = group->getContinuousJointModels();
134  // make sure that continuous joints wrap
135  for (const JointModel* joint : cjnt)
136  state.enforceBounds(joint);
137 
138  // Cartesian pose we start from
139  Eigen::Isometry3d start_pose = state.getGlobalLinkTransform(link) * link_offset;
140  Eigen::Isometry3d inv_offset = link_offset.inverse();
141 
142  // the target can be in the local reference frame (in which case we rotate it)
143  Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
144 
145  Eigen::Quaterniond start_quaternion(start_pose.linear());
146  Eigen::Quaterniond target_quaternion(rotated_target.linear());
147 
148  double rotation_distance = start_quaternion.angularDistance(target_quaternion);
149  double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
150 
151  // decide how many steps we will need for this trajectory
152  std::size_t translation_steps = 0;
153  if (max_step.translation > 0.0)
154  translation_steps = floor(translation_distance / max_step.translation);
155 
156  std::size_t rotation_steps = 0;
157  if (max_step.rotation > 0.0)
158  rotation_steps = floor(rotation_distance / max_step.rotation);
159  std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
160 
161  traj.clear();
162  traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
163 
164  double last_valid_percentage = 0.0;
165  Eigen::Isometry3d prev_pose = start_pose;
166  RobotState prev_state(state);
167  for (std::size_t i = 1; i <= steps; ++i)
168  {
169  double percentage = (double)i / (double)steps;
170 
171  Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
172  pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
173 
174  if (!state.setFromIK(group, pose * inv_offset, link->getName(), 0.0, validCallback, options) ||
175  !validateAndImproveInterval(prev_state, state, prev_pose, pose, traj, percentage, 1.0 / (double)steps, group,
176  link, precision, validCallback, options, link_offset))
177  break;
178 
179  prev_pose = pose;
180  prev_state = state;
181  last_valid_percentage = percentage;
182  }
183 
184  return last_valid_percentage;
185 }
186 
188  const RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
189  const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
190  const MaxEEFStep& max_step, const CartesianPrecision& precision, const GroupStateValidityCallbackFn& validCallback,
191  const kinematics::KinematicsQueryOptions& options, const Eigen::Isometry3d& link_offset)
192 {
193  double percentage_solved = 0.0;
194  for (std::size_t i = 0; i < waypoints.size(); ++i)
195  {
196  std::vector<RobotStatePtr> waypoint_traj;
197  double wp_percentage_solved =
198  computeCartesianPath(start_state, group, waypoint_traj, link, waypoints[i], global_reference_frame, max_step,
199  precision, validCallback, options, link_offset);
200 
201  std::vector<RobotStatePtr>::iterator start = waypoint_traj.begin();
202  if (i > 0 && !waypoint_traj.empty())
203  std::advance(start, 1);
204  traj.insert(traj.end(), start, waypoint_traj.end());
205 
206  if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
207  percentage_solved = (double)(i + 1) / (double)waypoints.size();
208  else
209  {
210  percentage_solved += wp_percentage_solved / (double)waypoints.size();
211  break;
212  }
213  start_state = traj.back().get();
214  }
215 
216  return percentage_solved;
217 }
218 
220  std::vector<RobotStatePtr>& traj, const LinkModel* link,
221  const Eigen::Vector3d& translation, bool global_reference_frame,
222  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
223  const GroupStateValidityCallbackFn& validCallback,
224  const kinematics::KinematicsQueryOptions& options)
225 {
226  const double distance = translation.norm();
227  // The target pose is obtained by adding the translation vector to the link's current pose
228  Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
229 
230  // the translation direction can be specified w.r.t. the local link frame (then rotate into global frame)
231  pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
232 
233 #pragma GCC diagnostic push
234 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
235  // call computeCartesianPath for the computed target pose in the global reference frame
236  return distance * computeCartesianPath(start_state, group, traj, link, pose, true, max_step, jump_threshold,
237  validCallback, options);
238 #pragma GCC diagnostic pop
239 }
240 
241 double CartesianInterpolator::computeCartesianPath(RobotState* start_state, const JointModelGroup* group,
242  std::vector<RobotStatePtr>& traj, const LinkModel* link,
243  const Eigen::Isometry3d& target, bool global_reference_frame,
244  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
245  const GroupStateValidityCallbackFn& validCallback,
246  const kinematics::KinematicsQueryOptions& options,
247  const Eigen::Isometry3d& link_offset)
248 {
249  // check unsanitized inputs for non-isometry
250  ASSERT_ISOMETRY(target)
251  ASSERT_ISOMETRY(link_offset)
252 
253  const std::vector<const JointModel*>& cjnt = group->getContinuousJointModels();
254  // make sure that continuous joints wrap
255  for (const JointModel* joint : cjnt)
256  start_state->enforceBounds(joint);
257 
258  // Cartesian pose we start from
259  Eigen::Isometry3d start_pose = start_state->getGlobalLinkTransform(link) * link_offset;
260  Eigen::Isometry3d offset = link_offset.inverse();
261 
262  // the target can be in the local reference frame (in which case we rotate it)
263  Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
264 
265  Eigen::Quaterniond start_quaternion(start_pose.linear());
266  Eigen::Quaterniond target_quaternion(rotated_target.linear());
267 
268  if (max_step.translation <= 0.0 && max_step.rotation <= 0.0)
269  {
271  "Invalid MaxEEFStep passed into computeCartesianPath. Both the MaxEEFStep.rotation and "
272  "MaxEEFStep.translation components must be non-negative and at least one component must be "
273  "greater than zero");
274  return 0.0;
275  }
276 
277  double rotation_distance = start_quaternion.angularDistance(target_quaternion);
278  double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
279 
280  // decide how many steps we will need for this trajectory
281  std::size_t translation_steps = 0;
282  if (max_step.translation > 0.0)
283  translation_steps = floor(translation_distance / max_step.translation);
284 
285  std::size_t rotation_steps = 0;
286  if (max_step.rotation > 0.0)
287  rotation_steps = floor(rotation_distance / max_step.rotation);
288 
289  // If we are testing for relative jumps, we always want at least MIN_STEPS_FOR_JUMP_THRESH steps
290  std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
291  if (jump_threshold.factor > 0 && steps < MIN_STEPS_FOR_JUMP_THRESH)
293 
294  // To limit absolute joint-space jumps, we pass consistency limits to the IK solver
295  std::vector<double> consistency_limits;
296  if (jump_threshold.prismatic > 0 || jump_threshold.revolute > 0)
297  for (const JointModel* jm : group->getActiveJointModels())
298  {
299  double limit;
300  switch (jm->getType())
301  {
303  limit = jump_threshold.revolute;
304  break;
306  limit = jump_threshold.prismatic;
307  break;
308  default:
309  limit = 0.0;
310  }
311  if (limit == 0.0)
312  limit = jm->getMaximumExtent();
313  consistency_limits.push_back(limit);
314  }
315 
316  traj.clear();
317  traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
318 
319  double last_valid_percentage = 0.0;
320  for (std::size_t i = 1; i <= steps; ++i)
321  {
322  double percentage = (double)i / (double)steps;
323 
324  Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
325  pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
326 
327  // Explicitly use a single IK attempt only: We want a smooth trajectory.
328  // Random seeding (of additional attempts) would probably create IK jumps.
329  if (start_state->setFromIK(group, pose * offset, link->getName(), consistency_limits, 0.0, validCallback, options))
330  traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
331  else
332  break;
333 
334  last_valid_percentage = percentage;
335  }
336 
337  last_valid_percentage *= checkJointSpaceJump(group, traj, jump_threshold);
338 
339  return last_valid_percentage;
340 }
341 
343  RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
344  const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame, const MaxEEFStep& max_step,
345  const JumpThreshold& jump_threshold, const GroupStateValidityCallbackFn& validCallback,
346  const kinematics::KinematicsQueryOptions& options, const Eigen::Isometry3d& link_offset)
347 {
348  double percentage_solved = 0.0;
349  for (std::size_t i = 0; i < waypoints.size(); ++i)
350  {
351  // Don't test joint space jumps for every waypoint, test them later on the whole trajectory.
352  static const JumpThreshold NO_JOINT_SPACE_JUMP_TEST;
353  std::vector<RobotStatePtr> waypoint_traj;
354 #pragma GCC diagnostic push
355 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
356  double wp_percentage_solved =
357  computeCartesianPath(start_state, group, waypoint_traj, link, waypoints[i], global_reference_frame, max_step,
358  NO_JOINT_SPACE_JUMP_TEST, validCallback, options, link_offset);
359 #pragma GCC diagnostic pop
360 
361  std::vector<RobotStatePtr>::iterator start = waypoint_traj.begin();
362  if (i > 0 && !waypoint_traj.empty())
363  std::advance(start, 1);
364  traj.insert(traj.end(), start, waypoint_traj.end());
365 
366  if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
367  percentage_solved = (double)(i + 1) / (double)waypoints.size();
368  else
369  {
370  percentage_solved += wp_percentage_solved / (double)waypoints.size();
371  break;
372  }
373  }
374 
375  percentage_solved *= checkJointSpaceJump(group, traj, jump_threshold);
376 
377  return percentage_solved;
378 }
379 
380 double CartesianInterpolator::checkJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
381  const JumpThreshold& jump_threshold)
382 {
383  double percentage_solved = 1.0;
384  if (traj.size() <= 1)
385  return percentage_solved;
386 
387  if (jump_threshold.factor > 0.0)
388  percentage_solved = checkRelativeJointSpaceJump(group, traj, jump_threshold.factor);
389 
390  double percentage_solved_absolute = 1.0;
391  if (jump_threshold.revolute > 0.0 || jump_threshold.prismatic > 0.0)
392  percentage_solved_absolute =
393  checkAbsoluteJointSpaceJump(group, traj, jump_threshold.revolute, jump_threshold.prismatic);
394 
395  return std::min(percentage_solved, percentage_solved_absolute);
396 }
397 
398 double CartesianInterpolator::checkRelativeJointSpaceJump(const JointModelGroup* group,
399  std::vector<RobotStatePtr>& traj,
400  double jump_threshold_factor)
401 {
402  if (traj.size() < MIN_STEPS_FOR_JUMP_THRESH)
403  {
405  "The computed trajectory is too short to detect jumps in joint-space "
406  "Need at least %zu steps, only got %zu. Try a lower max_step.",
407  MIN_STEPS_FOR_JUMP_THRESH, traj.size());
408  }
409 
410  std::vector<double> dist_vector;
411  dist_vector.reserve(traj.size() - 1);
412  double total_dist = 0.0;
413  for (std::size_t i = 1; i < traj.size(); ++i)
414  {
415  double dist_prev_point = traj[i]->distance(*traj[i - 1], group);
416  dist_vector.push_back(dist_prev_point);
417  total_dist += dist_prev_point;
418  }
419 
420  double percentage = 1.0;
421  // compute the average distance between the states we looked at
422  double thres = jump_threshold_factor * (total_dist / (double)dist_vector.size());
423  for (std::size_t i = 0; i < dist_vector.size(); ++i)
424  if (dist_vector[i] > thres)
425  {
426  ROS_DEBUG_NAMED(LOGNAME, "Truncating Cartesian path due to detected jump in joint-space distance");
427  percentage = (double)(i + 1) / (double)(traj.size());
428  traj.resize(i + 1);
429  break;
430  }
431 
432  return percentage;
433 }
434 
435 double CartesianInterpolator::checkAbsoluteJointSpaceJump(const JointModelGroup* group,
436  std::vector<RobotStatePtr>& traj, double revolute_threshold,
437  double prismatic_threshold)
438 {
439  bool check_revolute = revolute_threshold > 0.0;
440  bool check_prismatic = prismatic_threshold > 0.0;
441 
442  double joint_threshold;
443  bool check_joint;
444  bool still_valid = true;
445  const std::vector<const JointModel*>& joints = group->getActiveJointModels();
446  for (std::size_t traj_ix = 0, ix_end = traj.size() - 1; traj_ix != ix_end; ++traj_ix)
447  {
448  for (auto& joint : joints)
449  {
450  switch (joint->getType())
451  {
453  check_joint = check_revolute;
454  joint_threshold = revolute_threshold;
455  break;
457  check_joint = check_prismatic;
458  joint_threshold = prismatic_threshold;
459  break;
460  default:
462  "Joint %s has not supported type %s. \n"
463  "checkAbsoluteJointSpaceJump only supports prismatic and revolute joints.",
464  joint->getName().c_str(), joint->getTypeName().c_str());
465  continue;
466  }
467  if (check_joint)
468  {
469  double distance = traj[traj_ix]->distance(*traj[traj_ix + 1], joint);
470  if (distance > joint_threshold)
471  {
472  ROS_DEBUG_NAMED(LOGNAME, "Truncating Cartesian path due to detected jump of %.4f > %.4f in joint %s",
473  distance, joint_threshold, joint->getName().c_str());
474  still_valid = false;
475  break;
476  }
477  }
478  }
479 
480  if (!still_valid)
481  {
482  double percent_valid = (double)(traj_ix + 1) / (double)(traj.size());
483  traj.resize(traj_ix + 1);
484  return percent_valid;
485  }
486  }
487  return 1.0;
488 }
489 
490 } // end of namespace core
491 } // end of namespace moveit
moveit::core::LinkModel
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:71
moveit::core::GroupStateValidityCallbackFn
boost::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:136
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
moveit::core::JumpThreshold
Struct for containing jump_threshold.
Definition: cartesian_interpolator.h:130
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
moveit::core::CartesianInterpolator::checkRelativeJointSpaceJump
static double 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.
Definition: cartesian_interpolator.cpp:466
check_isometry.h
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
moveit::core::RobotState::getGlobalLinkTransform
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...
Definition: robot_state.h:1394
moveit::core::RobotState::setFromIK
bool setFromIK(const JointModelGroup *group, const geometry_msgs::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
Definition: robot_state.cpp:1558
moveit::core::JointModel::PRISMATIC
@ PRISMATIC
Definition: joint_model.h:181
moveit::core::JointModel::REVOLUTE
@ REVOLUTE
Definition: joint_model.h:180
moveit::core::CartesianInterpolator::computeCartesianPath
static double 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())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
moveit::core::JointModelGroup::getContinuousJointModels
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints used in this group (may include mimic joints).
Definition: joint_model_group.h:247
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
ASSERT_ISOMETRY
#define ASSERT_ISOMETRY(transform)
cartesian_interpolator.h
moveit::core::MaxEEFStep
Struct for containing max_step for computeCartesianPath.
Definition: cartesian_interpolator.h:157
moveit::core::CartesianInterpolator::checkJointSpaceJump
static double checkJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const JumpThreshold &jump_threshold)
Tests joint space jumps of a trajectory.
Definition: cartesian_interpolator.cpp:448
moveit::core::LOGNAME
const std::string LOGNAME
Definition: joint_model_group.cpp:165
moveit::core::CartesianInterpolator::checkAbsoluteJointSpaceJump
static double 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.
Definition: cartesian_interpolator.cpp:503
start
ROSCPP_DECL void start()
moveit::core::MIN_STEPS_FOR_JUMP_THRESH
static const std::size_t MIN_STEPS_FOR_JUMP_THRESH
It is recommended that there are at least 10 steps per trajectory for testing jump thresholds with co...
Definition: cartesian_interpolator.cpp:119
moveit::core::MaxEEFStep::translation
double translation
Definition: cartesian_interpolator.h:167
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
kinematics::KinematicsQueryOptions
A set of options for the kinematics solver.
Definition: kinematics_base.h:109
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit::core::MaxEEFStep::rotation
double rotation
Definition: cartesian_interpolator.h:168
moveit::core::LinkModel::getName
const std::string & getName() const
The name of this link.
Definition: link_model.h:80
moveit::core::CartesianPrecision
Definition: cartesian_interpolator.h:118
moveit::core::validateAndImproveInterval
bool validateAndImproveInterval(const RobotState &start_state, const RobotState &end_state, const Eigen::Isometry3d &start_pose, const Eigen::Isometry3d &end_pose, std::vector< RobotStatePtr > &traj, double &percentage, const double width, const JointModelGroup *group, const LinkModel *link, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback, const kinematics::KinematicsQueryOptions &options, const Eigen::Isometry3d &link_offset)
Definition: cartesian_interpolator.cpp:123
pr2_arm_kinematics::distance
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:86
moveit::core::RobotState::enforceBounds
void enforceBounds()
Definition: robot_state.cpp:939
moveit::core::JointModel
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:173
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Nov 21 2024 03:23:41