moveit2
The MoveIt Motion Planning Framework for ROS 2.
kinematic_constraint.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
44 
45 #include <geometric_shapes/bodies.h>
46 #include <moveit_msgs/msg/constraints.hpp>
47 
48 #include <iostream>
49 #include <vector>
50 
53 {
56 {
65  ConstraintEvaluationResult(bool result_satisfied = false, double dist = 0.0)
66  : satisfied(result_satisfied), distance(dist)
67  {
68  }
69 
70  bool satisfied;
71  double distance;
72 };
73 
74 MOVEIT_CLASS_FORWARD(KinematicConstraint); // Defines KinematicConstraintPtr, ConstPtr, WeakPtr... etc
75 
78 {
79 public:
82  {
88  };
89 
95  KinematicConstraint(const moveit::core::RobotModelConstPtr& model);
97 
99  virtual void clear() = 0;
100 
109  virtual ConstraintEvaluationResult decide(const moveit::core::RobotState& state, bool verbose = false) const = 0;
110 
116  virtual bool enabled() const = 0;
117 
129  virtual bool equal(const KinematicConstraint& other, double margin) const = 0;
130 
138  {
139  return type_;
140  }
141 
147  virtual void print(std::ostream& /*unused*/ = std::cout) const
148  {
149  }
150 
158  double getConstraintWeight() const
159  {
160  return constraint_weight_;
161  }
162 
169  const moveit::core::RobotModelConstPtr& getRobotModel() const
170  {
171  return robot_model_;
172  }
173 
174 protected:
176  moveit::core::RobotModelConstPtr robot_model_;
179 };
180 
181 MOVEIT_CLASS_FORWARD(JointConstraint); // Defines JointConstraintPtr, ConstPtr, WeakPtr... etc
182 
203 {
204 public:
210  JointConstraint(const moveit::core::RobotModelConstPtr& model)
212  {
214  }
215 
229  bool configure(const moveit_msgs::msg::JointConstraint& jc);
230 
246  bool equal(const KinematicConstraint& other, double margin) const override;
247 
248  ConstraintEvaluationResult decide(const moveit::core::RobotState& state, bool verbose = false) const override;
249  bool enabled() const override;
250  void clear() override;
251  void print(std::ostream& out = std::cout) const override;
252 
259  {
260  return joint_model_;
261  }
270  const std::string& getLocalVariableName() const
271  {
272  return local_variable_name_;
273  }
274 
282  const std::string& getJointVariableName() const
283  {
284  return joint_variable_name_;
285  }
286 
288  {
289  return joint_variable_index_;
290  }
291 
298  double getDesiredJointPosition() const
299  {
300  return joint_position_;
301  }
302 
309  double getJointToleranceAbove() const
310  {
311  return joint_tolerance_above_;
312  }
313 
320  double getJointToleranceBelow() const
321  {
322  return joint_tolerance_below_;
323  }
324 
325 protected:
328  std::string local_variable_name_;
329  std::string joint_variable_name_;
332 };
333 
334 MOVEIT_CLASS_FORWARD(OrientationConstraint); // Defines OrientationConstraintPtr, ConstPtr, WeakPtr... etc
335 
355 {
356 public:
358 
359 public:
365  OrientationConstraint(const moveit::core::RobotModelConstPtr& model)
366  : KinematicConstraint(model), link_model_(nullptr)
367  {
369  }
370 
384  bool configure(const moveit_msgs::msg::OrientationConstraint& oc, const moveit::core::Transforms& tf);
385 
402  bool equal(const KinematicConstraint& other, double margin) const override;
403 
404  void clear() override;
405  ConstraintEvaluationResult decide(const moveit::core::RobotState& state, bool verbose = false) const override;
406  bool enabled() const override;
407  void print(std::ostream& out = std::cout) const override;
408 
416  {
417  return link_model_;
418  }
419 
426  const std::string& getReferenceFrame() const
427  {
429  }
430 
437  bool mobileReferenceFrame() const
438  {
439  return mobile_frame_;
440  }
441 
449  const Eigen::Matrix3d& getDesiredRotationMatrixInRefFrame() const
450  {
451  // validity of the rotation matrix is enforced in configure()
452  return desired_R_in_frame_id_;
453  }
454 
462  const Eigen::Matrix3d& getDesiredRotationMatrix() const
463  {
464  // validity of the rotation matrix is enforced in configure()
466  }
467 
474  double getXAxisTolerance() const
475  {
477  }
478 
485  double getYAxisTolerance() const
486  {
488  }
489 
496  double getZAxisTolerance() const
497  {
499  }
500 
502  {
503  return parameterization_type_;
504  }
505 
506 protected:
508  Eigen::Matrix3d desired_R_in_frame_id_;
509  Eigen::Matrix3d desired_rotation_matrix_;
516 };
517 
518 MOVEIT_CLASS_FORWARD(PositionConstraint); // Defines PositionConstraintPtr, ConstPtr, WeakPtr... etc
519 
534 {
535 public:
537 
538 public:
544  PositionConstraint(const moveit::core::RobotModelConstPtr& model) : KinematicConstraint(model), link_model_(nullptr)
545  {
547  }
548 
565  bool configure(const moveit_msgs::msg::PositionConstraint& pc, const moveit::core::Transforms& tf);
566 
590  bool equal(const KinematicConstraint& other, double margin) const override;
591 
592  void clear() override;
593  ConstraintEvaluationResult decide(const moveit::core::RobotState& state, bool verbose = false) const override;
594  bool enabled() const override;
595  void print(std::ostream& out = std::cout) const override;
596 
604  {
605  return link_model_;
606  }
607 
615  {
616  return offset_;
617  }
618 
626  bool hasLinkOffset() const
627  {
628  if (!enabled())
629  return false;
630  return has_offset_;
631  }
632 
639  const std::vector<bodies::BodyPtr>& getConstraintRegions() const
640  {
641  return constraint_region_;
642  }
643 
650  const std::string& getReferenceFrame() const
651  {
652  return constraint_frame_id_;
653  }
654 
662  bool mobileReferenceFrame() const
663  {
664  if (!enabled())
665  return false;
666  return mobile_frame_;
667  }
668 
669 protected:
671  bool has_offset_;
672  std::vector<bodies::BodyPtr> constraint_region_;
674  EigenSTL::vector_Isometry3d constraint_region_pose_;
676  std::string constraint_frame_id_;
678 };
679 
680 MOVEIT_CLASS_FORWARD(VisibilityConstraint); // Defines VisibilityConstraintPtr, ConstPtr, WeakPtr... etc
681 
780 {
781 public:
783 
784 public:
790  VisibilityConstraint(const moveit::core::RobotModelConstPtr& model);
791 
808  bool configure(const moveit_msgs::msg::VisibilityConstraint& vc, const moveit::core::Transforms& tf);
809 
827  bool equal(const KinematicConstraint& other, double margin) const override;
828  void clear() override;
829 
838  shapes::Mesh* getVisibilityCone(const Eigen::Isometry3d& tform_world_to_sensor,
839  const Eigen::Isometry3d& tform_world_to_target) const;
840 
852  void getMarkers(const moveit::core::RobotState& state, visualization_msgs::msg::MarkerArray& markers) const;
853 
854  bool enabled() const override;
855  ConstraintEvaluationResult decide(const moveit::core::RobotState& state, bool verbose = false) const override;
856  void print(std::ostream& out = std::cout) const override;
857 
858 protected:
868  bool decideContact(const collision_detection::Contact& contact) const;
869 
870  moveit::core::RobotModelConstPtr robot_model_;
873  std::string target_frame_id_;
874  std::string sensor_frame_id_;
875  Eigen::Isometry3d sensor_pose_;
877  Eigen::Isometry3d target_pose_;
878  unsigned int cone_sides_;
879  EigenSTL::vector_Vector3d points_;
880  double target_radius_;
883 };
884 
885 MOVEIT_CLASS_FORWARD(KinematicConstraintSet); // Defines KinematicConstraintSetPtr, ConstPtr, WeakPtr... etc
886 
896 {
897 public:
899 
900 public:
906  KinematicConstraintSet(const moveit::core::RobotModelConstPtr& model) : robot_model_(model)
907  {
908  }
909 
911  {
912  clear();
913  }
914 
916  void clear();
917 
928  bool add(const moveit_msgs::msg::Constraints& c, const moveit::core::Transforms& tf);
929 
937  bool add(const std::vector<moveit_msgs::msg::JointConstraint>& jc);
938 
946  bool add(const std::vector<moveit_msgs::msg::PositionConstraint>& pc, const moveit::core::Transforms& tf);
947 
955  bool add(const std::vector<moveit_msgs::msg::OrientationConstraint>& oc, const moveit::core::Transforms& tf);
956 
964  bool add(const std::vector<moveit_msgs::msg::VisibilityConstraint>& vc, const moveit::core::Transforms& tf);
965 
977  ConstraintEvaluationResult decide(const moveit::core::RobotState& state, bool verbose = false) const;
978 
998  std::vector<ConstraintEvaluationResult>& results, bool verbose = false) const;
999 
1015  bool equal(const KinematicConstraintSet& other, double margin) const;
1016 
1022  void print(std::ostream& out = std::cout) const;
1023 
1030  const std::vector<moveit_msgs::msg::PositionConstraint>& getPositionConstraints() const
1031  {
1032  return position_constraints_;
1033  }
1034 
1041  const std::vector<moveit_msgs::msg::OrientationConstraint>& getOrientationConstraints() const
1042  {
1043  return orientation_constraints_;
1044  }
1045 
1052  const std::vector<moveit_msgs::msg::JointConstraint>& getJointConstraints() const
1053  {
1054  return joint_constraints_;
1055  }
1056 
1063  const std::vector<moveit_msgs::msg::VisibilityConstraint>& getVisibilityConstraints() const
1064  {
1065  return visibility_constraints_;
1066  }
1067 
1074  const moveit_msgs::msg::Constraints& getAllConstraints() const
1075  {
1076  return all_constraints_;
1077  }
1078 
1085  bool empty() const
1086  {
1087  return kinematic_constraints_.empty();
1088  }
1089 
1090 protected:
1091  moveit::core::RobotModelConstPtr robot_model_;
1092  std::vector<KinematicConstraintPtr>
1095  std::vector<moveit_msgs::msg::JointConstraint> joint_constraints_;
1097  std::vector<moveit_msgs::msg::PositionConstraint> position_constraints_;
1099  std::vector<moveit_msgs::msg::OrientationConstraint> orientation_constraints_;
1102  std::vector<moveit_msgs::msg::VisibilityConstraint> visibility_constraints_;
1105  moveit_msgs::msg::Constraints all_constraints_;
1106 };
1107 } // namespace kinematic_constraints
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.
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.
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.
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.
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.
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.
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 or tf frame.
bool mobileReferenceFrame() const
Whether or not a mobile reference frame is being employed.
double getXAxisTolerance() const
Gets the X axis tolerance.
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.
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.
const Eigen::Matrix3d & getDesiredRotationMatrixInRefFrame() const
The rotation target in the reference frame.
bool enabled() const override
This function returns true if this constraint is configured and able to decide whether states do meet...
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.
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.
moveit::core::RobotModelConstPtr robot_model_
A copy of the robot model used to create collision environments to check the cone against robot links...
shapes::Mesh * getVisibilityCone(const Eigen::Isometry3d &tform_world_to_sensor, const Eigen::Isometry3d &tform_world_to_target) const
Gets a trimesh shape representing the visibility cone.
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.
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.
unsigned int cone_sides_
Storage for the cone sides
bool decideContact(const collision_detection::Contact &contact) const
Function that gets passed into collision checking to allow some collisions.
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.
Definition: link_model.hpp:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.hpp:90
Provides an implementation of a snapshot of a transform tree that can be easily queried for transform...
Definition: transforms.hpp:59
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.hpp:89
Representation and evaluation of kinematic constraints.
MOVEIT_CLASS_FORWARD(KinematicConstraint)
Definition of a contact point.
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.