moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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 | |
ConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name) | |
Constructor. | |
virtual | ~ConstraintSampler () |
virtual bool | configure (const moveit_msgs::msg::Constraints &constr)=0 |
Function for configuring a constraint sampler given a Constraints message. | |
const std::string & | getGroupName () const |
Gets the group name set in the constructor. | |
const moveit::core::JointModelGroup * | getJointModelGroup () const |
Gets the joint model group. | |
const planning_scene::PlanningSceneConstPtr & | getPlanningScene () const |
Gets the planning scene. | |
const std::vector< std::string > & | getFrameDependency () const |
Return the names of the mobile frames whose pose is needed when sample() is called. | |
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. | |
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. | |
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. | |
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. | |
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. | |
virtual bool | sample (moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts)=0 |
Samples given the constraints, populating state. This function allows the parameter max_attempts to be set. | |
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. | |
bool | getVerbose () const |
Check if the sampler is set to verbose mode. | |
virtual void | setVerbose (bool verbose) |
Enable/disable verbose mode for sampler. | |
virtual const std::string & | getName () const =0 |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. | |
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 | |
bool | is_valid_ |
Holds the value for validity. | |
planning_scene::PlanningSceneConstPtr | scene_ |
Holds the planning scene. | |
const moveit::core::JointModelGroup *const | jmg_ |
Holds the joint model group associated with this constraint. | |
std::vector< std::string > | frame_depends_ |
Holds the set of frames that must exist in the reference state to allow samples to be drawn. | |
moveit::core::GroupStateValidityCallbackFn | group_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 group name associated with the constraint. 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 52 of file constraint_sampler.cpp.
|
inlinevirtual |
Definition at line 77 of file constraint_sampler.h.
|
protectedvirtual |
Clears all data from the constraint.
Reimplemented in constraint_samplers::JointConstraintSampler, and constraint_samplers::IKConstraintSampler.
Definition at line 62 of file constraint_sampler.cpp.
|
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::UnionConstraintSampler, constraint_samplers::JointConstraintSampler, and constraint_samplers::IKConstraintSampler.
|
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 134 of file constraint_sampler.h.
|
inline |
Gets the group name set in the constructor.
Definition at line 96 of file constraint_sampler.h.
|
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 143 of file constraint_sampler.h.
|
inline |
Gets the joint model group.
Definition at line 107 of file constraint_sampler.h.
|
pure virtual |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
Implemented in constraint_samplers::JointConstraintSampler, constraint_samplers::IKConstraintSampler, and constraint_samplers::UnionConstraintSampler.
|
inline |
Gets the planning scene.
Definition at line 118 of file constraint_sampler.h.
|
inline |
Check if the sampler is set to verbose mode.
Definition at line 232 of file constraint_sampler.h.
|
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 and configure() must have successfully been called.
Definition at line 226 of file constraint_sampler.h.
|
inline |
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.
state | The state into which the values will be placed. Only values for the group are written. The same state is used as reference if needed. |
Definition at line 169 of file constraint_sampler.h.
|
inline |
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.
[out] | state | The state into which the values will be placed. Only values for the group are written. |
[in] | reference_state | Reference state that will be used to do transforms or perform other actions |
Definition at line 200 of file constraint_sampler.h.
|
pure virtual |
Samples given the constraints, populating state. 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] | 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::JointConstraintSampler, constraint_samplers::IKConstraintSampler, and constraint_samplers::UnionConstraintSampler.
|
inline |
Samples given the constraints, populating state. This function allows the parameter max_attempts to be set.
state | The state into which the values will be placed. Only values for the group are written. The same state is used as reference if needed. | |
[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. |
Definition at line 185 of file constraint_sampler.h.
|
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 154 of file constraint_sampler.h.
|
inlinevirtual |
Enable/disable verbose mode for sampler.
Definition at line 238 of file constraint_sampler.h.
|
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 64 of file constraint_sampler.h.
|
protected |
Holds the set of frames that must exist in the reference state to allow samples to be drawn.
Definition at line 264 of file constraint_sampler.h.
|
protected |
Holds the callback for state validity.
Definition at line 266 of file constraint_sampler.h.
|
protected |
Holds the value for validity.
Definition at line 257 of file constraint_sampler.h.
|
protected |
Holds the joint model group associated with this constraint.
Definition at line 262 of file constraint_sampler.h.
|
protected |
Holds the planning scene.
Definition at line 260 of file constraint_sampler.h.
|
protected |
True if verbosity is on.
Definition at line 267 of file constraint_sampler.h.