Class RobotModelBase
Defined in File robot_model_base.h
Inheritance Relationships
Derived Type
public franka::RobotModel
(Class RobotModel)
Class Documentation
-
class RobotModelBase
Robot dynamic parameters computed from the URDF model with Pinocchio.
Subclassed by franka::RobotModel
Public Functions
-
virtual ~RobotModelBase() = default
-
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 .- Parameters:
q – [in] Joint position.
dq – [in] Joint velocity.
i_total – [in] Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit:
.m_total – [in] Weight of the attached total load including end effector. Unit:
.f_x_ctotal – [in] Translation from flange to center of mass of the attached total load. Unit:
.c_ne – [out] Coriolis force vector. Unit:
.
-
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. Unit:
.- Parameters:
q – [in] Joint position.
gravity_earth – [in] Earth’s gravity vector. Unit:
.m_total – [in] Weight of the attached total load including end effector. Unit:
.f_x_Ctotal – [in] Translation from flange to center of mass of the attached total load.
g_ne – [out] Gravity vector. Unit:
.
-
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. Unit:
.- Parameters:
q – [in] Joint position.
i_total – [in] Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit:
.m_total – [in] Weight of the attached total load including end effector. Unit:
.f_x_ctotal – [in] Translation from flange to center of mass of the attached total load. Unit:
.m_ne – [out] Vectorized 7x7 mass matrix, column-major.
-
virtual ~RobotModelBase() = default