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

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

#include <model.h>

Public Member Functions

std::array< double, 42 > bodyJacobian (Frame frame, const franka::RobotState &robot_state) const
 Gets the 6x7 Jacobian for the given frame, relative to that frame. More...
 
std::array< double, 42 > bodyJacobian (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 > coriolis (const franka::RobotState &robot_state) const noexcept
 Calculates the Coriolis force vector (state-space equation): $ c= C \times dq$, in $[Nm]$. 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
 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={{0., 0.,-9.81}}) const noexcept
 Calculates the gravity vector. More...
 
std::array< double, 7 > gravity (const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth={{0., 0.,-9.81}}) const noexcept
 Calculates the gravity vector. More...
 
std::array< double, 49 > mass (const franka::RobotState &robot_state) const noexcept
 Calculates the 7x7 mass matrix. 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
 Calculates the 7x7 mass matrix. More...
 
 Model (franka::Network &network)
 Creates a new Model instance. More...
 
 Model (Model &&model) noexcept
 Move-constructs a new Model instance. More...
 
Modeloperator= (Model &&model) noexcept
 Move-assigns this Model from another Model instance. More...
 
std::array< double, 16 > pose (Frame frame, const franka::RobotState &robot_state) const
 Gets the 4x4 pose matrix for the given frame in base frame. More...
 
std::array< double, 16 > pose (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. More...
 
std::array< double, 42 > zeroJacobian (Frame frame, const franka::RobotState &robot_state) const
 Gets the 6x7 Jacobian for the given joint relative to the base frame. More...
 
std::array< double, 42 > zeroJacobian (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...
 
 ~Model () noexcept
 Unloads the model library. More...
 

Private Attributes

std::unique_ptr< ModelLibrary > library_
 

Detailed Description

Calculates poses of joints and dynamic properties of the robot.

Definition at line 51 of file model.h.

Constructor & Destructor Documentation

franka::Model::Model ( franka::Network &  network)
explicit

Creates a new Model instance.

This constructor is for internal use only.

See also
Robot::loadModel
Parameters
[in]networkFor internal use.
Exceptions
ModelExceptionif the model library cannot be loaded.
franka::Model::Model ( Model &&  model)
noexcept

Move-constructs a new Model instance.

Parameters
[in]modelOther Model instance.
franka::Model::~Model ( )
noexcept

Unloads the model library.

Member Function Documentation

std::array<double, 42> franka::Model::bodyJacobian ( Frame  frame,
const franka::RobotState robot_state 
) const

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.
std::array<double, 42> franka::Model::bodyJacobian ( 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.

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.
std::array<double, 7> franka::Model::coriolis ( const franka::RobotState robot_state) const
noexcept

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.
std::array<double, 7> franka::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
noexcept

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.
std::array<double, 7> franka::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 = {{0., 0.,-9.81}} 
) const
noexcept

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}$. Default to {0.0, 0.0, -9.81}.
Returns
Gravity vector.
std::array<double, 7> franka::Model::gravity ( const franka::RobotState robot_state,
const std::array< double, 3 > &  gravity_earth = {{0., 0.,-9.81}} 
) const
noexcept

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}$. Default to {0.0, 0.0, -9.81}.
Returns
Gravity vector.
std::array<double, 49> franka::Model::mass ( const franka::RobotState robot_state) const
noexcept

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.
std::array<double, 49> franka::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
noexcept

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.
Model& franka::Model::operator= ( Model &&  model)
noexcept

Move-assigns this Model from another Model instance.

Parameters
[in]modelOther Model instance.
Returns
Model instance.
std::array<double, 16> franka::Model::pose ( Frame  frame,
const franka::RobotState robot_state 
) const

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.
std::array<double, 16> franka::Model::pose ( 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.

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

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.
std::array<double, 42> franka::Model::zeroJacobian ( 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.

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.

Member Data Documentation

std::unique_ptr<ModelLibrary> franka::Model::library_
private

Definition at line 280 of file model.h.


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


libfranka
Author(s): Franka Emika GmbH
autogenerated on Tue Jul 9 2019 03:32:01