37 #ifndef MOVEIT_CONSTRAINT_SAMPLERS_DEFAULT_UNION_CONSTRAINT_SAMPLER_ 38 #define MOVEIT_CONSTRAINT_SAMPLERS_DEFAULT_UNION_CONSTRAINT_SAMPLER_ 99 const std::vector<ConstraintSamplerPtr>& samplers);
120 virtual bool configure(
const moveit_msgs::Constraints& constr)
132 virtual bool canService(
const moveit_msgs::Constraints& constr)
const 153 unsigned int max_attempts);
164 static const std::string SAMPLER_NAME =
"UnionConstraintSampler";
UnionConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::vector< ConstraintSamplerPtr > &samplers)
Constructor, which will re-order its internal list of samplers on construction.
virtual bool canService(const moveit_msgs::Constraints &constr) const
No-op, as the union constraint sampler can act on anything.
virtual bool sample(robot_state::RobotState &state, const robot_state::RobotState &reference_state, unsigned int max_attempts)
Produces a sample from all configured samplers.
This class exists as a union of constraint samplers. It contains a vector of constraint samplers...
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
std::vector< ConstraintSamplerPtr > samplers_
Holder for sorted internal list of samplers.
virtual const std::string & getName() const
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format...
Representation of a robot's state. This includes position, velocity, acceleration and effort...
virtual bool configure(const moveit_msgs::Constraints &constr)
No-op, as the union constraint sampler is for already configured samplers.
virtual bool project(robot_state::RobotState &state, unsigned int max_attempts)
Project a sample given the constraints, updating the joint state group. This function allows the para...
const std::vector< ConstraintSamplerPtr > & getSamplers() const
Gets the sorted internal list of constraint samplers.