![]() |
libfranka 0.15.0
FCI C++ API
|
Implements RobotModelBase using Pinocchio. More...
#include <robot_model.h>
Public Member Functions | |
RobotModel (const std::string &urdf) | |
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) override |
Calculates the Coriolis force vector (state-space equation): c= C \times
dq, in [Nm]. | |
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) override |
Calculates the gravity vector. | |
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) override |
Calculates the 7x7 mass matrix. | |
Implements RobotModelBase using Pinocchio.
|
overridevirtual |
Calculates the Coriolis force vector (state-space equation): c= C \times dq, in [Nm].
[in] | q | Joint position. |
[in] | dq | Joint velocity. |
[in] | i_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: [kg \times m^2]. |
[in] | m_total | Weight of the attached total load including end effector. Unit: [kg]. |
[in] | f_x_ctotal | Translation from flange to center of mass of the attached total load. Unit: [m]. |
[out] | c_ne | Coriolis force vector. Unit: [Nm]. |
Implements RobotModelBase.
|
overridevirtual |
Calculates the gravity vector.
Unit: [Nm].
[in] | q | Joint position. |
[in] | gravity_earth | Earth's gravity vector. Unit: \frac{m}{s^2}. |
[in] | m_total | Weight of the attached total load including end effector. Unit: [kg]. |
[in] | f_x_Ctotal | Translation from flange to center of mass of the attached total load. |
[out] | g_ne | Gravity vector. Unit: [Nm]. |
Implements RobotModelBase.
|
overridevirtual |
Calculates the 7x7 mass matrix.
Unit: [kg \times m^2].
[in] | q | Joint position. |
[in] | i_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: [kg \times m^2]. |
[in] | m_total | Weight of the attached total load including end effector. Unit: [kg]. |
[in] | f_x_ctotal | Translation from flange to center of mass of the attached total load. Unit: [m]. |
[out] | m_ne | Vectorized 7x7 mass matrix, column-major. |
Implements RobotModelBase.