Go to the documentation of this file.
   46 #include <moveit_msgs/Constraints.h> 
   99   virtual void clear() = 0;
 
  147   virtual void print(std::ostream& out = std::cout)
 const 
  170   const moveit::core::RobotModelConstPtr& 
getRobotModel()
 const 
  203 class JointConstraint : 
public KinematicConstraint
 
  230   bool configure(
const moveit_msgs::JointConstraint& jc);
 
  251   void clear() 
override;
 
  252   void print(std::ostream& out = std::cout) 
const override;
 
  358   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  405   void clear() 
override;
 
  408   void print(std::ostream& out = std::cout) 
const override;
 
  537   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  593   void clear() 
override;
 
  596   void print(std::ostream& out = std::cout) 
const override;
 
  783   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  825   void clear() 
override;
 
  851   void print(std::ostream& out = std::cout) 
const override;
 
  891 class KinematicConstraintSet
 
  894   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  933   bool add(
const std::vector<moveit_msgs::JointConstraint>& jc);
 
  994                                     std::vector<ConstraintEvaluationResult>& results, 
bool verbose = 
false) 
const;
 
 1018   void print(std::ostream& out = std::cout) 
const;
 
 1088   std::vector<KinematicConstraintPtr>
 
  
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
A link from the robot. Contains the constant transform applied to the link and its geometry.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model associated with this constraint.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model used for by the Set.
const Eigen::Matrix3d & getDesiredRotationMatrix() const
The rotation target in the reference or tf frame.
int getJointVariableIndex() const
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
double max_range_angle_
Storage for the max range angle.
double getZAxisTolerance() const
Gets the Z axis tolerance.
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
double joint_tolerance_above_
ConstraintEvaluationResult(bool result_satisfied=false, double dist=0.0)
Constructor.
const std::vector< moveit_msgs::JointConstraint > & getJointConstraints() const
Get all joint constraints in the set.
virtual bool enabled() const =0
This function returns true if this constraint is configured and able to decide whether states do meet...
bool equal(const KinematicConstraintSet &other, double margin) const
Whether or not another KinematicConstraintSet is equal to this one.
double target_radius_
Storage for the target radius.
bool mobileReferenceFrame() const
Whether or not a mobile reference frame is being employed.
moveit_msgs::Constraints all_constraints_
Messages corresponding to all internal constraints.
double absolute_z_axis_tolerance_
const std::string & getReferenceFrame() const
Returns the reference frame.
int joint_variable_index_
The index of the joint variable name in the full robot state.
const std::vector< moveit_msgs::OrientationConstraint > & getOrientationConstraints() const
Get all orientation constraints in the set.
std::string constraint_frame_id_
The constraint frame id.
Representation and evaluation of kinematic constraints.
Eigen::Matrix3d desired_R_in_frame_id_
const std::string & getLocalVariableName() const
Gets the local variable name if this constraint was configured for a part of a multi-DOF joint.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
bool mobile_target_frame_
True if the target is a non-fixed frame relative to the transform frame.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two orientation constraints are the same.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two joint constraints are the same.
bool hasLinkOffset() const
If the constraint is enabled and the link offset is substantially different than zero.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
bool decideContact(const collision_detection::Contact &contact) const
Function that gets passed into collision checking to allow some collisions.
std::vector< moveit_msgs::OrientationConstraint > orientation_constraints_
Messages corresponding to all internal orientation constraints.
bool configure(const moveit_msgs::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::JointConstraint.
double getJointToleranceAbove() const
Gets the upper tolerance component of the joint constraint.
void print(std::ostream &out=std::cout) const override
Print the constraint data.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
std::string joint_variable_name_
The joint variable name.
bool satisfied
Whether or not the constraint or constraints were satisfied.
std::vector< moveit_msgs::PositionConstraint > position_constraints_
Messages corresponding to all internal position constraints.
virtual void print(std::ostream &out=std::cout) const
Print the constraint data.
const std::string & getJointVariableName() const
Gets the joint variable name, as known to the moveit::core::RobotModel.
Eigen::Isometry3d target_pose_
The target pose transformed into the transform frame.
std::string local_variable_name_
The local variable name for a multi DOF joint, if any.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two constraints are the same. For position constraints this means that:
unsigned int cone_sides_
Storage for the cone sides
Eigen::Isometry3d sensor_pose_
The sensor pose transformed into the transform frame.
std::vector< KinematicConstraintPtr > kinematic_constraints_
Shared pointers to all the member constraints.
bool configure(const moveit_msgs::VisibilityConstraint &vc, const moveit::core::Transforms &tf)
Configure the constraint based on a moveit_msgs::VisibilityConstraint.
JointConstraint(const moveit::core::RobotModelConstPtr &model)
Constructor.
int getParameterizationType() const
VisibilityConstraint(const moveit::core::RobotModelConstPtr &model)
Constructor.
double absolute_x_axis_tolerance_
Eigen::Matrix3d desired_rotation_matrix_
double distance
The distance evaluation from the constraint or constraints.
ConstraintType type_
The type of the constraint.
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
const std::vector< bodies::BodyPtr > & getConstraintRegions() const
Returns all the constraint regions.
Eigen::Matrix3d desired_rotation_matrix_inv_
const moveit::core::JointModel * joint_model_
The joint from the kinematic model for this constraint.
const std::vector< moveit_msgs::PositionConstraint > & getPositionConstraints() const
Get all position constraints in the set.
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
double max_view_angle_
Storage for the max view angle.
bool add(const moveit_msgs::Constraints &c, const moveit::core::Transforms &tf)
Add all known constraints.
const moveit::core::LinkModel * getLinkModel() const
Returns the associated link model, or NULL if not enabled.
const moveit::core::RobotModelConstPtr & getRobotModel() const
double joint_tolerance_below_
Position and tolerance values.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
void clear() override
Clear the stored constraint.
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
void clear() override
Clear the stored constraint.
const Eigen::Vector3d & getLinkOffset() const
Returns the target offset.
void print(std::ostream &out=std::cout) const override
Print the constraint data.
std::string desired_rotation_frame_id_
void clear()
Clear the stored constraints.
const moveit::core::LinkModel * link_model_
The link model constraint subject.
EigenSTL::vector_Vector3d points_
A set of points along the base of the circle.
void print(std::ostream &out=std::cout) const override
Print the constraint data.
~KinematicConstraintSet()
bool configure(const moveit_msgs::PositionConstraint &pc, const moveit::core::Transforms &tf)
Configure the constraint based on a moveit_msgs::PositionConstraint.
void clear() override
Clear the stored constraint.
virtual bool equal(const KinematicConstraint &other, double margin) const =0
Check if two constraints are the same. This means that the types are the same, the subject of the con...
A class that contains many different constraints, and can check RobotState *versus the full set....
virtual ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const =0
Decide whether the constraint is satisfied in the indicated state.
Class for constraints on the orientation of a link.
bool joint_is_continuous_
Whether or not the joint is continuous.
bool equal(const KinematicConstraint &other, double margin) const override
Check if two constraints are the same.
Class for constraints on the visibility relationship between a sensor and a target.
ConstraintType getType() const
Get the type of constraint.
double getXAxisTolerance() const
Gets the X axis tolerance.
MOVEIT_CLASS_FORWARD(KinematicConstraint)
std::string sensor_frame_id_
The sensor frame id.
bool empty() const
Returns whether or not there are any constraints in the set.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
Base class for representing a kinematic constraint.
const Eigen::Matrix3d & getDesiredRotationMatrixInRefFrame() const
The rotation target in the reference frame.
OrientationConstraint(const moveit::core::RobotModelConstPtr &model)
Constructor.
bool mobile_frame_
Whether or not a mobile frame is employed.
virtual void clear()=0
Clear the stored constraint.
EigenSTL::vector_Isometry3d constraint_region_pose_
The constraint region pose vector. All isometries are guaranteed to be valid.
const moveit::core::LinkModel * link_model_
bool mobile_sensor_frame_
True if the sensor is a non-fixed frame relative to the transform frame.
KinematicConstraint(const moveit::core::RobotModelConstPtr &model)
Constructor.
virtual ~KinematicConstraint()
Eigen::Vector3d offset_
The target offset.
void print(std::ostream &out=std::cout) const override
Print the constraint data.
std::vector< moveit_msgs::VisibilityConstraint > visibility_constraints_
Messages corresponding to all internal visibility constraints.
double getConstraintWeight() const
The weight of a constraint is a multiplicative factor associated to the distance computed by the deci...
shapes::Mesh * getVisibilityCone(const moveit::core::RobotState &state) const
Gets a trimesh shape representing the visibility cone.
double getYAxisTolerance() const
Gets the Y axis tolerance.
double getJointToleranceBelow() const
Gets the lower tolerance component of the joint constraint.
bool configure(const moveit_msgs::OrientationConstraint &oc, const moveit::core::Transforms &tf)
Configure the constraint based on a moveit_msgs::OrientationConstraint.
const moveit::core::LinkModel * getLinkModel() const
Gets the subject link model.
double constraint_weight_
The weight of a constraint is a multiplicative factor associated to the distance computed by the deci...
void print(std::ostream &out=std::cout) const
Print the constraint data.
const moveit_msgs::Constraints & getAllConstraints() const
Get all constraints in the set.
double absolute_y_axis_tolerance_
int parameterization_type_
int sensor_view_direction_
Storage for the sensor view direction.
void getMarkers(const moveit::core::RobotState &state, visualization_msgs::MarkerArray &markers) const
Adds markers associated with the visibility cone, sensor and target to the visualization array.
std::string target_frame_id_
The target frame id.
bool mobileReferenceFrame() const
If enabled and the specified frame is a mobile frame, return true. Otherwise, returns false.
const std::string & getReferenceFrame() const
The target frame of the planning_models::Transforms class, for interpreting the rotation frame.
ConstraintType
Enum for representing a constraint.
double getDesiredJointPosition() const
Gets the desired position component of the constraint.
collision_detection::CollisionEnvPtr collision_env_
A copy of the collision robot maintained for collision checking the cone against robot links.
const moveit::core::JointModel * getJointModel() const
Get the joint model for which this constraint operates.
std::vector< bodies::BodyPtr > constraint_region_
The constraint region vector.
KinematicConstraintSet(const moveit::core::RobotModelConstPtr &model)
Constructor.
bool has_offset_
Whether the offset is substantially different than 0.0.
PositionConstraint(const moveit::core::RobotModelConstPtr &model)
Constructor.
void clear() override
Clear the stored constraint.
const std::vector< moveit_msgs::VisibilityConstraint > & getVisibilityConstraints() const
Get all visibility constraints in the set.
std::vector< moveit_msgs::JointConstraint > joint_constraints_
Messages corresponding to all internal joint constraints.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Class for constraints on the XYZ position of a link.
Vec3fX< details::Vec3Data< double > > Vector3d
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
Struct for containing the results of constraint evaluation.
moveit_core
Author(s): Ioan Sucan 
, Sachin Chitta , Acorn Pooley 
autogenerated on Sat May 3 2025 02:25:32