Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_
00038 #define MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_
00039
00040 #include <moveit/robot_state/robot_state.h>
00041 #include <moveit/planning_scene/planning_scene.h>
00042
00044 namespace kinematics_metrics
00045 {
00046 MOVEIT_CLASS_FORWARD(KinematicsMetrics);
00047
00052 class KinematicsMetrics
00053 {
00054 public:
00056 KinematicsMetrics(const robot_model::RobotModelConstPtr& robot_model)
00057 : robot_model_(robot_model), penalty_multiplier_(0.0)
00058 {
00059 }
00060
00068 bool getManipulabilityIndex(const robot_state::RobotState& state, const std::string& group_name,
00069 double& manipulability_index, bool translation = false) const;
00070
00078 bool getManipulabilityIndex(const robot_state::RobotState& state,
00079 const robot_model::JointModelGroup* joint_model_group, double& manipulability_index,
00080 bool translation = false) const;
00081
00090 bool getManipulabilityEllipsoid(const robot_state::RobotState& state, const std::string& group_name,
00091 Eigen::MatrixXcd& eigen_values, Eigen::MatrixXcd& eigen_vectors) const;
00092
00101 bool getManipulabilityEllipsoid(const robot_state::RobotState& state,
00102 const robot_model::JointModelGroup* joint_model_group, Eigen::MatrixXcd& eigen_values,
00103 Eigen::MatrixXcd& eigen_vectors) const;
00104
00114 bool getManipulability(const robot_state::RobotState& state, const std::string& group_name, double& condition_number,
00115 bool translation = false) const;
00116
00126 bool getManipulability(const robot_state::RobotState& state, const robot_model::JointModelGroup* joint_model_group,
00127 double& condition_number, bool translation = false) const;
00128
00129 void setPenaltyMultiplier(double multiplier)
00130 {
00131 penalty_multiplier_ = fabs(multiplier);
00132 }
00133
00134 const double& getPenaltyMultiplier() const
00135 {
00136 return penalty_multiplier_;
00137 }
00138
00139 protected:
00140 robot_model::RobotModelConstPtr robot_model_;
00141
00142 private:
00155 double getJointLimitsPenalty(const robot_state::RobotState& state,
00156 const robot_model::JointModelGroup* joint_model_group) const;
00157
00158 double penalty_multiplier_;
00159 };
00160 }
00161
00162 #endif