model_kdl.cpp
Go to the documentation of this file.
2 
4 #include <ros/ros.h>
5 #include <Eigen/Dense>
6 #include <algorithm>
7 #include <array>
8 #include <kdl/chain.hpp>
9 #include <kdl/chainfksolverpos_recursive.hpp>
10 #include <kdl/frames.hpp>
11 #include <kdl/solveri.hpp>
12 #include <kdl/tree.hpp>
14 
15 namespace franka_gazebo {
16 
17 int ModelKDL::segment(franka::Frame frame) {
18  // clang-format off
19  switch (frame) {
20  case franka::Frame::kJoint1: return 1;
21  case franka::Frame::kJoint2: return 2;
22  case franka::Frame::kJoint3: return 3;
23  case franka::Frame::kJoint4: return 4;
24  case franka::Frame::kJoint5: return 5;
25  case franka::Frame::kJoint6: return 6;
26  case franka::Frame::kJoint7: return 7;
27  case franka::Frame::kFlange: return 8;
28  case franka::Frame::kEndEffector: return 9;
29  case franka::Frame::kStiffness: return 10;
30  default: return -1;
31  }
32  // clang-format on
33 }
34 
35 bool ModelKDL::isCloseToSingularity(const KDL::Jacobian& jacobian) const {
36  if (this->singularity_threshold_ < 0) {
37  return false;
38  }
39  Eigen::Matrix<double, 6, 6> mat = jacobian.data * jacobian.data.transpose();
40  Eigen::JacobiSVD<Eigen::MatrixXd> svd(mat, Eigen::ComputeFullU | Eigen::ComputeFullV);
41  double critical = svd.singularValues().tail(1)(0);
42  return critical < this->singularity_threshold_;
43 }
44 
45 // Implementation copied from <kdl/isolveri.hpp> because
46 // KDL::ChainDynSolver inherits *privately* from SolverI ... -.-'
47 std::string ModelKDL::strError(const int error) {
48  // clang-format off
49  switch(error) {
50  case KDL::SolverI::E_NOERROR: return "No error"; break;
51  case KDL::SolverI::E_NO_CONVERGE: return "Failed to converge"; break;
52  case KDL::SolverI::E_UNDEFINED: return "Undefined value"; break;
53  case KDL::SolverI::E_DEGRADED: return "Converged but degraded solution"; break;
54 #if ROS_VERSION_MINIMUM(1, 15, 0)
55  // These were introduced in melodic
56  case KDL::SolverI::E_NOT_UP_TO_DATE: return "Internal data structures not up to date with Chain"; break;
57  case KDL::SolverI::E_SIZE_MISMATCH: return "The size of the input does not match the internal state"; break;
58  case KDL::SolverI::E_MAX_ITERATIONS_EXCEEDED: return "The maximum number of iterations is exceeded"; break;
59  case KDL::SolverI::E_OUT_OF_RANGE: return "The requested index is out of range"; break;
60  case KDL::SolverI::E_NOT_IMPLEMENTED: return "The requested function is not yet implemented"; break;
61  case KDL::SolverI::E_SVD_FAILED: return "SVD failed"; break;
62 #endif
63  default: return "UNKNOWN ERROR";
64  }
65  // clang-format on
66 }
68  const std::string& root,
69  const std::string& tip,
70  double singularity_threshold)
71  : singularity_threshold_(singularity_threshold) {
72  KDL::Tree tree;
73  if (not kdl_parser::treeFromUrdfModel(model, tree)) {
74  throw std::invalid_argument("Cannot construct KDL tree from URDF");
75  }
76 
77  if (not tree.getChain(root, tip, this->chain_)) {
78  throw std::invalid_argument("Cannot find chain within URDF tree from root '" + root +
79  "' to tip '" + tip + "'. Do these links exist?");
80  }
81 
82  ROS_INFO_STREAM("KDL Model initialized for chain from '" << root << "' -> '" << tip << "'");
83 }
84 
85 void ModelKDL::augmentFrame(const std::string& name,
86  const std::array<double, 16>& transform,
87  KDL::Chain& chain) {
88  Eigen::Affine3d t;
89  KDL::Frame f;
90  t.matrix() = Eigen::Matrix4d(transform.data());
92  chain.addSegment(KDL::Segment(name, KDL::Joint(KDL::Joint::None), f));
93 }
94 
95 void ModelKDL::augmentFrame(const std::string& name,
96  const std::array<double, 3>& center_of_mass,
97  double mass,
98  const std::array<double, 9>& inertia,
99  KDL::Chain& chain) {
100  KDL::Vector kc;
101  KDL::RotationalInertia ki;
102  std::copy(center_of_mass.begin(), center_of_mass.end(), std::begin(kc.data));
103  std::copy(inertia.begin(), inertia.end(), std::begin(ki.data));
104 
105  chain.addSegment(KDL::Segment(name, KDL::Joint(KDL::Joint::None), KDL::Frame(KDL::Vector::Zero()),
106  KDL::RigidBodyInertia(mass, kc, ki)));
107 }
108 
109 std::array<double, 16> ModelKDL::pose(
110  franka::Frame frame,
111  const std::array<double, 7>& q,
112  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
113  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
114  const {
115  KDL::JntArray kq;
116  KDL::Frame kp;
117 
118  // Agument the chain with the two new Frames 'EE' and 'K'
119  KDL::Chain chain = this->chain_; // copy
120  augmentFrame("EE", F_T_EE, chain);
121  augmentFrame("K", EE_T_K, chain);
122 
123  KDL::ChainFkSolverPos_recursive solver(chain);
124 
125  kq.data = Eigen::Matrix<double, 7, 1>(q.data());
126 
127  int error = solver.JntToCart(kq, kp, segment(frame));
128  if (error != KDL::SolverI::E_NOERROR) {
129  throw std::logic_error("KDL forward kinematics pose calculation failed with error: " +
130  strError(error));
131  }
132  Eigen::Affine3d p;
134 
135  std::array<double, 16> result;
136  Eigen::MatrixXd::Map(&result[0], 4, 4) = p.matrix();
137 
138  return result;
139 }
140 
141 std::array<double, 42> ModelKDL::bodyJacobian(
142  franka::Frame frame,
143  const std::array<double, 7>& q,
144  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
145  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
146  const {
147  KDL::JntArray kq;
148  KDL::Jacobian J(7); // NOLINT(readability-identifier-naming)
149  kq.data = Eigen::Matrix<double, 7, 1>(q.data());
150 
151  // Augment the chain with the two virtual frames 'EE' and 'K'
152  KDL::Chain chain = this->chain_; // copy
153  augmentFrame("EE", F_T_EE, chain);
154  augmentFrame("K", EE_T_K, chain);
155 
156  KDL::ChainJntToJacSolver solver(chain);
157 
158  int seg = segment(frame);
159  int error = solver.JntToJac(kq, J, seg);
160  if (error != KDL::SolverI::E_NOERROR) {
161  throw std::logic_error("KDL zero jacobian calculation failed with error: " + strError(error));
162  }
163 
164  // Shift the zero jacobian to the "body" frame by using the rotation of the FK of that frame
165  KDL::Frame f = KDL::Frame::Identity();
166  auto transform = pose(frame, q, F_T_EE, EE_T_K);
167  Eigen::Affine3d t;
168  t.matrix() = Eigen::Matrix4d(transform.data());
170 
171  J.changeBase(f.M.Inverse());
172 
173  // Singularity check
174  if (isCloseToSingularity(J)) {
175  ROS_WARN_STREAM_THROTTLE(1, "Body Jacobian close to singularity");
176  }
177 
178  std::array<double, 42> result;
179  Eigen::MatrixXd::Map(&result[0], 6, 7) = J.data;
180 
181  return result;
182 }
183 
184 std::array<double, 42> ModelKDL::zeroJacobian(
185  franka::Frame frame,
186  const std::array<double, 7>& q,
187  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
188  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
189  const {
190  KDL::JntArray kq;
191  KDL::Jacobian J(7); // NOLINT(readability-identifier-naming)
192  kq.data = Eigen::Matrix<double, 7, 1>(q.data());
193 
194  // Augment the chain with the two virtual frames 'EE' and 'K'
195  KDL::Chain chain = this->chain_; // copy
196  augmentFrame("EE", F_T_EE, chain);
197  augmentFrame("K", EE_T_K, chain);
198 
199  KDL::ChainJntToJacSolver solver(chain);
200 
201  int error = solver.JntToJac(kq, J, segment(frame));
202  if (error != KDL::SolverI::E_NOERROR) {
203  throw std::logic_error("KDL zero jacobian calculation failed with error: " + strError(error));
204  }
205 
206  // Singularity Check
207  if (isCloseToSingularity(J)) {
208  ROS_WARN_STREAM_THROTTLE(1, "Zero Jacobian close to singularity");
209  }
210 
211  std::array<double, 42> result;
212  Eigen::MatrixXd::Map(&result[0], 6, 7) = J.data;
213 
214  return result;
215 }
216 
217 std::array<double, 49> ModelKDL::mass(
218  const std::array<double, 7>& q,
219  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
220  double m_total,
221  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
222  const {
223  KDL::JntArray kq;
224  KDL::JntSpaceInertiaMatrix M(7); // NOLINT(readability-identifier-naming)
225  kq.data = Eigen::Matrix<double, 7, 1>(q.data());
226 
227  KDL::Chain chain = this->chain_; // copy
228  augmentFrame("load", F_x_Ctotal, m_total, I_total, chain);
229  KDL::ChainDynParam solver(chain, KDL::Vector(0, 0, -9.81));
230 
231  int error = solver.JntToMass(kq, M);
232  if (error != KDL::SolverI::E_NOERROR) {
233  throw std::logic_error("KDL mass calculation failed with error: " + strError(error));
234  }
235 
236  std::array<double, 49> result;
237  Eigen::MatrixXd::Map(&result[0], 7, 7) = M.data;
238 
239  return result;
240 }
241 
242 std::array<double, 7> ModelKDL::coriolis(
243  const std::array<double, 7>& q,
244  const std::array<double, 7>& dq,
245  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
246  double m_total,
247  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
248  const {
249  KDL::JntArray kq, kdq, kc(7);
250  kq.data = Eigen::Matrix<double, 7, 1>(q.data());
251  kdq.data = Eigen::Matrix<double, 7, 1>(dq.data());
252 
253  KDL::Chain chain = this->chain_; // copy
254  augmentFrame("load", F_x_Ctotal, m_total, I_total, chain);
255  KDL::ChainDynParam solver(chain, KDL::Vector(0, 0, -9.81));
256 
257  int error = solver.JntToCoriolis(kq, kdq, kc);
258  if (error != KDL::SolverI::E_NOERROR) {
259  throw std::logic_error("KDL coriolis calculation failed with error: " + strError(error));
260  }
261 
262  std::array<double, 7> result;
263  Eigen::VectorXd::Map(&result[0], kc.data.size()) = kc.data;
264 
265  return result;
266 }
267 
268 std::array<double, 7> ModelKDL::gravity(
269  const std::array<double, 7>& q,
270  double m_total,
271  const std::array<double, 3>& F_x_Ctotal, // NOLINT(readability-identifier-naming)
272  const std::array<double, 3>& gravity_earth) const {
273  KDL::JntArray kq, kg(7);
274  KDL::Vector grav(gravity_earth[0], gravity_earth[1], gravity_earth[2]);
275  kq.data = Eigen::Matrix<double, 7, 1>(q.data());
276 
277  KDL::Chain chain = this->chain_; // copy
278  augmentFrame("load", F_x_Ctotal, m_total, {1, 0, 0, 0, 1, 0, 0, 0, 1}, chain);
279  KDL::ChainDynParam solver(chain, grav);
280 
281  int error = solver.JntToGravity(kq, kg);
282  if (error != KDL::SolverI::E_NOERROR) {
283  throw std::logic_error("KDL gravity calculation failed with error: " + strError(error));
284  }
285 
286  std::array<double, 7> result;
287  Eigen::VectorXd::Map(&result[0], kg.data.size()) = kg.data;
288 
289  return result;
290 }
291 } // namespace franka_gazebo
result
result
franka_gazebo
Definition: controller_verifier.h:8
franka_gazebo::ModelKDL::mass
std::array< double, 49 > mass(const std::array< double, 7 > &q, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const override
Calculates the 7x7 mass matrix.
Definition: model_kdl.cpp:217
franka_gazebo::ModelKDL::isCloseToSingularity
bool isCloseToSingularity(const KDL::Jacobian &jacobian) const
Definition: model_kdl.cpp:35
franka_gazebo::ModelKDL::zeroJacobian
std::array< double, 42 > zeroJacobian(franka::Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const override
Gets the 6x7 Jacobian for the given joint relative to the base frame.
Definition: model_kdl.cpp:184
ros.h
urdf::Model
kdl_parser::treeFromUrdfModel
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
f
f
franka_gazebo::ModelKDL::gravity
std::array< double, 7 > gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth) const override
Calculates the gravity vector.
Definition: model_kdl.cpp:268
franka_gazebo::ModelKDL::singularity_threshold_
double singularity_threshold_
Definition: model_kdl.h:196
franka_gazebo::ModelKDL::chain_
KDL::Chain chain_
Definition: model_kdl.h:195
ROS_WARN_STREAM_THROTTLE
#define ROS_WARN_STREAM_THROTTLE(period, args)
franka_gazebo::ModelKDL::bodyJacobian
std::array< double, 42 > bodyJacobian(franka::Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const override
Gets the 6x7 Jacobian for the given frame, relative to that frame.
Definition: model_kdl.cpp:141
franka_gazebo::ModelKDL::augmentFrame
static void augmentFrame(const std::string &name, const std::array< double, 16 > &transform, KDL::Chain &chain)
Augment a kinematic chain by adding a virtual frame to it.
Definition: model_kdl.cpp:85
franka_gazebo::ModelKDL::segment
static int segment(franka::Frame frame)
Definition: model_kdl.cpp:17
franka_gazebo::ModelKDL::ModelKDL
ModelKDL(const urdf::Model &model, const std::string &root, const std::string &tip, double singularity_threshold=-1)
Create a new implementation for the ModelBase with KDL as backend.
Definition: model_kdl.cpp:67
tf::transformEigenToKDL
void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
name
name
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
model_kdl.h
kdl_parser.hpp
franka_gazebo::ModelKDL::coriolis
std::array< double, 7 > coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const override
Calculates the Coriolis force vector (state-space equation): , in .
Definition: model_kdl.cpp:242
tf::transformKDLToEigen
void transformKDLToEigen(const KDL::Frame &k, Eigen::Affine3d &e)
franka_gazebo::ModelKDL::strError
static std::string strError(const int error)
Definition: model_kdl.cpp:47
eigen_kdl.h
error
def error(*args, **kwargs)
franka_gazebo::ModelKDL::pose
std::array< double, 16 > pose(franka::Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const override
Gets the 4x4 pose matrix for the given frame in base frame.
Definition: model_kdl.cpp:109


franka_gazebo
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:28