Go to the documentation of this file.
67 double& manipulability_index,
bool translation =
false)
const;
78 bool translation =
false)
const;
89 Eigen::MatrixXcd& eigen_values, Eigen::MatrixXcd& eigen_vectors)
const;
101 Eigen::MatrixXcd& eigen_values, Eigen::MatrixXcd& eigen_vectors)
const;
113 bool translation =
false)
const;
125 double& condition_number,
bool translation =
false)
const;
double getJointLimitsPenalty(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *joint_model_group) const
Defines a multiplier for the manipulabilty = 1 - exp ( -penalty_multipler_ * product_{i=1}{n} (distan...
KinematicsMetrics(const moveit::core::RobotModelConstPtr &robot_model)
Construct a KinematicsMetricss from a RobotModel.
Core components of MoveIt.
moveit::core::RobotModelConstPtr robot_model_
MOVEIT_CLASS_FORWARD(KinematicsMetrics)
const double & getPenaltyMultiplier() const
Namespace for kinematics metrics.
void setPenaltyMultiplier(double multiplier)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability.
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...
double penalty_multiplier_
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 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
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Tue Dec 24 2024 03:27:14