60 std::vector<kinematic_constraints::JointConstraint> jc;
61 for (
const moveit_msgs::JointConstraint& joint_constraint : constr.joint_constraints)
64 if (j.configure(joint_constraint))
68 return jc.empty() ? false :
configure(jc);
77 ROS_ERROR_NAMED(
"constraint_samplers",
"NULL group specified for constraint sampler");
83 std::map<std::string, JointInfo> bound_data;
84 bool some_valid_constraint =
false;
87 if (!joint_constraint.enabled())
94 some_valid_constraint =
true;
98 std::map<std::string, JointInfo>::iterator it = bound_data.find(joint_constraint.getJointVariableName());
99 if (it != bound_data.end())
105 joint_constraint.getDesiredJointPosition() - joint_constraint.getJointToleranceBelow()),
107 joint_constraint.getDesiredJointPosition() + joint_constraint.getJointToleranceAbove()));
109 ROS_DEBUG_NAMED(
"constraint_samplers",
"Bounds for %s JointConstraint are %g %g",
114 std::stringstream cs;
115 joint_constraint.print(cs);
117 "The constraints for joint '%s' are such that "
118 "there are no possible values for the joint: min_bound: %g, max_bound: %g. Failing.\n",
123 bound_data[joint_constraint.getJointVariableName()] = ji;
126 if (!some_valid_constraint)
128 ROS_WARN_NAMED(
"constraint_samplers",
"No valid joint constraints");
132 for (std::pair<const std::string, JointInfo>& it : bound_data)
138 if (bound_data.find(joint->getName()) == bound_data.end() && joint->getVariableCount() > 0 &&
139 joint->getMimic() ==
nullptr)
142 const std::vector<std::string>& vars = joint->getVariableNames();
145 bool all_found =
true;
146 for (
const std::string& var : vars)
147 if (bound_data.find(var) == bound_data.end())
170 ROS_WARN_NAMED(
"constraint_samplers",
"JointConstraintSampler not configured, won't sample");
175 std::vector<double> v;
176 for (std::size_t i = 0; i <
unbounded_.size(); ++i)
180 for (std::size_t j = 0; j < v.size(); ++j)
185 for (
const JointInfo& bound :
bounds_)
233 const kinematic_constraints::OrientationConstraintPtr& oc)
234 : position_constraint_(pc), orientation_constraint_(oc)
258 ROS_WARN_NAMED(
"constraint_samplers",
"No enabled constraints in sampling pose");
269 "Position and orientation constraints need to be specified for the same link "
270 "in order to use IK-based sampling");
281 ROS_WARN_NAMED(
"constraint_samplers",
"No solver instance in setup");
291 for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
292 for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
293 if (constr.position_constraints[p].link_name == constr.orientation_constraints[o].link_name)
295 kinematic_constraints::PositionConstraintPtr pc(
297 kinematic_constraints::OrientationConstraintPtr oc(
299 if (pc->configure(constr.position_constraints[p],
scene_->getTransforms()) &&
300 oc->configure(constr.orientation_constraints[o],
scene_->getTransforms()))
301 return configure(IKSamplingPose(pc, oc));
304 for (
const moveit_msgs::PositionConstraint& position_constraint : constr.position_constraints)
306 kinematic_constraints::PositionConstraintPtr pc(
308 if (pc->configure(position_constraint,
scene_->getTransforms()))
312 for (
const moveit_msgs::OrientationConstraint& orientation_constraint : constr.orientation_constraints)
314 kinematic_constraints::OrientationConstraintPtr oc(
316 if (oc->configure(orientation_constraint,
scene_->getTransforms()))
327 const std::vector<bodies::BodyPtr>& constraint_regions =
331 vol += constraint_region->computeVolume();
332 if (!constraint_regions.empty())
367 "The IK solver expects requests in frame '%s' but this frame is not known to the sampler. "
368 "Ignoring transformation (IK may fail)",
374 bool wrong_link =
false;
382 for (
const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
400 for (
const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
414 "IK cannot be performed for link '%s'. The solver can report IK solutions for link '%s'.",
418 kb_->getTipFrame().c_str());
425 unsigned int max_attempts)
431 "IKConstraintSampler received dirty robot state, but valid transforms are required. "
443 for (std::size_t i = 0; i < b.size(); ++i)
451 ROS_ERROR_NAMED(
"constraint_samplers",
"Unable to sample a point inside the constraint region");
457 ROS_ERROR_NAMED(
"constraint_samplers",
"Unable to sample a point inside the constraint region. "
458 "Constraint region is empty when it should not be.");
471 temp_state.setToRandomPositions(
jmg_);
488 Eigen::Isometry3d diff;
490 moveit_msgs::OrientationConstraint::XYZ_EULER_ANGLES)
492 diff = Eigen::Isometry3d(Eigen::AngleAxisd(angle_x, Eigen::Vector3d::UnitX()) *
493 Eigen::AngleAxisd(angle_y, Eigen::Vector3d::UnitY()) *
494 Eigen::AngleAxisd(angle_z, Eigen::Vector3d::UnitZ()));
497 moveit_msgs::OrientationConstraint::ROTATION_VECTOR)
500 diff = Eigen::Isometry3d(Eigen::AngleAxisd(rotation_vector.norm(), rotation_vector.normalized()));
506 "The parameterization type for the orientation constraints is invalid.");
513 quat = Eigen::Quaterniond(reqr.linear());
522 Eigen::Isometry3d rt(
t.linear() * quat);
523 quat = Eigen::Quaterniond(rt.linear());
531 quat = Eigen::Quaterniond(q[3], q[0], q[1], q[2]);
546 const std::vector<double>& ik_sol, moveit_msgs::MoveItErrorCodes& error_code)
549 std::vector<double> solution(bij.size());
550 for (std::size_t i = 0; i < bij.size(); ++i)
551 solution[i] = ik_sol[bij[i]];
552 if (constraint(state, jmg, &solution[0]))
553 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
560 unsigned int max_attempts)
562 return sampleHelper(state, reference_state, max_attempts);
566 unsigned int max_attempts)
570 ROS_WARN_NAMED(
"constraint_samplers",
"IKConstraintSampler not configured, won't sample");
576 adapted_ik_validity_callback = [
this, state_ptr = &state](
const geometry_msgs::Pose& ,
577 const std::vector<double>& joints,
578 moveit_msgs::MoveItErrorCodes& error_code) {
582 for (
unsigned int a = 0; a < max_attempts; ++a)
586 Eigen::Quaterniond quat;
590 ROS_INFO_NAMED(
"constraint_samplers",
"IK constraint sampler was unable to produce a pose to run IK for");
599 Eigen::Isometry3d ikq(Eigen::Translation3d(
point) * quat);
602 point = ikq.translation();
603 quat = Eigen::Quaterniond(ikq.linear());
609 Eigen::Isometry3d ikq(Eigen::Translation3d(
point) * quat);
611 point = ikq.translation();
612 quat = Eigen::Quaterniond(ikq.linear());
615 geometry_msgs::Pose ik_query;
616 ik_query.position.x =
point.x();
617 ik_query.position.y =
point.y();
618 ik_query.position.z =
point.z();
619 ik_query.orientation.x = quat.x();
620 ik_query.orientation.y = quat.y();
621 ik_query.orientation.z = quat.z();
622 ik_query.orientation.w = quat.w();
644 std::vector<double> seed(ik_joint_bijection.size(), 0.0);
645 std::vector<double> vals;
653 assert(vals.size() == ik_joint_bijection.size());
654 for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
655 seed[i] = vals[ik_joint_bijection[i]];
657 std::vector<double> ik_sol;
658 moveit_msgs::MoveItErrorCodes error;
660 if (adapted_ik_validity_callback ?
661 kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, adapted_ik_validity_callback, error) :
662 kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, error))
664 assert(ik_sol.size() == ik_joint_bijection.size());
665 std::vector<double> solution(ik_joint_bijection.size());
666 for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
667 solution[ik_joint_bijection[i]] = ik_sol[i];
675 error.val != moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE &&
677 ROS_ERROR_NAMED(
"constraint_samplers",
"IK solver failed with error %d", error.val);