Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes
constraint_samplers::ConstraintSampler Class Reference

ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a particular group of a robot. More...

#include <constraint_sampler.h>

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

List of all members.

Public Member Functions

virtual bool configure (const moveit_msgs::Constraints &constr)=0
 Function for configuring a constraint sampler given a Constraints message.
 ConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
 Constructor.
const std::vector< std::string > & getFrameDependency () const
 Return the names of the mobile frames whose pose is needed when sample() is called.
const std::string & getGroupName () const
 Gets the group name set in the constructor.
const
robot_state::GroupStateValidityCallbackFn & 
getGroupStateValidityCallback () 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.
const
robot_model::JointModelGroup
getJointModelGroup () const
 Gets the joint model group.
virtual const std::string & getName () const =0
 Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
const
planning_scene::PlanningSceneConstPtr & 
getPlanningScene () const
 Gets the planning scene.
bool getVerbose () const
 Check if the sampler is set to verbose mode.
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.
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.
virtual bool project (robot_state::RobotState &state, unsigned int max_attempts)=0
 Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set.
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.
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.
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.
virtual bool sample (robot_state::RobotState &state, const robot_state::RobotState &reference_state, unsigned int max_attempts)=0
 Samples given the constraints, populating state. This function allows the parameter max_attempts to be set.
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.
virtual void setVerbose (bool verbose)
 Enable/disable verbose mode for sampler.
virtual ~ConstraintSampler ()

Static Public Attributes

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.

Protected Member Functions

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

Protected Attributes

std::vector< std::string > frame_depends_
 Holds the set of frames that must exist in the reference state to allow samples to be drawn.
robot_state::GroupStateValidityCallbackFn group_state_validity_callback_
 Holds the callback for state validity.
bool is_valid_
 Holds the value for validity.
const
robot_model::JointModelGroup
jmg_
 Holds the joint model group associated with this constraint.
planning_scene::PlanningSceneConstPtr scene_
 Holds the planning scene.
bool verbose_
 True if verbosity is on.

Detailed Description

ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a particular group of a robot.

Definition at line 60 of file constraint_sampler.h.


Constructor & Destructor Documentation

constraint_samplers::ConstraintSampler::ConstraintSampler ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  group_name 
)

Constructor.

Parameters:
[in]sceneThe planning scene that will be used for constraint checking
[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 39 of file constraint_sampler.cpp.

Definition at line 78 of file constraint_sampler.h.


Member Function Documentation

void constraint_samplers::ConstraintSampler::clear ( ) [protected, virtual]

Clears all data from the constraint.

Reimplemented in constraint_samplers::IKConstraintSampler, and constraint_samplers::JointConstraintSampler.

Definition at line 50 of file constraint_sampler.cpp.

virtual bool constraint_samplers::ConstraintSampler::configure ( const moveit_msgs::Constraints &  constr) [pure virtual]

Function for configuring a constraint sampler given a Constraints message.

Parameters:
[in]constrThe constraints from which to construct a sampler
Returns:
True if the configuration is successful. If true, isValid should also true. If false, isValid should return false

Implemented in constraint_samplers::IKConstraintSampler, constraint_samplers::UnionConstraintSampler, and constraint_samplers::JointConstraintSampler.

const std::vector<std::string>& constraint_samplers::ConstraintSampler::getFrameDependency ( ) const [inline]

Return the names of the mobile frames whose pose is needed when sample() is called.

Mobile frames mean frames other than the reference frame of the kinematic model. These frames may move when the kinematic state changes. Frame dependency can help determine an ordering from a set of constraint samplers - for more information see the derived class documentation for UnionConstraintSampler.

Returns:
The list of names whose pose is needed

Definition at line 135 of file constraint_sampler.h.

const std::string& constraint_samplers::ConstraintSampler::getGroupName ( ) const [inline]

Gets the group name set in the constructor.

Returns:
The group name

Definition at line 97 of file constraint_sampler.h.

const robot_state::GroupStateValidityCallbackFn& constraint_samplers::ConstraintSampler::getGroupStateValidityCallback ( ) const [inline]

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.

Definition at line 144 of file constraint_sampler.h.

Gets the joint model group.

Returns:
The joint model group

Definition at line 108 of file constraint_sampler.h.

virtual const std::string& constraint_samplers::ConstraintSampler::getName ( ) const [pure virtual]

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

Returns:
string of name

Implemented in constraint_samplers::IKConstraintSampler, constraint_samplers::UnionConstraintSampler, and constraint_samplers::JointConstraintSampler.

const planning_scene::PlanningSceneConstPtr& constraint_samplers::ConstraintSampler::getPlanningScene ( ) const [inline]

Gets the planning scene.

Returns:
The planning scene as a const ptr

Definition at line 119 of file constraint_sampler.h.

Check if the sampler is set to verbose mode.

Definition at line 261 of file constraint_sampler.h.

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.

Returns:
True if the sampler is valid, and otherwise false.

Definition at line 255 of file constraint_sampler.h.

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.

Parameters:
stateThe state which specifies the state to be projected, according to the constraints. Only values for the group are written. The same state is used as reference if needed.
Returns:
True if a sample was successfully projected, false otherwise

Definition at line 216 of file constraint_sampler.h.

virtual bool constraint_samplers::ConstraintSampler::project ( robot_state::RobotState state,
unsigned int  max_attempts 
) [pure 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

Implemented in constraint_samplers::IKConstraintSampler, constraint_samplers::UnionConstraintSampler, and constraint_samplers::JointConstraintSampler.

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.

Parameters:
stateThe state into which the values will be placed. Only values for the group are written. The same state is used as reference if needed.
Returns:
True if a sample was successfully taken, false otherwise

Definition at line 170 of file constraint_sampler.h.

bool constraint_samplers::ConstraintSampler::sample ( robot_state::RobotState state,
unsigned int  max_attempts 
) [inline]

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

Parameters:
stateThe state into which the values will be placed. Only values for the group are written. The same state is used as reference if needed.
[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

Definition at line 186 of file constraint_sampler.h.

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.

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
Returns:
True if a sample was successfully taken, false otherwise

Definition at line 201 of file constraint_sampler.h.

virtual bool constraint_samplers::ConstraintSampler::sample ( robot_state::RobotState state,
const robot_state::RobotState reference_state,
unsigned int  max_attempts 
) [pure 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

Implemented in constraint_samplers::IKConstraintSampler, constraint_samplers::UnionConstraintSampler, and constraint_samplers::JointConstraintSampler.

void constraint_samplers::ConstraintSampler::setGroupStateValidityCallback ( const robot_state::GroupStateValidityCallbackFn &  callback) [inline]

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.

Parameters:
callbackThe callback to set

Definition at line 155 of file constraint_sampler.h.

virtual void constraint_samplers::ConstraintSampler::setVerbose ( bool  verbose) [inline, virtual]

Enable/disable verbose mode for sampler.

Definition at line 267 of file constraint_sampler.h.


Member Data Documentation

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.

Definition at line 65 of file constraint_sampler.h.

std::vector<std::string> constraint_samplers::ConstraintSampler::frame_depends_ [protected]

Holds the set of frames that must exist in the reference state to allow samples to be drawn.

Definition at line 291 of file constraint_sampler.h.

robot_state::GroupStateValidityCallbackFn constraint_samplers::ConstraintSampler::group_state_validity_callback_ [protected]

Holds the callback for state validity.

Definition at line 292 of file constraint_sampler.h.

Holds the value for validity.

Definition at line 286 of file constraint_sampler.h.

Holds the joint model group associated with this constraint.

Definition at line 289 of file constraint_sampler.h.

planning_scene::PlanningSceneConstPtr constraint_samplers::ConstraintSampler::scene_ [protected]

Holds the planning scene.

Definition at line 288 of file constraint_sampler.h.

True if verbosity is on.

Definition at line 294 of file constraint_sampler.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:50