37 #ifndef MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_ 38 #define MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_ 69 double& manipulability_index,
bool translation =
false)
const;
80 bool translation =
false)
const;
91 Eigen::MatrixXcd& eigen_values, Eigen::MatrixXcd& eigen_vectors)
const;
103 Eigen::MatrixXcd& eigen_vectors)
const;
115 bool translation =
false)
const;
127 double& condition_number,
bool translation =
false)
const;
Core components of MoveIt!
MOVEIT_CLASS_FORWARD(KinematicsMetrics)
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} (distan...
const double & getPenaltyMultiplier() const
Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability.
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 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 large...
void setPenaltyMultiplier(double multiplier)
robot_model::RobotModelConstPtr robot_model_
Representation of a robot's state. This includes position, velocity, acceleration and effort...
double penalty_multiplier_
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.
KinematicsMetrics(const robot_model::RobotModelConstPtr &robot_model)
Construct a KinematicsMetricss from a RobotModel.
Namespace for kinematics metrics.