moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | List of all members
constraint_samplers::ConstraintSampler Class Referenceabstract

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]
Collaboration diagram for constraint_samplers::ConstraintSampler:
Collaboration graph
[legend]

Public Member Functions

 ConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
 Constructor. More...
 
virtual ~ConstraintSampler ()
 
virtual bool configure (const moveit_msgs::msg::Constraints &constr)=0
 Function for configuring a constraint sampler given a Constraints message. More...
 
const std::string & getGroupName () const
 Gets the group name set in the constructor. More...
 
const moveit::core::JointModelGroupgetJointModelGroup () const
 Gets the joint model group. More...
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene () const
 Gets the planning scene. 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 moveit::core::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...
 
void setGroupStateValidityCallback (const moveit::core::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...
 
bool sample (moveit::core::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 (moveit::core::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 (moveit::core::RobotState &state, const moveit::core::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...
 
virtual bool sample (moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts)=0
 Samples given the constraints, populating state. This function allows the parameter max_attempts to be set. 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 getVerbose () const
 Check if the sampler is set to verbose mode. More...
 
virtual void setVerbose (bool verbose)
 Enable/disable verbose mode for sampler. More...
 
virtual const std::string & getName () const =0
 Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. More...
 

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. More...
 

Protected Member Functions

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

Protected Attributes

bool is_valid_
 Holds the value for validity. More...
 
planning_scene::PlanningSceneConstPtr scene_
 Holds the planning scene. More...
 
const moveit::core::JointModelGroup *const jmg_
 Holds the joint model group associated with this constraint. More...
 
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...
 
moveit::core::GroupStateValidityCallbackFn group_state_validity_callback_
 Holds the callback for state validity. More...
 
bool verbose_
 True if verbosity is on. More...
 

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 59 of file constraint_sampler.h.

Constructor & Destructor Documentation

◆ ConstraintSampler()

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 52 of file constraint_sampler.cpp.

Here is the call graph for this function:

◆ ~ConstraintSampler()

virtual constraint_samplers::ConstraintSampler::~ConstraintSampler ( )
inlinevirtual

Definition at line 77 of file constraint_sampler.h.

Member Function Documentation

◆ clear()

void constraint_samplers::ConstraintSampler::clear ( )
protectedvirtual

Clears all data from the constraint.

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

Definition at line 62 of file constraint_sampler.cpp.

Here is the caller graph for this function:

◆ configure()

virtual bool constraint_samplers::ConstraintSampler::configure ( const moveit_msgs::msg::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::JointConstraintSampler, and constraint_samplers::UnionConstraintSampler.

◆ getFrameDependency()

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 134 of file constraint_sampler.h.

◆ getGroupName()

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

Gets the group name set in the constructor.

Returns
The group name

Definition at line 96 of file constraint_sampler.h.

Here is the call graph for this function:

◆ getGroupStateValidityCallback()

const moveit::core::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 143 of file constraint_sampler.h.

◆ getJointModelGroup()

const moveit::core::JointModelGroup* constraint_samplers::ConstraintSampler::getJointModelGroup ( ) const
inline

Gets the joint model group.

Returns
The joint model group

Definition at line 107 of file constraint_sampler.h.

Here is the caller graph for this function:

◆ getName()

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::UnionConstraintSampler, constraint_samplers::IKConstraintSampler, and constraint_samplers::JointConstraintSampler.

◆ getPlanningScene()

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 118 of file constraint_sampler.h.

◆ getVerbose()

bool constraint_samplers::ConstraintSampler::getVerbose ( ) const
inline

Check if the sampler is set to verbose mode.

Definition at line 232 of file constraint_sampler.h.

◆ isValid()

bool constraint_samplers::ConstraintSampler::isValid ( ) const
inline

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 226 of file constraint_sampler.h.

Here is the caller graph for this function:

◆ sample() [1/4]

bool constraint_samplers::ConstraintSampler::sample ( moveit::core::RobotState state)
inline

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 169 of file constraint_sampler.h.

Here is the caller graph for this function:

◆ sample() [2/4]

bool constraint_samplers::ConstraintSampler::sample ( moveit::core::RobotState state,
const moveit::core::RobotState reference_state 
)
inline

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 200 of file constraint_sampler.h.

Here is the call graph for this function:

◆ sample() [3/4]

virtual bool constraint_samplers::ConstraintSampler::sample ( moveit::core::RobotState state,
const moveit::core::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::UnionConstraintSampler, constraint_samplers::IKConstraintSampler, and constraint_samplers::JointConstraintSampler.

◆ sample() [4/4]

bool constraint_samplers::ConstraintSampler::sample ( moveit::core::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 185 of file constraint_sampler.h.

Here is the call graph for this function:

◆ setGroupStateValidityCallback()

void constraint_samplers::ConstraintSampler::setGroupStateValidityCallback ( const moveit::core::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 154 of file constraint_sampler.h.

◆ setVerbose()

virtual void constraint_samplers::ConstraintSampler::setVerbose ( bool  verbose)
inlinevirtual

Enable/disable verbose mode for sampler.

Definition at line 238 of file constraint_sampler.h.

Member Data Documentation

◆ DEFAULT_MAX_SAMPLING_ATTEMPTS

const unsigned int constraint_samplers::ConstraintSampler::DEFAULT_MAX_SAMPLING_ATTEMPTS = 2
static

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 64 of file constraint_sampler.h.

◆ frame_depends_

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 264 of file constraint_sampler.h.

◆ group_state_validity_callback_

moveit::core::GroupStateValidityCallbackFn constraint_samplers::ConstraintSampler::group_state_validity_callback_
protected

Holds the callback for state validity.

Definition at line 266 of file constraint_sampler.h.

◆ is_valid_

bool constraint_samplers::ConstraintSampler::is_valid_
protected

Holds the value for validity.

Definition at line 257 of file constraint_sampler.h.

◆ jmg_

const moveit::core::JointModelGroup* const constraint_samplers::ConstraintSampler::jmg_
protected

Holds the joint model group associated with this constraint.

Definition at line 262 of file constraint_sampler.h.

◆ scene_

planning_scene::PlanningSceneConstPtr constraint_samplers::ConstraintSampler::scene_
protected

Holds the planning scene.

Definition at line 260 of file constraint_sampler.h.

◆ verbose_

bool constraint_samplers::ConstraintSampler::verbose_
protected

True if verbosity is on.

Definition at line 267 of file constraint_sampler.h.


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