ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a particular group of a robot. More...
#include <constraint_sampler.h>
Public Member Functions | |
virtual bool | configure (const moveit_msgs::Constraints &constr)=0 |
Function for configuring a constraint sampler given a Constraints message. | |
ConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name) | |
Constructor. | |
const std::vector< std::string > & | getFrameDependency () const |
Return the names of the mobile frames whose pose is needed when sample() is called. | |
const std::string & | getGroupName () const |
Gets the group name set in the constructor. | |
const robot_model::JointModelGroup * | getJointModelGroup () const |
Gets the joint model group. | |
const planning_scene::PlanningSceneConstPtr & | getPlanningScene () const |
Gets the planning scene. | |
const robot_state::StateValidityCallbackFn & | getStateValidityCallback () 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. | |
bool | getVerbose () const |
Check if the sampler is set to verbose mode. | |
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. | |
bool | project (robot_state::JointStateGroup *jsg, const robot_state::RobotState &reference_state) |
Project a sample given the constraints, updating the joint state group. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to project the sample. | |
virtual bool | project (robot_state::JointStateGroup *jsg, const robot_state::RobotState &reference_state, unsigned int max_attempts)=0 |
Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set. | |
bool | sample (robot_state::JointStateGroup *jsg, const robot_state::RobotState &reference_state) |
Samples given the constraints, populating the joint state group. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to take a sample. | |
virtual bool | sample (robot_state::JointStateGroup *jsg, const robot_state::RobotState &reference_state, unsigned int max_attempts)=0 |
Samples given the constraints, populating the joint state group. This function allows the parameter max_attempts to be set. | |
void | setStateValidityCallback (const robot_state::StateValidityCallbackFn &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. | |
void | setVerbose (bool flag) |
Enable/disable verbose mode for sampler. | |
virtual | ~ConstraintSampler () |
Static Public Attributes | |
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. | |
Protected Member Functions | |
virtual void | clear () |
Clears all data from the constraint. | |
Protected Attributes | |
std::vector< std::string > | frame_depends_ |
Holds the set of frames that must exist in the reference state to allow samples to be drawn. | |
bool | is_valid_ |
Holds the value for validity. | |
const robot_model::JointModelGroup * | jmg_ |
Holds the joint model group associated with this constraint. | |
planning_scene::PlanningSceneConstPtr | scene_ |
Holds the planning scene. | |
robot_state::StateValidityCallbackFn | state_validity_callback_ |
Holds the callback for state validity. | |
bool | verbose_ |
True if verbosity is on. |
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a particular group of a robot.
Definition at line 59 of file constraint_sampler.h.
constraint_samplers::ConstraintSampler::ConstraintSampler | ( | const planning_scene::PlanningSceneConstPtr & | scene, |
const std::string & | group_name | ||
) |
Constructor.
[in] | scene | The planning scene that will be used for constraint checking |
[in] | group_name | The name of the group that will be sampled. Will be invalid if no group name is passed in or the joint model group cannot be found in the kinematic model |
Definition at line 39 of file constraint_sampler.cpp.
virtual constraint_samplers::ConstraintSampler::~ConstraintSampler | ( | ) | [inline, virtual] |
Definition at line 73 of file constraint_sampler.h.
void constraint_samplers::ConstraintSampler::clear | ( | ) | [protected, virtual] |
Clears all data from the constraint.
Reimplemented in constraint_samplers::IKConstraintSampler, and constraint_samplers::JointConstraintSampler.
Definition at line 55 of file constraint_sampler.cpp.
virtual bool constraint_samplers::ConstraintSampler::configure | ( | const moveit_msgs::Constraints & | constr | ) | [pure virtual] |
Function for configuring a constraint sampler given a Constraints message.
[in] | constr | The constraints from which to construct a sampler |
Implemented in constraint_samplers::IKConstraintSampler, constraint_samplers::UnionConstraintSampler, and constraint_samplers::JointConstraintSampler.
const std::vector<std::string>& constraint_samplers::ConstraintSampler::getFrameDependency | ( | ) | const [inline] |
Return the names of the mobile frames whose pose is needed when sample() is called.
Mobile frames mean frames other than the reference frame of the kinematic model. These frames may move when the kinematic state changes. Frame dependency can help determine an ordering from a set of constraint samplers - for more information see the derived class documentation for UnionConstraintSampler.
Definition at line 129 of file constraint_sampler.h.
const std::string& constraint_samplers::ConstraintSampler::getGroupName | ( | ) | const [inline] |
Gets the group name set in the constructor.
Definition at line 91 of file constraint_sampler.h.
const robot_model::JointModelGroup* constraint_samplers::ConstraintSampler::getJointModelGroup | ( | ) | const [inline] |
Gets the joint model group.
Definition at line 102 of file constraint_sampler.h.
const planning_scene::PlanningSceneConstPtr& constraint_samplers::ConstraintSampler::getPlanningScene | ( | ) | const [inline] |
Gets the planning scene.
Definition at line 113 of file constraint_sampler.h.
const robot_state::StateValidityCallbackFn& constraint_samplers::ConstraintSampler::getStateValidityCallback | ( | ) | const [inline] |
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.
Definition at line 137 of file constraint_sampler.h.
bool constraint_samplers::ConstraintSampler::getVerbose | ( | ) | const [inline] |
Check if the sampler is set to verbose mode.
Definition at line 223 of file constraint_sampler.h.
bool constraint_samplers::ConstraintSampler::isValid | ( | ) | const [inline] |
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.
Definition at line 217 of file constraint_sampler.h.
bool constraint_samplers::ConstraintSampler::project | ( | robot_state::JointStateGroup * | jsg, |
const robot_state::RobotState & | reference_state | ||
) | [inline] |
Project a sample given the constraints, updating the joint state group. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to project the sample.
[out] | jsg | The joint state group which specifies the state to be projected, according to the constraints |
[in] | reference_state | Reference state that will be used to do transforms or perform other actions |
Definition at line 178 of file constraint_sampler.h.
virtual bool constraint_samplers::ConstraintSampler::project | ( | robot_state::JointStateGroup * | jsg, |
const robot_state::RobotState & | reference_state, | ||
unsigned int | max_attempts | ||
) | [pure virtual] |
Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set.
[out] | jsg | The joint state group which specifies the state to be projected, according to the constraints |
[in] | reference_state | Reference state that will be used to do transforms or perform other actions |
[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. |
Implemented in constraint_samplers::IKConstraintSampler, constraint_samplers::UnionConstraintSampler, and constraint_samplers::JointConstraintSampler.
bool constraint_samplers::ConstraintSampler::sample | ( | robot_state::JointStateGroup * | jsg, |
const robot_state::RobotState & | reference_state | ||
) | [inline] |
Samples given the constraints, populating the joint state group. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be passed in as the maximum number of attempts to make to take a sample.
[out] | jsg | The joint state group into which the values will be placed |
[in] | reference_state | Reference state that will be used to do transforms or perform other actions |
Definition at line 162 of file constraint_sampler.h.
virtual bool constraint_samplers::ConstraintSampler::sample | ( | robot_state::JointStateGroup * | jsg, |
const robot_state::RobotState & | reference_state, | ||
unsigned int | max_attempts | ||
) | [pure virtual] |
Samples given the constraints, populating the joint state group. This function allows the parameter max_attempts to be set.
[out] | jsg | The joint state group into which the values will be placed |
[in] | reference_state | Reference state that will be used to do transforms or perform other actions |
[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. |
Implemented in constraint_samplers::IKConstraintSampler, constraint_samplers::UnionConstraintSampler, and constraint_samplers::JointConstraintSampler.
void constraint_samplers::ConstraintSampler::setStateValidityCallback | ( | const robot_state::StateValidityCallbackFn & | callback | ) | [inline] |
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.
callback | The callback to set |
Definition at line 147 of file constraint_sampler.h.
void constraint_samplers::ConstraintSampler::setVerbose | ( | bool | flag | ) | [inline] |
Enable/disable verbose mode for sampler.
Definition at line 229 of file constraint_sampler.h.
const unsigned int constraint_samplers::ConstraintSampler::DEFAULT_MAX_SAMPLING_ATTEMPTS = 2 [static] |
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.
Definition at line 63 of file constraint_sampler.h.
std::vector<std::string> constraint_samplers::ConstraintSampler::frame_depends_ [protected] |
Holds the set of frames that must exist in the reference state to allow samples to be drawn.
Definition at line 246 of file constraint_sampler.h.
bool constraint_samplers::ConstraintSampler::is_valid_ [protected] |
Holds the value for validity.
Definition at line 242 of file constraint_sampler.h.
const robot_model::JointModelGroup* constraint_samplers::ConstraintSampler::jmg_ [protected] |
Holds the joint model group associated with this constraint.
Definition at line 245 of file constraint_sampler.h.
Holds the planning scene.
Definition at line 244 of file constraint_sampler.h.
robot_state::StateValidityCallbackFn constraint_samplers::ConstraintSampler::state_validity_callback_ [protected] |
Holds the callback for state validity.
Definition at line 247 of file constraint_sampler.h.
bool constraint_samplers::ConstraintSampler::verbose_ [protected] |
True if verbosity is on.
Definition at line 248 of file constraint_sampler.h.