JointConstraintSampler is a class that allows the sampling of joints in a particular group of the robot, subject to a set of individual joint constraints. More...
#include <default_constraint_samplers.h>
Classes | |
struct | JointInfo |
An internal structure used for maintaining constraints on a particular joint. More... | |
Public Member Functions | |
bool | configure (const moveit_msgs::Constraints &constr) override |
Configures a joint constraint given a Constraints message. More... | |
bool | configure (const std::vector< kinematic_constraints::JointConstraint > &jc) |
Configures a joint constraint given a vector of constraints. More... | |
std::size_t | getConstrainedJointCount () const |
Gets the number of constrained joints - joints that have an additional bound beyond the joint limits. More... | |
const std::string & | getName () const override |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format. More... | |
std::size_t | getUnconstrainedJointCount () const |
Gets the number of unconstrained joints - joint that have no additional bound beyond the joint limits. More... | |
JointConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name) | |
bool | sample (moveit::core::RobotState &state, const moveit::core::RobotState &ks, unsigned int max_attempts) override |
Samples given the constraints, populating state. This function allows the parameter max_attempts to be set. 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 Member Functions | |
void | clear () override |
Clears all data from the constraint. More... | |
Protected Attributes | |
std::vector< JointInfo > | bounds_ |
The bounds for any joint with bounds that are more restrictive than the joint limits. More... | |
random_numbers::RandomNumberGenerator | random_number_generator_ |
Random number generator used to sample. More... | |
std::vector< unsigned int > | uindex_ |
The index of the unbounded joints in the joint state vector. More... | |
std::vector< const moveit::core::JointModel * > | unbounded_ |
The joints that are not bounded except by joint limits. More... | |
std::vector< double > | values_ |
Values associated with this group to avoid continuously reallocating. 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... | |
JointConstraintSampler is a class that allows the sampling of joints in a particular group of the robot, subject to a set of individual joint constraints.
The set of individual joint constraint reduce the allowable bounds used in the sampling. Unconstrained values will be sampled within their limits.
Definition at line 90 of file default_constraint_samplers.h.
|
inline |
Constructor
[in] | scene | The planning scene used to check the constraint |
[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 103 of file default_constraint_samplers.h.
|
overrideprotectedvirtual |
Clears all data from the constraint.
Reimplemented from constraint_samplers::ConstraintSampler.
Definition at line 226 of file default_constraint_samplers.cpp.
|
overridevirtual |
Configures a joint constraint given a Constraints message.
If more than one constraint for a particular joint is specified, the most restrictive set of bounds will be used (highest minimum value, lowest maximum value). For the configuration to be successful, the following condition must be met, in addition to the conditions specified in configure(const std::vector<kinematic_constraints::JointConstraint> &jc) :
[in] | constr | The message containing the constraints |
Implements constraint_samplers::ConstraintSampler.
Definition at line 89 of file default_constraint_samplers.cpp.
bool constraint_samplers::JointConstraintSampler::configure | ( | const std::vector< kinematic_constraints::JointConstraint > & | jc | ) |
Configures a joint constraint given a vector of constraints.
If more than one constraint for a particular joint is specified, the most restrictive set of bounds will be used (highest minimum value, lowest_maximum value. For the configuration to be successful, the following conditions must be met:
[in] | jc | The vector of joint constraints |
Definition at line 103 of file default_constraint_samplers.cpp.
|
inline |
Gets the number of constrained joints - joints that have an additional bound beyond the joint limits.
Definition at line 164 of file default_constraint_samplers.h.
|
inlineoverridevirtual |
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
Implements constraint_samplers::ConstraintSampler.
Definition at line 185 of file default_constraint_samplers.h.
|
inline |
Gets the number of unconstrained joints - joint that have no additional bound beyond the joint limits.
Definition at line 175 of file default_constraint_samplers.h.
|
overridevirtual |
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. |
Implements constraint_samplers::ConstraintSampler.
Definition at line 196 of file default_constraint_samplers.cpp.
|
protected |
The bounds for any joint with bounds that are more restrictive than the joint limits.
Definition at line 229 of file default_constraint_samplers.h.
|
protected |
Random number generator used to sample.
Definition at line 228 of file default_constraint_samplers.h.
|
protected |
The index of the unbounded joints in the joint state vector.
Definition at line 234 of file default_constraint_samplers.h.
|
protected |
The joints that are not bounded except by joint limits.
Definition at line 232 of file default_constraint_samplers.h.
|
protected |
Values associated with this group to avoid continuously reallocating.
Definition at line 235 of file default_constraint_samplers.h.