41 #include <ompl/base/Constraint.h> 
   46 #include <moveit_msgs/msg/constraints.hpp> 
   71   Bounds(
const std::vector<double>& lower, 
const std::vector<double>& upper);
 
   83   Eigen::VectorXd 
penalty(
const Eigen::Ref<const Eigen::VectorXd>& 
x) 
const;
 
   91   Eigen::VectorXd 
derivative(
const Eigen::Ref<const Eigen::VectorXd>& 
x) 
const;
 
   93   std::size_t 
size() 
const;
 
   96   std::vector<double> lower_, upper_;
 
  126   BaseConstraint(
const moveit::core::RobotModelConstPtr& robot_model, 
const std::string& 
group,
 
  127                  const unsigned int num_dofs, 
const unsigned int num_cons = 3);
 
  134   void init(
const moveit_msgs::msg::Constraints& constraints);
 
  140   void function(
const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::VectorXd> out) 
const override;
 
  147   void jacobian(
const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::MatrixXd> out) 
const override;
 
  155   Eigen::Isometry3d 
forwardKinematics(
const Eigen::Ref<const Eigen::VectorXd>& joint_values) 
const;
 
  180   virtual Eigen::VectorXd 
calcError(
const Eigen::Ref<const Eigen::VectorXd>& ) 
const;
 
  194   virtual Eigen::MatrixXd 
calcErrorJacobian(
const Eigen::Ref<const Eigen::VectorXd>& ) 
const;
 
  260   BoxConstraint(
const moveit::core::RobotModelConstPtr& robot_model, 
const std::string& 
group,
 
  261                 const unsigned int num_dofs);
 
  278   Eigen::VectorXd 
calcError(
const Eigen::Ref<const Eigen::VectorXd>& 
x) 
const override;
 
  292   Eigen::MatrixXd 
calcErrorJacobian(
const Eigen::Ref<const Eigen::VectorXd>& 
x) 
const override;
 
  313                              const unsigned int num_dofs);
 
  321   void function(
const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::VectorXd> out) 
const override;
 
  323   void jacobian(
const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::MatrixXd> out) 
const override;
 
  347   static constexpr 
double EQUALITY_CONSTRAINT_THRESHOLD{ 0.001 };
 
  350   std::vector<bool> is_dim_constrained_;
 
  381                         const unsigned int num_dofs)
 
  401   Eigen::VectorXd 
calcError(
const Eigen::Ref<const Eigen::VectorXd>& 
x) 
const override;
 
  415   Eigen::MatrixXd 
calcErrorJacobian(
const Eigen::Ref<const Eigen::VectorXd>& 
x) 
const override;
 
  441                                                 const std::string& 
group,
 
  442                                                 const moveit_msgs::msg::Constraints& constraints);
 
  451   double t{ std::abs(angle) };
 
  452   Eigen::Matrix3d r_skew;
 
  453   r_skew << 0, -axis[2], axis[1], axis[2], 0, -axis[0], -axis[1], axis[0], 0;
 
  457   c = (1 - 0.5 * t * std::sin(t) / (1 - std::cos(t)));
 
  459   return Eigen::Matrix3d::Identity() - 0.5 * r_skew + (r_skew * r_skew / (t * t)) * 
c;
 
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
 
Abstract base class for different types of constraints, implementations of ompl::base::Constraint.
 
Eigen::Quaterniond target_orientation_
target for equality constraints, nominal value for inequality constraints.
 
virtual void parseConstraintMsg(const moveit_msgs::msg::Constraints &constraints)=0
Parse bounds on position and orientation parameters from MoveIt's constraint message.
 
const std::string & getLinkName()
 
TSStateStorage state_storage_
Thread-safe storage of the robot state.
 
const moveit::core::JointModelGroup * joint_model_group_
 
virtual Eigen::MatrixXd calcErrorJacobian(const Eigen::Ref< const Eigen::VectorXd > &) const
For inequality constraints: calculate the Jacobian for the current parameters that are being constrai...
 
Bounds bounds_
Upper and lower bounds on constrained variables.
 
const Eigen::Quaterniond getTargetOrientation()
 
virtual Eigen::VectorXd calcError(const Eigen::Ref< const Eigen::VectorXd > &) const
For inequality constraints: calculate the value of the parameter that is being constrained by the bou...
 
const Eigen::Vector3d getTargetPosition()
 
Eigen::Isometry3d forwardKinematics(const Eigen::Ref< const Eigen::VectorXd > &joint_values) const
Wrapper for forward kinematics calculated by MoveIt's Robot State.
 
std::string link_name_
Robot link the constraints are applied to.
 
Eigen::MatrixXd robotGeometricJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_values) const
Calculate the robot's geometric Jacobian using MoveIt's Robot State.
 
BaseConstraint(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group, const unsigned int num_dofs, const unsigned int num_cons=3)
Construct a BaseConstraint using 3 num_cons by default because all constraints currently implemented ...
 
Eigen::Vector3d target_position_
target for equality constraints, nominal value for inequality constraints.
 
void init(const moveit_msgs::msg::Constraints &constraints)
Initialize constraint based on message content.
 
void jacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_values, Eigen::Ref< Eigen::MatrixXd > out) const override
Jacobian of the constraint function.
 
Represents upper and lower bound on the elements of a vector.
 
Eigen::VectorXd derivative(const Eigen::Ref< const Eigen::VectorXd > &x) const
Derivative of the penalty function ^ | | -1-1-1 0 0 0 +1+1+1 |---------------------—>
 
Eigen::VectorXd penalty(const Eigen::Ref< const Eigen::VectorXd > &x) const
Distance to region inside bounds.
 
friend std::ostream & operator<<(std::ostream &os, const ompl_interface::Bounds &bounds)
Pretty printing of bounds.
 
Box shaped position constraints.
 
Eigen::MatrixXd calcErrorJacobian(const Eigen::Ref< const Eigen::VectorXd > &x) const override
For inequality constraints: calculate the Jacobian for the current parameters that are being constrai...
 
BoxConstraint(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group, const unsigned int num_dofs)
 
Eigen::VectorXd calcError(const Eigen::Ref< const Eigen::VectorXd > &x) const override
For inequality constraints: calculate the value of the parameter that is being constrained by the bou...
 
void parseConstraintMsg(const moveit_msgs::msg::Constraints &constraints) override
Parse bounds on position parameters from MoveIt's constraint message.
 
Equality constraints on a link's position.
 
void parseConstraintMsg(const moveit_msgs::msg::Constraints &constraints) override
Parse bounds on position parameters from MoveIt's constraint message.
 
void jacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_values, Eigen::Ref< Eigen::MatrixXd > out) const override
 
EqualityPositionConstraint(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group, const unsigned int num_dofs)
 
Orientation constraints parameterized using exponential coordinates.
 
Eigen::MatrixXd calcErrorJacobian(const Eigen::Ref< const Eigen::VectorXd > &x) const override
For inequality constraints: calculate the Jacobian for the current parameters that are being constrai...
 
OrientationConstraint(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group, const unsigned int num_dofs)
 
void parseConstraintMsg(const moveit_msgs::msg::Constraints &constraints) override
Parse bounds on orientation parameters from MoveIt's constraint message.
 
Eigen::VectorXd calcError(const Eigen::Ref< const Eigen::VectorXd > &x) const override
For inequality constraints: calculate the value of the parameter that is being constrained by the bou...
 
Vec3fX< details::Vec3Data< double > > Vector3d
 
The MoveIt interface to OMPL.
 
Bounds orientationConstraintMsgToBoundVector(const moveit_msgs::msg::OrientationConstraint &ori_con)
Extract orientation constraints from the MoveIt message.
 
std::ostream & operator<<(std::ostream &os, const ompl_interface::Bounds &bounds)
Pretty printing of bounds.
 
Eigen::Matrix3d angularVelocityToAngleAxis(const double &angle, const Eigen::Ref< const Eigen::Vector3d > &axis)
Return a matrix to convert angular velocity to angle-axis velocity Based on: https://ethz....
 
MOVEIT_CLASS_FORWARD(ValidStateSampler)
 
ompl::base::ConstraintPtr createOMPLConstraints(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group, const moveit_msgs::msg::Constraints &constraints)
Factory to create constraints based on what is in the MoveIt constraint message.
 
Bounds positionConstraintMsgToBoundVector(const moveit_msgs::msg::PositionConstraint &pos_con)
Extract position constraints from the MoveIt message.