42 #include <tf2_eigen/tf2_eigen.hpp> 
   44 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_planners_ompl.ompl_constraints");
 
   52 Bounds::Bounds(
const std::vector<double>& lower, 
const std::vector<double>& upper)
 
   53   : lower_(lower), upper_(upper), size_(lower.size())
 
   56   assert(lower_.size() == upper_.size());
 
   61   assert((
long)lower_.size() == 
x.size());
 
   64   for (
unsigned int i = 0; i < 
x.size(); ++i)
 
   66     if (
x[i] < lower_.at(i))
 
   70     else if (
x[i] > upper_.at(i))
 
   84   assert((
long)lower_.size() == 
x.size());
 
   87   for (
unsigned int i = 0; i < 
x.size(); ++i)
 
   89     if (
x[i] < lower_.at(i))
 
   93     else if (
x[i] > upper_.at(i))
 
  113   for (std::size_t i{ 0 }; i < bounds.
size(); ++i)
 
  115     os << 
"( " << bounds.lower_[i] << 
", " << bounds.upper_[i] << 
" )\n";
 
  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))
 
  138                               Eigen::Ref<Eigen::VectorXd> out)
 const 
  140   const Eigen::VectorXd current_values = 
calcError(joint_values);
 
  145                               Eigen::Ref<Eigen::MatrixXd> out)
 const 
  147   const Eigen::VectorXd constraint_error = 
calcError(joint_values);
 
  148   const Eigen::VectorXd constraint_derivative = 
bounds_.
derivative(constraint_error);
 
  152     out.row(i) = constraint_derivative[i] * robot_jacobian.row(i);
 
  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());
 
  184       LOGGER, 
"BaseConstraint: Constraint method calcErrorJacobian was not overridden, so it should not be used.");
 
  185   return Eigen::MatrixXd::Zero(getCoDimension(), n_);
 
  192                              const unsigned int num_dofs)
 
  203   geometry_msgs::msg::Point position =
 
  204       constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
 
  208   tf2::fromMsg(constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).orientation,
 
  211   link_name_ = constraints.position_constraints.at(0).link_name;
 
  228                                                        const std::string& 
group, 
const unsigned int num_dofs)
 
  235   const auto dims = constraints.position_constraints.at(0).constraint_region.primitives.at(0).dimensions;
 
  237   is_dim_constrained_ = { 
false, 
false, 
false };
 
  238   for (std::size_t i = 0; i < dims.size(); ++i)
 
  240     if (dims.at(i) < EQUALITY_CONSTRAINT_THRESHOLD)
 
  242       if (dims.at(i) < getTolerance())
 
  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);
 
  252       is_dim_constrained_.at(i) = 
true;
 
  257   geometry_msgs::msg::Point position =
 
  258       constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
 
  262   tf2::fromMsg(constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).orientation,
 
  265   link_name_ = constraints.position_constraints.at(0).link_name;
 
  269                                           Eigen::Ref<Eigen::VectorXd> out)
 const 
  273   for (std::size_t dim = 0; dim < 3; ++dim)
 
  275     if (is_dim_constrained_.at(dim))
 
  277       out[dim] = error[dim];  
 
  287                                           Eigen::Ref<Eigen::MatrixXd> out)
 const 
  291   for (std::size_t dim = 0; dim < 3; ++dim)
 
  293     if (is_dim_constrained_.at(dim))
 
  295       out.row(dim) = jac.row(dim);  
 
  309   link_name_ = constraints.orientation_constraints.at(0).link_name;
 
  315   Eigen::AngleAxisd aa(orientation_difference);
 
  316   return aa.axis() * aa.angle();
 
  322   Eigen::AngleAxisd aa{ orientation_difference };
 
  331   auto dims = pos_con.constraint_region.primitives.at(0).dimensions;
 
  334   for (
auto& dim : dims)
 
  338       dim = std::numeric_limits<double>::infinity();
 
  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 } };
 
  348   std::vector<double> dims = { ori_con.absolute_x_axis_tolerance, ori_con.absolute_y_axis_tolerance,
 
  349                                ori_con.absolute_z_axis_tolerance };
 
  352   for (
auto& dim : dims)
 
  355       dim = std::numeric_limits<double>::infinity();
 
  357   return { { -dims[0], -dims[1], -dims[2] }, { dims[0], dims[1], dims[2] } };
 
  364                                                 const std::string& 
group,
 
  365                                                 const moveit_msgs::msg::Constraints& constraints)
 
  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();
 
  375   std::vector<ompl::base::ConstraintPtr> ompl_constraints;
 
  378     RCLCPP_WARN(LOGGER, 
"Only a single position constraint is supported. Using the first one.");
 
  382     RCLCPP_WARN(LOGGER, 
"Only a single orientation constraint is supported. Using the first one.");
 
  386     BaseConstraintPtr pos_con;
 
  387     if (constraints.name == 
"use_equality_constraints")
 
  389       pos_con = std::make_shared<EqualityPositionConstraint>(robot_model, 
group, num_dofs);
 
  393       pos_con = std::make_shared<BoxConstraint>(robot_model, 
group, num_dofs);
 
  395     pos_con->init(constraints);
 
  396     ompl_constraints.emplace_back(pos_con);
 
  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);
 
  404   if (num_pos_con < 1 && num_ori_con < 1)
 
  406     RCLCPP_ERROR(LOGGER, 
"No path constraints found in planning request.");
 
  409   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.
 
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...
 
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...
 
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
 
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....
 
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.