libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
robot_model_base.h
1// Copyright (c) 2024 Franka Robotics 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
11 public:
12 virtual ~RobotModelBase() = default;
27 virtual void coriolis(const std::array<double, 7>& q,
28 const std::array<double, 7>& dq,
29 const std::array<double, 9>& i_total,
30 double m_total,
31 const std::array<double, 3>& f_x_ctotal,
32 std::array<double, 7>& c_ne) = 0;
43 virtual void gravity(const std::array<double, 7>& q,
44 const std::array<double, 3>& g_earth,
45 double m_total,
46 const std::array<double, 3>& f_x_ctotal,
47 std::array<double, 7>& g_ne) = 0;
48
61 virtual void mass(const std::array<double, 7>& q,
62 const std::array<double, 9>& i_total,
63 double m_total,
64 const std::array<double, 3>& f_x_ctotal,
65 std::array<double, 49>& m_ne) = 0;
66};
Robot dynamic parameters computed from the URDF model with Pinocchio.
Definition robot_model_base.h:10
virtual void 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, std::array< double, 7 > &c_ne)=0
Calculates the Coriolis force vector (state-space equation): , in .
virtual void gravity(const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne)=0
Calculates the gravity vector.
virtual void 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, std::array< double, 49 > &m_ne)=0
Calculates the 7x7 mass matrix.