moveit2
The MoveIt Motion Planning Framework for ROS 2.
ompl_constraints.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, KU Leuven
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 KU Leuven 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: Jeroen De Maeyer, Boston Cleek */
36 
37 #pragma once
38 
39 #include <ostream>
40 
41 #include <ompl/base/Constraint.h>
42 
46 #include <moveit_msgs/msg/constraints.hpp>
47 
48 namespace ompl_interface
49 {
53 
67 class Bounds
68 {
69 public:
70  Bounds();
71  Bounds(const std::vector<double>& lower, const std::vector<double>& upper);
83  Eigen::VectorXd penalty(const Eigen::Ref<const Eigen::VectorXd>& x) const;
84 
91  Eigen::VectorXd derivative(const Eigen::Ref<const Eigen::VectorXd>& x) const;
92 
93  std::size_t size() const;
94 
95 private:
96  std::vector<double> lower_, upper_;
97  std::size_t size_;
98 
99  friend std::ostream& operator<<(std::ostream& os, const ompl_interface::Bounds& bounds);
100 };
101 
103 std::ostream& operator<<(std::ostream& os, const ompl_interface::Bounds& bounds);
104 
105 /****************************
106  * Base class for constraints
107  * **************************/
121 class BaseConstraint : public ompl::base::Constraint
122 {
123 public:
126  BaseConstraint(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group,
127  const unsigned int num_dofs, const unsigned int num_cons = 3);
128 
134  void init(const moveit_msgs::msg::Constraints& constraints);
135 
140  void function(const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::VectorXd> out) const override;
141 
147  void jacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::MatrixXd> out) const override;
148 
155  Eigen::Isometry3d forwardKinematics(const Eigen::Ref<const Eigen::VectorXd>& joint_values) const;
156 
163  Eigen::MatrixXd robotGeometricJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values) const;
164 
169  virtual void parseConstraintMsg(const moveit_msgs::msg::Constraints& constraints) = 0;
170 
180  virtual Eigen::VectorXd calcError(const Eigen::Ref<const Eigen::VectorXd>& /*x*/) const;
181 
194  virtual Eigen::MatrixXd calcErrorJacobian(const Eigen::Ref<const Eigen::VectorXd>& /*x*/) const;
195 
196  // the methods below are specifically for debugging and testing
197 
198  const std::string& getLinkName()
199  {
200  return link_name_;
201  }
202 
204  {
205  return target_position_;
206  }
207 
208  const Eigen::Quaterniond getTargetOrientation()
209  {
210  return target_orientation_;
211  }
212 
213 protected:
221 
222  // all attributes below can be considered const as soon as the constraint message is parsed
223  // but I (jeroendm) do not know how to elegantly express this in C++
224  // parsing the constraints message and passing all this data members separately to the constructor
225  // is a solution, but it adds complexity outside this class, which is also not ideal.
226 
228  std::string link_name_;
229 
232 
235 
237  Eigen::Quaterniond target_orientation_;
238 
239 public:
240  // Macro for classes containing fixed size eigen vectors that are dynamically allocated when used.
241  // https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
243 };
244 
245 /******************************************
246  * Box constraint
247  * ****************************************/
258 {
259 public:
260  BoxConstraint(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group,
261  const unsigned int num_dofs);
262 
267  void parseConstraintMsg(const moveit_msgs::msg::Constraints& constraints) override;
268 
278  Eigen::VectorXd calcError(const Eigen::Ref<const Eigen::VectorXd>& x) const override;
279 
292  Eigen::MatrixXd calcErrorJacobian(const Eigen::Ref<const Eigen::VectorXd>& x) const override;
293 };
294 
295 /******************************************
296  * Equality Position Constraints
297  * ****************************************/
310 {
311 public:
312  EqualityPositionConstraint(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group,
313  const unsigned int num_dofs);
314 
319  void parseConstraintMsg(const moveit_msgs::msg::Constraints& constraints) override;
320 
321  void function(const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::VectorXd> out) const override;
322 
323  void jacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values, Eigen::Ref<Eigen::MatrixXd> out) const override;
324 
325 private:
347  static constexpr double EQUALITY_CONSTRAINT_THRESHOLD{ 0.001 };
348 
350  std::vector<bool> is_dim_constrained_;
351 };
352 
353 /******************************************
354  * Orientation constraints
355  * ****************************************/
378 {
379 public:
380  OrientationConstraint(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group,
381  const unsigned int num_dofs)
382  : BaseConstraint(robot_model, group, num_dofs)
383  {
384  }
385 
390  void parseConstraintMsg(const moveit_msgs::msg::Constraints& constraints) override;
391 
401  Eigen::VectorXd calcError(const Eigen::Ref<const Eigen::VectorXd>& x) const override;
402 
415  Eigen::MatrixXd calcErrorJacobian(const Eigen::Ref<const Eigen::VectorXd>& x) const override;
416 };
417 
424 Bounds positionConstraintMsgToBoundVector(const moveit_msgs::msg::PositionConstraint& pos_con);
425 
437 Bounds orientationConstraintMsgToBoundVector(const moveit_msgs::msg::OrientationConstraint& ori_con);
438 
440 ompl::base::ConstraintPtr createOMPLConstraints(const moveit::core::RobotModelConstPtr& robot_model,
441  const std::string& group,
442  const moveit_msgs::msg::Constraints& constraints);
443 
449 inline Eigen::Matrix3d angularVelocityToAngleAxis(double angle, const Eigen::Ref<const Eigen::Vector3d>& axis)
450 {
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;
454  r_skew *= angle;
455 
456  double c;
457  c = (1 - 0.5 * t * std::sin(t) / (1 - std::cos(t)));
458 
459  return Eigen::Matrix3d::Identity() - 0.5 * r_skew + (r_skew * r_skew / (t * t)) * c;
460 }
461 
462 } // namespace ompl_interface
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 |---------------------—>
std::size_t size() const
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
Definition: fcl_compat.h:89
The MoveIt interface to OMPL.
Bounds orientationConstraintMsgToBoundVector(const moveit_msgs::msg::OrientationConstraint &ori_con)
Extract orientation constraints from the MoveIt message.
MOVEIT_CLASS_FORWARD(ConstraintApproximation)
std::ostream & operator<<(std::ostream &os, const ompl_interface::Bounds &bounds)
Pretty printing of bounds.
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.
Eigen::Matrix3d angularVelocityToAngleAxis(double angle, const Eigen::Ref< const Eigen::Vector3d > &axis)
Return a matrix to convert angular velocity to angle-axis velocity Based on: https://ethz....
Bounds positionConstraintMsgToBoundVector(const moveit_msgs::msg::PositionConstraint &pos_con)
Extract position constraints from the MoveIt message.