moveit2
The MoveIt Motion Planning Framework for ROS 2.
ompl_constraints.cpp
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 #include <algorithm>
38 #include <iterator>
39 
41 
42 #include <tf2_eigen/tf2_eigen.hpp>
43 
44 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_planners_ompl.ompl_constraints");
45 
46 namespace ompl_interface
47 {
48 Bounds::Bounds() : size_(0)
49 {
50 }
51 
52 Bounds::Bounds(const std::vector<double>& lower, const std::vector<double>& upper)
53  : lower_(lower), upper_(upper), size_(lower.size())
54 {
55  // how to report this in release mode??
56  assert(lower_.size() == upper_.size());
57 }
58 
59 Eigen::VectorXd Bounds::penalty(const Eigen::Ref<const Eigen::VectorXd>& x) const
60 {
61  assert((long)lower_.size() == x.size());
62  Eigen::VectorXd penalty(x.size());
63 
64  for (unsigned int i = 0; i < x.size(); ++i)
65  {
66  if (x[i] < lower_.at(i))
67  {
68  penalty[i] = lower_.at(i) - x[i];
69  }
70  else if (x[i] > upper_.at(i))
71  {
72  penalty[i] = x[i] - upper_.at(i);
73  }
74  else
75  {
76  penalty[i] = 0.0;
77  }
78  }
79  return penalty;
80 }
81 
82 Eigen::VectorXd Bounds::derivative(const Eigen::Ref<const Eigen::VectorXd>& x) const
83 {
84  assert((long)lower_.size() == x.size());
85  Eigen::VectorXd derivative(x.size());
86 
87  for (unsigned int i = 0; i < x.size(); ++i)
88  {
89  if (x[i] < lower_.at(i))
90  {
91  derivative[i] = -1.0;
92  }
93  else if (x[i] > upper_.at(i))
94  {
95  derivative[i] = 1.0;
96  }
97  else
98  {
99  derivative[i] = 0.0;
100  }
101  }
102  return derivative;
103 }
104 
105 std::size_t Bounds::size() const
106 {
107  return size_;
108 }
109 
110 std::ostream& operator<<(std::ostream& os, const ompl_interface::Bounds& bounds)
111 {
112  os << "Bounds:\n";
113  for (std::size_t i{ 0 }; i < bounds.size(); ++i)
114  {
115  os << "( " << bounds.lower_[i] << ", " << bounds.upper_[i] << " )\n";
116  }
117  return os;
118 }
119 
120 /****************************
121  * Base class for constraints
122  * **************************/
123 BaseConstraint::BaseConstraint(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group,
124  const unsigned int num_dofs, const unsigned int num_cons_)
125  : ompl::base::Constraint(num_dofs, num_cons_)
126  , state_storage_(robot_model)
127  , joint_model_group_(robot_model->getJointModelGroup(group))
128 
129 {
130 }
131 
132 void BaseConstraint::init(const moveit_msgs::msg::Constraints& constraints)
133 {
134  parseConstraintMsg(constraints);
135 }
136 
137 void BaseConstraint::function(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
138  Eigen::Ref<Eigen::VectorXd> out) const
139 {
140  const Eigen::VectorXd current_values = calcError(joint_values);
141  out = bounds_.penalty(current_values);
142 }
143 
144 void BaseConstraint::jacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
145  Eigen::Ref<Eigen::MatrixXd> out) const
146 {
147  const Eigen::VectorXd constraint_error = calcError(joint_values);
148  const Eigen::VectorXd constraint_derivative = bounds_.derivative(constraint_error);
149  const Eigen::MatrixXd robot_jacobian = calcErrorJacobian(joint_values);
150  for (std::size_t i = 0; i < bounds_.size(); ++i)
151  {
152  out.row(i) = constraint_derivative[i] * robot_jacobian.row(i);
153  }
154 }
155 
156 Eigen::Isometry3d BaseConstraint::forwardKinematics(const Eigen::Ref<const Eigen::VectorXd>& joint_values) const
157 {
159  robot_state->setJointGroupPositions(joint_model_group_, joint_values);
160  return robot_state->getGlobalLinkTransform(link_name_);
161 }
162 
163 Eigen::MatrixXd BaseConstraint::robotGeometricJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values) const
164 {
166  robot_state->setJointGroupPositions(joint_model_group_, joint_values);
167  Eigen::MatrixXd jacobian;
168  // return value (success) not used, could return a garbage jacobian.
170  Eigen::Vector3d(0.0, 0.0, 0.0), jacobian);
171  return jacobian;
172 }
173 
174 Eigen::VectorXd BaseConstraint::calcError(const Eigen::Ref<const Eigen::VectorXd>& /*x*/) const
175 {
176  RCLCPP_WARN_STREAM(LOGGER,
177  "BaseConstraint: Constraint method calcError was not overridden, so it should not be used.");
178  return Eigen::VectorXd::Zero(getCoDimension());
179 }
180 
181 Eigen::MatrixXd BaseConstraint::calcErrorJacobian(const Eigen::Ref<const Eigen::VectorXd>& /*x*/) const
182 {
183  RCLCPP_WARN_STREAM(
184  LOGGER, "BaseConstraint: Constraint method calcErrorJacobian was not overridden, so it should not be used.");
185  return Eigen::MatrixXd::Zero(getCoDimension(), n_);
186 }
187 
188 /******************************************
189  * Position constraints
190  * ****************************************/
191 BoxConstraint::BoxConstraint(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group,
192  const unsigned int num_dofs)
193  : BaseConstraint(robot_model, group, num_dofs)
194 {
195 }
196 
197 void BoxConstraint::parseConstraintMsg(const moveit_msgs::msg::Constraints& constraints)
198 {
199  assert(bounds_.size() == 0);
200  bounds_ = positionConstraintMsgToBoundVector(constraints.position_constraints.at(0));
201 
202  // extract target position and orientation
203  geometry_msgs::msg::Point position =
204  constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
205 
206  target_position_ << position.x, position.y, position.z;
207 
208  tf2::fromMsg(constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).orientation,
210 
211  link_name_ = constraints.position_constraints.at(0).link_name;
212 }
213 
214 Eigen::VectorXd BoxConstraint::calcError(const Eigen::Ref<const Eigen::VectorXd>& x) const
215 {
216  return target_orientation_.matrix().transpose() * (forwardKinematics(x).translation() - target_position_);
217 }
218 
219 Eigen::MatrixXd BoxConstraint::calcErrorJacobian(const Eigen::Ref<const Eigen::VectorXd>& x) const
220 {
221  return target_orientation_.matrix().transpose() * robotGeometricJacobian(x).topRows(3);
222 }
223 
224 /******************************************
225  * Equality constraints
226  * ****************************************/
227 EqualityPositionConstraint::EqualityPositionConstraint(const moveit::core::RobotModelConstPtr& robot_model,
228  const std::string& group, const unsigned int num_dofs)
229  : BaseConstraint(robot_model, group, num_dofs)
230 {
231 }
232 
233 void EqualityPositionConstraint::parseConstraintMsg(const moveit_msgs::msg::Constraints& constraints)
234 {
235  const auto dims = constraints.position_constraints.at(0).constraint_region.primitives.at(0).dimensions;
236 
237  is_dim_constrained_ = { false, false, false };
238  for (std::size_t i = 0; i < dims.size(); ++i)
239  {
240  if (dims.at(i) < EQUALITY_CONSTRAINT_THRESHOLD)
241  {
242  if (dims.at(i) < getTolerance())
243  {
244  RCLCPP_ERROR_STREAM(
245  LOGGER,
246  "Dimension: " << i
247  << " of position constraint is smaller than the tolerance used to evaluate the constraints. "
248  "This will make all states invalid and planning will fail. Please use a value between: "
249  << getTolerance() << " and " << EQUALITY_CONSTRAINT_THRESHOLD);
250  }
251 
252  is_dim_constrained_.at(i) = true;
253  }
254  }
255 
256  // extract target position and orientation
257  geometry_msgs::msg::Point position =
258  constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
259 
260  target_position_ << position.x, position.y, position.z;
261 
262  tf2::fromMsg(constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).orientation,
264 
265  link_name_ = constraints.position_constraints.at(0).link_name;
266 }
267 
268 void EqualityPositionConstraint::function(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
269  Eigen::Ref<Eigen::VectorXd> out) const
270 {
271  Eigen::Vector3d error =
272  target_orientation_.matrix().transpose() * (forwardKinematics(joint_values).translation() - target_position_);
273  for (std::size_t dim = 0; dim < 3; ++dim)
274  {
275  if (is_dim_constrained_.at(dim))
276  {
277  out[dim] = error[dim]; // equality constraint dimension
278  }
279  else
280  {
281  out[dim] = 0.0; // unbounded dimension
282  }
283  }
284 }
285 
286 void EqualityPositionConstraint::jacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
287  Eigen::Ref<Eigen::MatrixXd> out) const
288 {
289  out.setZero();
290  Eigen::MatrixXd jac = target_orientation_.matrix().transpose() * robotGeometricJacobian(joint_values).topRows(3);
291  for (std::size_t dim = 0; dim < 3; ++dim)
292  {
293  if (is_dim_constrained_.at(dim))
294  {
295  out.row(dim) = jac.row(dim); // equality constraint dimension
296  }
297  }
298 }
299 
300 /******************************************
301  * Orientation constraints
302  * ****************************************/
303 void OrientationConstraint::parseConstraintMsg(const moveit_msgs::msg::Constraints& constraints)
304 {
305  bounds_ = orientationConstraintMsgToBoundVector(constraints.orientation_constraints.at(0));
306 
307  tf2::fromMsg(constraints.orientation_constraints.at(0).orientation, target_orientation_);
308 
309  link_name_ = constraints.orientation_constraints.at(0).link_name;
310 }
311 
312 Eigen::VectorXd OrientationConstraint::calcError(const Eigen::Ref<const Eigen::VectorXd>& x) const
313 {
314  Eigen::Matrix3d orientation_difference = forwardKinematics(x).linear().transpose() * target_orientation_;
315  Eigen::AngleAxisd aa(orientation_difference);
316  return aa.axis() * aa.angle();
317 }
318 
319 Eigen::MatrixXd OrientationConstraint::calcErrorJacobian(const Eigen::Ref<const Eigen::VectorXd>& x) const
320 {
321  Eigen::Matrix3d orientation_difference = forwardKinematics(x).linear().transpose() * target_orientation_;
322  Eigen::AngleAxisd aa{ orientation_difference };
323  return -angularVelocityToAngleAxis(aa.angle(), aa.axis()) * robotGeometricJacobian(x).bottomRows(3);
324 }
325 
326 /************************************
327  * MoveIt constraint message parsing
328  * **********************************/
329 Bounds positionConstraintMsgToBoundVector(const moveit_msgs::msg::PositionConstraint& pos_con)
330 {
331  auto dims = pos_con.constraint_region.primitives.at(0).dimensions;
332 
333  // dimension of -1 signifies unconstrained parameter, so set to infinity
334  for (auto& dim : dims)
335  {
336  if (dim == -1)
337  {
338  dim = std::numeric_limits<double>::infinity();
339  }
340  }
341 
342  return { { -dims.at(0) / 2.0, -dims.at(1) / 2.0, -dims.at(2) / 2.0 },
343  { dims.at(0) / 2.0, dims.at(1) / 2.0, dims.at(2) / 2.0 } };
344 }
345 
346 Bounds orientationConstraintMsgToBoundVector(const moveit_msgs::msg::OrientationConstraint& ori_con)
347 {
348  std::vector<double> dims = { ori_con.absolute_x_axis_tolerance, ori_con.absolute_y_axis_tolerance,
349  ori_con.absolute_z_axis_tolerance };
350 
351  // dimension of -1 signifies unconstrained parameter, so set to infinity
352  for (auto& dim : dims)
353  {
354  if (dim == -1)
355  dim = std::numeric_limits<double>::infinity();
356  }
357  return { { -dims[0], -dims[1], -dims[2] }, { dims[0], dims[1], dims[2] } };
358 }
359 
360 /******************************************
361  * OMPL Constraints Factory
362  * ****************************************/
363 ompl::base::ConstraintPtr createOMPLConstraints(const moveit::core::RobotModelConstPtr& robot_model,
364  const std::string& group,
365  const moveit_msgs::msg::Constraints& constraints)
366 {
367  // TODO(bostoncleek): does this reach the end w/o a return ?
368 
369  const std::size_t num_dofs = robot_model->getJointModelGroup(group)->getVariableCount();
370  const std::size_t num_pos_con = constraints.position_constraints.size();
371  const std::size_t num_ori_con = constraints.orientation_constraints.size();
372 
373  // This factory method contains template code to support position and/or orientation constraints.
374  // If the specified constraints are invalid, a nullptr is returned.
375  std::vector<ompl::base::ConstraintPtr> ompl_constraints;
376  if (num_pos_con > 1)
377  {
378  RCLCPP_WARN(LOGGER, "Only a single position constraint is supported. Using the first one.");
379  }
380  if (num_ori_con > 1)
381  {
382  RCLCPP_WARN(LOGGER, "Only a single orientation constraint is supported. Using the first one.");
383  }
384  if (num_pos_con > 0)
385  {
386  BaseConstraintPtr pos_con;
387  if (constraints.name == "use_equality_constraints")
388  {
389  pos_con = std::make_shared<EqualityPositionConstraint>(robot_model, group, num_dofs);
390  }
391  else
392  {
393  pos_con = std::make_shared<BoxConstraint>(robot_model, group, num_dofs);
394  }
395  pos_con->init(constraints);
396  ompl_constraints.emplace_back(pos_con);
397  }
398  if (num_ori_con > 0)
399  {
400  auto ori_con = std::make_shared<OrientationConstraint>(robot_model, group, num_dofs);
401  ori_con->init(constraints);
402  ompl_constraints.emplace_back(ori_con);
403  }
404  if (num_pos_con < 1 && num_ori_con < 1)
405  {
406  RCLCPP_ERROR(LOGGER, "No path constraints found in planning request.");
407  return nullptr;
408  }
409  return std::make_shared<ompl::base::ConstraintIntersection>(num_dofs, ompl_constraints);
410 }
411 } // namespace ompl_interface
const LinkModel * getLinkModel(const std::string &link) const
Get a link by its name. Throw an exception if the link is not part of this group.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1339
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
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.
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.
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...
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.
void function(const Eigen::Ref< const Eigen::VectorXd > &joint_values, Eigen::Ref< Eigen::VectorXd > out) const override
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.
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.
void function(const Eigen::Ref< const Eigen::VectorXd > &joint_values, Eigen::Ref< Eigen::VectorXd > out) const override
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)
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...
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...
moveit::core::RobotState * getStateStorage() const
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.
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....
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.
x
Definition: pick.py:64