kinematics_metrics.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Sachin Chitta */
00036 
00037 #include <moveit/kinematics_metrics/kinematics_metrics.h>
00038 #include <Eigen/Eigenvalues>
00039 #include <boost/math/constants/constants.hpp>
00040 
00041 namespace kinematics_metrics
00042 {
00043 
00044 double KinematicsMetrics::getJointLimitsPenalty(const robot_state::RobotState &state, const robot_model::JointModelGroup *joint_model_group) const
00045 {
00046   if (fabs(penalty_multiplier_) <= boost::math::tools::epsilon<double>())
00047      return 1.0;
00048   double joint_limits_multiplier(1.0);
00049   const std::vector<const robot_model::JointModel*> &joint_model_vector = joint_model_group->getJointModels();
00050   for (std::size_t i = 0; i < joint_model_vector.size(); ++i)
00051   {
00052     if (joint_model_vector[i]->getType() == robot_model::JointModel::REVOLUTE)
00053     {
00054       const robot_model::RevoluteJointModel* revolute_model = static_cast<const robot_model::RevoluteJointModel*>(joint_model_vector[i]);
00055       if (revolute_model->isContinuous())
00056         continue;
00057     }
00058     if (joint_model_vector[i]->getType() == robot_model::JointModel::PLANAR)
00059     {
00060       const robot_model::JointModel::Bounds &bounds = joint_model_vector[i]->getVariableBounds();
00061       if (bounds[0].min_position_ == -std::numeric_limits<double>::max() || bounds[0].max_position_ == std::numeric_limits<double>::max() ||
00062           bounds[1].min_position_ == -std::numeric_limits<double>::max() || bounds[1].max_position_ == std::numeric_limits<double>::max() ||
00063           bounds[2].min_position_ == -boost::math::constants::pi<double>() || bounds[2].max_position_ == boost::math::constants::pi<double>())
00064         continue;
00065     }
00066     if (joint_model_vector[i]->getType() == robot_model::JointModel::FLOATING)
00067     {
00068       //Joint limits are not well-defined for floating joints
00069       continue;
00070     }
00071     const double *joint_values = state.getJointPositions(joint_model_vector[i]);
00072     const robot_model::JointModel::Bounds &bounds = joint_model_vector[i]->getVariableBounds();
00073     std::vector<double> lower_bounds, upper_bounds;
00074     for (std::size_t j = 0; j < bounds.size(); ++j)
00075     {
00076       lower_bounds.push_back(bounds[j].min_position_);
00077       upper_bounds.push_back(bounds[j].max_position_);
00078     }
00079     double lower_bound_distance = joint_model_vector[i]->distance(joint_values, &lower_bounds[0]);
00080     double upper_bound_distance = joint_model_vector[i]->distance(joint_values, &upper_bounds[0]);
00081     double range = lower_bound_distance + upper_bound_distance;
00082     if (range <= boost::math::tools::epsilon<double>())
00083       continue;
00084     joint_limits_multiplier *= (lower_bound_distance * upper_bound_distance/(range*range));
00085   }
00086   return (1.0 - exp(-penalty_multiplier_*joint_limits_multiplier));
00087 }
00088 
00089 bool KinematicsMetrics::getManipulabilityIndex(const robot_state::RobotState &state,
00090                                                const std::string &group_name,
00091                                                double &manipulability_index,
00092                                                bool translation) const
00093 {
00094   const robot_model::JointModelGroup *joint_model_group = robot_model_->getJointModelGroup(group_name);
00095   if (joint_model_group)
00096     return getManipulabilityIndex(state, joint_model_group, manipulability_index, translation);
00097   else
00098     return false;
00099 }
00100 
00101 bool KinematicsMetrics::getManipulabilityIndex(const robot_state::RobotState &state,
00102                                                const robot_model::JointModelGroup *joint_model_group,
00103                                                double &manipulability_index,
00104                                                bool translation) const
00105 {
00106   // state.getJacobian() only works for chain groups.
00107   if(!joint_model_group->isChain())
00108   {
00109     return false;
00110   }
00111 
00112   Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
00113   // Get joint limits penalty
00114   double penalty = getJointLimitsPenalty(state, joint_model_group);
00115   if (translation)
00116   {
00117     if(jacobian.cols()<6)
00118     {
00119       Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian.topLeftCorner(3,jacobian.cols()));
00120       Eigen::MatrixXd singular_values = svdsolver.singularValues();
00121       manipulability_index = 1.0;
00122       for(unsigned int i=0; i < singular_values.rows(); ++i)
00123       {
00124         logDebug("moveit.kin_metrics: Singular value: %d %f",i,singular_values(i,0));
00125         manipulability_index *= singular_values(i,0);
00126       }
00127       // Get manipulability index
00128       manipulability_index = penalty * manipulability_index;
00129     }
00130     else
00131     {
00132       Eigen::MatrixXd jacobian_2 = jacobian.topLeftCorner(3,jacobian.cols());
00133       Eigen::MatrixXd matrix = jacobian_2*jacobian_2.transpose();
00134       // Get manipulability index
00135       manipulability_index = penalty * sqrt(matrix.determinant());
00136     }
00137   }
00138   else
00139   {
00140     if(jacobian.cols()<6)
00141     {
00142       Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian);
00143       Eigen::MatrixXd singular_values = svdsolver.singularValues();
00144       manipulability_index = 1.0;
00145       for(unsigned int i=0; i < singular_values.rows(); ++i)
00146       {
00147         logDebug("moveit.kin_metrics: Singular value: %d %f",i,singular_values(i,0));
00148         manipulability_index *= singular_values(i,0);
00149       }
00150       // Get manipulability index
00151       manipulability_index = penalty * manipulability_index;
00152     }
00153     else
00154     {
00155       Eigen::MatrixXd matrix = jacobian*jacobian.transpose();
00156       // Get manipulability index
00157       manipulability_index = penalty * sqrt(matrix.determinant());
00158     }
00159   }
00160   return true;
00161 }
00162 
00163 bool KinematicsMetrics::getManipulabilityEllipsoid(const robot_state::RobotState &state,
00164                                                    const std::string &group_name,
00165                                                    Eigen::MatrixXcd &eigen_values,
00166                                                    Eigen::MatrixXcd &eigen_vectors) const
00167 {
00168   const robot_model::JointModelGroup *joint_model_group = robot_model_->getJointModelGroup(group_name);
00169   if (joint_model_group)
00170     return getManipulabilityEllipsoid(state, joint_model_group, eigen_values, eigen_vectors);
00171   else
00172     return false;
00173 }
00174 
00175 bool KinematicsMetrics::getManipulabilityEllipsoid(const robot_state::RobotState &state,
00176                                                    const robot_model::JointModelGroup *joint_model_group,
00177                                                    Eigen::MatrixXcd &eigen_values,
00178                                                    Eigen::MatrixXcd &eigen_vectors) const
00179 {
00180   // state.getJacobian() only works for chain groups.
00181   if(!joint_model_group->isChain())
00182   {
00183     return false;
00184   }
00185 
00186   Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
00187   Eigen::MatrixXd matrix = jacobian*jacobian.transpose();
00188   Eigen::EigenSolver<Eigen::MatrixXd> eigensolver(matrix.block(0, 0, 3, 3));
00189   eigen_values = eigensolver.eigenvalues();
00190   eigen_vectors = eigensolver.eigenvectors();
00191   return true;
00192 }
00193 
00194 bool KinematicsMetrics::getManipulability(const robot_state::RobotState &state,
00195                                           const std::string &group_name,
00196                                           double &manipulability,
00197                                           bool translation) const
00198 {
00199   const robot_model::JointModelGroup *joint_model_group = robot_model_->getJointModelGroup(group_name);
00200   if (joint_model_group)
00201     return getManipulability(state, joint_model_group, manipulability, translation);
00202   else
00203     return false;
00204 }
00205 
00206 bool KinematicsMetrics::getManipulability(const robot_state::RobotState &state,
00207                                           const robot_model::JointModelGroup *joint_model_group,
00208                                           double &manipulability,
00209                                           bool translation) const
00210 {
00211   // state.getJacobian() only works for chain groups.
00212   if(!joint_model_group->isChain())
00213   {
00214     return false;
00215   }
00216   // Get joint limits penalty
00217   double penalty = getJointLimitsPenalty(state, joint_model_group);
00218   if (translation)
00219   {
00220     Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
00221     Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian.topLeftCorner(3,jacobian.cols()));
00222     Eigen::MatrixXd singular_values = svdsolver.singularValues();
00223     for (int i = 0; i < singular_values.rows(); ++i)
00224       logDebug("moveit.kin_metrics: Singular value: %d %f",i,singular_values(i,0));
00225     manipulability = penalty * singular_values.minCoeff()/singular_values.maxCoeff();
00226   }
00227   else
00228   {
00229     Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
00230     Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian);
00231     Eigen::MatrixXd singular_values = svdsolver.singularValues();
00232     for(int i=0; i < singular_values.rows(); ++i)
00233       logDebug("moveit.kin_metrics: Singular value: %d %f",i,singular_values(i,0));
00234     manipulability = penalty * singular_values.minCoeff()/singular_values.maxCoeff();
00235   }
00236   return true;
00237 }
00238 
00239 } // namespace


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:52