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)
84 if (!mid_state.setFromIK(group, mid_pose * link_offset.inverse(), link->getName(), 0.0, validCallback, options))
88 const auto half_width = width / 2.0;
89 const auto old_percentage = percentage;
90 percentage = percentage - half_width;
92 link, precision, validCallback, options, link_offset))
95 percentage = old_percentage;
97 precision, validCallback, options, link_offset);
101 std::vector<RobotStatePtr>& traj,
const LinkModel* link,
103 const MaxEEFStep& max_step,
const CartesianPrecision& precision,
107 const double distance = translation.norm();
109 Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
112 pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
116 computeCartesianPath(start_state, group, traj, link, pose,
true, max_step, precision, validCallback, options);
120 std::vector<RobotStatePtr>& traj,
const LinkModel* link,
121 const Eigen::Isometry3d& target,
bool global_reference_frame,
125 const Eigen::Isometry3d& link_offset)
140 Eigen::Isometry3d inv_offset = link_offset.inverse();
143 Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
145 Eigen::Quaterniond start_quaternion(start_pose.linear());
146 Eigen::Quaterniond target_quaternion(rotated_target.linear());
148 double rotation_distance = start_quaternion.angularDistance(target_quaternion);
149 double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
152 std::size_t translation_steps = 0;
154 translation_steps = floor(translation_distance / max_step.
translation);
156 std::size_t rotation_steps = 0;
158 rotation_steps = floor(rotation_distance / max_step.
rotation);
159 std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
162 traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
164 double last_valid_percentage = 0.0;
165 Eigen::Isometry3d prev_pose = start_pose;
167 for (std::size_t i = 1; i <= steps; ++i)
169 double percentage = (double)i / (
double)steps;
171 Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
172 pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
174 if (!state.
setFromIK(group, pose * inv_offset, link->
getName(), 0.0, validCallback, options) ||
176 link, precision, validCallback, options, link_offset))
181 last_valid_percentage = percentage;
184 return last_valid_percentage;
193 double percentage_solved = 0.0;
194 for (std::size_t i = 0; i < waypoints.size(); ++i)
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);
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());
206 if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
207 percentage_solved = (double)(i + 1) / (double)waypoints.size();
210 percentage_solved += wp_percentage_solved / (double)waypoints.size();
213 start_state = traj.back().get();
216 return percentage_solved;
220 std::vector<RobotStatePtr>& traj,
const LinkModel* link,
226 const double distance = translation.norm();
231 pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
233 #pragma GCC diagnostic push
234 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
237 validCallback, options);
238 #pragma GCC diagnostic pop
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,
247 const Eigen::Isometry3d& link_offset)
253 const std::vector<const JointModel*>& cjnt = group->getContinuousJointModels();
255 for (
const JointModel* joint : cjnt)
256 start_state->enforceBounds(joint);
259 Eigen::Isometry3d start_pose = start_state->getGlobalLinkTransform(link) * link_offset;
260 Eigen::Isometry3d offset = link_offset.inverse();
263 Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
265 Eigen::Quaterniond start_quaternion(start_pose.linear());
266 Eigen::Quaterniond target_quaternion(rotated_target.linear());
268 if (max_step.translation <= 0.0 && max_step.rotation <= 0.0)
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");
277 double rotation_distance = start_quaternion.angularDistance(target_quaternion);
278 double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
281 std::size_t translation_steps = 0;
282 if (max_step.translation > 0.0)
283 translation_steps = floor(translation_distance / max_step.translation);
285 std::size_t rotation_steps = 0;
286 if (max_step.rotation > 0.0)
287 rotation_steps = floor(rotation_distance / max_step.rotation);
290 std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
295 std::vector<double> consistency_limits;
296 if (jump_threshold.prismatic > 0 || jump_threshold.revolute > 0)
297 for (
const JointModel* jm : group->getActiveJointModels())
300 switch (jm->getType())
303 limit = jump_threshold.revolute;
306 limit = jump_threshold.prismatic;
312 limit = jm->getMaximumExtent();
313 consistency_limits.push_back(limit);
317 traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
319 double last_valid_percentage = 0.0;
320 for (std::size_t i = 1; i <= steps; ++i)
322 double percentage = (double)i / (
double)steps;
324 Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
325 pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
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));
334 last_valid_percentage = percentage;
339 return last_valid_percentage;
343 RobotState* start_state,
const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
const LinkModel* link,
348 double percentage_solved = 0.0;
349 for (std::size_t i = 0; i < waypoints.size(); ++i)
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
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());
366 if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
367 percentage_solved = (double)(i + 1) / (double)waypoints.size();
370 percentage_solved += wp_percentage_solved / (double)waypoints.size();
377 return percentage_solved;
381 const JumpThreshold& jump_threshold)
383 double percentage_solved = 1.0;
384 if (traj.size() <= 1)
385 return percentage_solved;
387 if (jump_threshold.factor > 0.0)
390 double percentage_solved_absolute = 1.0;
391 if (jump_threshold.revolute > 0.0 || jump_threshold.prismatic > 0.0)
392 percentage_solved_absolute =
395 return std::min(percentage_solved, percentage_solved_absolute);
399 std::vector<RobotStatePtr>& traj,
400 double jump_threshold_factor)
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.",
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)
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;
420 double percentage = 1.0;
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)
427 percentage = (double)(i + 1) / (double)(traj.size());
436 std::vector<RobotStatePtr>& traj,
double revolute_threshold,
437 double prismatic_threshold)
439 bool check_revolute = revolute_threshold > 0.0;
440 bool check_prismatic = prismatic_threshold > 0.0;
442 double joint_threshold;
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)
448 for (
auto& joint : joints)
450 switch (joint->getType())
453 check_joint = check_revolute;
454 joint_threshold = revolute_threshold;
457 check_joint = check_prismatic;
458 joint_threshold = prismatic_threshold;
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());
469 double distance = traj[traj_ix]->distance(*traj[traj_ix + 1], joint);
473 distance, joint_threshold, joint->getName().c_str());
482 double percent_valid = (double)(traj_ix + 1) / (double)(traj.size());
483 traj.resize(traj_ix + 1);
484 return percent_valid;