Public Member Functions | Private Attributes | List of all members
franka_hw::Model Class Reference

An implementation of the abstract ModelBase specialized for obtaining the model from the real robot. More...

#include <model.h>

Inheritance diagram for franka_hw::Model:
Inheritance graph
[legend]

Public Member Functions

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): $ c= C \times dq$, in $[Nm]$. 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...
 
- Public Member Functions inherited from franka_hw::ModelBase
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): $ c= C \times dq$, in $[Nm]$. 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
 

Private Attributes

franka::Model model_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ Model()

franka_hw::Model::Model ( franka::Model &&  model)
inline

Create a new Model instance wrapped around a franka::Model.

Definition at line 22 of file model.h.

Member Function Documentation

◆ bodyJacobian()

std::array<double, 42> franka_hw::Model::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
inlineoverridevirtual

Gets the 6x7 Jacobian for the given frame, relative to that frame.

The Jacobian is represented as a 6x7 matrix in column-major format.

Parameters
[in]frameThe desired frame.
[in]qJoint position.
[in]F_T_EEEnd effector in flange frame.
[in]EE_T_KStiffness frame K in the end effector frame.
Returns
Vectorized 6x7 Jacobian, column-major.

Implements franka_hw::ModelBase.

Definition at line 33 of file model.h.

◆ coriolis()

std::array<double, 7> franka_hw::Model::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
inlineoverridevirtualnoexcept

Calculates the Coriolis force vector (state-space equation): $ c= C \times dq$, in $[Nm]$.

Parameters
[in]qJoint position.
[in]dqJoint velocity.
[in]I_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: $[kg \times m^2]$.
[in]m_totalWeight of the attached total load including end effector. Unit: $[kg]$.
[in]F_x_CtotalTranslation from flange to center of mass of the attached total load. Unit: $[m]$.
Returns
Coriolis force vector.

Implements franka_hw::ModelBase.

Definition at line 60 of file model.h.

◆ gravity()

std::array<double, 7> franka_hw::Model::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
inlineoverridevirtualnoexcept

Calculates the gravity vector.

Unit: $[Nm]$.

Parameters
[in]qJoint position.
[in]m_totalWeight of the attached total load including end effector. Unit: $[kg]$.
[in]F_x_CtotalTranslation from flange to center of mass of the attached total load. Unit: $[m]$.
[in]gravity_earthEarth's gravity vector. Unit: $\frac{m}{s^2}$.
Returns
Gravity vector.

Implements franka_hw::ModelBase.

Definition at line 70 of file model.h.

◆ mass()

std::array<double, 49> franka_hw::Model::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
inlineoverridevirtualnoexcept

Calculates the 7x7 mass matrix.

Unit: $[kg \times m^2]$.

Parameters
[in]qJoint position.
[in]I_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: $[kg \times m^2]$.
[in]m_totalWeight of the attached total load including end effector. Unit: $[kg]$.
[in]F_x_CtotalTranslation from flange to center of mass of the attached total load. Unit: $[m]$.
Returns
Vectorized 7x7 mass matrix, column-major.

Implements franka_hw::ModelBase.

Definition at line 51 of file model.h.

◆ pose()

std::array<double, 16> franka_hw::Model::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
inlineoverridevirtual

Gets the 4x4 pose matrix for the given frame in base frame.

The pose is represented as a 4x4 matrix in column-major format.

Parameters
[in]frameThe desired frame.
[in]qJoint position.
[in]F_T_EEEnd effector in flange frame.
[in]EE_T_KStiffness frame K in the end effector frame.
Returns
Vectorized 4x4 pose matrix, column-major.

Implements franka_hw::ModelBase.

Definition at line 24 of file model.h.

◆ zeroJacobian()

std::array<double, 42> franka_hw::Model::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
inlineoverridevirtual

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.

Parameters
[in]frameThe desired frame.
[in]qJoint position.
[in]F_T_EEEnd effector in flange frame.
[in]EE_T_KStiffness frame K in the end effector frame.
Returns
Vectorized 6x7 Jacobian, column-major.

Implements franka_hw::ModelBase.

Definition at line 42 of file model.h.

Member Data Documentation

◆ model_

franka::Model franka_hw::Model::model_
private

Definition at line 79 of file model.h.


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


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21