Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
constraint_samplers::JointConstraintSampler Class Reference

JointConstraintSampler is a class that allows the sampling of joints in a particular group of the robot, subject to a set of individual joint constraints. More...

#include <default_constraint_samplers.h>

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

Classes

struct  JointInfo
 An internal structure used for maintaining constraints on a particular joint. More...
 

Public Member Functions

virtual bool configure (const moveit_msgs::Constraints &constr)
 Configures a joint constraint given a Constraints message. More...
 
bool configure (const std::vector< kinematic_constraints::JointConstraint > &jc)
 Configures a joint constraint given a vector of constraints. More...
 
std::size_t getConstrainedJointCount () const
 Gets the number of constrained joints - joints that have an additional bound beyond the joint limits. More...
 
virtual const std::string & getName () const
 Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. More...
 
std::size_t getUnconstrainedJointCount () const
 Gets the number of unconstrained joints - joint that have no additional bound beyond the joint limits. More...
 
 JointConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
 
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. More...
 
virtual bool sample (robot_state::RobotState &state, const robot_state::RobotState &ks, unsigned int max_attempts)
 Samples given the constraints, populating state. This function allows the parameter max_attempts to be set. More...
 
- Public Member Functions inherited from constraint_samplers::ConstraintSampler
 ConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
 Constructor. More...
 
const std::vector< std::string > & getFrameDependency () const
 Return the names of the mobile frames whose pose is needed when sample() is called. More...
 
const std::string & getGroupName () const
 Gets the group name set in the constructor. More...
 
const robot_state::GroupStateValidityCallbackFngetGroupStateValidityCallback () const
 Gets the callback used to determine state validity during sampling. The sampler will attempt to satisfy this constraint if possible, but there is no guarantee. More...
 
const robot_model::JointModelGroupgetJointModelGroup () const
 Gets the joint model group. More...
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene () const
 Gets the planning scene. More...
 
bool getVerbose () const
 Check if the sampler is set to verbose mode. More...
 
bool isValid () const
 Returns whether or not the constraint sampler is valid or not. To be valid, the joint model group must be available in the kinematic model and configure() must have successfully been called. More...
 
bool project (robot_state::RobotState &state)
 Project a sample given the constraints, updating the joint state group. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to project the sample. More...
 
bool sample (robot_state::RobotState &state)
 Samples given the constraints, populating state. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to take a sample. More...
 
bool sample (robot_state::RobotState &state, unsigned int max_attempts)
 Samples given the constraints, populating state. This function allows the parameter max_attempts to be set. More...
 
bool sample (robot_state::RobotState &state, const robot_state::RobotState &reference_state)
 Samples given the constraints, populating state. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to take a sample. More...
 
void setGroupStateValidityCallback (const robot_state::GroupStateValidityCallbackFn &callback)
 Sets the callback used to determine the state validity during sampling. The sampler will attempt to satisfy this constraint if possible, but there is no guarantee. More...
 
virtual void setVerbose (bool verbose)
 Enable/disable verbose mode for sampler. More...
 
virtual ~ConstraintSampler ()
 

Protected Member Functions

virtual void clear ()
 Clears all data from the constraint. More...
 

Protected Attributes

std::vector< JointInfobounds_
 The bounds for any joint with bounds that are more restrictive than the joint limits. More...
 
random_numbers::RandomNumberGenerator random_number_generator_
 Random number generator used to sample. More...
 
std::vector< unsigned int > uindex_
 The index of the unbounded joints in the joint state vector. More...
 
std::vector< const robot_model::JointModel * > unbounded_
 The joints that are not bounded except by joint limits. More...
 
std::vector< double > values_
 Values associated with this group to avoid continuously reallocating. More...
 
- Protected Attributes inherited from constraint_samplers::ConstraintSampler
std::vector< std::string > frame_depends_
 Holds the set of frames that must exist in the reference state to allow samples to be drawn. More...
 
robot_state::GroupStateValidityCallbackFn group_state_validity_callback_
 Holds the callback for state validity. More...
 
bool is_valid_
 Holds the value for validity. More...
 
const robot_model::JointModelGroup *const jmg_
 Holds the joint model group associated with this constraint. More...
 
planning_scene::PlanningSceneConstPtr scene_
 Holds the planning scene. More...
 
bool verbose_
 True if verbosity is on. More...
 

Additional Inherited Members

- Static Public Attributes inherited from constraint_samplers::ConstraintSampler
static const unsigned int DEFAULT_MAX_SAMPLING_ATTEMPTS = 2
 The default value associated with a sampling request. By default if a valid sample cannot be produced in this many attempts, it returns with no sample. More...
 

Detailed Description

JointConstraintSampler is a class that allows the sampling of joints in a particular group of the robot, subject to a set of individual joint constraints.

The set of individual joint constraint reduce the allowable bounds used in the sampling. Unconstrained values will be sampled within their limits.

Definition at line 57 of file default_constraint_samplers.h.

Constructor & Destructor Documentation

constraint_samplers::JointConstraintSampler::JointConstraintSampler ( 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 70 of file default_constraint_samplers.h.

Member Function Documentation

void constraint_samplers::JointConstraintSampler::clear ( )
protectedvirtual

Clears all data from the constraint.

Reimplemented from constraint_samplers::ConstraintSampler.

Definition at line 185 of file default_constraint_samplers.cpp.

bool constraint_samplers::JointConstraintSampler::configure ( const moveit_msgs::Constraints &  constr)
virtual

Configures a joint constraint given a Constraints message.

If more than one constraint for a particular joint is specified, the most restrictive set of bounds will be used (highest minimum value, lowest maximum value). For the configuration to be successful, the following condition must be met, in addition to the conditions specified in configure(const std::vector<kinematic_constraints::JointConstraint> &jc) :

  • The Constraints message must contain one or more valid joint constraints (where validity is judged by the ability to configure a JointConstraint)
Parameters
[in]constrThe message containing the constraints
Returns
True if the conditions are met, otherwise false

Implements constraint_samplers::ConstraintSampler.

Definition at line 45 of file default_constraint_samplers.cpp.

bool constraint_samplers::JointConstraintSampler::configure ( const std::vector< kinematic_constraints::JointConstraint > &  jc)

Configures a joint constraint given a vector of constraints.

If more than one constraint for a particular joint is specified, the most restrictive set of bounds will be used (highest minimum value, lowest_maximum value. For the configuration to be successful, the following conditions must be met:

  • The vector must contain one or more valid, enabled joint constraints
  • At least one constraint must reference a joint in the indicated group. If no additional bounds exist for this group, then RobotState::setToRandomPositions() can be used to generate a sample independently from the constraint_samplers infrastructure.
  • The constraints must allow a sampleable region for all joints, where the most restrictive minimum bound is less than the most restrictive maximum bound
Parameters
[in]jcThe vector of joint constraints
Returns
True if the conditions are met, otherwise false

Definition at line 59 of file default_constraint_samplers.cpp.

std::size_t constraint_samplers::JointConstraintSampler::getConstrainedJointCount ( ) const
inline

Gets the number of constrained joints - joints that have an additional bound beyond the joint limits.

Returns
The number of constrained joints.

Definition at line 131 of file default_constraint_samplers.h.

virtual const std::string& constraint_samplers::JointConstraintSampler::getName ( ) const
inlinevirtual

Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.

Returns
string of name

Implements constraint_samplers::ConstraintSampler.

Definition at line 152 of file default_constraint_samplers.h.

std::size_t constraint_samplers::JointConstraintSampler::getUnconstrainedJointCount ( ) const
inline

Gets the number of unconstrained joints - joint that have no additional bound beyond the joint limits.

Returns
The number of unconstrained joints.

Definition at line 142 of file default_constraint_samplers.h.

bool constraint_samplers::JointConstraintSampler::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.

Parameters
[out]stateThe state into which the values will be placed. Only values for the group are written.
[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 180 of file default_constraint_samplers.cpp.

bool constraint_samplers::JointConstraintSampler::sample ( robot_state::RobotState state,
const robot_state::RobotState reference_state,
unsigned int  max_attempts 
)
virtual

Samples given the constraints, populating state. This function allows the parameter max_attempts to be set.

Parameters
[out]stateThe state into which the values will be placed. Only values for the group are written.
[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 taken, false otherwise

Implements constraint_samplers::ConstraintSampler.

Definition at line 150 of file default_constraint_samplers.cpp.

Member Data Documentation

std::vector<JointInfo> constraint_samplers::JointConstraintSampler::bounds_
protected

The bounds for any joint with bounds that are more restrictive than the joint limits.

Definition at line 196 of file default_constraint_samplers.h.

random_numbers::RandomNumberGenerator constraint_samplers::JointConstraintSampler::random_number_generator_
protected

Random number generator used to sample.

Definition at line 195 of file default_constraint_samplers.h.

std::vector<unsigned int> constraint_samplers::JointConstraintSampler::uindex_
protected

The index of the unbounded joints in the joint state vector.

Definition at line 201 of file default_constraint_samplers.h.

std::vector<const robot_model::JointModel*> constraint_samplers::JointConstraintSampler::unbounded_
protected

The joints that are not bounded except by joint limits.

Definition at line 199 of file default_constraint_samplers.h.

std::vector<double> constraint_samplers::JointConstraintSampler::values_
protected

Values associated with this group to avoid continuously reallocating.

Definition at line 202 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 Sun Oct 18 2020 13:16:34