Public Member Functions | List of all members
franka_hw::ModelBase Class Referenceabstract

Calculates poses of joints and dynamic properties of the robot. More...

#include <model_base.h>

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

Public Member Functions

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...
 
virtual 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 =0
 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...
 
virtual 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 =0
 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...
 
virtual 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 =0
 Calculates the gravity vector. More...
 
std::array< double, 49 > mass (const franka::RobotState &robot_state) const
 Calculates the 7x7 mass matrix. More...
 
virtual 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 =0
 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...
 
virtual 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 =0
 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 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 =0
 Gets the 6x7 Jacobian for the given joint relative to the base frame. More...
 
virtual ~ModelBase () noexcept=default
 

Detailed Description

Calculates poses of joints and dynamic properties of the robot.

This abstract class serves as an extendable interface for different implementations. To get the dynamic model from a real robot refer to

See also
franka_hw::Model.
Note
Although this class is abstract, it offers default implementations for all methods which take a RobotState. The default implementation simply delegates the class to their pure virtual counterparts.

Definition at line 20 of file model_base.h.

Constructor & Destructor Documentation

◆ ~ModelBase()

virtual franka_hw::ModelBase::~ModelBase ( )
virtualdefaultnoexcept

Member Function Documentation

◆ bodyJacobian() [1/2]

std::array<double, 42> franka_hw::ModelBase::bodyJacobian ( franka::Frame  frame,
const franka::RobotState &  robot_state 
) const
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.

Parameters
[in]frameThe desired frame.
[in]robot_stateState from which the pose should be calculated.
Returns
Vectorized 6x7 Jacobian, column-major.

Definition at line 67 of file model_base.h.

◆ bodyJacobian() [2/2]

virtual std::array<double, 42> franka_hw::ModelBase::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
pure virtual

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.

Implemented in franka_hw::Model.

◆ coriolis() [1/2]

std::array<double, 7> franka_hw::ModelBase::coriolis ( const franka::RobotState &  robot_state) const
inline

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

Parameters
[in]robot_stateState from which the Coriolis force vector should be calculated.
Returns
Coriolis force vector.

Definition at line 164 of file model_base.h.

◆ coriolis() [2/2]

virtual std::array<double, 7> franka_hw::ModelBase::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
pure virtual

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.

Implemented in franka_hw::Model.

◆ gravity() [1/4]

std::array<double, 7> franka_hw::ModelBase::gravity ( const franka::RobotState &  robot_state) const
inline

Calculates the gravity vector.

Unit: $[Nm]$. Assumes default gravity vector of -9.81 m/s^2

Parameters
[in]robot_stateState from which the gravity vector should be calculated.
Returns
Gravity vector.

Definition at line 236 of file model_base.h.

◆ gravity() [2/4]

std::array<double, 7> franka_hw::ModelBase::gravity ( const franka::RobotState &  robot_state,
const std::array< double, 3 > &  gravity_earth 
) const
inline

Calculates the gravity vector.

Unit: $[Nm]$.

Parameters
[in]robot_stateState from which the gravity vector should be calculated.
[in]gravity_earthEarth's gravity vector. Unit: $\frac{m}{s^2}$.
Returns
Gravity vector.

Definition at line 252 of file model_base.h.

◆ gravity() [3/4]

std::array<double, 7> franka_hw::ModelBase::gravity ( const std::array< double, 7 > &  q,
double  m_total,
const std::array< double, 3 > &  F_x_Ctotal 
) const
inline

Calculates the gravity vector.

Unit: $[Nm]$. Assumes default gravity vector of -9.81 m/s^2

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]$.
Returns
Gravity vector.

Definition at line 203 of file model_base.h.

◆ gravity() [4/4]

virtual std::array<double, 7> franka_hw::ModelBase::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
pure virtual

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.

Implemented in franka_hw::Model.

◆ mass() [1/2]

std::array<double, 49> franka_hw::ModelBase::mass ( const franka::RobotState &  robot_state) const
inline

Calculates the 7x7 mass matrix.

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

Parameters
[in]robot_stateState from which the pose should be calculated.
Returns
Vectorized 7x7 mass matrix, column-major.

Definition at line 132 of file model_base.h.

◆ mass() [2/2]

virtual std::array<double, 49> franka_hw::ModelBase::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
pure virtual

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.

Implemented in franka_hw::Model.

◆ pose() [1/2]

std::array<double, 16> franka_hw::ModelBase::pose ( franka::Frame  frame,
const franka::RobotState &  robot_state 
) const
inline

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]robot_stateState from which the pose should be calculated.
Returns
Vectorized 4x4 pose matrix, column-major.

Definition at line 34 of file model_base.h.

◆ pose() [2/2]

virtual std::array<double, 16> franka_hw::ModelBase::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
pure virtual

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.

Implemented in franka_hw::Model.

◆ zeroJacobian() [1/2]

std::array<double, 42> franka_hw::ModelBase::zeroJacobian ( franka::Frame  frame,
const franka::RobotState &  robot_state 
) const
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.

Parameters
[in]frameThe desired frame.
[in]robot_stateState from which the pose should be calculated.
Returns
Vectorized 6x7 Jacobian, column-major.

Definition at line 101 of file model_base.h.

◆ zeroJacobian() [2/2]

virtual std::array<double, 42> franka_hw::ModelBase::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
pure virtual

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.

Implemented in franka_hw::Model.


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