This class exists as a union of constraint samplers. It contains a vector of constraint samplers, and will sample from each of them. More...
#include <union_constraint_sampler.h>
Public Member Functions | |
virtual bool | canService (const moveit_msgs::Constraints &constr) const |
No-op, as the union constraint sampler can act on anything. | |
virtual bool | configure (const moveit_msgs::Constraints &constr) |
No-op, as the union constraint sampler is for already configured samplers. | |
virtual const std::string & | getName () const |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. | |
const std::vector < ConstraintSamplerPtr > & | getSamplers () const |
Gets the sorted internal list of constraint 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 parameter max_attempts to be set. | |
virtual bool | sample (robot_state::RobotState &state, const robot_state::RobotState &reference_state, unsigned int max_attempts) |
Produces a sample from all 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. | |
Protected Attributes | |
std::vector< ConstraintSamplerPtr > | samplers_ |
Holder for sorted internal list of samplers. |
This class exists as a union of constraint samplers. It contains a vector of constraint samplers, and will sample from each of them.
When asked to sample it will call the samplers in a sorted order that samples more general groups - like a robot's whole body - before sampling more specific groups, such as a robot's arm. Member samplers can operate on all or part of a joint state group vector, with later samplers potentially overwriting previous samplers.
Definition at line 57 of file union_constraint_sampler.h.
constraint_samplers::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.
The samplers need not all refer to the same group, as long as all are part of the kinematic model. The sampler will sort the samplers based on a set of criteria - where A and B are two samplers being considered for swapping by a sort algorithm:
[in] | scene | The planning scene |
[in] | group_name | The group name is ignored, as each sampler already has a group name |
[in] | samplers | A vector of already configured samplers that will be applied for future samples |
Definition at line 108 of file union_constraint_sampler.cpp.
virtual bool constraint_samplers::UnionConstraintSampler::canService | ( | const moveit_msgs::Constraints & | constr | ) | const [inline, virtual] |
No-op, as the union constraint sampler can act on anything.
[in] | constr | Constraint message |
Definition at line 133 of file union_constraint_sampler.h.
virtual bool constraint_samplers::UnionConstraintSampler::configure | ( | const moveit_msgs::Constraints & | constr | ) | [inline, virtual] |
No-op, as the union constraint sampler is for already configured samplers.
[in] | constr | Constraint message |
Implements constraint_samplers::ConstraintSampler.
Definition at line 121 of file union_constraint_sampler.h.
virtual const std::string& constraint_samplers::UnionConstraintSampler::getName | ( | ) | const [inline, virtual] |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
Implements constraint_samplers::ConstraintSampler.
Definition at line 162 of file union_constraint_sampler.h.
const std::vector<ConstraintSamplerPtr>& constraint_samplers::UnionConstraintSampler::getSamplers | ( | ) | const [inline] |
Gets the sorted internal list of constraint samplers.
Definition at line 108 of file union_constraint_sampler.h.
bool constraint_samplers::UnionConstraintSampler::project | ( | robot_state::RobotState & | state, |
unsigned int | max_attempts | ||
) | [virtual] |
Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set.
[out] | state | The state into which the values will be placed. Only values for the group are written. |
[in] | max_attempts | The maximum number of times to attempt to draw a sample. If no sample has been drawn in this number of attempts, false will be returned. |
Implements constraint_samplers::ConstraintSampler.
Definition at line 143 of file union_constraint_sampler.cpp.
bool constraint_samplers::UnionConstraintSampler::sample | ( | robot_state::RobotState & | state, |
const robot_state::RobotState & | reference_state, | ||
unsigned int | max_attempts | ||
) | [virtual] |
Produces a sample from all configured samplers.
This function will call each sampler in sorted order independently of the group associated with the sampler. The function will also operate independently of the joint state group passed in as an argument. If any sampler fails, the sample fails altogether.
[in] | state | State where the group sample is written to |
[in] | reference_state | Reference kinematic state that will be passed through to samplers |
[in] | max_attempts | Max attempts, which will be passed through to samplers |
Implements constraint_samplers::ConstraintSampler.
Definition at line 125 of file union_constraint_sampler.cpp.
std::vector<ConstraintSamplerPtr> constraint_samplers::UnionConstraintSampler::samplers_ [protected] |
Holder for sorted internal list of samplers.
Definition at line 170 of file union_constraint_sampler.h.