#include <constraint_sampler_allocator.h>
 | 
|   | ConstraintSamplerAllocator () | 
|   | 
| virtual  | ~ConstraintSamplerAllocator () | 
|   | 
| virtual ConstraintSamplerPtr  | alloc (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr)=0 | 
|   | 
| virtual bool  | canService (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr) const =0 | 
|   | 
◆ ConstraintSamplerAllocator()
  
  
      
        
          | constraint_samplers::ConstraintSamplerAllocator::ConstraintSamplerAllocator  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
 
◆ ~ConstraintSamplerAllocator()
  
  
      
        
          | virtual constraint_samplers::ConstraintSamplerAllocator::~ConstraintSamplerAllocator  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
inlinevirtual   | 
  
 
 
◆ alloc()
  
  
      
        
          | virtual ConstraintSamplerPtr constraint_samplers::ConstraintSamplerAllocator::alloc  | 
          ( | 
          const planning_scene::PlanningSceneConstPtr &  | 
          scene,  | 
         
        
           | 
           | 
          const std::string &  | 
          group_name,  | 
         
        
           | 
           | 
          const moveit_msgs::msg::Constraints &  | 
          constr  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
pure virtual   | 
  
 
 
◆ canService()
  
  
      
        
          | virtual bool constraint_samplers::ConstraintSamplerAllocator::canService  | 
          ( | 
          const planning_scene::PlanningSceneConstPtr &  | 
          scene,  | 
         
        
           | 
           | 
          const std::string &  | 
          group_name,  | 
         
        
           | 
           | 
          const moveit_msgs::msg::Constraints &  | 
          constr  | 
         
        
           | 
          ) | 
           |  const | 
         
       
   | 
  
pure virtual   | 
  
 
 
The documentation for this class was generated from the following file: