model_kdl.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <franka/robot_state.h>
4 #include <franka_hw/model_base.h>
5 #include <urdf/model.h>
6 #include <array>
7 #include <kdl/chaindynparam.hpp>
8 #include <kdl/chainfksolver.hpp>
9 #include <kdl/chainjnttojacsolver.hpp>
10 #include <memory>
11 #include <string>
12 
13 namespace franka_gazebo {
14 
22  public:
34  ModelKDL(const urdf::Model& model,
35  const std::string& root,
36  const std::string& tip,
37  double singularity_threshold = -1);
38 
51  std::array<double, 16> pose(
52  franka::Frame frame,
53  const std::array<double, 7>& q,
54  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
55  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
56  const override;
57 
72  std::array<double, 42> bodyJacobian(
73  franka::Frame frame,
74  const std::array<double, 7>& q,
75  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
76  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
77  const override;
78 
91  std::array<double, 42> zeroJacobian(
92  franka::Frame frame,
93  const std::array<double, 7>& q,
94  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
95  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
96  const override;
97 
111  std::array<double, 49> mass(
112  const std::array<double, 7>& q,
113  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
114  double m_total,
115  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
116  const override;
117 
133  std::array<double, 7> coriolis(
134  const std::array<double, 7>& q,
135  const std::array<double, 7>& dq,
136  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
137  double m_total,
138  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
139  const override;
140 
153  std::array<double, 7> gravity(
154  const std::array<double, 7>& q,
155  double m_total,
156  const std::array<double, 3>& F_x_Ctotal, // NOLINT(readability-identifier-naming)
157  const std::array<double, 3>& gravity_earth) const override;
158 
168  static void augmentFrame(const std::string& name,
169  const std::array<double, 16>& transform,
170  KDL::Chain& chain);
171 
184  static void augmentFrame(const std::string& name,
185  const std::array<double, 3>& center_of_mass,
186  double mass,
187  const std::array<double, 9>& inertia,
188  KDL::Chain& chain);
189 
190  private:
191  static int segment(franka::Frame frame);
192  static std::string strError(const int error);
193  bool isCloseToSingularity(const KDL::Jacobian& jacobian) const;
194 
195  KDL::Chain chain_;
197 };
198 
199 } // namespace franka_gazebo
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
urdf::Model
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
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
franka_hw::ModelBase
name
name
model.h
franka_gazebo::ModelKDL
Calculates poses of links and dynamic properties of the robot.
Definition: model_kdl.h:21
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
model_base.h
franka_gazebo::ModelKDL::strError
static std::string strError(const int error)
Definition: model_kdl.cpp:47
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