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

Handle to perform calculations using the dynamic model of a robot. More...

#include <franka_model_interface.h>

Public Member Functions

 FrankaModelHandle ()=delete
 
 FrankaModelHandle (const std::string &name, franka::Model &model, franka::RobotState &robot_state)
 Creates an instance of a FrankaModelHandle. More...
 
std::array< double, 42 > getBodyJacobian (const franka::Frame &frame) const
 Gets the 6x7 Jacobian for the given frame, relative to that frame. More...
 
std::array< double, 42 > getBodyJacobian (const 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
 Gets the 6x7 Jacobian for the given frame, relative to that frame. More...
 
std::array< double, 7 > getCoriolis () const
 Calculates the Coriolis force vector (state-space equation) from the current robot state: $ c= C \times dq$, in $[Nm]$. More...
 
std::array< double, 7 > getCoriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &total_inertia, double total_mass, const std::array< double, 3 > &F_x_Ctotal) const
 Calculates the Coriolis force vector (state-space equation) from the given robot state: $ c= C \times dq$, in $[Nm]$. More...
 
std::array< double, 7 > getGravity (const std::array< double, 3 > &gravity_earth={{0., 0.,-9.81}}) const
 Calculates the gravity vector from the current robot state. More...
 
std::array< double, 7 > getGravity (const std::array< double, 7 > &q, double total_mass, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0.,-9.81}}) const
 Calculates the gravity vector from the given robot state. More...
 
std::array< double, 49 > getMass () const
 Calculates the 7x7 mass matrix from the current robot state. More...
 
std::array< double, 49 > getMass (const std::array< double, 7 > &q, const std::array< double, 9 > &total_inertia, double total_mass, const std::array< double, 3 > &F_x_Ctotal) const
 Calculates the 7x7 mass matrix from a given robot state. More...
 
std::string getName () const noexcept
 Gets the name of the model handle. More...
 
std::array< double, 16 > getPose (const franka::Frame &frame) const
 Gets the 4x4 pose matrix for the given frame in base frame, calculated from the current robot state. More...
 
std::array< double, 16 > getPose (const 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
 Gets the 4x4 pose matrix for the given frame in base frame, calculated from the given robot state. More...
 
std::array< double, 42 > getZeroJacobian (const franka::Frame &frame) const
 Gets the 6x7 Jacobian for the given joint relative to the base frame. More...
 
std::array< double, 42 > getZeroJacobian (const 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
 Gets the 6x7 Jacobian for the given joint relative to the base frame. More...
 

Private Attributes

const franka::Modelmodel_
 
std::string name_
 
const franka::RobotStaterobot_state_
 

Detailed Description

Handle to perform calculations using the dynamic model of a robot.

Definition at line 17 of file franka_model_interface.h.

Constructor & Destructor Documentation

franka_hw::FrankaModelHandle::FrankaModelHandle ( )
delete
franka_hw::FrankaModelHandle::FrankaModelHandle ( const std::string &  name,
franka::Model model,
franka::RobotState robot_state 
)
inline

Creates an instance of a FrankaModelHandle.

Parameters
[in]nameThe name of the model handle.
[in]modelA reference to the franka::Model instance wrapped by this handle.
[in]robot_stateA reference to the current robot state.

Definition at line 28 of file franka_model_interface.h.

Member Function Documentation

std::array<double, 42> franka_hw::FrankaModelHandle::getBodyJacobian ( const franka::Frame frame) 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 and calculated from the current robot state.

Parameters
[in]frameThe desired frame.
Returns
Vectorized 6x7 Jacobian, column-major.
See also
franka::Model::bodyJacobian

Definition at line 199 of file franka_model_interface.h.

std::array<double, 42> franka_hw::FrankaModelHandle::getBodyJacobian ( const 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
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 and calculated from the given robot state.

Parameters
[in]frameThe desired frame.
[in]qJoint position. Unit: $[rad]$.
[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.
See also
franka::Model::bodyJacobian

Definition at line 218 of file franka_model_interface.h.

std::array<double, 7> franka_hw::FrankaModelHandle::getCoriolis ( ) const
inline

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

Returns
Coriolis force vector.
See also
franka::Model::coriolis

Definition at line 79 of file franka_model_interface.h.

std::array<double, 7> franka_hw::FrankaModelHandle::getCoriolis ( const std::array< double, 7 > &  q,
const std::array< double, 7 > &  dq,
const std::array< double, 9 > &  total_inertia,
double  total_mass,
const std::array< double, 3 > &  F_x_Ctotal 
) const
inline

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

Parameters
[in]qJoint position. Unit: $[rad]$.
[in]dqJoint velocity. Unit: $[\frac{rad}{s}]$.
[in]total_inertiaInertia 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]total_massWeight 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 including end effector. Unit: $[m]$.
Returns
Coriolis force vector.
See also
franka::Model::coriolis

Definition at line 99 of file franka_model_interface.h.

std::array<double, 7> franka_hw::FrankaModelHandle::getGravity ( const std::array< double, 3 > &  gravity_earth = { {0., 0., -9.81}}) const
inline

Calculates the gravity vector from the current robot state.

Unit: $[Nm]$.

Parameters
[in]gravity_earthEarth's gravity vector. Unit: $\frac{m}{s^2}$. Default to {0.0, 0.0, -9.81}.
Returns
Gravity vector.
See also
franka::Model::gravity

Definition at line 118 of file franka_model_interface.h.

std::array<double, 7> franka_hw::FrankaModelHandle::getGravity ( const std::array< double, 7 > &  q,
double  total_mass,
const std::array< double, 3 > &  F_x_Ctotal,
const std::array< double, 3 > &  gravity_earth = {{0., 0., -9.81}} 
) const
inline

Calculates the gravity vector from the given robot state.

Unit: $[Nm]$.

Parameters
[in]qJoint position. Unit: $[rad]$.
[in]total_massWeight 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 including end effector. Unit: $[m]$.
[in]gravity_earthEarth's gravity vector. Unit: $\frac{m}{s^2}$. Default to {0.0, 0.0, -9.81}.
Returns
Gravity vector.
See also
franka::Model::gravity

Definition at line 139 of file franka_model_interface.h.

std::array<double, 49> franka_hw::FrankaModelHandle::getMass ( ) const
inline

Calculates the 7x7 mass matrix from the current robot state.

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

Returns
Vectorized 7x7 mass matrix, column-major.
See also
franka::Model::mass

Definition at line 45 of file franka_model_interface.h.

std::array<double, 49> franka_hw::FrankaModelHandle::getMass ( const std::array< double, 7 > &  q,
const std::array< double, 9 > &  total_inertia,
double  total_mass,
const std::array< double, 3 > &  F_x_Ctotal 
) const
inline

Calculates the 7x7 mass matrix from a given robot state.

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

Parameters
[in]qJoint position. Unit: $[rad]$.
[in]total_inertiaInertia 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]total_massWeight 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 including end effector. Unit: $[m]$.
Returns
Vectorized 7x7 mass matrix, column-major.
See also
franka::Model::mass

Definition at line 63 of file franka_model_interface.h.

std::string franka_hw::FrankaModelHandle::getName ( ) const
inlinenoexcept

Gets the name of the model handle.

Returns
Name of the model handle.

Definition at line 36 of file franka_model_interface.h.

std::array<double, 16> franka_hw::FrankaModelHandle::getPose ( const franka::Frame frame) const
inline

Gets the 4x4 pose matrix for the given frame in base frame, calculated from the current robot state.

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

Parameters
[in]frameThe desired frame.
Returns
Vectorized 4x4 pose matrix, column-major.
See also
franka::Model::pose

Definition at line 159 of file franka_model_interface.h.

std::array<double, 16> franka_hw::FrankaModelHandle::getPose ( const 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
inline

Gets the 4x4 pose matrix for the given frame in base frame, calculated from the given robot state.

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

Parameters
[in]frameThe desired frame.
[in]qJoint position. Unit: $[rad]$.
[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.
See also
franka::Model::pose

Definition at line 178 of file franka_model_interface.h.

std::array<double, 42> franka_hw::FrankaModelHandle::getZeroJacobian ( const franka::Frame frame) 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 and calculated from the current robot state.

Parameters
[in]frameThe desired frame.
Returns
Vectorized 6x7 Jacobian, column-major.
See also
franka::Model::zeroJacobian

Definition at line 239 of file franka_model_interface.h.

std::array<double, 42> franka_hw::FrankaModelHandle::getZeroJacobian ( const 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
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 and calculated from the given robot state.

Parameters
[in]frameThe desired frame.
[in]qJoint position. Unit: $[rad]$.
[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.
See also
franka::Model::zeroJacobian

Definition at line 258 of file franka_model_interface.h.

Member Data Documentation

const franka::Model* franka_hw::FrankaModelHandle::model_
private

Definition at line 269 of file franka_model_interface.h.

std::string franka_hw::FrankaModelHandle::name_
private

Definition at line 268 of file franka_model_interface.h.

const franka::RobotState* franka_hw::FrankaModelHandle::robot_state_
private

Definition at line 270 of file franka_model_interface.h.


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


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:05