Public Member Functions | Protected Member Functions | Protected Attributes
constraint_samplers::IKConstraintSampler Class Reference

A class that allows the sampling of IK constraints. More...

#include <default_constraint_samplers.h>

Inheritance diagram for constraint_samplers::IKConstraintSampler:
Inheritance graph
[legend]

List of all members.

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.
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::JointStateGroup *jsg, const robot_state::RobotState &reference_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::JointStateGroup *jsg, const robot_state::RobotState &ks, unsigned int max_attempts)
 Produces an IK sample, putting the result in the JointStateGroup.
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::JointStateGroup *jsg, 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::JointStateGroup *jsg, const robot_state::RobotState &ks, unsigned int max_attempts, bool project)

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.

Detailed Description

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 283 of file default_constraint_samplers.h.


Constructor & Destructor Documentation

constraint_samplers::IKConstraintSampler::IKConstraintSampler ( const planning_scene::PlanningSceneConstPtr scene,
const std::string &  group_name 
) [inline]

Constructor.

Parameters:
[in]sceneThe planning scene used to check the constraint
[in]group_nameThe 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 297 of file default_constraint_samplers.h.


Member Function Documentation

bool constraint_samplers::IKConstraintSampler::callIK ( const geometry_msgs::Pose &  ik_query,
const kinematics::KinematicsBase::IKCallbackFn adapted_ik_validity_callback,
double  timeout,
robot_state::JointStateGroup jsg,
bool  use_as_seed 
) [protected]

Actually calls IK on the given pose, generating a random seed state.

Parameters:
ik_queryThe pose for solving IK, assumed to be for the tip frame in the base frame
timeoutThe timeout for the IK search
jsgThe joint state group into which to place the solution
use_as_seedIf true, the state values in jsg are used as seed for the IK
Returns:
True if IK returns successfully with the timeout, and otherwise false.

Definition at line 533 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 225 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).

Parameters:
constrThe Constraint message
Returns:
True if some valid position and orientation constraints exist and the overloaded configuration function returns true. Otherwise, returns false.

Implements constraint_samplers::ConstraintSampler.

Definition at line 269 of file default_constraint_samplers.cpp.

Configures the Constraint given a IKSamplingPose.

This function performs the actual constraint configuration. It returns true if the following are true:

  • The IKSamplingPose has either a valid orientation or position constraint
  • The position and orientation constraints are specified for the same link
  • There is a valid IK solver instance for the indicated group. This will be only be the case if a group has a specific solver associated with it. For situations where the super-group doesn't have a solver, but all subgroups have solvers, then use the ConstraintSamplerManager.
  • The kinematic model has both the links associated with the IK solver's tip and base frames.
  • The link specified in the constraints is the tip link of the IK solver
Parameters:
[in]spThe variable that contains the position and orientation constraints
Returns:
True if all conditions are met and the group specified in the constructor is valid. Otherwise, false.

Definition at line 233 of file default_constraint_samplers.cpp.

Gets the timeout argument passed to the IK solver.

Returns:
The IK timeout

Definition at line 361 of file default_constraint_samplers.h.

Gets the link name associated with this sampler.

Returns:
The associated link name

Definition at line 315 of file default_constraint_samplers.cpp.

Gets the orientation constraint associated with this sampler.

Returns:
The orientation constraint, or an empty boost::shared_ptr if none has been specified

Definition at line 392 of file default_constraint_samplers.h.

Gets the position constraint associated with this sampler.

Returns:
The position constraint, or an empty boost::shared_ptr if none has been specified

Definition at line 382 of file default_constraint_samplers.h.

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.

Returns:
Returns the sum of the volumes of all constraint regions associated with the position and orientation constraints.

Definition at line 297 of file default_constraint_samplers.cpp.

Performs checks and sets various internal values associated with the IK solver.

Returns:
True if the IK solver exists and if it associated with the expected base frame and tip frames. Otherwise false.

Definition at line 322 of file default_constraint_samplers.cpp.

bool constraint_samplers::IKConstraintSampler::project ( robot_state::JointStateGroup jsg,
const robot_state::RobotState reference_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.

Parameters:
[out]jsgThe joint state group which specifies the state to be projected, according to the constraints
[in]reference_stateReference state that will be used to do transforms or perform other actions
[in]max_attemptsThe 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.
Returns:
True if a sample was successfully projected, false otherwise

Implements constraint_samplers::ConstraintSampler.

Definition at line 526 of file default_constraint_samplers.cpp.

bool constraint_samplers::IKConstraintSampler::sample ( robot_state::JointStateGroup jsg,
const robot_state::RobotState ks,
unsigned int  max_attempts 
) [virtual]

Produces an IK sample, putting the result in the JointStateGroup.

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.

Parameters:
jsgThe joint state group in question. Must match the group passed in the constructor or will return false.
ksA reference state that will be used for transforming the IK poses
max_attemptsThe number of attempts to both sample and try IK
Returns:
True if a valid sample pose was produced and valid IK found for that pose. Otherwise false.

Implements constraint_samplers::ConstraintSampler.

Definition at line 478 of file default_constraint_samplers.cpp.

bool constraint_samplers::IKConstraintSampler::sampleHelper ( robot_state::JointStateGroup jsg,
const robot_state::RobotState ks,
unsigned int  max_attempts,
bool  project 
) [protected]

Definition at line 483 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.

Parameters:
[out]posThe position component of the sample
[out]quatThe orientation component of the sample
[in]ksThe reference state used for performing transforms
[in]max_attemptsThe maximum attempts to try to sample - applies only to the position constraint
Returns:
True if a sample was successfully produced, otherwise false

Definition at line 361 of file default_constraint_samplers.cpp.

void constraint_samplers::IKConstraintSampler::setIKTimeout ( double  timeout) [inline]

Sets the timeout argument passed to the IK solver.

Parameters:
timeoutThe timeout argument that will be used in future IK calls

Definition at line 371 of file default_constraint_samplers.h.


Member Data Documentation

Holds the base from of the IK solver.

Definition at line 500 of file default_constraint_samplers.h.

Holds the timeout associated with IK.

Definition at line 499 of file default_constraint_samplers.h.

Holds the kinematics solver.

Definition at line 498 of file default_constraint_samplers.h.

Random generator used by the sampler.

Definition at line 496 of file default_constraint_samplers.h.

Holder for the pose used for sampling.

Definition at line 497 of file default_constraint_samplers.h.

True if the frame associated with the kinematic model is different than the base frame of the IK solver.

Definition at line 501 of file default_constraint_samplers.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:48