Calculates poses of joints and dynamic properties of the robot. More...
#include <model_base.h>
Public Member Functions | |
std::array< double, 42 > | bodyJacobian (franka::Frame frame, const franka::RobotState &robot_state) const |
Gets the 6x7 Jacobian for the given frame, relative to that frame. More... | |
virtual std::array< double, 42 > | bodyJacobian (franka::Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const =0 |
Gets the 6x7 Jacobian for the given frame, relative to that frame. More... | |
std::array< double, 7 > | coriolis (const franka::RobotState &robot_state) const |
Calculates the Coriolis force vector (state-space equation): ![]() ![]() | |
virtual std::array< double, 7 > | 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 =0 |
Calculates the Coriolis force vector (state-space equation): ![]() ![]() | |
std::array< double, 7 > | gravity (const franka::RobotState &robot_state) const |
Calculates the gravity vector. More... | |
std::array< double, 7 > | gravity (const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const |
Calculates the gravity vector. More... | |
std::array< double, 7 > | gravity (const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal) const |
Calculates the gravity vector. More... | |
virtual std::array< double, 7 > | gravity (const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth) const =0 |
Calculates the gravity vector. More... | |
std::array< double, 49 > | mass (const franka::RobotState &robot_state) const |
Calculates the 7x7 mass matrix. More... | |
virtual std::array< double, 49 > | 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) const =0 |
Calculates the 7x7 mass matrix. More... | |
std::array< double, 16 > | pose (franka::Frame frame, const franka::RobotState &robot_state) const |
Gets the 4x4 pose matrix for the given frame in base frame. More... | |
virtual std::array< double, 16 > | pose (franka::Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const =0 |
Gets the 4x4 pose matrix for the given frame in base frame. More... | |
std::array< double, 42 > | zeroJacobian (franka::Frame frame, const franka::RobotState &robot_state) const |
Gets the 6x7 Jacobian for the given joint relative to the base frame. More... | |
virtual std::array< double, 42 > | zeroJacobian (franka::Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const =0 |
Gets the 6x7 Jacobian for the given joint relative to the base frame. More... | |
virtual | ~ModelBase () noexcept=default |
Calculates poses of joints and dynamic properties of the robot.
This abstract class serves as an extendable interface for different implementations. To get the dynamic model from a real robot refer to
Definition at line 20 of file model_base.h.
|
virtualdefaultnoexcept |
|
inline |
Gets the 6x7 Jacobian for the given frame, relative to that frame.
The Jacobian is represented as a 6x7 matrix in column-major format.
[in] | frame | The desired frame. |
[in] | robot_state | State from which the pose should be calculated. |
Definition at line 67 of file model_base.h.
|
pure virtual |
Gets the 6x7 Jacobian for the given frame, relative to that frame.
The Jacobian is represented as a 6x7 matrix in column-major format.
[in] | frame | The desired frame. |
[in] | q | Joint position. |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
Implemented in franka_hw::Model.
|
inline |
Calculates the Coriolis force vector (state-space equation): , in
.
[in] | robot_state | State from which the Coriolis force vector should be calculated. |
Definition at line 164 of file model_base.h.
|
pure virtual |
Calculates the Coriolis force vector (state-space equation): , in
.
[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: ![]() |
[in] | m_total | Weight of the attached total load including end effector. Unit: ![]() |
[in] | F_x_Ctotal | Translation from flange to center of mass of the attached total load. Unit: ![]() |
Implemented in franka_hw::Model.
|
inline |
Calculates the gravity vector.
Unit: . Assumes default gravity vector of -9.81 m/s^2
[in] | robot_state | State from which the gravity vector should be calculated. |
Definition at line 236 of file model_base.h.
|
inline |
Calculates the gravity vector.
Unit: .
[in] | robot_state | State from which the gravity vector should be calculated. |
[in] | gravity_earth | Earth's gravity vector. Unit: ![]() |
Definition at line 252 of file model_base.h.
|
inline |
Calculates the gravity vector.
Unit: . Assumes default gravity vector of -9.81 m/s^2
[in] | q | Joint position. |
[in] | m_total | Weight of the attached total load including end effector. Unit: ![]() |
[in] | F_x_Ctotal | Translation from flange to center of mass of the attached total load. Unit: ![]() |
Definition at line 203 of file model_base.h.
|
pure virtual |
Calculates the gravity vector.
Unit: .
[in] | q | Joint position. |
[in] | m_total | Weight of the attached total load including end effector. Unit: ![]() |
[in] | F_x_Ctotal | Translation from flange to center of mass of the attached total load. Unit: ![]() |
[in] | gravity_earth | Earth's gravity vector. Unit: ![]() |
Implemented in franka_hw::Model.
|
inline |
Calculates the 7x7 mass matrix.
Unit: .
[in] | robot_state | State from which the pose should be calculated. |
Definition at line 132 of file model_base.h.
|
pure virtual |
Calculates the 7x7 mass matrix.
Unit: .
[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: ![]() |
[in] | m_total | Weight of the attached total load including end effector. Unit: ![]() |
[in] | F_x_Ctotal | Translation from flange to center of mass of the attached total load. Unit: ![]() |
Implemented in franka_hw::Model.
|
inline |
Gets the 4x4 pose matrix for the given frame in base frame.
The pose is represented as a 4x4 matrix in column-major format.
[in] | frame | The desired frame. |
[in] | robot_state | State from which the pose should be calculated. |
Definition at line 34 of file model_base.h.
|
pure virtual |
Gets the 4x4 pose matrix for the given frame in base frame.
The pose is represented as a 4x4 matrix in column-major format.
[in] | frame | The desired frame. |
[in] | q | Joint position. |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
Implemented in franka_hw::Model.
|
inline |
Gets the 6x7 Jacobian for the given joint relative to the base frame.
The Jacobian is represented as a 6x7 matrix in column-major format.
[in] | frame | The desired frame. |
[in] | robot_state | State from which the pose should be calculated. |
Definition at line 101 of file model_base.h.
|
pure virtual |
Gets the 6x7 Jacobian for the given joint relative to the base frame.
The Jacobian is represented as a 6x7 matrix in column-major format.
[in] | frame | The desired frame. |
[in] | q | Joint position. |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
Implemented in franka_hw::Model.