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 &constraint) const |
No-op, as the union constraint sampler can act on anything. More... | |
bool | configure (const moveit_msgs::Constraints &constraint) override |
No-op, as the union constraint sampler is for already configured samplers. More... | |
const std::string & | getName () const override |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. More... | |
const std::vector< ConstraintSamplerPtr > & | getSamplers () const |
Gets the sorted internal list of constraint samplers. More... | |
bool | sample (moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override |
Produces a sample from all configured samplers. More... | |
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. More... | |
Public Member Functions inherited from constraint_samplers::ConstraintSampler | |
ConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name) | |
Constructor. More... | |
const std::vector< std::string > & | getFrameDependency () const |
Return the names of the mobile frames whose pose is needed when sample() is called. More... | |
const std::string & | getGroupName () const |
Gets the group name set in the constructor. More... | |
const moveit::core::GroupStateValidityCallbackFn & | getGroupStateValidityCallback () const |
Gets the callback used to determine state validity during sampling. The sampler will attempt to satisfy this constraint if possible, but there is no guarantee. More... | |
const moveit::core::JointModelGroup * | getJointModelGroup () const |
Gets the joint model group. More... | |
const planning_scene::PlanningSceneConstPtr & | getPlanningScene () const |
Gets the planning scene. More... | |
bool | getVerbose () const |
Check if the sampler is set to verbose mode. More... | |
bool | isValid () const |
Returns whether or not the constraint sampler is valid or not. To be valid, the joint model group must be available in the kinematic model and configure() must have successfully been called. More... | |
bool | sample (moveit::core::RobotState &state) |
Samples given the constraints, populating state. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to take a sample. More... | |
bool | sample (moveit::core::RobotState &state, const moveit::core::RobotState &reference_state) |
Samples given the constraints, populating state. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to take a sample. More... | |
bool | sample (moveit::core::RobotState &state, unsigned int max_attempts) |
Samples given the constraints, populating state. This function allows the parameter max_attempts to be set. More... | |
void | setGroupStateValidityCallback (const moveit::core::GroupStateValidityCallbackFn &callback) |
Sets the callback used to determine the state validity during sampling. The sampler will attempt to satisfy this constraint if possible, but there is no guarantee. More... | |
virtual void | setVerbose (bool verbose) |
Enable/disable verbose mode for sampler. More... | |
virtual | ~ConstraintSampler () |
Protected Attributes | |
std::vector< ConstraintSamplerPtr > | samplers_ |
Holder for sorted internal list of samplers. More... | |
Protected Attributes inherited from constraint_samplers::ConstraintSampler | |
std::vector< std::string > | frame_depends_ |
Holds the set of frames that must exist in the reference state to allow samples to be drawn. More... | |
moveit::core::GroupStateValidityCallbackFn | group_state_validity_callback_ |
Holds the callback for state validity. More... | |
bool | is_valid_ |
Holds the value for validity. More... | |
const moveit::core::JointModelGroup *const | jmg_ |
Holds the joint model group associated with this constraint. More... | |
planning_scene::PlanningSceneConstPtr | scene_ |
Holds the planning scene. More... | |
bool | verbose_ |
True if verbosity is on. More... | |
Additional Inherited Members | |
Static Public Attributes inherited from constraint_samplers::ConstraintSampler | |
static const unsigned int | DEFAULT_MAX_SAMPLING_ATTEMPTS = 2 |
The default value associated with a sampling request. By default if a valid sample cannot be produced in this many attempts, it returns with no sample. More... | |
Protected Member Functions inherited from constraint_samplers::ConstraintSampler | |
virtual void | clear () |
Clears all data from the constraint. More... | |
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 88 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 139 of file union_constraint_sampler.cpp.
|
inlinevirtual |
No-op, as the union constraint sampler can act on anything.
[in] | constraint | Constraint message |
Definition at line 196 of file union_constraint_sampler.h.
|
inlineoverridevirtual |
No-op, as the union constraint sampler is for already configured samplers.
[in] | constraint | Constraint message |
Implements constraint_samplers::ConstraintSampler.
Definition at line 183 of file union_constraint_sampler.h.
|
inlineoverridevirtual |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
Implements constraint_samplers::ConstraintSampler.
Definition at line 225 of file union_constraint_sampler.h.
|
inline |
Gets the sorted internal list of constraint samplers.
Definition at line 170 of file union_constraint_sampler.h.
|
overridevirtual |
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 158 of file union_constraint_sampler.cpp.
|
protected |
Holder for sorted internal list of samplers.
Definition at line 232 of file union_constraint_sampler.h.