|
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 override |
| Gets the 6x7 Jacobian for the given frame, relative to that frame. More...
|
|
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 noexcept override |
| Calculates the Coriolis force vector (state-space equation): , in . More...
|
|
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 noexcept override |
| Calculates the gravity vector. More...
|
|
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 noexcept override |
| Calculates the 7x7 mass matrix. More...
|
|
| Model (franka::Model &&model) |
| Create a new Model instance wrapped around a franka::Model. More...
|
|
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 override |
| Gets the 4x4 pose matrix for the given frame in base frame. More...
|
|
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 override |
| Gets the 6x7 Jacobian for the given joint relative to the base frame. More...
|
|
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...
|
|
std::array< double, 7 > | coriolis (const franka::RobotState &robot_state) const |
| Calculates the Coriolis force vector (state-space equation): , in . More...
|
|
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...
|
|
std::array< double, 49 > | mass (const franka::RobotState &robot_state) const |
| 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...
|
|
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 | ~ModelBase () noexcept=default |
|
An implementation of the abstract ModelBase specialized for obtaining the model from the real robot.
This class is a thin wrapper around a franka::Model and delegates all calls to that
Definition at line 17 of file model.h.