Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
Public Member Functions | List of all members
franky::Model Class Reference

A wrapper around franka::Model that uses Eigen types. More...

#include <model.hpp>

Public Member Functions

 Model (franka::Model model)
 
 Model (const Model &)=delete
 
Modeloperator= (const Model &)=delete
 
 Model (Model &&other) noexcept
 
Modeloperator= (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.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ Model() [1/3]

franky::Model::Model ( franka::Model  model)
explicit
Parameters
modelThe underlying franka::Model instance to wrap.

◆ Model() [2/3]

franky::Model::Model ( const Model )
delete

◆ Model() [3/3]

franky::Model::Model ( Model &&  other)
noexcept

Member Function Documentation

◆ bodyJacobian() [1/2]

Jacobian franky::Model::bodyJacobian ( franka::Frame  frame,
const RobotState state 
) const

Calculates the body Jacobian in base frame.

Parameters
frameThe frame for which the Jacobian is computed.
stateThe current robot state.
Returns
The 6x7 body Jacobian matrix.

◆ bodyJacobian() [2/2]

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.

Parameters
frameThe frame for which the Jacobian is computed.
qRobot joint angles [rad].
F_T_EETransformation from flange to end-effector frame.
EE_T_KTransformation from end-effector frame to stiffness frame.
Returns
The 6x7 body Jacobian matrix.

◆ coriolis() [1/2]

Vector7d franky::Model::coriolis ( const RobotState state) const

Calculates the Coriolis force vector.

Parameters
stateThe current robot state.
Returns
The Coriolis vector [Nm].

◆ coriolis() [2/2]

Vector7d franky::Model::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.

Parameters
qRobot joint angles [rad].
dqRobot joint velocities [rad/s].
I_totalCombined load and robot inertia [kg·m²].
m_totalCombined mass of robot and load [kg].
F_x_CtotalCenter of mass relative to flange frame [m].
Returns
The Coriolis vector [Nm].

◆ gravity() [1/3]

Vector7d franky::Model::gravity ( const RobotState state) const

Calculates the gravity vector using default gravity direction (0, 0, -9.81).

Parameters
stateThe current robot state.
Returns
The gravity vector [Nm].

◆ gravity() [2/3]

Vector7d franky::Model::gravity ( const RobotState state,
const Eigen::Vector3d &  gravity_earth 
) const

Calculates the gravity vector.

Parameters
stateThe current robot state.
gravity_earthGravity vector in base frame [m/s²].
Returns
The gravity vector [Nm].

◆ gravity() [3/3]

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.

Parameters
qRobot joint angles [rad].
m_totalCombined mass of robot and load [kg].
F_x_CtotalCenter of mass relative to flange frame [m].
gravity_earthGravity vector in base frame [m/s²], default is (0, 0, -9.81).
Returns
The gravity vector [Nm].

◆ mass() [1/2]

Eigen::Matrix< double, 7, 7 > franky::Model::mass ( const RobotState state) const

Calculates the mass matrix.

Parameters
stateThe current robot state.
Returns
The 7x7 mass matrix.

◆ mass() [2/2]

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.

Parameters
qRobot joint angles [rad].
I_totalCombined load and robot inertia [kg·m²].
m_totalCombined mass of robot and load [kg].
F_x_CtotalCenter of mass relative to flange frame [m].
Returns
The 7x7 mass matrix.

◆ operator=() [1/2]

Model & franky::Model::operator= ( const Model )
delete

◆ operator=() [2/2]

Model & franky::Model::operator= ( Model &&  other)
noexcept

◆ pose() [1/2]

Affine franky::Model::pose ( franka::Frame  frame,
const RobotState state 
) const

Calculates the pose of a frame relative to the base frame.

Parameters
frameThe frame whose pose should be returned.
stateThe current robot state.
Returns
The pose as an affine transformation matrix.

◆ pose() [2/2]

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.

Parameters
frameThe frame whose pose should be returned.
qRobot joint angles [rad].
F_T_EETransformation from flange to end-effector frame.
EE_T_KTransformation from end-effector frame to stiffness frame.
Returns
The pose as an affine transformation matrix.

◆ zeroJacobian() [1/2]

Jacobian franky::Model::zeroJacobian ( franka::Frame  frame,
const RobotState state 
) const

Calculates the zero Jacobian in base frame.

Parameters
frameThe frame for which the Jacobian is computed.
stateThe current robot state.
Returns
The 6x7 zero Jacobian matrix.

◆ zeroJacobian() [2/2]

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.

Parameters
frameThe frame for which the Jacobian is computed.
qRobot joint angles [rad].
F_T_EETransformation from flange to end-effector frame.
EE_T_KTransformation from end-effector frame to stiffness frame.
Returns
The 6x7 zero Jacobian matrix.

The documentation for this class was generated from the following files: