![]() |
libfranka 0.18.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 | 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, const std::array< double, 3 > &g_earth, std::array< double, 7 > &c_ne)=0 |
| Calculates the Coriolis force vector with configurable gravity (recommended implementation). | |
| 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 inertia matrix. | |
| virtual std::array< double, 16 > | pose (const std::array< double, 7 > &q, int joint_index)=0 |
| Calculates the homogeneous transformation matrix for the specified joint or link. | |
| virtual std::array< double, 16 > | poseEe (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee)=0 |
| Calculates the homogeneous transformation matrix for the end effector, applying the end effector transformation. | |
| virtual std::array< double, 16 > | poseFlange (const std::array< double, 7 > &q)=0 |
| Calculates the homogeneous transformation matrix for the flange. | |
| virtual std::array< double, 16 > | poseStiffness (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee, const std::array< double, 16 > &ee_t_k)=0 |
| Calculates the homogeneous transformation matrix for the stiffness frame. | |
| virtual std::array< double, 42 > | bodyJacobian (const std::array< double, 7 > &q, int joint_index)=0 |
| Calculates the 6x7 body Jacobian for the given joint, relative to that joint's frame. | |
| virtual std::array< double, 42 > | bodyJacobianFlange (const std::array< double, 7 > &q)=0 |
| Calculates the 6x7 body Jacobian for the flange frame, relative to that frame. | |
| virtual std::array< double, 42 > | bodyJacobianEe (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee)=0 |
| Calculates the 6x7 body Jacobian for the end effector frame, relative to that frame. | |
| virtual std::array< double, 42 > | bodyJacobianStiffness (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee, const std::array< double, 16 > &ee_t_k)=0 |
| Calculates the 6x7 body Jacobian for the stiffness frame, relative to that frame. | |
| virtual std::array< double, 42 > | zeroJacobian (const std::array< double, 7 > &q, int joint_index)=0 |
| Calculates the 6x7 zero Jacobian for the given joint, relative to the base frame. | |
| virtual std::array< double, 42 > | zeroJacobianFlange (const std::array< double, 7 > &q)=0 |
| Calculates the 6x7 zero Jacobian for the flange frame, relative to the base frame. | |
| virtual std::array< double, 42 > | zeroJacobianEe (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee)=0 |
| Calculates the 6x7 zero Jacobian for the end effector frame, relative to the base frame. | |
| virtual std::array< double, 42 > | zeroJacobianStiffness (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee, const std::array< double, 16 > &ee_t_k)=0 |
| Calculates the 6x7 zero Jacobian for the stiffness frame, relative to the base frame. | |
Robot dynamic parameters computed from the URDF model with Pinocchio.
|
pure virtual |
Calculates the 6x7 body Jacobian for the given joint, relative to that joint's frame.
| [in] | q | Joint position. |
| [in] | joint_index | The index of the joint/link for which to calculate the Jacobian. |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the 6x7 body Jacobian for the end effector frame, relative to that frame.
| [in] | q | Joint position. |
| [in] | f_t_ee | The transformation from flange to end effector (4x4 matrix, column-major). |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the 6x7 body Jacobian for the flange frame, relative to that frame.
| [in] | q | Joint position. |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the 6x7 body Jacobian for the stiffness frame, relative to that frame.
| [in] | q | Joint position. |
| [in] | f_t_ee | The transformation from flange to end effector (4x4 matrix, column-major). |
| [in] | ee_t_k | The transformation from end effector to stiffness frame (4x4 matrix, column-major). |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the Coriolis force vector with configurable gravity (recommended implementation).
Unit: \([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]\). |
| [in] | g_earth | Earth's gravity vector. Unit: \(\frac{m}{s^2}\). |
| [out] | c_ne | Coriolis force vector. Unit: \([Nm]\). |
Implemented in franka::RobotModel.
|
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 inertia 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 inertia matrix, column-major. |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the homogeneous transformation matrix for the specified joint or link.
| [in] | q | Joint position. |
| [in] | joint_index | The index of the joint/link for which to calculate the pose. |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the homogeneous transformation matrix for the end effector, applying the end effector transformation.
| [in] | q | Joint position. |
| [in] | f_t_ee | The transformation from flange to end effector (4x4 matrix, column-major). |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the homogeneous transformation matrix for the flange.
| [in] | q | Joint position. |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the homogeneous transformation matrix for the stiffness frame.
| [in] | q | Joint position. |
| [in] | f_t_ee | The transformation from flange to end effector (4x4 matrix, column-major). |
| [in] | ee_t_k | The transformation from end effector to stiffness frame (4x4 matrix, column-major). |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the 6x7 zero Jacobian for the given joint, relative to the base frame.
| [in] | q | Joint position. |
| [in] | joint_index | The index of the joint/link for which to calculate the Jacobian. |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the 6x7 zero Jacobian for the end effector frame, relative to the base frame.
| [in] | q | Joint position. |
| [in] | f_t_ee | The transformation from flange to end effector (4x4 matrix, column-major). |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the 6x7 zero Jacobian for the flange frame, relative to the base frame.
| [in] | q | Joint position. |
Implemented in franka::RobotModel.
|
pure virtual |
Calculates the 6x7 zero Jacobian for the stiffness frame, relative to the base frame.
| [in] | q | Joint position. |
| [in] | f_t_ee | The transformation from flange to end effector (4x4 matrix, column-major). |
| [in] | ee_t_k | The transformation from end effector to stiffness frame (4x4 matrix, column-major). |
Implemented in franka::RobotModel.