Go to the documentation of this file.
58 class JointConstraintSampler :
public ConstraintSampler
94 bool configure(
const moveit_msgs::Constraints& constr)
override;
121 bool configure(
const std::vector<kinematic_constraints::JointConstraint>& jc);
153 const std::string&
getName()
const override
155 static const std::string SAMPLER_NAME =
"JointConstraintSampler";
170 min_bound_ = -std::numeric_limits<double>::max();
171 max_bound_ = std::numeric_limits<double>::max();
194 void clear()
override;
197 std::vector<JointInfo>
bounds_;
202 std::vector<unsigned int>
uindex_;
256 IKSamplingPose(
const kinematic_constraints::PositionConstraintPtr& pc);
265 IKSamplingPose(
const kinematic_constraints::OrientationConstraintPtr& oc);
275 IKSamplingPose(
const kinematic_constraints::PositionConstraintPtr& pc,
276 const kinematic_constraints::OrientationConstraintPtr& oc);
280 kinematic_constraints::OrientationConstraintPtr
307 IKConstraintSampler(
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name)
337 bool configure(
const moveit_msgs::Constraints& constr)
override;
452 unsigned int max_attempts)
override;
477 unsigned int max_attempts);
484 const std::string&
getName()
const override
486 static const std::string SAMPLER_NAME =
"IKConstraintSampler";
491 void clear()
override;
511 bool callIK(
const geometry_msgs::Pose& ik_query,
515 unsigned int max_attempts);
520 kinematics::KinematicsBaseConstPtr
kb_;
A structure for potentially holding a position constraint and an orientation constraint for use durin...
random_numbers::RandomNumberGenerator createSeededRNG(const std::string &seed_param)
double getSamplingVolume() const
Gets the volume associated with the position and orientation constraints.
A class that allows the sampling of IK constraints.
std::size_t getUnconstrainedJointCount() const
Gets the number of unconstrained joints - joint that have no additional bound beyond the joint limits...
void setIKTimeout(double timeout)
Sets the timeout argument passed to the IK solver.
void clear() override
Clears all data from the constraint.
IKSamplingPose sampling_pose_
Holder for the pose used for sampling.
const kinematic_constraints::PositionConstraintPtr & getPositionConstraint() const
Gets the position constraint associated with this sampler.
random_numbers::RandomNumberGenerator random_number_generator_
Random generator used by the sampler.
const std::string & getLinkName() const
Gets the link name associated with this sampler.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
double ik_timeout_
Holds the timeout associated with IK.
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
kinematic_constraints::PositionConstraintPtr position_constraint_
Holds the position constraint for sampling.
random_numbers::RandomNumberGenerator random_number_generator_
Random number generator used to sample.
std::vector< unsigned int > uindex_
The index of the unbounded joints in the joint state vector.
Eigen::Isometry3d eef_to_ik_tip_transform_
Holds the transformation from end effector to IK tip frame.
IKConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
Constructor.
IKSamplingPose()
Empty constructor.
std::vector< double > values_
Values associated with this group to avoid continuously reallocating.
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
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< JointInfo > bounds_
The bounds for any joint with bounds that are more restrictive than the joint limits.
Class for constraints on the orientation of a link.
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
Produces an IK sample.
bool loadIKSolver()
Performs checks and sets various internal values associated with the IK solver.
const kinematic_constraints::OrientationConstraintPtr & getOrientationConstraint() const
Gets the orientation constraint associated with this sampler.
void clear() override
Clears all data from the constraint.
bool transform_ik_
True if the frame associated with the kinematic model is different than the base frame of the IK solv...
kinematics::KinematicsBaseConstPtr kb_
Holds the kinematics solver.
bool callIK(const geometry_msgs::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.
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.
double getIKTimeout() const
Gets the timeout argument passed to the IK solver.
bool sampleHelper(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts)
bool configure(const moveit_msgs::Constraints &constr) override
Configures a joint constraint given a Constraints message.
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
std::size_t getConstrainedJointCount() const
Gets the number of constrained joints - joints that have an additional bound beyond the joint limits.
std::string ik_frame_
Holds the base from of the IK solver.
void potentiallyAdjustMinMaxBounds(double min, double max)
Function that adjusts the joints only if they are more restrictive. This means that the min limit is ...
kinematic_constraints::OrientationConstraintPtr orientation_constraint_
Holds the orientation constraint for sampling.
bool validate(moveit::core::RobotState &state) const
JointConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
bool configure(const moveit_msgs::Constraints &constr) override
Configures the IK constraint given a constraints message.
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.
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
std::vector< const moveit::core::JointModel * > unbounded_
The joints that are not bounded except by joint limits.
MOVEIT_CLASS_FORWARD(ConstraintSampler)
ConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
Constructor.
Class for constraints on the XYZ position of a link.
Vec3fX< details::Vec3Data< double > > Vector3d
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14