Go to the documentation of this file.
56 class UnionConstraintSampler :
public ConstraintSampler
98 const std::vector<ConstraintSamplerPtr>& samplers);
106 const std::vector<ConstraintSamplerPtr>&
getSamplers()
const
119 bool configure(
const moveit_msgs::Constraints& constraint)
override
132 virtual bool canService(
const moveit_msgs::Constraints& constraint)
const
154 unsigned int max_attempts)
override;
161 const std::string&
getName()
const override
163 static const std::string SAMPLER_NAME =
"UnionConstraintSampler";
168 std::vector<ConstraintSamplerPtr>
samplers_;
virtual bool canService(const moveit_msgs::Constraints &constraint) const
No-op, as the union constraint sampler can act on anything.
const std::string & getName() const override
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.
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
Produces a sample from all configured samplers.
std::vector< ConstraintSamplerPtr > samplers_
Holder for sorted internal list of samplers.
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
bool configure(const moveit_msgs::Constraints &constraint) override
No-op, as the union constraint sampler is for already configured samplers.
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.
const std::vector< ConstraintSamplerPtr > & getSamplers() const
Gets the sorted internal list of constraint samplers.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15