Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
constraint_samplers::ConstraintSamplerManager Class Reference

This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs::Constraints. More...

#include <constraint_sampler_manager.h>

Public Member Functions

 ConstraintSamplerManager ()
 Empty constructor. More...
 
void registerSamplerAllocator (const ConstraintSamplerAllocatorPtr &sa)
 Allows the user to specify an alternate ConstraintSamplerAllocation. More...
 
ConstraintSamplerPtr selectSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr) const
 Selects among the potential sampler allocators. More...
 

Static Public Member Functions

static ConstraintSamplerPtr selectDefaultSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr)
 Default logic to select a ConstraintSampler given a constraints message. More...
 

Private Attributes

std::vector< ConstraintSamplerAllocatorPtr > sampler_alloc_
 Holds the constraint sampler allocators, which will be tested in order. More...
 

Detailed Description

This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs::Constraints.

It contains logic that will generate either a JointConstraintSampler, an IKConstraintSampler, or a UnionConstraintSampler depending on the contents of the Constraints message and the group in question.

Definition at line 57 of file constraint_sampler_manager.h.

Constructor & Destructor Documentation

constraint_samplers::ConstraintSamplerManager::ConstraintSamplerManager ( )
inline

Empty constructor.

Definition at line 64 of file constraint_sampler_manager.h.

Member Function Documentation

void constraint_samplers::ConstraintSamplerManager::registerSamplerAllocator ( const ConstraintSamplerAllocatorPtr &  sa)
inline

Allows the user to specify an alternate ConstraintSamplerAllocation.

Parameters
saThe constraint sampler allocator that will be used

Definition at line 72 of file constraint_sampler_manager.h.

constraint_samplers::ConstraintSamplerPtr constraint_samplers::ConstraintSamplerManager::selectDefaultSampler ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  group_name,
const moveit_msgs::Constraints &  constr 
)
static

Default logic to select a ConstraintSampler given a constraints message.

This function will generate a sampler using the joint_constraint, position_constraint, and orientation_constraint vectors from the Constraints argument. The type of constraint sampler that is produced depends on which constraint vectors have been populated. The following rules are applied:

  • If every joint in the group indicated by group_name is constrained by a valid joint constraint in the joint_constraints vector, a JointConstraintSampler with all bounded joints in returned.
  • If not every joint is constrained, but no position and orientation constraints are specified, or no valid IKConstraintSampler can be created, then a JointConstraintSampler with some unbounded joints is returned.
  • If position and orientation constraints are present and there is an IKSolver for the group, the function will attempt to create an IKConstraintSampler.
  • If there is no direct IK solver for the group, or no valid IKConstraintSampler could be generated, and there are subgroup IKSolvers, the function will attempt to generate a sampler from the various subgroup solvers.
    • It will attempt to determine which constraints act on the IK link for the sub-group IK solvers, and attempts to create ConstraintSampler functions by recursively calling selectDefaultSampler for the sub-group.
    • If any samplers are valid, it adds them to a vector of type ConstraintSamplerPtr.
    • Once it has iterated through each sub-group, if any samplers are valid, they are returned in a UnionConstraintSampler, along with a JointConstraintSampler if one exists.
      Parameters
      sceneThe planning scene that will be used to create the ConstraintSampler
      group_nameThe group name for which to create a sampler
      constrThe set of constraints for which to create a sampler
      Returns
      A valid ConstraintSamplerPtr if one could be allocated, and otherwise an empty ConstraintSamplerPtr

Definition at line 56 of file constraint_sampler_manager.cpp.

constraint_samplers::ConstraintSamplerPtr constraint_samplers::ConstraintSamplerManager::selectSampler ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  group_name,
const moveit_msgs::Constraints &  constr 
) const

Selects among the potential sampler allocators.

This function will iterate through the constraint sampler allocators, trying to find one that can service the constraints. The first one that can service the request will be called. If no allocators can service the Constraints, or there are no allocators, the selectDefaultSampler will be called.

Parameters
sceneThe planning scene that will be passed into the constraint sampler
group_nameThe group name for which to allocate the constraint sampler
constrThe constraints
Returns
An allocated ConstraintSamplerPtr, or an empty pointer if none could be allocated

Definition at line 43 of file constraint_sampler_manager.cpp.

Member Data Documentation

std::vector<ConstraintSamplerAllocatorPtr> constraint_samplers::ConstraintSamplerManager::sampler_alloc_
private

Holds the constraint sampler allocators, which will be tested in order.

Definition at line 144 of file constraint_sampler_manager.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 Jul 10 2019 04:03:05