A class that allows the sampling of IK constraints. More...
#include <default_constraint_samplers.h>
Public Member Functions | |
virtual bool | configure (const moveit_msgs::Constraints &constr) |
Configures the IK constraint given a constraints message. | |
bool | configure (const IKSamplingPose &sp) |
Configures the Constraint given a IKSamplingPose. | |
double | getIKTimeout () const |
Gets the timeout argument passed to the IK solver. | |
const std::string & | getLinkName () const |
Gets the link name associated with this sampler. | |
virtual const std::string & | getName () const |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. | |
const boost::shared_ptr < kinematic_constraints::OrientationConstraint > & | getOrientationConstraint () const |
Gets the orientation constraint associated with this sampler. | |
const boost::shared_ptr < kinematic_constraints::PositionConstraint > & | getPositionConstraint () const |
Gets the position constraint associated with this sampler. | |
double | getSamplingVolume () const |
Gets the volume associated with the position and orientation constraints. | |
IKConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name) | |
Constructor. | |
virtual bool | project (robot_state::RobotState &state, unsigned int max_attempts) |
Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set. | |
virtual bool | sample (robot_state::RobotState &state, const robot_state::RobotState &reference_state, unsigned int max_attempts) |
Produces an IK sample. | |
bool | samplePose (Eigen::Vector3d &pos, Eigen::Quaterniond &quat, const robot_state::RobotState &ks, unsigned int max_attempts) |
Returns a pose that falls within the constraint regions. | |
void | setIKTimeout (double timeout) |
Sets the timeout argument passed to the IK solver. | |
Protected Member Functions | |
bool | callIK (const geometry_msgs::Pose &ik_query, const kinematics::KinematicsBase::IKCallbackFn &adapted_ik_validity_callback, double timeout, robot_state::RobotState &state, bool use_as_seed) |
Actually calls IK on the given pose, generating a random seed state. | |
virtual void | clear () |
Clears all data from the constraint. | |
bool | loadIKSolver () |
Performs checks and sets various internal values associated with the IK solver. | |
bool | sampleHelper (robot_state::RobotState &state, const robot_state::RobotState &reference_state, unsigned int max_attempts, bool project) |
bool | validate (robot_state::RobotState &state) const |
Protected Attributes | |
std::string | ik_frame_ |
Holds the base from of the IK solver. | |
double | ik_timeout_ |
Holds the timeout associated with IK. | |
kinematics::KinematicsBaseConstPtr | kb_ |
Holds the kinematics solver. | |
random_numbers::RandomNumberGenerator | random_number_generator_ |
Random generator used by the sampler. | |
IKSamplingPose | sampling_pose_ |
Holder for the pose used for sampling. | |
bool | transform_ik_ |
True if the frame associated with the kinematic model is different than the base frame of the IK solver. |
A class that allows the sampling of IK constraints.
An IK constraint can have a position constraint, and orientation constraint, or both. The constraint will attempt to sample a pose that adheres to the constraint, and then solves IK for that pose.
Definition at line 293 of file default_constraint_samplers.h.
constraint_samplers::IKConstraintSampler::IKConstraintSampler | ( | const planning_scene::PlanningSceneConstPtr & | scene, |
const std::string & | group_name | ||
) | [inline] |
Constructor.
[in] | scene | The planning scene used to check the constraint |
[in] | group_name | The group name associated with the constraint. Will be invalid if no group name is passed in or the joint model group cannot be found in the kinematic model |
Definition at line 307 of file default_constraint_samplers.h.
bool constraint_samplers::IKConstraintSampler::callIK | ( | const geometry_msgs::Pose & | ik_query, |
const kinematics::KinematicsBase::IKCallbackFn & | adapted_ik_validity_callback, | ||
double | timeout, | ||
robot_state::RobotState & | state, | ||
bool | use_as_seed | ||
) | [protected] |
Actually calls IK on the given pose, generating a random seed state.
ik_query | The pose for solving IK, assumed to be for the tip frame in the base frame |
timeout | The timeout for the IK search |
jsg | The joint state group into which to place the solution |
use_as_seed | If true, the state values in jsg are used as seed for the IK |
Definition at line 544 of file default_constraint_samplers.cpp.
void constraint_samplers::IKConstraintSampler::clear | ( | ) | [protected, virtual] |
Clears all data from the constraint.
Reimplemented from constraint_samplers::ConstraintSampler.
Definition at line 217 of file default_constraint_samplers.cpp.
bool constraint_samplers::IKConstraintSampler::configure | ( | const moveit_msgs::Constraints & | constr | ) | [virtual] |
Configures the IK constraint given a constraints message.
If the constraints message contains both orientation constraints and positions constraints, the function iterates through each potential pair until it finds a pair of position orientation constraints that lead to valid configuration of kinematic constraints. It creates an IKSamplingPose from these and calls configure(const IKSamplingPose &sp). If no pair leads to both having valid configuration, it will attempt to iterate through the position constraints in the Constraints message, calling configure(const IKSamplingPose &sp) on the resulting IKSamplingPose. Finally, if no valid position constraints exist it will attempt the same procedure with the orientation constraints. If no valid position or orientation constraints exist, it will return false. For more information, see the docs for configure(const IKSamplingPose &sp).
constr | The Constraint message |
Implements constraint_samplers::ConstraintSampler.
Definition at line 261 of file default_constraint_samplers.cpp.
bool constraint_samplers::IKConstraintSampler::configure | ( | const IKSamplingPose & | sp | ) |
Configures the Constraint given a IKSamplingPose.
This function performs the actual constraint configuration. It returns true if the following are true:
[in] | sp | The variable that contains the position and orientation constraints |
Definition at line 225 of file default_constraint_samplers.cpp.
double constraint_samplers::IKConstraintSampler::getIKTimeout | ( | ) | const [inline] |
Gets the timeout argument passed to the IK solver.
Definition at line 371 of file default_constraint_samplers.h.
const std::string & constraint_samplers::IKConstraintSampler::getLinkName | ( | ) | const |
Gets the link name associated with this sampler.
Definition at line 307 of file default_constraint_samplers.cpp.
virtual const std::string& constraint_samplers::IKConstraintSampler::getName | ( | ) | const [inline, virtual] |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
Implements constraint_samplers::ConstraintSampler.
Definition at line 486 of file default_constraint_samplers.h.
const boost::shared_ptr<kinematic_constraints::OrientationConstraint>& constraint_samplers::IKConstraintSampler::getOrientationConstraint | ( | ) | const [inline] |
Gets the orientation constraint associated with this sampler.
Definition at line 402 of file default_constraint_samplers.h.
const boost::shared_ptr<kinematic_constraints::PositionConstraint>& constraint_samplers::IKConstraintSampler::getPositionConstraint | ( | ) | const [inline] |
Gets the position constraint associated with this sampler.
Definition at line 392 of file default_constraint_samplers.h.
double constraint_samplers::IKConstraintSampler::getSamplingVolume | ( | ) | const |
Gets the volume associated with the position and orientation constraints.
This function computes the volume of the sampling constraint. The volume associated with the position constraint is either the product of the volume of all position constraint regions, or 1.0 otherwise. The volume associated with the orientation constraint is the product of all the axis tolerances, or 1.0 otherwise. If both are specified, the product of the volumes is returned.
Definition at line 289 of file default_constraint_samplers.cpp.
bool constraint_samplers::IKConstraintSampler::loadIKSolver | ( | ) | [protected] |
Performs checks and sets various internal values associated with the IK solver.
Definition at line 314 of file default_constraint_samplers.cpp.
bool constraint_samplers::IKConstraintSampler::project | ( | robot_state::RobotState & | state, |
unsigned int | max_attempts | ||
) | [virtual] |
Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set.
[out] | state | The state into which the values will be placed. Only values for the group are written. |
[in] | max_attempts | The maximum number of times to attempt to draw a sample. If no sample has been drawn in this number of attempts, false will be returned. |
Implements constraint_samplers::ConstraintSampler.
Definition at line 531 of file default_constraint_samplers.cpp.
bool constraint_samplers::IKConstraintSampler::sample | ( | robot_state::RobotState & | state, |
const robot_state::RobotState & | reference_state, | ||
unsigned int | max_attempts | ||
) | [virtual] |
Produces an IK sample.
This function first calls the samplePose function to produce a position and orientation in the constraint region. It then calls IK on that pose. If a pose that satisfies the constraints can be determined, and IK returns a solution for that pose, then the joint values associated with the joint group will be populated with the results of the IK, and the function will return true. The function will attempt to sample a pose up to max_attempts number of times, and then call IK on that value. If IK is not successful, it will repeat the pose sample and IK procedure max_attempt times. If in any iteration a valid pose cannot be sample within max_attempts time, it will return false.
jsg | The joint state group in question. Must match the group passed in the constructor or will return false. |
ks | A reference state that will be used for transforming the IK poses |
max_attempts | The number of attempts to both sample and try IK |
Implements constraint_samplers::ConstraintSampler.
Definition at line 487 of file default_constraint_samplers.cpp.
bool constraint_samplers::IKConstraintSampler::sampleHelper | ( | robot_state::RobotState & | state, |
const robot_state::RobotState & | reference_state, | ||
unsigned int | max_attempts, | ||
bool | project | ||
) | [protected] |
Definition at line 492 of file default_constraint_samplers.cpp.
bool constraint_samplers::IKConstraintSampler::samplePose | ( | Eigen::Vector3d & | pos, |
Eigen::Quaterniond & | quat, | ||
const robot_state::RobotState & | ks, | ||
unsigned int | max_attempts | ||
) |
Returns a pose that falls within the constraint regions.
If a position constraint is specified, then a position is produced by selecting a random region among the constraint regions and taking a sample in that region. If no region is valid the function returns false. If no position constraint is specified, a position is produced by assigning a random valid value to each group joint, performing forward kinematics, and taking the resulting pose. If an orientation constraint is specified, then an quaternion is produced by sampling a difference value within the axis tolerances and applying the difference rotation to the orientation constraint target. Otherwise, a random quaternion is produced.
[out] | pos | The position component of the sample |
[out] | quat | The orientation component of the sample |
[in] | ks | The reference state used for performing transforms |
[in] | max_attempts | The maximum attempts to try to sample - applies only to the position constraint |
Definition at line 379 of file default_constraint_samplers.cpp.
void constraint_samplers::IKConstraintSampler::setIKTimeout | ( | double | timeout | ) | [inline] |
Sets the timeout argument passed to the IK solver.
timeout | The timeout argument that will be used in future IK calls |
Definition at line 381 of file default_constraint_samplers.h.
bool constraint_samplers::IKConstraintSampler::validate | ( | robot_state::RobotState & | state | ) | const [protected] |
Definition at line 537 of file default_constraint_samplers.cpp.
std::string constraint_samplers::IKConstraintSampler::ik_frame_ [protected] |
Holds the base from of the IK solver.
Definition at line 522 of file default_constraint_samplers.h.
double constraint_samplers::IKConstraintSampler::ik_timeout_ [protected] |
Holds the timeout associated with IK.
Definition at line 521 of file default_constraint_samplers.h.
Holds the kinematics solver.
Definition at line 520 of file default_constraint_samplers.h.
random_numbers::RandomNumberGenerator constraint_samplers::IKConstraintSampler::random_number_generator_ [protected] |
Random generator used by the sampler.
Definition at line 518 of file default_constraint_samplers.h.
Holder for the pose used for sampling.
Definition at line 519 of file default_constraint_samplers.h.
bool constraint_samplers::IKConstraintSampler::transform_ik_ [protected] |
True if the frame associated with the kinematic model is different than the base frame of the IK solver.
Definition at line 523 of file default_constraint_samplers.h.