| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability. More...
#include <kinematics_metrics.h>
Public Member Functions | |
| KinematicsMetrics (const moveit::core::RobotModelConstPtr &robot_model) | |
| Construct a KinematicsMetricss from a RobotModel.  More... | |
| 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.  More... | |
| bool | getManipulabilityIndex (const moveit::core::RobotState &state, const moveit::core::JointModelGroup *joint_model_group, double &manipulability_index, bool translation=false) const | 
| Get the manipulability for a given group at a given joint configuration.  More... | |
| 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.  More... | |
| bool | getManipulabilityEllipsoid (const moveit::core::RobotState &state, const moveit::core::JointModelGroup *joint_model_group, Eigen::MatrixXcd &eigen_values, Eigen::MatrixXcd &eigen_vectors) const | 
| Get the (translation) manipulability ellipsoid for a given group at a given joint configuration.  More... | |
| 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 largest singular values of the Jacobian matrix J.  More... | |
| bool | getManipulability (const moveit::core::RobotState &state, const moveit::core::JointModelGroup *joint_model_group, double &condition_number, bool translation=false) const | 
| Get the manipulability = sigma_min/sigma_max where sigma_min and sigma_max are the smallest and largest singular values of the Jacobian matrix J.  More... | |
| void | setPenaltyMultiplier (double multiplier) | 
| const double & | getPenaltyMultiplier () const | 
Protected Attributes | |
| moveit::core::RobotModelConstPtr | robot_model_ | 
Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability.
Definition at line 50 of file kinematics_metrics.h.
      
  | 
  inline | 
Construct a KinematicsMetricss from a RobotModel.
Definition at line 54 of file kinematics_metrics.h.
| bool kinematics_metrics::KinematicsMetrics::getManipulability | ( | const moveit::core::RobotState & | state, | 
| const moveit::core::JointModelGroup * | joint_model_group, | ||
| double & | condition_number, | ||
| bool | translation = false  | 
        ||
| ) | const | 
Get the manipulability = sigma_min/sigma_max where sigma_min and sigma_max are the smallest and largest singular values of the Jacobian matrix J.
| state | Complete kinematic state for the robot | 
| joint_model_group | A pointer to the desired joint model group | 
| condition_number | Condition number for JJ^T | 
Definition at line 209 of file kinematics_metrics.cpp.

| bool kinematics_metrics::KinematicsMetrics::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 largest singular values of the Jacobian matrix J.
| state | Complete kinematic state for the robot | 
| group_name | The group name (e.g. "arm") | 
| condition_number | Condition number for JJ^T | 
Definition at line 199 of file kinematics_metrics.cpp.
| bool kinematics_metrics::KinematicsMetrics::getManipulabilityEllipsoid | ( | const moveit::core::RobotState & | state, | 
| const moveit::core::JointModelGroup * | joint_model_group, | ||
| Eigen::MatrixXcd & | eigen_values, | ||
| Eigen::MatrixXcd & | eigen_vectors | ||
| ) | const | 
Get the (translation) manipulability ellipsoid for a given group at a given joint configuration.
| state | Complete kinematic state for the robot | 
| joint_model_group | A pointer to the desired joint model group | 
| eigen_values | The eigen values for the translation part of JJ^T | 
| eigen_vectors | The eigen vectors for the translation part of JJ^T | 
Definition at line 180 of file kinematics_metrics.cpp.

| bool kinematics_metrics::KinematicsMetrics::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.
| state | Complete kinematic state for the robot | 
| group_name | The group name (e.g. "arm") | 
| eigen_values | The eigen values for the translation part of JJ^T | 
| eigen_vectors | The eigen vectors for the translation part of JJ^T | 
Definition at line 169 of file kinematics_metrics.cpp.
| bool kinematics_metrics::KinematicsMetrics::getManipulabilityIndex | ( | const moveit::core::RobotState & | state, | 
| const moveit::core::JointModelGroup * | joint_model_group, | ||
| double & | manipulability_index, | ||
| bool | translation = false  | 
        ||
| ) | const | 
Get the manipulability for a given group at a given joint configuration.
| state | Complete kinematic state for the robot | 
| joint_model_group | A pointer to the desired joint model group | 
| manipulability_index | The computed manipulability = sqrt(det(JJ^T)) | 
Definition at line 108 of file kinematics_metrics.cpp.

| bool kinematics_metrics::KinematicsMetrics::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.
| state | Complete kinematic state for the robot | 
| group_name | The group name (e.g. "arm") | 
| manipulability_index | The computed manipulability = sqrt(det(JJ^T)) | 
Definition at line 98 of file kinematics_metrics.cpp.
      
  | 
  inline | 
Definition at line 132 of file kinematics_metrics.h.
      
  | 
  inline | 
Definition at line 127 of file kinematics_metrics.h.
      
  | 
  protected | 
Definition at line 138 of file kinematics_metrics.h.