kinematics_metrics.h
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 #pragma once
38 
40 
43 {
44 MOVEIT_CLASS_FORWARD(KinematicsMetrics); // Defines KinematicsMetricsPtr, ConstPtr, WeakPtr... etc
45 
51 {
52 public:
54  KinematicsMetrics(const moveit::core::RobotModelConstPtr& robot_model)
56  {
57  }
58 
66  bool getManipulabilityIndex(const moveit::core::RobotState& state, const std::string& group_name,
67  double& manipulability_index, bool translation = false) const;
68 
77  const moveit::core::JointModelGroup* joint_model_group, double& manipulability_index,
78  bool translation = false) const;
79 
88  bool getManipulabilityEllipsoid(const moveit::core::RobotState& state, const std::string& group_name,
89  Eigen::MatrixXcd& eigen_values, Eigen::MatrixXcd& eigen_vectors) const;
90 
100  const moveit::core::JointModelGroup* joint_model_group,
101  Eigen::MatrixXcd& eigen_values, Eigen::MatrixXcd& eigen_vectors) const;
102 
112  bool getManipulability(const moveit::core::RobotState& state, const std::string& group_name, double& condition_number,
113  bool translation = false) const;
114 
124  bool getManipulability(const moveit::core::RobotState& state, const moveit::core::JointModelGroup* joint_model_group,
125  double& condition_number, bool translation = false) const;
126 
127  void setPenaltyMultiplier(double multiplier)
128  {
129  penalty_multiplier_ = fabs(multiplier);
130  }
131 
132  const double& getPenaltyMultiplier() const
133  {
134  return penalty_multiplier_;
135  }
136 
137 protected:
138  moveit::core::RobotModelConstPtr robot_model_;
139 
140 private:
154  const moveit::core::JointModelGroup* joint_model_group) const;
155 
156  double penalty_multiplier_;
157 };
158 } // namespace kinematics_metrics
kinematics_metrics::KinematicsMetrics::getJointLimitsPenalty
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...
Definition: kinematics_metrics.cpp:76
kinematics_metrics::KinematicsMetrics::KinematicsMetrics
KinematicsMetrics(const moveit::core::RobotModelConstPtr &robot_model)
Construct a KinematicsMetricss from a RobotModel.
Definition: kinematics_metrics.h:86
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
kinematics_metrics::KinematicsMetrics::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: kinematics_metrics.h:170
kinematics_metrics::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(KinematicsMetrics)
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
kinematics_metrics::KinematicsMetrics::getPenaltyMultiplier
const double & getPenaltyMultiplier() const
Definition: kinematics_metrics.h:164
kinematics_metrics
Namespace for kinematics metrics.
Definition: kinematics_metrics.h:42
kinematics_metrics::KinematicsMetrics::setPenaltyMultiplier
void setPenaltyMultiplier(double multiplier)
Definition: kinematics_metrics.h:159
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
kinematics_metrics::KinematicsMetrics
Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability.
Definition: kinematics_metrics.h:82
kinematics_metrics::KinematicsMetrics::getManipulability
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...
Definition: kinematics_metrics.cpp:227
kinematics_metrics::KinematicsMetrics::penalty_multiplier_
double penalty_multiplier_
Definition: kinematics_metrics.h:188
kinematics_metrics::KinematicsMetrics::getManipulabilityEllipsoid
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.
Definition: kinematics_metrics.cpp:197
kinematics_metrics::KinematicsMetrics::getManipulabilityIndex
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.
Definition: kinematics_metrics.cpp:126
robot_state.h


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:35