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