model.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <array>
4 
5 #include <franka/model.h>
6 #include <franka_hw/model_base.h>
7 
8 namespace franka_hw {
9 
17 class Model : public ModelBase {
18  public:
22  Model(franka::Model&& model) : model_(std::move(model)) {}
23 
24  std::array<double, 16> pose(
25  franka::Frame frame,
26  const std::array<double, 7>& q,
27  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
28  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
29  const override {
30  return model_.pose(frame, q, F_T_EE, EE_T_K);
31  }
32 
33  std::array<double, 42> bodyJacobian(
34  franka::Frame frame,
35  const std::array<double, 7>& q,
36  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
37  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
38  const override {
39  return model_.bodyJacobian(frame, q, F_T_EE, EE_T_K);
40  }
41 
42  std::array<double, 42> zeroJacobian(
43  franka::Frame frame,
44  const std::array<double, 7>& q,
45  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
46  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
47  const override {
48  return model_.zeroJacobian(frame, q, F_T_EE, EE_T_K);
49  }
50 
51  std::array<double, 49> mass(
52  const std::array<double, 7>& q,
53  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
54  double m_total,
55  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
56  const noexcept override {
57  return model_.mass(q, I_total, m_total, F_x_Ctotal);
58  }
59 
60  std::array<double, 7> coriolis(
61  const std::array<double, 7>& q,
62  const std::array<double, 7>& dq,
63  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
64  double m_total,
65  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
66  const noexcept override {
67  return model_.coriolis(q, dq, I_total, m_total, F_x_Ctotal);
68  }
69 
70  std::array<double, 7> gravity(
71  const std::array<double, 7>& q,
72  double m_total,
73  const std::array<double, 3>& F_x_Ctotal, // NOLINT(readability-identifier-naming)
74  const std::array<double, 3>& gravity_earth) const noexcept override {
75  return model_.gravity(q, m_total, F_x_Ctotal, gravity_earth);
76  }
77 
78  private:
79  franka::Model model_;
80 };
81 
82 } // namespace franka_hw
franka_hw::Model::Model
Model(franka::Model &&model)
Create a new Model instance wrapped around a franka::Model.
Definition: model.h:22
model_base.h
franka_hw::Model
An implementation of the abstract ModelBase specialized for obtaining the model from the real robot.
Definition: model.h:17
franka_hw::Model::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 noexcept override
Calculates the gravity vector.
Definition: model.h:70
franka_hw::Model::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 noexcept override
Calculates the 7x7 mass matrix.
Definition: model.h:51
franka_hw::ModelBase
Calculates poses of joints and dynamic properties of the robot.
Definition: model_base.h:20
franka_hw::Model::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.h:42
franka_hw::Model::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.h:33
franka_hw::Model::model_
franka::Model model_
Definition: model.h:79
franka_hw::Model::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.h:24
franka_hw
Definition: control_mode.h:8
std
franka_hw::Model::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 noexcept override
Calculates the Coriolis force vector (state-space equation): , in .
Definition: model.h:60


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