40 #include <rclcpp/rclcpp.hpp>
99 const std::vector<ConstraintSamplerPtr>& samplers);
120 bool configure(
const moveit_msgs::msg::Constraints& )
override
132 virtual bool canService(
const moveit_msgs::msg::Constraints& )
const
153 unsigned int max_attempts)
override;
164 static const std::string SAMPLER_NAME =
"UnionConstraintSampler";
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
This class exists as a union of constraint samplers. It contains a vector of constraint samplers,...
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
bool configure(const moveit_msgs::msg::Constraints &) override
No-op, as the union constraint sampler is for already configured samplers.
virtual bool canService(const moveit_msgs::msg::Constraints &) const
No-op, as the union constraint sampler can act on anything.
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.
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
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.
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.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
The constraint samplers namespace contains a number of methods for generating samples based on a cons...