|
franky 1.1.2
A High-Level Motion API for Franka
|
A wrapper around franka::Model that uses Eigen types. More...
#include <model.hpp>
Public Member Functions | |
| Model (franka::Model model) | |
| Model (const Model &)=delete | |
| Model & | operator= (const Model &)=delete |
| Model (Model &&other) noexcept | |
| Model & | operator= (Model &&other) noexcept |
| Affine | pose (franka::Frame frame, const RobotState &state) const |
| Calculates the pose of a frame relative to the base frame. | |
| Affine | pose (franka::Frame frame, const Vector7d &q, const Affine &F_T_EE, const Affine &EE_T_K) const |
| Calculates the pose of a frame relative to the base frame. | |
| Jacobian | bodyJacobian (franka::Frame frame, const RobotState &state) const |
| Calculates the body Jacobian in base frame. | |
| Jacobian | bodyJacobian (franka::Frame frame, const Vector7d &q, const Affine &F_T_EE, const Affine &EE_T_K) const |
| Calculates the body Jacobian in base frame. | |
| Jacobian | zeroJacobian (franka::Frame frame, const RobotState &state) const |
| Calculates the zero Jacobian in base frame. | |
| Jacobian | zeroJacobian (franka::Frame frame, const Vector7d &q, const Affine &F_T_EE, const Affine &EE_T_K) const |
| Calculates the zero Jacobian in base frame. | |
| Eigen::Matrix< double, 7, 7 > | mass (const RobotState &state) const |
| Calculates the mass matrix. | |
| Eigen::Matrix< double, 7, 7 > | mass (const Vector7d &q, const Eigen::Matrix3d &I_total, double m_total, const Eigen::Vector3d &F_x_Ctotal) const |
| Calculates the mass matrix. | |
| Vector7d | coriolis (const RobotState &state) const |
| Calculates the Coriolis force vector. | |
| Vector7d | coriolis (const Vector7d &q, const Vector7d &dq, const Eigen::Matrix3d &I_total, double m_total, const Eigen::Vector3d &F_x_Ctotal) const |
| Calculates the Coriolis force vector. | |
| Vector7d | gravity (const RobotState &state, const Eigen::Vector3d &gravity_earth) const |
| Calculates the gravity vector. | |
| Vector7d | gravity (const RobotState &state) const |
| Calculates the gravity vector using default gravity direction (0, 0, -9.81). | |
| Vector7d | gravity (const Vector7d &q, double m_total, const Eigen::Vector3d &F_x_Ctotal, const Eigen::Vector3d &gravity_earth={0., 0., -9.81}) const |
| Calculates the gravity vector. | |
A wrapper around franka::Model that uses Eigen types.
This class exposes the same functionality as franka::Model, but uses Eigen types for inputs and outputs instead of std::array. All 2D arrays are returned as Eigen matrices.
|
explicit |
| model | The underlying franka::Model instance to wrap. |
|
noexcept |
| Jacobian franky::Model::bodyJacobian | ( | franka::Frame | frame, |
| const RobotState & | state | ||
| ) | const |
Calculates the body Jacobian in base frame.
| frame | The frame for which the Jacobian is computed. |
| state | The current robot state. |
| Jacobian franky::Model::bodyJacobian | ( | franka::Frame | frame, |
| const Vector7d & | q, | ||
| const Affine & | F_T_EE, | ||
| const Affine & | EE_T_K | ||
| ) | const |
Calculates the body Jacobian in base frame.
| frame | The frame for which the Jacobian is computed. |
| q | Robot joint angles [rad]. |
| F_T_EE | Transformation from flange to end-effector frame. |
| EE_T_K | Transformation from end-effector frame to stiffness frame. |
| Vector7d franky::Model::coriolis | ( | const RobotState & | state | ) | const |
Calculates the Coriolis force vector.
| state | The current robot state. |
| Vector7d franky::Model::gravity | ( | const RobotState & | state | ) | const |
Calculates the gravity vector using default gravity direction (0, 0, -9.81).
| state | The current robot state. |
| Vector7d franky::Model::gravity | ( | const RobotState & | state, |
| const Eigen::Vector3d & | gravity_earth | ||
| ) | const |
Calculates the gravity vector.
| state | The current robot state. |
| gravity_earth | Gravity vector in base frame [m/s²]. |
| Vector7d franky::Model::gravity | ( | const Vector7d & | q, |
| double | m_total, | ||
| const Eigen::Vector3d & | F_x_Ctotal, | ||
| const Eigen::Vector3d & | gravity_earth = {0., 0., -9.81} |
||
| ) | const |
Calculates the gravity vector.
| q | Robot joint angles [rad]. |
| m_total | Combined mass of robot and load [kg]. |
| F_x_Ctotal | Center of mass relative to flange frame [m]. |
| gravity_earth | Gravity vector in base frame [m/s²], default is (0, 0, -9.81). |
| Eigen::Matrix< double, 7, 7 > franky::Model::mass | ( | const RobotState & | state | ) | const |
Calculates the mass matrix.
| state | The current robot state. |
| Eigen::Matrix< double, 7, 7 > franky::Model::mass | ( | const Vector7d & | q, |
| const Eigen::Matrix3d & | I_total, | ||
| double | m_total, | ||
| const Eigen::Vector3d & | F_x_Ctotal | ||
| ) | const |
Calculates the mass matrix.
| q | Robot joint angles [rad]. |
| I_total | Combined load and robot inertia [kg·m²]. |
| m_total | Combined mass of robot and load [kg]. |
| F_x_Ctotal | Center of mass relative to flange frame [m]. |
| Affine franky::Model::pose | ( | franka::Frame | frame, |
| const RobotState & | state | ||
| ) | const |
Calculates the pose of a frame relative to the base frame.
| frame | The frame whose pose should be returned. |
| state | The current robot state. |
| Affine franky::Model::pose | ( | franka::Frame | frame, |
| const Vector7d & | q, | ||
| const Affine & | F_T_EE, | ||
| const Affine & | EE_T_K | ||
| ) | const |
Calculates the pose of a frame relative to the base frame.
| frame | The frame whose pose should be returned. |
| q | Robot joint angles [rad]. |
| F_T_EE | Transformation from flange to end-effector frame. |
| EE_T_K | Transformation from end-effector frame to stiffness frame. |
| Jacobian franky::Model::zeroJacobian | ( | franka::Frame | frame, |
| const RobotState & | state | ||
| ) | const |
Calculates the zero Jacobian in base frame.
| frame | The frame for which the Jacobian is computed. |
| state | The current robot state. |
| Jacobian franky::Model::zeroJacobian | ( | franka::Frame | frame, |
| const Vector7d & | q, | ||
| const Affine & | F_T_EE, | ||
| const Affine & | EE_T_K | ||
| ) | const |
Calculates the zero Jacobian in base frame.
| frame | The frame for which the Jacobian is computed. |
| q | Robot joint angles [rad]. |
| F_T_EE | Transformation from flange to end-effector frame. |
| EE_T_K | Transformation from end-effector frame to stiffness frame. |