Handle to perform calculations using the dynamic model of a robot. More...
#include <franka_model_interface.h>
Public Member Functions | |
FrankaModelHandle ()=delete | |
FrankaModelHandle (const std::string &name, franka::Model &model, franka::RobotState &robot_state) | |
Creates an instance of a FrankaModelHandle. More... | |
std::array< double, 42 > | getBodyJacobian (const franka::Frame &frame) const |
Gets the 6x7 Jacobian for the given frame, relative to that frame. More... | |
std::array< double, 42 > | getBodyJacobian (const 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 |
Gets the 6x7 Jacobian for the given frame, relative to that frame. More... | |
std::array< double, 7 > | getCoriolis () const |
Calculates the Coriolis force vector (state-space equation) from the current robot state: , in . More... | |
std::array< double, 7 > | getCoriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &total_inertia, double total_mass, const std::array< double, 3 > &F_x_Ctotal) const |
Calculates the Coriolis force vector (state-space equation) from the given robot state: , in . More... | |
std::array< double, 7 > | getGravity (const std::array< double, 3 > &gravity_earth={{0., 0.,-9.81}}) const |
Calculates the gravity vector from the current robot state. More... | |
std::array< double, 7 > | getGravity (const std::array< double, 7 > &q, double total_mass, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0.,-9.81}}) const |
Calculates the gravity vector from the given robot state. More... | |
std::array< double, 49 > | getMass () const |
Calculates the 7x7 mass matrix from the current robot state. More... | |
std::array< double, 49 > | getMass (const std::array< double, 7 > &q, const std::array< double, 9 > &total_inertia, double total_mass, const std::array< double, 3 > &F_x_Ctotal) const |
Calculates the 7x7 mass matrix from a given robot state. More... | |
std::string | getName () const noexcept |
Gets the name of the model handle. More... | |
std::array< double, 16 > | getPose (const franka::Frame &frame) const |
Gets the 4x4 pose matrix for the given frame in base frame, calculated from the current robot state. More... | |
std::array< double, 16 > | getPose (const 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 |
Gets the 4x4 pose matrix for the given frame in base frame, calculated from the given robot state. More... | |
std::array< double, 42 > | getZeroJacobian (const franka::Frame &frame) const |
Gets the 6x7 Jacobian for the given joint relative to the base frame. More... | |
std::array< double, 42 > | getZeroJacobian (const 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 |
Gets the 6x7 Jacobian for the given joint relative to the base frame. More... | |
Private Attributes | |
const franka::Model * | model_ |
std::string | name_ |
const franka::RobotState * | robot_state_ |
Handle to perform calculations using the dynamic model of a robot.
Definition at line 17 of file franka_model_interface.h.
|
delete |
|
inline |
Creates an instance of a FrankaModelHandle.
[in] | name | The name of the model handle. |
[in] | model | A reference to the franka::Model instance wrapped by this handle. |
[in] | robot_state | A reference to the current robot state. |
Definition at line 28 of file franka_model_interface.h.
|
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 and calculated from the current robot state.
[in] | frame | The desired frame. |
Definition at line 199 of file franka_model_interface.h.
|
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 and calculated from the given robot state.
[in] | frame | The desired frame. |
[in] | q | Joint position. Unit: . |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
Definition at line 218 of file franka_model_interface.h.
|
inline |
Calculates the Coriolis force vector (state-space equation) from the current robot state: , in .
Definition at line 79 of file franka_model_interface.h.
|
inline |
Calculates the Coriolis force vector (state-space equation) from the given robot state: , in .
[in] | q | Joint position. Unit: . |
[in] | dq | Joint velocity. Unit: . |
[in] | total_inertia | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: . |
[in] | total_mass | 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 including end effector. Unit: . |
Definition at line 99 of file franka_model_interface.h.
|
inline |
Calculates the gravity vector from the current robot state.
Unit: .
[in] | gravity_earth | Earth's gravity vector. Unit: . Default to {0.0, 0.0, -9.81}. |
Definition at line 118 of file franka_model_interface.h.
|
inline |
Calculates the gravity vector from the given robot state.
Unit: .
[in] | q | Joint position. Unit: . |
[in] | total_mass | 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 including end effector. Unit: . |
[in] | gravity_earth | Earth's gravity vector. Unit: . Default to {0.0, 0.0, -9.81}. |
Definition at line 139 of file franka_model_interface.h.
|
inline |
Calculates the 7x7 mass matrix from the current robot state.
Unit: .
Definition at line 45 of file franka_model_interface.h.
|
inline |
Calculates the 7x7 mass matrix from a given robot state.
Unit: .
[in] | q | Joint position. Unit: . |
[in] | total_inertia | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: . |
[in] | total_mass | 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 including end effector. Unit: . |
Definition at line 63 of file franka_model_interface.h.
|
inlinenoexcept |
Gets the name of the model handle.
Definition at line 36 of file franka_model_interface.h.
|
inline |
Gets the 4x4 pose matrix for the given frame in base frame, calculated from the current robot state.
The pose is represented as a 4x4 matrix in column-major format.
[in] | frame | The desired frame. |
Definition at line 159 of file franka_model_interface.h.
|
inline |
Gets the 4x4 pose matrix for the given frame in base frame, calculated from the given robot state.
The pose is represented as a 4x4 matrix in column-major format.
[in] | frame | The desired frame. |
[in] | q | Joint position. Unit: . |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
Definition at line 178 of file franka_model_interface.h.
|
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 and calculated from the current robot state.
[in] | frame | The desired frame. |
Definition at line 239 of file franka_model_interface.h.
|
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 and calculated from the given robot state.
[in] | frame | The desired frame. |
[in] | q | Joint position. Unit: . |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
Definition at line 258 of file franka_model_interface.h.
|
private |
Definition at line 269 of file franka_model_interface.h.
|
private |
Definition at line 268 of file franka_model_interface.h.
|
private |
Definition at line 270 of file franka_model_interface.h.