libfranka 0.15.0
FCI C++ API
|
Robot dynamic parameters computed from the URDF model with Pinocchio. More...
#include <robot_model_base.h>
Public Member Functions | |
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): \( c= C \times
dq\), in \([Nm]\). | |
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. | |
Robot dynamic parameters computed from the URDF model with Pinocchio.
|
pure virtual |
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]\). |
Implemented in franka::RobotModel.
|
pure virtual |
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]\). |
Implemented in franka::RobotModel.
|
pure virtual |
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. |
Implemented in franka::RobotModel.