37 #ifndef MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_MANAGER_ 38 #define MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_MANAGER_ 92 ConstraintSamplerPtr
selectSampler(
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name,
93 const moveit_msgs::Constraints& constr)
const;
138 static ConstraintSamplerPtr
selectDefaultSampler(
const planning_scene::PlanningSceneConstPtr& scene,
139 const std::string& group_name,
140 const moveit_msgs::Constraints& constr);
143 std::vector<ConstraintSamplerAllocatorPtr>
std::vector< ConstraintSamplerAllocatorPtr > sampler_alloc_
Holds the constraint sampler allocators, which will be tested in order.
MOVEIT_CLASS_FORWARD(ConstraintSampler)
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
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 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.
void registerSamplerAllocator(const ConstraintSamplerAllocatorPtr &sa)
Allows the user to specify an alternate ConstraintSamplerAllocation.
This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs...
ConstraintSamplerManager()
Empty constructor.