Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes
kinematics_metrics::KinematicsMetrics Class Reference

Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability. More...

#include <kinematics_metrics.h>

List of all members.

Public Member Functions

bool getManipulability (const robot_state::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.
bool getManipulability (const robot_state::RobotState &state, const robot_model::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.
bool getManipulabilityEllipsoid (const robot_state::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 getManipulabilityEllipsoid (const robot_state::RobotState &state, const robot_model::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.
bool getManipulabilityIndex (const robot_state::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.
bool getManipulabilityIndex (const robot_state::RobotState &state, const robot_model::JointModelGroup *joint_model_group, double &manipulability_index, bool translation=false) const
 Get the manipulability for a given group at a given joint configuration.
const double & getPenaltyMultiplier () const
 KinematicsMetrics (const robot_model::RobotModelConstPtr &robot_model)
 Construct a KinematicsMetricss from a RobotModel.
void setPenaltyMultiplier (double multiplier)

Protected Attributes

robot_model::RobotModelConstPtr robot_model_

Private Member Functions

double getJointLimitsPenalty (const robot_state::RobotState &state, const robot_model::JointModelGroup *joint_model_group) const
 Defines a multiplier for the manipulabilty = 1 - exp ( -penalty_multipler_ * product_{i=1}{n} (distance_to_lower_limit * distance_to_higher_limit/(joint_range*joint_range))) where n is the number of joints in the group. Floating joints are ignored in this computation. Planar joints with finite bounds are considered. Set penalty_multiplier_ to 0 if you don't want this multiplier to have any effect on the manipulability measures. See "Workspace Geometric Characterization and Manipulability of Industrial Robots", Ming-June, Tsia, PhD Thesis, Ohio State University, 1986, for more details.

Private Attributes

double penalty_multiplier_

Detailed Description

Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability.

Definition at line 52 of file kinematics_metrics.h.


Constructor & Destructor Documentation

kinematics_metrics::KinematicsMetrics::KinematicsMetrics ( const robot_model::RobotModelConstPtr &  robot_model) [inline]

Construct a KinematicsMetricss from a RobotModel.

Definition at line 56 of file kinematics_metrics.h.


Member Function Documentation

double kinematics_metrics::KinematicsMetrics::getJointLimitsPenalty ( const robot_state::RobotState state,
const robot_model::JointModelGroup joint_model_group 
) const [private]

Defines a multiplier for the manipulabilty = 1 - exp ( -penalty_multipler_ * product_{i=1}{n} (distance_to_lower_limit * distance_to_higher_limit/(joint_range*joint_range))) where n is the number of joints in the group. Floating joints are ignored in this computation. Planar joints with finite bounds are considered. Set penalty_multiplier_ to 0 if you don't want this multiplier to have any effect on the manipulability measures. See "Workspace Geometric Characterization and Manipulability of Industrial Robots", Ming-June, Tsia, PhD Thesis, Ohio State University, 1986, for more details.

Returns:
multiplier that is multiplied with every manipulability measure computed here

Definition at line 43 of file kinematics_metrics.cpp.

bool kinematics_metrics::KinematicsMetrics::getManipulability ( const robot_state::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.

Parameters:
stateComplete kinematic state for the robot
group_nameThe group name (e.g. "arm")
condition_numberCondition number for JJ^T
Returns:
False if the group was not found

Definition at line 194 of file kinematics_metrics.cpp.

bool kinematics_metrics::KinematicsMetrics::getManipulability ( const robot_state::RobotState state,
const robot_model::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.

Parameters:
stateComplete kinematic state for the robot
joint_model_groupA pointer to the desired joint model group
condition_numberCondition number for JJ^T
Returns:
False if the group was not found

Definition at line 204 of file kinematics_metrics.cpp.

bool kinematics_metrics::KinematicsMetrics::getManipulabilityEllipsoid ( const robot_state::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.

Parameters:
stateComplete kinematic state for the robot
group_nameThe group name (e.g. "arm")
eigen_valuesThe eigen values for the translation part of JJ^T
eigen_vectorsThe eigen vectors for the translation part of JJ^T
Returns:
False if the group was not found

Definition at line 164 of file kinematics_metrics.cpp.

bool kinematics_metrics::KinematicsMetrics::getManipulabilityEllipsoid ( const robot_state::RobotState state,
const robot_model::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.

Parameters:
stateComplete kinematic state for the robot
joint_model_groupA pointer to the desired joint model group
eigen_valuesThe eigen values for the translation part of JJ^T
eigen_vectorsThe eigen vectors for the translation part of JJ^T
Returns:
False if the group was not found

Definition at line 175 of file kinematics_metrics.cpp.

bool kinematics_metrics::KinematicsMetrics::getManipulabilityIndex ( const robot_state::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.

Parameters:
stateComplete kinematic state for the robot
group_nameThe group name (e.g. "arm")
manipulability_indexThe computed manipulability = sqrt(det(JJ^T))
Returns:
False if the group was not found

Definition at line 93 of file kinematics_metrics.cpp.

bool kinematics_metrics::KinematicsMetrics::getManipulabilityIndex ( const robot_state::RobotState state,
const robot_model::JointModelGroup joint_model_group,
double &  manipulability_index,
bool  translation = false 
) const

Get the manipulability for a given group at a given joint configuration.

Parameters:
stateComplete kinematic state for the robot
joint_model_groupA pointer to the desired joint model group
manipulability_indexThe computed manipulability = sqrt(det(JJ^T))
Returns:
False if the group was not found

Definition at line 103 of file kinematics_metrics.cpp.

Definition at line 134 of file kinematics_metrics.h.

Definition at line 129 of file kinematics_metrics.h.


Member Data Documentation

Definition at line 158 of file kinematics_metrics.h.

robot_model::RobotModelConstPtr kinematics_metrics::KinematicsMetrics::robot_model_ [protected]

Definition at line 140 of file kinematics_metrics.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Jul 24 2017 02:20:44