52 virtual bool configure(
const moveit_msgs::Constraints &constr)
57 virtual bool sample(planning_models::RobotState *::JointStateGroup *jsg,
const planning_models::RobotState& reference_state,
unsigned int max_attempts)
69 virtual constraint_samplers::ConstraintSamplerPtr
alloc(
const planning_scene::PlanningSceneConstPtr &scene,
const std::string &group_name,
const moveit_msgs::Constraints &constr)
72 cs->configure(constr);
76 virtual bool canService(
const planning_scene::PlanningSceneConstPtr &scene,
const std::string &group_name,
const moveit_msgs::Constraints &constr)
const PR2ConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
ConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
virtual constraint_samplers::ConstraintSamplerPtr alloc(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr)
virtual bool sample(planning_models::RobotState *::JointStateGroup *jsg, const planning_models::RobotState &reference_state, unsigned int max_attempts)
virtual bool configure(const moveit_msgs::Constraints &constr)
virtual bool canService(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr) const
PLUGINLIB_EXPORT_CLASS(pr2_constraint_sampler::PR2ConstraintSamplerAllocator, constraint_samplers::ConstraintSamplerAllocator)