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. | |
void | registerSamplerAllocator (const ConstraintSamplerAllocatorPtr &sa) |
Allows the user to specify an alternate ConstraintSamplerAllocation. | |
ConstraintSamplerPtr | selectSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr) const |
Selects among the potential sampler allocators. | |
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. | |
Private Attributes | |
std::vector < ConstraintSamplerAllocatorPtr > | sampler_alloc_ |
Holds the constraint sampler allocators, which will be tested in order. |
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 56 of file constraint_sampler_manager.h.
Empty constructor.
Definition at line 63 of file constraint_sampler_manager.h.
void constraint_samplers::ConstraintSamplerManager::registerSamplerAllocator | ( | const ConstraintSamplerAllocatorPtr & | sa | ) | [inline] |
Allows the user to specify an alternate ConstraintSamplerAllocation.
sa | The constraint sampler allocator that will be used |
Definition at line 71 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:
scene | The planning scene that will be used to create the ConstraintSampler |
group_name | The group name for which to create a sampler |
constr | The set of constraints for which to create a sampler |
Definition at line 54 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.
scene | The planning scene that will be passed into the constraint sampler |
group_name | The group name for which to allocate the constraint sampler |
constr | The constraints |
Definition at line 42 of file constraint_sampler_manager.cpp.
std::vector<ConstraintSamplerAllocatorPtr> constraint_samplers::ConstraintSamplerManager::sampler_alloc_ [private] |
Holds the constraint sampler allocators, which will be tested in order.
Definition at line 134 of file constraint_sampler_manager.h.