41 #include <rclcpp/rclcpp.hpp> 
   42 #include <rclcpp/clock.hpp> 
   43 #include <rclcpp/duration.hpp> 
   76     sampler_alloc_.push_back(sa);
 
   94   ConstraintSamplerPtr 
selectSampler(
const planning_scene::PlanningSceneConstPtr& 
scene, 
const std::string& group_name,
 
   95                                      const moveit_msgs::msg::Constraints& constr) 
const;
 
  141                                                    const std::string& group_name,
 
  142                                                    const moveit_msgs::msg::Constraints& constr);
 
  145   std::vector<ConstraintSamplerAllocatorPtr>
 
This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs...
 
void registerSamplerAllocator(const ConstraintSamplerAllocatorPtr &sa)
Allows the user to specify an alternate ConstraintSamplerAllocation.
 
static ConstraintSamplerPtr selectDefaultSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr)
Default logic to select a ConstraintSampler given a constraints message.
 
ConstraintSamplerManager()
Empty constructor.
 
ConstraintSamplerPtr selectSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr) const
Selects among the potential sampler allocators.
 
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
 
MOVEIT_CLASS_FORWARD(ConstraintSampler)