43#include <tf2_eigen/tf2_eigen.hpp> 
   59Bounds::Bounds(
const std::vector<double>& lower, 
const std::vector<double>& upper)
 
   60  : lower_(lower), upper_(upper), size_(lower.size())
 
   63  assert(lower_.size() == upper_.size());
 
 
   68  assert(
static_cast<long>(lower_.size()) == x.size());
 
   69  Eigen::VectorXd 
penalty(x.size());
 
   71  for (
unsigned int i = 0; i < x.size(); ++i)
 
   73    if (x[i] < lower_.at(i))
 
   75      penalty[i] = lower_.at(i) - x[i];
 
   77    else if (x[i] > upper_.at(i))
 
   79      penalty[i] = x[i] - upper_.at(i);
 
 
   91  assert(
static_cast<long>(lower_.size()) == x.size());
 
   94  for (
unsigned int i = 0; i < x.size(); ++i)
 
   96    if (x[i] < lower_.at(i))
 
  100    else if (x[i] > upper_.at(i))
 
 
  120  for (std::size_t i{ 0 }; i < bounds.
size(); ++i)
 
  122    os << 
"( " << bounds.lower_[i] << 
", " << bounds.upper_[i] << 
" )\n";
 
 
  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))
 
 
  145                              Eigen::Ref<Eigen::VectorXd> out)
 const 
  147  const Eigen::VectorXd current_values = 
calcError(joint_values);
 
 
  152                              Eigen::Ref<Eigen::MatrixXd> out)
 const 
  154  const Eigen::VectorXd constraint_error = 
calcError(joint_values);
 
  155  const Eigen::VectorXd constraint_derivative = 
bounds_.
derivative(constraint_error);
 
  159    out.row(i) = constraint_derivative[i] * robot_jacobian.row(i);
 
 
  177                           Eigen::Vector3d(0.0, 0.0, 0.0), 
jacobian);
 
 
  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());
 
 
  191      getLogger(), 
"BaseConstraint: Constraint method calcErrorJacobian was not overridden, so it should not be used.");
 
  192  return Eigen::MatrixXd::Zero(getCoDimension(), n_);
 
 
  199                             const unsigned int num_dofs)
 
 
  210  geometry_msgs::msg::Point position =
 
  211      constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
 
  215  tf2::fromMsg(constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).orientation,
 
  218  link_name_ = constraints.position_constraints.at(0).link_name;
 
 
  235                                                       const std::string& group, 
const unsigned int num_dofs)
 
 
  242  const auto dims = constraints.position_constraints.at(0).constraint_region.primitives.at(0).dimensions;
 
  244  is_dim_constrained_ = { 
false, 
false, 
false };
 
  245  for (std::size_t i = 0; i < dims.size(); ++i)
 
  247    if (dims.at(i) < EQUALITY_CONSTRAINT_THRESHOLD)
 
  249      if (dims.at(i) < getTolerance())
 
  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);
 
  259      is_dim_constrained_.at(i) = 
true;
 
  264  geometry_msgs::msg::Point position =
 
  265      constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
 
  269  tf2::fromMsg(constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).orientation,
 
  272  link_name_ = constraints.position_constraints.at(0).link_name;
 
 
  276                                          Eigen::Ref<Eigen::VectorXd> out)
 const 
  278  Eigen::Vector3d error =
 
  280  for (std::size_t dim = 0; dim < 3; ++dim)
 
  282    if (is_dim_constrained_.at(dim))
 
  284      out[dim] = error[dim];  
 
 
  294                                          Eigen::Ref<Eigen::MatrixXd> out)
 const 
  298  for (std::size_t dim = 0; dim < 3; ++dim)
 
  300    if (is_dim_constrained_.at(dim))
 
  302      out.row(dim) = jac.row(dim);  
 
 
  316  link_name_ = constraints.orientation_constraints.at(0).link_name;
 
 
  322  Eigen::AngleAxisd aa(orientation_difference);
 
  323  return aa.axis() * aa.angle();
 
 
  329  Eigen::AngleAxisd aa{ orientation_difference };
 
 
  338  auto dims = pos_con.constraint_region.primitives.at(0).dimensions;
 
  341  for (
auto& dim : dims)
 
  345      dim = std::numeric_limits<double>::infinity();
 
  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 } };
 
 
  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 };
 
  359  for (
auto& dim : dims)
 
  362      dim = std::numeric_limits<double>::infinity();
 
  364  return { { -dims[0], -dims[1], -dims[2] }, { dims[0], dims[1], dims[2] } };
 
 
  371                                                const std::string& group,
 
  372                                                const moveit_msgs::msg::Constraints& constraints)
 
  376  std::vector<ompl::base::ConstraintPtr> ompl_constraints;
 
  377  const std::size_t num_dofs = robot_model->getJointModelGroup(group)->getVariableCount();
 
  380  if (!constraints.position_constraints.empty())
 
  382    if (constraints.position_constraints.size() > 1)
 
  384      RCLCPP_WARN(getLogger(), 
"Only a single position constraint is supported. Using the first one.");
 
  387    const auto& primitives = constraints.position_constraints.at(0).constraint_region.primitives;
 
  388    if (primitives.size() > 1)
 
  390      RCLCPP_WARN(getLogger(), 
"Only a single position primitive is supported. Using the first one.");
 
  392    if (primitives.empty() || primitives.at(0).type != shape_msgs::msg::SolidPrimitive::BOX)
 
  394      RCLCPP_ERROR(getLogger(), 
"Unable to plan with the requested position constraint. " 
  395                                "Only BOX primitive shapes are supported as constraint region.");
 
  399      BaseConstraintPtr pos_con;
 
  400      if (constraints.name == 
"use_equality_constraints")
 
  402        pos_con = std::make_shared<EqualityPositionConstraint>(robot_model, group, num_dofs);
 
  406        pos_con = std::make_shared<BoxConstraint>(robot_model, group, num_dofs);
 
  408      pos_con->init(constraints);
 
  409      ompl_constraints.emplace_back(pos_con);
 
  414  if (!constraints.orientation_constraints.empty())
 
  416    if (constraints.orientation_constraints.size() > 1)
 
  418      RCLCPP_WARN(getLogger(), 
"Only a single orientation constraint is supported. Using the first one.");
 
  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);
 
  427  if (ompl_constraints.empty())
 
  429    RCLCPP_ERROR(getLogger(), 
"Failed to parse any supported path constraints from planning request.");
 
  433  return std::make_shared<ompl::base::ConstraintIntersection>(num_dofs, ompl_constraints);
 
 
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.
 
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 |---------------------—>
 
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()
 
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
 
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.