41 #include <random_numbers/random_numbers.h>
42 #include <rclcpp/rclcpp.hpp>
44 #include <Eigen/Geometry>
112 bool configure(
const moveit_msgs::msg::Constraints& constr)
override;
139 bool configure(
const std::vector<kinematic_constraints::JointConstraint>& jc);
175 static const std::string SAMPLER_NAME =
"JointConstraintSampler";
190 min_bound_ = -std::numeric_limits<double>::max();
191 max_bound_ = std::numeric_limits<double>::max();
214 void clear()
override;
276 IKSamplingPose(
const kinematic_constraints::PositionConstraintPtr& pc);
285 IKSamplingPose(
const kinematic_constraints::OrientationConstraintPtr& oc);
295 IKSamplingPose(
const kinematic_constraints::PositionConstraintPtr& pc,
296 const kinematic_constraints::OrientationConstraintPtr& oc);
300 kinematic_constraints::OrientationConstraintPtr
374 bool configure(
const moveit_msgs::msg::Constraints& constr)
override;
489 unsigned int max_attempts)
override;
515 unsigned int max_attempts);
524 static const std::string SAMPLER_NAME =
"IKConstraintSampler";
529 void clear()
override;
549 bool callIK(
const geometry_msgs::msg::Pose& ik_query,
553 unsigned int max_attempts,
bool project);
558 kinematics::KinematicsBaseConstPtr
kb_;
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
A class that allows the sampling of IK constraints.
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.
const kinematic_constraints::PositionConstraintPtr & getPositionConstraint() const
Gets the position constraint associated with this sampler.
double getIKTimeout() const
Gets the timeout argument passed to the IK solver.
IKConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
Constructor.
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.
void setIKTimeout(double timeout)
Sets the timeout argument passed to the IK solver.
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.
IKConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, unsigned int seed)
Constructor.
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...
const kinematic_constraints::OrientationConstraintPtr & getOrientationConstraint() const
Gets the orientation constraint associated with this sampler.
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.
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
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.
JointConstraintSampler is a class that allows the sampling of joints in a particular group of the rob...
std::vector< unsigned int > uindex_
The index of the unbounded joints in the joint state vector.
JointConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, unsigned int seed)
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.
JointConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
std::size_t getUnconstrainedJointCount() const
Gets the number of unconstrained joints - joint that have no additional bound beyond the joint limits...
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.
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
std::size_t getConstrainedJointCount() const
Gets the number of constrained joints - joints that have an additional bound beyond the joint limits.
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.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
MOVEIT_CLASS_FORWARD(ConstraintSampler)
Vec3fX< details::Vec3Data< double > > Vector3d
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 ...