37 #include <Eigen/Dense> 
   38 #include <Eigen/Eigenvalues> 
   42 #include <rclcpp/logger.hpp> 
   43 #include <rclcpp/logging.hpp> 
   47 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_kinematics_metrics.kinematics_metrics");
 
   52   if (fabs(penalty_multiplier_) <= std::numeric_limits<double>::min())
 
   54   double joint_limits_multiplier(1.0);
 
   55   const std::vector<const moveit::core::JointModel*>& joint_model_vector = joint_model_group->
getJointModels();
 
   68       if (bounds[0].min_position_ == -std::numeric_limits<double>::max() ||
 
   69           bounds[0].max_position_ == std::numeric_limits<double>::max() ||
 
   70           bounds[1].min_position_ == -std::numeric_limits<double>::max() ||
 
   71           bounds[1].max_position_ == std::numeric_limits<double>::max() || bounds[2].min_position_ == -M_PI ||
 
   72           bounds[2].max_position_ == M_PI)
 
   82     std::vector<double> lower_bounds, upper_bounds;
 
   85       lower_bounds.push_back(bound.min_position_);
 
   86       upper_bounds.push_back(bound.max_position_);
 
   88     double lower_bound_distance = joint_model->distance(joint_values, &lower_bounds[0]);
 
   89     double upper_bound_distance = joint_model->distance(joint_values, &upper_bounds[0]);
 
   90     double range = lower_bound_distance + upper_bound_distance;
 
   91     if (range <= std::numeric_limits<double>::min())
 
   93     joint_limits_multiplier *= (lower_bound_distance * upper_bound_distance / (range * range));
 
   95   return (1.0 - exp(-penalty_multiplier_ * joint_limits_multiplier));
 
   99                                                double& manipulability_index, 
bool translation)
 const 
  102   if (joint_model_group)
 
  110                                                double& manipulability_index, 
bool translation)
 const 
  113   if (!joint_model_group->
isChain())
 
  118   Eigen::MatrixXd jacobian = state.
getJacobian(joint_model_group);
 
  120   double penalty = getJointLimitsPenalty(state, joint_model_group);
 
  123     if (jacobian.cols() < 6)
 
  125       Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian.topLeftCorner(3, jacobian.cols()));
 
  126       Eigen::MatrixXd singular_values = svdsolver.singularValues();
 
  127       manipulability_index = 1.0;
 
  128       for (
unsigned int i = 0; i < singular_values.rows(); ++i)
 
  130         RCLCPP_DEBUG(LOGGER, 
"Singular value: %d %f", i, singular_values(i, 0));
 
  131         manipulability_index *= singular_values(i, 0);
 
  134       manipulability_index = penalty * manipulability_index;
 
  138       Eigen::MatrixXd jacobian_2 = jacobian.topLeftCorner(3, jacobian.cols());
 
  139       Eigen::MatrixXd matrix = jacobian_2 * jacobian_2.transpose();
 
  141       manipulability_index = penalty * sqrt(matrix.determinant());
 
  146     if (jacobian.cols() < 6)
 
  148       Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian);
 
  149       Eigen::MatrixXd singular_values = svdsolver.singularValues();
 
  150       manipulability_index = 1.0;
 
  151       for (
unsigned int i = 0; i < singular_values.rows(); ++i)
 
  153         RCLCPP_DEBUG(LOGGER, 
"Singular value: %d %f", i, singular_values(i, 0));
 
  154         manipulability_index *= singular_values(i, 0);
 
  157       manipulability_index = penalty * manipulability_index;
 
  161       Eigen::MatrixXd matrix = jacobian * jacobian.transpose();
 
  163       manipulability_index = penalty * sqrt(matrix.determinant());
 
  170                                                    Eigen::MatrixXcd& eigen_values,
 
  171                                                    Eigen::MatrixXcd& eigen_vectors)
 const 
  174   if (joint_model_group)
 
  182                                                    Eigen::MatrixXcd& eigen_values,
 
  183                                                    Eigen::MatrixXcd& eigen_vectors)
 const 
  186   if (!joint_model_group->
isChain())
 
  191   Eigen::MatrixXd jacobian = state.
getJacobian(joint_model_group);
 
  192   Eigen::MatrixXd matrix = jacobian * jacobian.transpose();
 
  193   Eigen::EigenSolver<Eigen::MatrixXd> eigensolver(matrix.block(0, 0, 3, 3));
 
  194   eigen_values = eigensolver.eigenvalues();
 
  195   eigen_vectors = eigensolver.eigenvectors();
 
  200                                           double& manipulability, 
bool translation)
 const 
  203   if (joint_model_group)
 
  211                                           double& manipulability, 
bool translation)
 const 
  214   if (!joint_model_group->
isChain())
 
  219   double penalty = getJointLimitsPenalty(state, joint_model_group);
 
  222     Eigen::MatrixXd jacobian = state.
getJacobian(joint_model_group);
 
  223     Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian.topLeftCorner(3, jacobian.cols()));
 
  224     Eigen::MatrixXd singular_values = svdsolver.singularValues();
 
  225     for (
int i = 0; i < singular_values.rows(); ++i)
 
  227       RCLCPP_DEBUG(LOGGER, 
"Singular value: %d %f", i, singular_values(i, 0));
 
  230     manipulability = penalty * singular_values.minCoeff() / singular_values.maxCoeff();
 
  234     Eigen::MatrixXd jacobian = state.
getJacobian(joint_model_group);
 
  235     Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian);
 
  236     Eigen::MatrixXd singular_values = svdsolver.singularValues();
 
  237     for (
int i = 0; i < singular_values.rows(); ++i)
 
  239       RCLCPP_DEBUG(LOGGER, 
"Singular value: %d %f", i, singular_values(i, 0));
 
  241     manipulability = penalty * singular_values.minCoeff() / singular_values.maxCoeff();
 
bool getManipulability(const moveit::core::RobotState &state, const std::string &group_name, double &condition_number, bool translation=false) const
Get the manipulability = sigma_min/sigma_max where sigma_min and sigma_max are the smallest and large...
 
bool getManipulabilityIndex(const moveit::core::RobotState &state, const std::string &group_name, double &manipulability_index, bool translation=false) const
Get the manipulability for a given group at a given joint configuration.
 
moveit::core::RobotModelConstPtr robot_model_
 
bool getManipulabilityEllipsoid(const moveit::core::RobotState &state, const std::string &group_name, Eigen::MatrixXcd &eigen_values, Eigen::MatrixXcd &eigen_vectors) const
Get the (translation) manipulability ellipsoid for a given group at a given joint configuration.
 
bool isChain() const
Check if this group is a linear chain.
 
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
 
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
 
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
 
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
 
bool isContinuous() const
Check if this joint wraps around.
 
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.
 
const double * getJointPositions(const std::string &joint_name) const
 
Namespace for kinematics metrics.