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

This class exists as a union of constraint samplers. It contains a vector of constraint samplers, and will sample from each of them. More...

#include <union_constraint_sampler.h>

Inheritance diagram for constraint_samplers::UnionConstraintSampler:
Inheritance graph
[legend]
Collaboration diagram for constraint_samplers::UnionConstraintSampler:
Collaboration graph
[legend]

Public Member Functions

 UnionConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::vector< ConstraintSamplerPtr > &samplers)
 Constructor, which will re-order its internal list of samplers on construction. More...
 
const std::vector< ConstraintSamplerPtr > & getSamplers () const
 Gets the sorted internal list of constraint samplers. More...
 
bool configure (const moveit_msgs::msg::Constraints &) override
 No-op, as the union constraint sampler is for already configured samplers. More...
 
virtual bool canService (const moveit_msgs::msg::Constraints &) const
 No-op, as the union constraint sampler can act on anything. More...
 
bool sample (moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
 Produces a sample from all configured samplers. More...
 
const std::string & getName () const override
 Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. More...
 
- Public Member Functions inherited from constraint_samplers::ConstraintSampler
 ConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
 Constructor. More...
 
virtual ~ConstraintSampler ()
 
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...
 
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...
 

Protected Attributes

std::vector< ConstraintSamplerPtr > samplers_
 Holder for sorted internal list of samplers. More...
 
- Protected Attributes inherited from constraint_samplers::ConstraintSampler
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...
 

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...
 
- Protected Member Functions inherited from constraint_samplers::ConstraintSampler
virtual void clear ()
 Clears all data from the constraint. More...
 

Detailed Description

This class exists as a union of constraint samplers. It contains a vector of constraint samplers, and will sample from each of them.

When asked to sample it will call the samplers in a sorted order that samples more general groups - like a robot's whole body - before sampling more specific groups, such as a robot's arm. Member samplers can operate on all or part of a joint state group vector, with later samplers potentially overwriting previous samplers.

Definition at line 57 of file union_constraint_sampler.h.

Constructor & Destructor Documentation

◆ UnionConstraintSampler()

constraint_samplers::UnionConstraintSampler::UnionConstraintSampler ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  group_name,
const std::vector< ConstraintSamplerPtr > &  samplers 
)

Constructor, which will re-order its internal list of samplers on construction.

The samplers need not all refer to the same group, as long as all are part of the kinematic model. The sampler will sort the samplers based on a set of criteria - where A and B are two samplers being considered for swapping by a sort algorithm:

  • If the set of links updated by the group of A are a proper subset of the set of links updated by the group of B, A and B are not swapped. If the updated links of B are a proper set of the updated links of A, A and B are swapped.
  • Otherwise, the groups associated with A and B are either disjoint in terms of updated links or have an equivalent group. In this case, it is determined if any updated links in the group for A exist in the frame dependency of B, or vice-versa.
  • If A depends on B, and B depends on A, a warning message is printed that circular dependencies are likely to lead to bad samples. A and B are not swapped.
  • If one of the frame dependencies of B is a link updated by A, but not vice-versa, the samplers are swapped.
  • If one of the frame dependencies of A is a link updated by B, but not vice-versa, the samplers are not swapped.
  • If no dependency exists, the samplers are swapped according to alphabetical order.
Parameters
[in]sceneThe planning scene
[in]group_nameThe group name is ignored, as each sampler already has a group name
[in]samplersA vector of already configured samplers that will be applied for future samples
Returns

Definition at line 126 of file union_constraint_sampler.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ canService()

virtual bool constraint_samplers::UnionConstraintSampler::canService ( const moveit_msgs::msg::Constraints &  ) const
inlinevirtual

No-op, as the union constraint sampler can act on anything.

Parameters
[in]constrConstraint message
Returns
Always true

Definition at line 132 of file union_constraint_sampler.h.

◆ configure()

bool constraint_samplers::UnionConstraintSampler::configure ( const moveit_msgs::msg::Constraints &  )
inlineoverridevirtual

No-op, as the union constraint sampler is for already configured samplers.

Parameters
[in]constrConstraint message
Returns
Always true

Implements constraint_samplers::ConstraintSampler.

Definition at line 120 of file union_constraint_sampler.h.

◆ getName()

const std::string& constraint_samplers::UnionConstraintSampler::getName ( ) const
inlineoverridevirtual

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 160 of file union_constraint_sampler.h.

◆ getSamplers()

const std::vector<ConstraintSamplerPtr>& constraint_samplers::UnionConstraintSampler::getSamplers ( ) const
inline

Gets the sorted internal list of constraint samplers.

Returns
The sorted internal list of constraint samplers

Definition at line 107 of file union_constraint_sampler.h.

Here is the caller graph for this function:

◆ sample()

bool constraint_samplers::UnionConstraintSampler::sample ( moveit::core::RobotState state,
const moveit::core::RobotState reference_state,
unsigned int  max_attempts 
)
overridevirtual

Produces a sample from all configured samplers.

This function will call each sampler in sorted order independently of the group associated with the sampler. The function will also operate independently of the joint state group passed in as an argument. If any sampler fails, the sample fails altogether.

Parameters
[in]stateState where the group sample is written to
[in]reference_stateReference kinematic state that will be passed through to samplers
[in]max_attemptsMax attempts, which will be passed through to samplers
Returns
True if all individual samplers return true

Implements constraint_samplers::ConstraintSampler.

Definition at line 145 of file union_constraint_sampler.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ samplers_

std::vector<ConstraintSamplerPtr> constraint_samplers::UnionConstraintSampler::samplers_
protected

Holder for sorted internal list of samplers.

Definition at line 167 of file union_constraint_sampler.h.


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