53 const std::string 
LOGNAME = 
"cartesian_interpolator";
 
   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,
 
   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;
 
   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());
 
   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)
 
   76     traj.push_back(std::make_shared<moveit::core::RobotState>(end_state));
 
   80   if (width < precision.max_resolution)
 
   83                    precision.max_resolution);
 
   88   if (!mid_state.setFromIK(group, mid_pose * link_offset.inverse(), link->getName(), 0.0, validCallback, options))
 
   92   const auto half_width = width / 2.0;
 
   93   const auto old_percentage = percentage;
 
   94   percentage = percentage - half_width;
 
   96                                   link, precision, validCallback, options, link_offset))
 
   99   percentage = old_percentage;
 
  101                                     precision, validCallback, options, link_offset);
 
  105                                                    std::vector<RobotStatePtr>& traj, 
const LinkModel* link,
 
  107                                                    const MaxEEFStep& max_step, 
const CartesianPrecision& precision,
 
  111   const double distance = translation.norm();
 
  113   Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
 
  116   pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
 
  120          computeCartesianPath(start_state, group, traj, link, pose, 
true, max_step, precision, validCallback, options);
 
  124                                                    std::vector<RobotStatePtr>& traj, 
const LinkModel* link,
 
  125                                                    const Eigen::Isometry3d& target, 
bool global_reference_frame,
 
  129                                                    const Eigen::Isometry3d& link_offset)
 
  144   Eigen::Isometry3d inv_offset = link_offset.inverse();
 
  147   Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
 
  149   Eigen::Quaterniond start_quaternion(start_pose.linear());
 
  150   Eigen::Quaterniond target_quaternion(rotated_target.linear());
 
  152   double rotation_distance = start_quaternion.angularDistance(target_quaternion);
 
  153   double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
 
  156   std::size_t translation_steps = 0;
 
  158     translation_steps = floor(translation_distance / max_step.
translation);
 
  160   std::size_t rotation_steps = 0;
 
  162     rotation_steps = floor(rotation_distance / max_step.
rotation);
 
  163   std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
 
  166   traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
 
  168   double last_valid_percentage = 0.0;
 
  169   Eigen::Isometry3d prev_pose = start_pose;
 
  171   for (std::size_t i = 1; i <= steps; ++i)
 
  173     double percentage = (double)i / (
double)steps;
 
  175     Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
 
  176     pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
 
  178     if (!state.
setFromIK(group, pose * inv_offset, link->
getName(), 0.0, validCallback, options) ||
 
  180                                     link, precision, validCallback, options, link_offset))
 
  185     last_valid_percentage = percentage;
 
  188   return last_valid_percentage;
 
  197   double percentage_solved = 0.0;
 
  198   for (std::size_t i = 0; i < waypoints.size(); ++i)
 
  200     std::vector<RobotStatePtr> waypoint_traj;
 
  201     double wp_percentage_solved =
 
  202         computeCartesianPath(start_state, group, waypoint_traj, link, waypoints[i], global_reference_frame, max_step,
 
  203                              precision, validCallback, options, link_offset);
 
  205     std::vector<RobotStatePtr>::iterator 
start = waypoint_traj.begin();
 
  206     if (i > 0 && !waypoint_traj.empty())
 
  207       std::advance(
start, 1);
 
  208     traj.insert(traj.end(), 
start, waypoint_traj.end());
 
  210     if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
 
  211       percentage_solved = (double)(i + 1) / (double)waypoints.size();
 
  214       percentage_solved += wp_percentage_solved / (double)waypoints.size();
 
  217     start_state = traj.back().get();
 
  220   return percentage_solved;
 
  224                                                    std::vector<RobotStatePtr>& traj, 
const LinkModel* link,
 
  230   const double distance = translation.norm();
 
  235   pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
 
  237 #pragma GCC diagnostic push 
  238 #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 
  241                                          validCallback, options);
 
  242 #pragma GCC diagnostic pop 
  246                                                    std::vector<RobotStatePtr>& traj, 
const LinkModel* link,
 
  247                                                    const Eigen::Isometry3d& target, 
bool global_reference_frame,
 
  248                                                    const MaxEEFStep& max_step, 
const JumpThreshold& jump_threshold,
 
  251                                                    const Eigen::Isometry3d& link_offset)
 
  257   const std::vector<const JointModel*>& cjnt = group->getContinuousJointModels();
 
  259   for (
const JointModel* joint : cjnt)
 
  260     start_state->enforceBounds(joint);
 
  263   Eigen::Isometry3d start_pose = start_state->getGlobalLinkTransform(link) * link_offset;
 
  264   Eigen::Isometry3d offset = link_offset.inverse();
 
  267   Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
 
  269   Eigen::Quaterniond start_quaternion(start_pose.linear());
 
  270   Eigen::Quaterniond target_quaternion(rotated_target.linear());
 
  272   if (max_step.translation <= 0.0 && max_step.rotation <= 0.0)
 
  275                     "Invalid MaxEEFStep passed into computeCartesianPath. Both the MaxEEFStep.rotation and " 
  276                     "MaxEEFStep.translation components must be non-negative and at least one component must be " 
  277                     "greater than zero");
 
  281   double rotation_distance = start_quaternion.angularDistance(target_quaternion);
 
  282   double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
 
  285   std::size_t translation_steps = 0;
 
  286   if (max_step.translation > 0.0)
 
  287     translation_steps = floor(translation_distance / max_step.translation);
 
  289   std::size_t rotation_steps = 0;
 
  290   if (max_step.rotation > 0.0)
 
  291     rotation_steps = floor(rotation_distance / max_step.rotation);
 
  294   std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
 
  299   std::vector<double> consistency_limits;
 
  300   if (jump_threshold.prismatic > 0 || jump_threshold.revolute > 0)
 
  301     for (
const JointModel* jm : group->getActiveJointModels())
 
  304       switch (jm->getType())
 
  307           limit = jump_threshold.revolute;
 
  310           limit = jump_threshold.prismatic;
 
  316         limit = jm->getMaximumExtent();
 
  317       consistency_limits.push_back(limit);
 
  321   traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
 
  323   double last_valid_percentage = 0.0;
 
  324   for (std::size_t i = 1; i <= steps; ++i)
 
  326     double percentage = (double)i / (
double)steps;
 
  328     Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
 
  329     pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
 
  333     if (start_state->setFromIK(group, pose * offset, link->getName(), consistency_limits, 0.0, validCallback, options))
 
  334       traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
 
  338     last_valid_percentage = percentage;
 
  343   return last_valid_percentage;
 
  347     RobotState* start_state, 
const JointModelGroup* group, std::vector<RobotStatePtr>& traj, 
const LinkModel* link,
 
  352   double percentage_solved = 0.0;
 
  353   for (std::size_t i = 0; i < waypoints.size(); ++i)
 
  356     static const JumpThreshold NO_JOINT_SPACE_JUMP_TEST;
 
  357     std::vector<RobotStatePtr> waypoint_traj;
 
  358 #pragma GCC diagnostic push 
  359 #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 
  360     double wp_percentage_solved =
 
  361         computeCartesianPath(start_state, group, waypoint_traj, link, waypoints[i], global_reference_frame, max_step,
 
  362                              NO_JOINT_SPACE_JUMP_TEST, validCallback, options, link_offset);
 
  363 #pragma GCC diagnostic pop 
  365     std::vector<RobotStatePtr>::iterator 
start = waypoint_traj.begin();
 
  366     if (i > 0 && !waypoint_traj.empty())
 
  367       std::advance(start, 1);
 
  368     traj.insert(traj.end(), start, waypoint_traj.end());
 
  370     if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
 
  371       percentage_solved = (double)(i + 1) / (double)waypoints.size();
 
  374       percentage_solved += wp_percentage_solved / (double)waypoints.size();
 
  381   return percentage_solved;
 
  385                                                   const JumpThreshold& jump_threshold)
 
  387   double percentage_solved = 1.0;
 
  388   if (traj.size() <= 1)
 
  389     return percentage_solved;
 
  391   if (jump_threshold.factor > 0.0)
 
  394   double percentage_solved_absolute = 1.0;
 
  395   if (jump_threshold.revolute > 0.0 || jump_threshold.prismatic > 0.0)
 
  396     percentage_solved_absolute =
 
  399   return std::min(percentage_solved, percentage_solved_absolute);
 
  403                                                           std::vector<RobotStatePtr>& traj,
 
  404                                                           double jump_threshold_factor)
 
  409                    "The computed trajectory is too short to detect jumps in joint-space " 
  410                    "Need at least %zu steps, only got %zu. Try a lower max_step.",
 
  414   std::vector<double> dist_vector;
 
  415   dist_vector.reserve(traj.size() - 1);
 
  416   double total_dist = 0.0;
 
  417   for (std::size_t i = 1; i < traj.size(); ++i)
 
  419     double dist_prev_point = traj[i]->distance(*traj[i - 1], group);
 
  420     dist_vector.push_back(dist_prev_point);
 
  421     total_dist += dist_prev_point;
 
  424   double percentage = 1.0;
 
  426   double thres = jump_threshold_factor * (total_dist / (double)dist_vector.size());
 
  427   for (std::size_t i = 0; i < dist_vector.size(); ++i)
 
  428     if (dist_vector[i] > thres)
 
  431       percentage = (double)(i + 1) / (double)(traj.size());
 
  440                                                           std::vector<RobotStatePtr>& traj, 
double revolute_threshold,
 
  441                                                           double prismatic_threshold)
 
  443   bool check_revolute = revolute_threshold > 0.0;
 
  444   bool check_prismatic = prismatic_threshold > 0.0;
 
  446   double joint_threshold;
 
  448   bool still_valid = 
true;
 
  449   const std::vector<const JointModel*>& joints = group->getActiveJointModels();
 
  450   for (std::size_t traj_ix = 0, ix_end = traj.size() - 1; traj_ix != ix_end; ++traj_ix)
 
  452     for (
auto& joint : joints)
 
  454       switch (joint->getType())
 
  457           check_joint = check_revolute;
 
  458           joint_threshold = revolute_threshold;
 
  461           check_joint = check_prismatic;
 
  462           joint_threshold = prismatic_threshold;
 
  466                          "Joint %s has not supported type %s. \n" 
  467                          "checkAbsoluteJointSpaceJump only supports prismatic and revolute joints.",
 
  468                          joint->getName().c_str(), joint->getTypeName().c_str());
 
  473         double distance = traj[traj_ix]->distance(*traj[traj_ix + 1], joint);
 
  477                           distance, joint_threshold, joint->getName().c_str());
 
  486       double percent_valid = (double)(traj_ix + 1) / (double)(traj.size());
 
  487       traj.resize(traj_ix + 1);
 
  488       return percent_valid;