38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_constraint_samplers.default_constraint_samplers");
50 std::vector<kinematic_constraints::JointConstraint> jc;
51 for (
const moveit_msgs::msg::JointConstraint& joint_constraint : constr.joint_constraints)
58 return jc.empty() ? false :
configure(jc);
67 RCLCPP_ERROR(LOGGER,
"nullptr group specified for constraint sampler");
73 std::map<std::string, JointInfo> bound_data;
74 bool some_valid_constraint =
false;
77 if (!joint_constraint.enabled())
84 some_valid_constraint =
true;
88 std::map<std::string, JointInfo>::iterator it = bound_data.find(joint_constraint.getJointVariableName());
89 if (it != bound_data.end())
95 joint_constraint.getDesiredJointPosition() - joint_constraint.getJointToleranceBelow()),
97 joint_constraint.getDesiredJointPosition() + joint_constraint.getJointToleranceAbove()));
99 RCLCPP_DEBUG(LOGGER,
"Bounds for %s JointConstraint are %g %g", joint_constraint.getJointVariableName().c_str(),
104 std::stringstream cs;
105 joint_constraint.print(cs);
107 "The constraints for joint '%s' are such that "
108 "there are no possible values for the joint: min_bound: %g, max_bound: %g. Failing.\n",
113 bound_data[joint_constraint.getJointVariableName()] = ji;
116 if (!some_valid_constraint)
118 RCLCPP_WARN(LOGGER,
"No valid joint constraints");
122 for (std::pair<const std::string, JointInfo>& it : bound_data)
128 if (bound_data.find(joint->getName()) == bound_data.end() && joint->getVariableCount() > 0 &&
129 joint->getMimic() ==
nullptr)
132 const std::vector<std::string>& vars = joint->getVariableNames();
135 bool all_found =
true;
136 for (
const std::string& var : vars)
137 if (bound_data.find(var) == bound_data.end())
160 RCLCPP_WARN(LOGGER,
"JointConstraintSampler not configured, won't sample");
165 std::vector<double> v;
166 for (std::size_t i = 0; i <
unbounded_.size(); ++i)
170 for (std::size_t j = 0; j < v.size(); ++j)
186 return sample(state, state, max_attempts);
228 const kinematic_constraints::OrientationConstraintPtr& oc)
229 : position_constraint_(pc), orientation_constraint_(oc)
253 RCLCPP_WARN(LOGGER,
"No enabled constraints in sampling pose");
263 RCLCPP_ERROR(LOGGER,
"Position and orientation constraints need to be specified for the same link "
264 "in order to use IK-based sampling");
275 RCLCPP_WARN(LOGGER,
"No solver instance in setup");
285 for (std::size_t
p = 0;
p < constr.position_constraints.size(); ++
p)
286 for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
287 if (constr.position_constraints[
p].link_name == constr.orientation_constraints[o].link_name)
289 kinematic_constraints::PositionConstraintPtr pc(
291 kinematic_constraints::OrientationConstraintPtr oc(
293 if (pc->configure(constr.position_constraints[
p],
scene_->getTransforms()) &&
294 oc->configure(constr.orientation_constraints[o],
scene_->getTransforms()))
298 for (
const moveit_msgs::msg::PositionConstraint& position_constraint : constr.position_constraints)
300 kinematic_constraints::PositionConstraintPtr pc(
302 if (pc->configure(position_constraint,
scene_->getTransforms()))
306 for (
const moveit_msgs::msg::OrientationConstraint& orientation_constraint : constr.orientation_constraints)
308 kinematic_constraints::OrientationConstraintPtr oc(
310 if (oc->configure(orientation_constraint,
scene_->getTransforms()))
321 const std::vector<bodies::BodyPtr>& constraint_regions =
324 for (
const bodies::BodyPtr& constraint_region : constraint_regions)
325 vol += constraint_region->computeVolume();
326 if (!constraint_regions.empty())
348 RCLCPP_ERROR(LOGGER,
"No IK solver");
361 "The IK solver expects requests in frame '%s' but this frame is not known to the sampler. "
362 "Ignoring transformation (IK may fail)",
368 bool wrong_link =
false;
376 for (
const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
394 for (
const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
407 RCLCPP_ERROR(LOGGER,
"IK cannot be performed for link '%s'. The solver can report IK solutions for link '%s'.",
411 kb_->getTipFrame().c_str());
418 unsigned int max_attempts)
423 RCLCPP_ERROR(LOGGER,
"IKConstraintSampler received dirty robot state, but valid transforms are required. "
435 for (std::size_t i = 0; i < b.size(); ++i)
443 RCLCPP_ERROR(LOGGER,
"Unable to sample a point inside the constraint region");
449 RCLCPP_ERROR(LOGGER,
"Unable to sample a point inside the constraint region. "
450 "Constraint region is empty when it should not be.");
480 Eigen::Isometry3d diff;
482 moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES)
484 diff = Eigen::Isometry3d(Eigen::AngleAxisd(angle_x, Eigen::Vector3d::UnitX()) *
485 Eigen::AngleAxisd(angle_y, Eigen::Vector3d::UnitY()) *
486 Eigen::AngleAxisd(angle_z, Eigen::Vector3d::UnitZ()));
489 moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR)
492 diff = Eigen::Isometry3d(Eigen::AngleAxisd(rotation_vector.norm(), rotation_vector.normalized()));
497 RCLCPP_ERROR(LOGGER,
"The parameterization type for the orientation constraints is invalid.");
503 quat = Eigen::Quaterniond(reqr.linear());
512 Eigen::Isometry3d rt(t.linear() * quat);
513 quat = Eigen::Quaterniond(rt.linear());
521 quat = Eigen::Quaterniond(q[3], q[0], q[1], q[2]);
536 const std::vector<double>& ik_sol, moveit_msgs::msg::MoveItErrorCodes& error_code)
539 std::vector<double> solution(bij.size());
540 for (std::size_t i = 0; i < bij.size(); ++i)
541 solution[i] = ik_sol[bij[i]];
542 if (constraint(state, jmg, &solution[0]))
543 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
545 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
550 unsigned int max_attempts)
552 return sampleHelper(state, reference_state, max_attempts,
false);
556 unsigned int max_attempts,
bool project)
560 RCLCPP_WARN(LOGGER,
"IKConstraintSampler not configured, won't sample");
566 adapted_ik_validity_callback = [
this, state_ptr = &state](
const geometry_msgs::msg::Pose&,
567 const std::vector<double>& joints,
568 moveit_msgs::msg::MoveItErrorCodes& error_code) {
572 for (
unsigned int a = 0;
a < max_attempts; ++
a)
576 Eigen::Quaterniond quat;
577 if (!
samplePose(point, quat, reference_state, max_attempts))
580 RCLCPP_INFO(LOGGER,
"IK constraint sampler was unable to produce a pose to run IK for");
589 Eigen::Isometry3d ikq(Eigen::Translation3d(point) * quat);
592 point = ikq.translation();
593 quat = Eigen::Quaterniond(ikq.linear());
599 Eigen::Isometry3d ikq(Eigen::Translation3d(point) * quat);
601 point = ikq.translation();
602 quat = Eigen::Quaterniond(ikq.linear());
605 geometry_msgs::msg::Pose ik_query;
606 ik_query.position.x = point.x();
607 ik_query.position.y = point.y();
608 ik_query.position.z = point.z();
609 ik_query.orientation.x = quat.x();
610 ik_query.orientation.y = quat.y();
611 ik_query.orientation.z = quat.z();
612 ik_query.orientation.w = quat.w();
639 std::vector<double> seed(ik_joint_bijection.size(), 0.0);
640 std::vector<double> vals;
648 assert(vals.size() == ik_joint_bijection.size());
649 for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
650 seed[i] = vals[ik_joint_bijection[i]];
652 std::vector<double> ik_sol;
653 moveit_msgs::msg::MoveItErrorCodes error;
655 if (adapted_ik_validity_callback ?
656 kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, adapted_ik_validity_callback, error) :
657 kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, error))
659 assert(ik_sol.size() == ik_joint_bijection.size());
660 std::vector<double> solution(ik_joint_bijection.size());
661 for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
662 solution[ik_joint_bijection[i]] = ik_sol[i];
669 if (error.val != moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION &&
670 error.val != moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE &&
671 error.val != moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT)
673 RCLCPP_ERROR(LOGGER,
"IK solver failed with error %d", error.val);
677 RCLCPP_INFO(LOGGER,
"IK failed");
bool is_valid_
Holds the value for validity.
std::vector< std::string > frame_depends_
Holds the set of frames that must exist in the reference state to allow samples to be drawn.
const moveit::core::JointModelGroup *const jmg_
Holds the joint model group associated with this constraint.
virtual void clear()
Clears all data from the constraint.
moveit::core::GroupStateValidityCallbackFn group_state_validity_callback_
Holds the callback for state validity.
bool verbose_
True if verbosity is on.
planning_scene::PlanningSceneConstPtr scene_
Holds the planning scene.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures the IK constraint given a constraints message.
double ik_timeout_
Holds the timeout associated with IK.
bool loadIKSolver()
Performs checks and sets various internal values associated with the IK solver.
const std::string & getLinkName() const
Gets the link name associated with this sampler.
bool validate(moveit::core::RobotState &state) const
IKSamplingPose sampling_pose_
Holder for the pose used for sampling.
bool callIK(const geometry_msgs::msg::Pose &ik_query, const kinematics::KinematicsBase::IKCallbackFn &adapted_ik_validity_callback, double timeout, moveit::core::RobotState &state, bool use_as_seed)
Actually calls IK on the given pose, generating a random seed state.
double getSamplingVolume() const
Gets the volume associated with the position and orientation constraints.
Eigen::Isometry3d eef_to_ik_tip_transform_
Holds the transformation from end effector to IK tip frame.
bool need_eef_to_ik_tip_transform_
True if the tip frame of the inverse kinematic is different than the frame of the end effector.
kinematics::KinematicsBaseConstPtr kb_
Holds the kinematics solver.
void clear() override
Clears all data from the constraint.
std::string ik_frame_
Holds the base from of the IK solver.
random_numbers::RandomNumberGenerator random_number_generator_
Random generator used by the sampler.
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
Project a sample given the constraints, updating the joint state group. This function allows the para...
bool transform_ik_
True if the frame associated with the kinematic model is different than the base frame of the IK solv...
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
Produces an IK sample.
bool sampleHelper(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts, bool project)
bool samplePose(Eigen::Vector3d &pos, Eigen::Quaterniond &quat, const moveit::core::RobotState &ks, unsigned int max_attempts)
Returns a pose that falls within the constraint regions.
std::vector< unsigned int > uindex_
The index of the unbounded joints in the joint state vector.
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
Project a sample given the constraints, updating the joint state group. This function allows the para...
void clear() override
Clears all data from the constraint.
random_numbers::RandomNumberGenerator random_number_generator_
Random number generator used to sample.
std::vector< const moveit::core::JointModel * > unbounded_
The joints that are not bounded except by joint limits.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures a joint constraint given a Constraints message.
std::vector< JointInfo > bounds_
The bounds for any joint with bounds that are more restrictive than the joint limits.
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &ks, unsigned int max_attempts) override
Samples given the constraints, populating state. This function allows the parameter max_attempts to b...
std::vector< double > values_
Values associated with this group to avoid continuously reallocating.
Class for handling single DOF joint constraints.
bool configure(const moveit_msgs::msg::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::msg::JointConstraint.
Class for constraints on the orientation of a link.
Class for constraints on the XYZ position of a link.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
double getDefaultIKTimeout() const
Get the default IK timeout.
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
const std::vector< size_t > & getKinematicsSolverJointBijection() const
Return the mapping between the order of the joints in this group and the order of the joints in the k...
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const std::string & getName() const
Get the name of the joint.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
A link from the robot. Contains the constant transform applied to the link and its geometry.
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
const std::string & getName() const
The name of this link.
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState)....
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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...
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool dirtyLinkTransforms() const
void update(bool force=false)
Update all transforms.
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
Vec3fX< details::Vec3Data< double > > Vector3d
Representation and evaluation of kinematic constraints.
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_...
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
A structure for potentially holding a position constraint and an orientation constraint for use durin...
IKSamplingPose()
Empty constructor.
kinematic_constraints::PositionConstraintPtr position_constraint_
Holds the position constraint for sampling.
kinematic_constraints::OrientationConstraintPtr orientation_constraint_
Holds the orientation constraint for sampling.
An internal structure used for maintaining constraints on a particular joint.
void potentiallyAdjustMinMaxBounds(double min, double max)
Function that adjusts the joints only if they are more restrictive. This means that the min limit is ...