moveit2
The MoveIt Motion Planning Framework for ROS 2.
kinematics_metrics.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sachin Chitta */
36 
37 #include <Eigen/Dense>
38 #include <Eigen/Eigenvalues>
39 #include <limits>
40 #include <math.h>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 
45 namespace kinematics_metrics
46 {
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kinematics_metrics.kinematics_metrics");
48 
49 double KinematicsMetrics::getJointLimitsPenalty(const moveit::core::RobotState& state,
50  const moveit::core::JointModelGroup* joint_model_group) const
51 {
52  if (fabs(penalty_multiplier_) <= std::numeric_limits<double>::min())
53  return 1.0;
54  double joint_limits_multiplier(1.0);
55  const std::vector<const moveit::core::JointModel*>& joint_model_vector = joint_model_group->getJointModels();
56  for (const moveit::core::JointModel* joint_model : joint_model_vector)
57  {
58  if (joint_model->getType() == moveit::core::JointModel::REVOLUTE)
59  {
60  const moveit::core::RevoluteJointModel* revolute_model =
61  static_cast<const moveit::core::RevoluteJointModel*>(joint_model);
62  if (revolute_model->isContinuous())
63  continue;
64  }
65  if (joint_model->getType() == moveit::core::JointModel::PLANAR)
66  {
67  const moveit::core::JointModel::Bounds& bounds = joint_model->getVariableBounds();
68  if (bounds[0].min_position_ == -std::numeric_limits<double>::max() ||
69  bounds[0].max_position_ == std::numeric_limits<double>::max() ||
70  bounds[1].min_position_ == -std::numeric_limits<double>::max() ||
71  bounds[1].max_position_ == std::numeric_limits<double>::max() || bounds[2].min_position_ == -M_PI ||
72  bounds[2].max_position_ == M_PI)
73  continue;
74  }
75  if (joint_model->getType() == moveit::core::JointModel::FLOATING)
76  {
77  // Joint limits are not well-defined for floating joints
78  continue;
79  }
80  const double* joint_values = state.getJointPositions(joint_model);
81  const moveit::core::JointModel::Bounds& bounds = joint_model->getVariableBounds();
82  std::vector<double> lower_bounds, upper_bounds;
83  for (const moveit::core::VariableBounds& bound : bounds)
84  {
85  lower_bounds.push_back(bound.min_position_);
86  upper_bounds.push_back(bound.max_position_);
87  }
88  double lower_bound_distance = joint_model->distance(joint_values, &lower_bounds[0]);
89  double upper_bound_distance = joint_model->distance(joint_values, &upper_bounds[0]);
90  double range = lower_bound_distance + upper_bound_distance;
91  if (range <= std::numeric_limits<double>::min())
92  continue;
93  joint_limits_multiplier *= (lower_bound_distance * upper_bound_distance / (range * range));
94  }
95  return (1.0 - exp(-penalty_multiplier_ * joint_limits_multiplier));
96 }
97 
98 bool KinematicsMetrics::getManipulabilityIndex(const moveit::core::RobotState& state, const std::string& group_name,
99  double& manipulability_index, bool translation) const
100 {
101  const moveit::core::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group_name);
102  if (joint_model_group)
103  return getManipulabilityIndex(state, joint_model_group, manipulability_index, translation);
104  else
105  return false;
106 }
107 
109  const moveit::core::JointModelGroup* joint_model_group,
110  double& manipulability_index, bool translation) const
111 {
112  // state.getJacobian() only works for chain groups.
113  if (!joint_model_group->isChain())
114  {
115  return false;
116  }
117 
118  Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
119  // Get joint limits penalty
120  double penalty = getJointLimitsPenalty(state, joint_model_group);
121  if (translation)
122  {
123  if (jacobian.cols() < 6)
124  {
125  Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian.topLeftCorner(3, jacobian.cols()));
126  Eigen::MatrixXd singular_values = svdsolver.singularValues();
127  manipulability_index = 1.0;
128  for (unsigned int i = 0; i < singular_values.rows(); ++i)
129  {
130  RCLCPP_DEBUG(LOGGER, "Singular value: %d %f", i, singular_values(i, 0));
131  manipulability_index *= singular_values(i, 0);
132  }
133  // Get manipulability index
134  manipulability_index = penalty * manipulability_index;
135  }
136  else
137  {
138  Eigen::MatrixXd jacobian_2 = jacobian.topLeftCorner(3, jacobian.cols());
139  Eigen::MatrixXd matrix = jacobian_2 * jacobian_2.transpose();
140  // Get manipulability index
141  manipulability_index = penalty * sqrt(matrix.determinant());
142  }
143  }
144  else
145  {
146  if (jacobian.cols() < 6)
147  {
148  Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian);
149  Eigen::MatrixXd singular_values = svdsolver.singularValues();
150  manipulability_index = 1.0;
151  for (unsigned int i = 0; i < singular_values.rows(); ++i)
152  {
153  RCLCPP_DEBUG(LOGGER, "Singular value: %d %f", i, singular_values(i, 0));
154  manipulability_index *= singular_values(i, 0);
155  }
156  // Get manipulability index
157  manipulability_index = penalty * manipulability_index;
158  }
159  else
160  {
161  Eigen::MatrixXd matrix = jacobian * jacobian.transpose();
162  // Get manipulability index
163  manipulability_index = penalty * sqrt(matrix.determinant());
164  }
165  }
166  return true;
167 }
168 
169 bool KinematicsMetrics::getManipulabilityEllipsoid(const moveit::core::RobotState& state, const std::string& group_name,
170  Eigen::MatrixXcd& eigen_values,
171  Eigen::MatrixXcd& eigen_vectors) const
172 {
173  const moveit::core::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group_name);
174  if (joint_model_group)
175  return getManipulabilityEllipsoid(state, joint_model_group, eigen_values, eigen_vectors);
176  else
177  return false;
178 }
179 
181  const moveit::core::JointModelGroup* joint_model_group,
182  Eigen::MatrixXcd& eigen_values,
183  Eigen::MatrixXcd& eigen_vectors) const
184 {
185  // state.getJacobian() only works for chain groups.
186  if (!joint_model_group->isChain())
187  {
188  return false;
189  }
190 
191  Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
192  Eigen::MatrixXd matrix = jacobian * jacobian.transpose();
193  Eigen::EigenSolver<Eigen::MatrixXd> eigensolver(matrix.block(0, 0, 3, 3));
194  eigen_values = eigensolver.eigenvalues();
195  eigen_vectors = eigensolver.eigenvectors();
196  return true;
197 }
198 
199 bool KinematicsMetrics::getManipulability(const moveit::core::RobotState& state, const std::string& group_name,
200  double& manipulability, bool translation) const
201 {
202  const moveit::core::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group_name);
203  if (joint_model_group)
204  return getManipulability(state, joint_model_group, manipulability, translation);
205  else
206  return false;
207 }
208 
210  const moveit::core::JointModelGroup* joint_model_group,
211  double& manipulability, bool translation) const
212 {
213  // state.getJacobian() only works for chain groups.
214  if (!joint_model_group->isChain())
215  {
216  return false;
217  }
218  // Get joint limits penalty
219  double penalty = getJointLimitsPenalty(state, joint_model_group);
220  if (translation)
221  {
222  Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
223  Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian.topLeftCorner(3, jacobian.cols()));
224  Eigen::MatrixXd singular_values = svdsolver.singularValues();
225  for (int i = 0; i < singular_values.rows(); ++i)
226  {
227  RCLCPP_DEBUG(LOGGER, "Singular value: %d %f", i, singular_values(i, 0));
228  }
229 
230  manipulability = penalty * singular_values.minCoeff() / singular_values.maxCoeff();
231  }
232  else
233  {
234  Eigen::MatrixXd jacobian = state.getJacobian(joint_model_group);
235  Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jacobian);
236  Eigen::MatrixXd singular_values = svdsolver.singularValues();
237  for (int i = 0; i < singular_values.rows(); ++i)
238  {
239  RCLCPP_DEBUG(LOGGER, "Singular value: %d %f", i, singular_values(i, 0));
240  }
241  manipulability = penalty * singular_values.minCoeff() / singular_values.maxCoeff();
242  }
243  return true;
244 }
245 
246 } // end of namespace kinematics_metrics
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...
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::RobotModelConstPtr robot_model_
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 isChain() const
Check if this group is a linear chain.
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
bool isContinuous() const
Check if this joint wraps around.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:557
Namespace for kinematics metrics.