franka_model_interface.h
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
3 #pragma once
4 
5 #include <array>
6 #include <string>
7 
8 #include <franka/model.h>
9 #include <franka/robot_state.h>
10 #include <franka_hw/model.h>
11 #include <franka_hw/model_base.h>
13 
14 namespace franka_hw {
15 
20  public:
21  FrankaModelHandle() = delete;
22 
30  FrankaModelHandle(const std::string& name,
31  franka_hw::ModelBase& model,
32  franka::RobotState& robot_state)
33  : name_(name), model_(&model), robot_state_(&robot_state) {}
34 
40  std::string getName() const noexcept { return name_; }
41 
49  std::array<double, 49> getMass() const { return model_->mass(*robot_state_); }
50 
67  std::array<double, 49> getMass(
68  const std::array<double, 7>& q,
69  const std::array<double, 9>& total_inertia,
70  double total_mass,
71  const std::array<double, 3>& F_x_Ctotal) const { // NOLINT (readability-identifier-naming)
72  return model_->mass(q, total_inertia, total_mass, F_x_Ctotal);
73  }
74 
83  std::array<double, 7> getCoriolis() const { return model_->coriolis(*robot_state_); }
84 
103  std::array<double, 7> getCoriolis(
104  const std::array<double, 7>& q,
105  const std::array<double, 7>& dq,
106  const std::array<double, 9>& total_inertia,
107  double total_mass,
108  const std::array<double, 3>& F_x_Ctotal) const { // NOLINT (readability-identifier-naming)
109  return model_->coriolis(q, dq, total_inertia, total_mass, F_x_Ctotal);
110  }
111 
122  std::array<double, 7> getGravity(const std::array<double, 3>& gravity_earth = {
123  {0., 0., -9.81}}) const {
124  return model_->gravity(*robot_state_, gravity_earth);
125  }
126 
143  std::array<double, 7> getGravity(
144  const std::array<double, 7>& q,
145  double total_mass,
146  const std::array<double, 3>& F_x_Ctotal, // NOLINT (readability-identifier-naming)
147  const std::array<double, 3>& gravity_earth = {{0., 0., -9.81}}) const {
148  return model_->gravity(q, total_mass, F_x_Ctotal, gravity_earth);
149  }
150 
163  std::array<double, 16> getPose(const franka::Frame& frame) const {
164  return model_->pose(frame, *robot_state_);
165  }
166 
182  std::array<double, 16> getPose(
183  const franka::Frame& frame,
184  const std::array<double, 7>& q,
185  const std::array<double, 16>& F_T_EE, // NOLINT (readability-identifier-naming)
186  const std::array<double, 16>& EE_T_K) // NOLINT (readability-identifier-naming)
187  const {
188  return model_->pose(frame, q, F_T_EE, EE_T_K);
189  }
190 
203  std::array<double, 42> getBodyJacobian(const franka::Frame& frame) const {
204  return model_->bodyJacobian(frame, *robot_state_);
205  }
206 
222  std::array<double, 42> getBodyJacobian(
223  const franka::Frame& frame,
224  const std::array<double, 7>& q,
225  const std::array<double, 16>& F_T_EE, // NOLINT (readability-identifier-naming)
226  const std::array<double, 16>& EE_T_K) // NOLINT (readability-identifier-naming)
227  const {
228  return model_->bodyJacobian(frame, q, F_T_EE, EE_T_K);
229  }
230 
243  std::array<double, 42> getZeroJacobian(const franka::Frame& frame) const {
244  return model_->zeroJacobian(frame, *robot_state_);
245  }
246 
262  std::array<double, 42> getZeroJacobian(
263  const franka::Frame& frame,
264  const std::array<double, 7>& q,
265  const std::array<double, 16>& F_T_EE, // NOLINT (readability-identifier-naming)
266  const std::array<double, 16>& EE_T_K) // NOLINT (readability-identifier-naming)
267  const {
268  return model_->zeroJacobian(frame, q, F_T_EE, EE_T_K);
269  }
270 
271  private:
272  std::string name_;
274  const franka::RobotState* robot_state_;
275 };
276 
281 };
282 
283 } // namespace franka_hw
franka_hw::ModelBase::pose
std::array< double, 16 > pose(franka::Frame frame, const franka::RobotState &robot_state) const
Gets the 4x4 pose matrix for the given frame in base frame.
Definition: model_base.h:34
franka_hw::FrankaModelHandle::getBodyJacobian
std::array< double, 42 > getBodyJacobian(const franka::Frame &frame) const
Gets the 6x7 Jacobian for the given frame, relative to that frame.
Definition: franka_model_interface.h:203
franka_hw::FrankaModelHandle::getPose
std::array< double, 16 > getPose(const 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
Gets the 4x4 pose matrix for the given frame in base frame, calculated from the given robot state.
Definition: franka_model_interface.h:182
model.h
franka_hw::ModelBase::coriolis
std::array< double, 7 > coriolis(const franka::RobotState &robot_state) const
Calculates the Coriolis force vector (state-space equation): , in .
Definition: model_base.h:164
franka_hw::FrankaModelHandle::getCoriolis
std::array< double, 7 > getCoriolis() const
Calculates the Coriolis force vector (state-space equation) from the current robot state: ,...
Definition: franka_model_interface.h:83
franka_hw::FrankaModelHandle::name_
std::string name_
Definition: franka_model_interface.h:272
franka_hw::FrankaModelHandle::getGravity
std::array< double, 7 > getGravity(const std::array< double, 7 > &q, double total_mass, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const
Calculates the gravity vector from the given robot state.
Definition: franka_model_interface.h:143
franka_hw::ModelBase::gravity
std::array< double, 7 > gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal) const
Calculates the gravity vector.
Definition: model_base.h:203
franka_hw::FrankaModelHandle::getPose
std::array< double, 16 > getPose(const franka::Frame &frame) const
Gets the 4x4 pose matrix for the given frame in base frame, calculated from the current robot state.
Definition: franka_model_interface.h:163
franka_hw::FrankaModelHandle::FrankaModelHandle
FrankaModelHandle()=delete
franka_hw::FrankaModelHandle::robot_state_
const franka::RobotState * robot_state_
Definition: franka_model_interface.h:274
franka_hw::ModelBase::mass
std::array< double, 49 > mass(const franka::RobotState &robot_state) const
Calculates the 7x7 mass matrix.
Definition: model_base.h:132
model_base.h
franka_hw::ModelBase::zeroJacobian
std::array< double, 42 > zeroJacobian(franka::Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given joint relative to the base frame.
Definition: model_base.h:101
franka_hw::FrankaModelHandle::getCoriolis
std::array< double, 7 > getCoriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &total_inertia, double total_mass, const std::array< double, 3 > &F_x_Ctotal) const
Calculates the Coriolis force vector (state-space equation) from the given robot state: ,...
Definition: franka_model_interface.h:103
franka_hw::ModelBase
Calculates poses of joints and dynamic properties of the robot.
Definition: model_base.h:20
franka_hw::FrankaModelHandle::getMass
std::array< double, 49 > getMass() const
Calculates the 7x7 mass matrix from the current robot state.
Definition: franka_model_interface.h:49
franka_hw::FrankaModelHandle::getBodyJacobian
std::array< double, 42 > getBodyJacobian(const 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
Gets the 6x7 Jacobian for the given frame, relative to that frame.
Definition: franka_model_interface.h:222
franka_hw::FrankaModelHandle::getZeroJacobian
std::array< double, 42 > getZeroJacobian(const 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
Gets the 6x7 Jacobian for the given joint relative to the base frame.
Definition: franka_model_interface.h:262
franka_hw::FrankaModelInterface
Hardware interface to perform calculations using the dynamic model of a robot.
Definition: franka_model_interface.h:280
franka_hw
Definition: control_mode.h:8
franka_hw::FrankaModelHandle::getName
std::string getName() const noexcept
Gets the name of the model handle.
Definition: franka_model_interface.h:40
franka_hw::FrankaModelHandle::getZeroJacobian
std::array< double, 42 > getZeroJacobian(const franka::Frame &frame) const
Gets the 6x7 Jacobian for the given joint relative to the base frame.
Definition: franka_model_interface.h:243
franka_hw::FrankaModelHandle::getGravity
std::array< double, 7 > getGravity(const std::array< double, 3 > &gravity_earth={ {0., 0., -9.81}}) const
Calculates the gravity vector from the current robot state.
Definition: franka_model_interface.h:122
franka_hw::FrankaModelHandle::model_
const franka_hw::ModelBase * model_
Definition: franka_model_interface.h:273
franka_hw::ModelBase::bodyJacobian
std::array< double, 42 > bodyJacobian(franka::Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given frame, relative to that frame.
Definition: model_base.h:67
franka_hw::FrankaModelHandle
Handle to perform calculations using the dynamic model of a robot.
Definition: franka_model_interface.h:19
hardware_interface::HardwareResourceManager
franka_hw::FrankaModelHandle::FrankaModelHandle
FrankaModelHandle(const std::string &name, franka_hw::ModelBase &model, franka::RobotState &robot_state)
Creates an instance of a FrankaModelHandle.
Definition: franka_model_interface.h:30
franka_hw::FrankaModelHandle::getMass
std::array< double, 49 > getMass(const std::array< double, 7 > &q, const std::array< double, 9 > &total_inertia, double total_mass, const std::array< double, 3 > &F_x_Ctotal) const
Calculates the 7x7 mass matrix from a given robot state.
Definition: franka_model_interface.h:67
hardware_resource_manager.h


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