41#include <rclcpp/rclcpp.hpp>
58 virtual ConstraintSamplerPtr
alloc(
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name,
59 const moveit_msgs::msg::Constraints& constr) = 0;
61 virtual bool canService(
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name,
62 const moveit_msgs::msg::Constraints& constr)
const = 0;
#define MOVEIT_CLASS_FORWARD(C)
virtual bool canService(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr) const =0
ConstraintSamplerAllocator()
virtual ~ConstraintSamplerAllocator()
virtual ConstraintSamplerPtr alloc(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr)=0
The constraint samplers namespace contains a number of methods for generating samples based on a cons...