moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
A class that contains many different constraints, and can check RobotState *versus the full set. A set is satisfied if and only if all constraints are satisfied. More...
#include <kinematic_constraint.h>
Public Member Functions | |
KinematicConstraintSet (const moveit::core::RobotModelConstPtr &model) | |
Constructor. More... | |
~KinematicConstraintSet () | |
void | clear () |
Clear the stored constraints. More... | |
bool | add (const moveit_msgs::msg::Constraints &c, const moveit::core::Transforms &tf) |
Add all known constraints. More... | |
bool | add (const std::vector< moveit_msgs::msg::JointConstraint > &jc) |
Add a vector of joint constraints. More... | |
bool | add (const std::vector< moveit_msgs::msg::PositionConstraint > &pc, const moveit::core::Transforms &tf) |
Add a vector of position constraints. More... | |
bool | add (const std::vector< moveit_msgs::msg::OrientationConstraint > &oc, const moveit::core::Transforms &tf) |
Add a vector of orientation constraints. More... | |
bool | add (const std::vector< moveit_msgs::msg::VisibilityConstraint > &vc, const moveit::core::Transforms &tf) |
Add a vector of visibility constraints. More... | |
ConstraintEvaluationResult | decide (const moveit::core::RobotState &state, bool verbose=false) const |
Determines whether all constraints are satisfied by state, returning a single evaluation result. More... | |
ConstraintEvaluationResult | decide (const moveit::core::RobotState &state, std::vector< ConstraintEvaluationResult > &results, bool verbose=false) const |
Determines whether all constraints are satisfied by state, returning a vector of results through a parameter in addition to a summed result. More... | |
bool | equal (const KinematicConstraintSet &other, double margin) const |
Whether or not another KinematicConstraintSet is equal to this one. More... | |
void | print (std::ostream &out=std::cout) const |
Print the constraint data. More... | |
const std::vector< moveit_msgs::msg::PositionConstraint > & | getPositionConstraints () const |
Get all position constraints in the set. More... | |
const std::vector< moveit_msgs::msg::OrientationConstraint > & | getOrientationConstraints () const |
Get all orientation constraints in the set. More... | |
const std::vector< moveit_msgs::msg::JointConstraint > & | getJointConstraints () const |
Get all joint constraints in the set. More... | |
const std::vector< moveit_msgs::msg::VisibilityConstraint > & | getVisibilityConstraints () const |
Get all visibility constraints in the set. More... | |
const moveit_msgs::msg::Constraints & | getAllConstraints () const |
Get all constraints in the set. More... | |
bool | empty () const |
Returns whether or not there are any constraints in the set. More... | |
Protected Attributes | |
moveit::core::RobotModelConstPtr | robot_model_ |
The kinematic model used for by the Set. More... | |
std::vector< KinematicConstraintPtr > | kinematic_constraints_ |
Shared pointers to all the member constraints. More... | |
std::vector< moveit_msgs::msg::JointConstraint > | joint_constraints_ |
Messages corresponding to all internal joint constraints. More... | |
std::vector< moveit_msgs::msg::PositionConstraint > | position_constraints_ |
Messages corresponding to all internal position constraints. More... | |
std::vector< moveit_msgs::msg::OrientationConstraint > | orientation_constraints_ |
Messages corresponding to all internal orientation constraints. More... | |
std::vector< moveit_msgs::msg::VisibilityConstraint > | visibility_constraints_ |
Messages corresponding to all internal visibility constraints. More... | |
moveit_msgs::msg::Constraints | all_constraints_ |
Messages corresponding to all internal constraints. More... | |
A class that contains many different constraints, and can check RobotState *versus the full set. A set is satisfied if and only if all constraints are satisfied.
The set may contain any number of different kinds of constraints. All constraints, including invalid ones, are stored internally.
Definition at line 871 of file kinematic_constraint.h.
|
inline |
Constructor.
[in] | model | The kinematic model used for constraint evaluation |
Definition at line 882 of file kinematic_constraint.h.
|
inline |
bool kinematic_constraints::KinematicConstraintSet::add | ( | const moveit_msgs::msg::Constraints & | c, |
const moveit::core::Transforms & | tf | ||
) |
Add all known constraints.
[in] | c | A message potentially contain vectors of constraints of add types |
Definition at line 1250 of file kinematic_constraint.cpp.
bool kinematic_constraints::KinematicConstraintSet::add | ( | const std::vector< moveit_msgs::msg::JointConstraint > & | jc | ) |
Add a vector of joint constraints.
[in] | jc | A vector of joint constraints |
Definition at line 1187 of file kinematic_constraint.cpp.
bool kinematic_constraints::KinematicConstraintSet::add | ( | const std::vector< moveit_msgs::msg::OrientationConstraint > & | oc, |
const moveit::core::Transforms & | tf | ||
) |
Add a vector of orientation constraints.
[in] | oc | A vector of orientation constraints |
Definition at line 1218 of file kinematic_constraint.cpp.
bool kinematic_constraints::KinematicConstraintSet::add | ( | const std::vector< moveit_msgs::msg::PositionConstraint > & | pc, |
const moveit::core::Transforms & | tf | ||
) |
Add a vector of position constraints.
[in] | pc | A vector of position constraints |
Definition at line 1202 of file kinematic_constraint.cpp.
bool kinematic_constraints::KinematicConstraintSet::add | ( | const std::vector< moveit_msgs::msg::VisibilityConstraint > & | vc, |
const moveit::core::Transforms & | tf | ||
) |
Add a vector of visibility constraints.
[in] | vc | A vector of visibility constraints |
Definition at line 1234 of file kinematic_constraint.cpp.
void kinematic_constraints::KinematicConstraintSet::clear | ( | ) |
Clear the stored constraints.
Definition at line 1177 of file kinematic_constraint.cpp.
ConstraintEvaluationResult kinematic_constraints::KinematicConstraintSet::decide | ( | const moveit::core::RobotState & | state, |
bool | verbose = false |
||
) | const |
Determines whether all constraints are satisfied by state, returning a single evaluation result.
[in] | state | The state to test |
[in] | verbose | Whether or not to make each constraint give debug output |
Definition at line 1259 of file kinematic_constraint.cpp.
ConstraintEvaluationResult kinematic_constraints::KinematicConstraintSet::decide | ( | const moveit::core::RobotState & | state, |
std::vector< ConstraintEvaluationResult > & | results, | ||
bool | verbose = false |
||
) | const |
Determines whether all constraints are satisfied by state, returning a vector of results through a parameter in addition to a summed result.
[in] | state | The state to test |
[out] | results | The individual results from constraint evaluation on each constraint contained in the set. |
[in] | verbose | Whether to print the results of each constraint check. |
Definition at line 1272 of file kinematic_constraint.cpp.
|
inline |
Returns whether or not there are any constraints in the set.
Definition at line 1061 of file kinematic_constraint.h.
bool kinematic_constraints::KinematicConstraintSet::equal | ( | const KinematicConstraintSet & | other, |
double | margin | ||
) | const |
Whether or not another KinematicConstraintSet is equal to this one.
Equality means that for each constraint in this set there is a constraint in the other set for which equal() is true with the given margin. Multiple constraints in this set can be matched to single constraints in the other set. Some constraints in the other set may not be matched to constraints in this set.
[in] | other | The other set against which to test |
[in] | margin | The margin to apply to all individual constraint equality tests |
Definition at line 1295 of file kinematic_constraint.cpp.
|
inline |
Get all constraints in the set.
Definition at line 1050 of file kinematic_constraint.h.
|
inline |
Get all joint constraints in the set.
Definition at line 1028 of file kinematic_constraint.h.
|
inline |
Get all orientation constraints in the set.
Definition at line 1017 of file kinematic_constraint.h.
|
inline |
Get all position constraints in the set.
Definition at line 1006 of file kinematic_constraint.h.
|
inline |
Get all visibility constraints in the set.
Definition at line 1039 of file kinematic_constraint.h.
void kinematic_constraints::KinematicConstraintSet::print | ( | std::ostream & | out = std::cout | ) | const |
Print the constraint data.
[in] | out | The file stream for printing |
Definition at line 1288 of file kinematic_constraint.cpp.
|
protected |
Messages corresponding to all internal constraints.
Definition at line 1081 of file kinematic_constraint.h.
|
protected |
Messages corresponding to all internal joint constraints.
Definition at line 1071 of file kinematic_constraint.h.
|
protected |
Shared pointers to all the member constraints.
Definition at line 1069 of file kinematic_constraint.h.
|
protected |
Messages corresponding to all internal orientation constraints.
Definition at line 1075 of file kinematic_constraint.h.
|
protected |
Messages corresponding to all internal position constraints.
Definition at line 1073 of file kinematic_constraint.h.
|
protected |
The kinematic model used for by the Set.
Definition at line 1067 of file kinematic_constraint.h.
|
protected |
Messages corresponding to all internal visibility constraints.
Definition at line 1078 of file kinematic_constraint.h.