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
00038 #ifndef MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_
00039 #define MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_
00040
00041 #include <moveit/robot_state/robot_state.h>
00042 #include <moveit/planning_scene/planning_scene.h>
00043
00045 namespace kinematics_metrics
00046 {
00047
00052 class KinematicsMetrics
00053 {
00054 public:
00055
00057 KinematicsMetrics(const robot_model::RobotModelConstPtr &kinematic_model) :
00058 kinematic_model_(kinematic_model), penalty_multiplier_(0.0)
00059 {
00060 }
00061
00069 bool getManipulabilityIndex(const robot_state::RobotState &kinematic_state,
00070 const std::string &group_name,
00071 double &manipulability_index,
00072 bool translation = false) const;
00073
00081 bool getManipulabilityIndex(const robot_state::RobotState &kinematic_state,
00082 const robot_model::JointModelGroup *joint_model_group,
00083 double &manipulability_index,
00084 bool translation = false) const;
00085
00094 bool getManipulabilityEllipsoid(const robot_state::RobotState &kinematic_state,
00095 const std::string &group_name,
00096 Eigen::MatrixXcd &eigen_values,
00097 Eigen::MatrixXcd &eigen_vectors) const;
00098
00107 bool getManipulabilityEllipsoid(const robot_state::RobotState &kinematic_state,
00108 const robot_model::JointModelGroup *joint_model_group,
00109 Eigen::MatrixXcd &eigen_values,
00110 Eigen::MatrixXcd &eigen_vectors) const;
00111
00121 bool getManipulability(const robot_state::RobotState &kinematic_state,
00122 const std::string &group_name,
00123 double &condition_number,
00124 bool translation = false) const;
00125
00135 bool getManipulability(const robot_state::RobotState &kinematic_state,
00136 const robot_model::JointModelGroup *joint_model_group,
00137 double &condition_number,
00138 bool translation = false) const;
00139
00140 void setPenaltyMultiplier(double multiplier)
00141 {
00142 penalty_multiplier_ = fabs(multiplier);
00143 }
00144
00145 const double& getPenaltyMultiplier() const
00146 {
00147 return penalty_multiplier_;
00148 }
00149
00150 protected:
00151
00152 robot_model::RobotModelConstPtr kinematic_model_;
00153
00154 Eigen::MatrixXd getJacobian(const robot_state::RobotState &kinematic_state,
00155 const robot_model::JointModelGroup *joint_model_group) const;
00156
00157 private:
00158
00169 double getJointLimitsPenalty(const robot_state::JointStateGroup* joint_state_group) const;
00170
00171 double penalty_multiplier_;
00172
00173 };
00174
00175 typedef boost::shared_ptr<KinematicsMetrics> KinematicsMetricsPtr;
00176 typedef boost::shared_ptr<const KinematicsMetrics> KinematicsMetricsConstPtr;
00177
00178 }
00179
00180 #endif