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