libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
Public Member Functions | List of all members
RobotModelBase Class Referenceabstract

Robot dynamic parameters computed from the URDF model with Pinocchio. More...

#include <robot_model_base.h>

Inheritance diagram for RobotModelBase:
Inheritance graph
[legend]

Public Member Functions

virtual void 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, std::array< double, 7 > &c_ne)=0
 Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).
 
virtual void gravity (const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne)=0
 Calculates the gravity vector.
 
virtual void 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, std::array< double, 49 > &m_ne)=0
 Calculates the 7x7 mass matrix.
 

Detailed Description

Robot dynamic parameters computed from the URDF model with Pinocchio.

Member Function Documentation

◆ coriolis()

virtual void RobotModelBase::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,
std::array< double, 7 > &  c_ne 
)
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]\).
[out]c_neCoriolis force vector. Unit: \([Nm]\).

Implemented in franka::RobotModel.

◆ gravity()

virtual void RobotModelBase::gravity ( const std::array< double, 7 > &  q,
const std::array< double, 3 > &  g_earth,
double  m_total,
const std::array< double, 3 > &  f_x_ctotal,
std::array< double, 7 > &  g_ne 
)
pure virtual

Calculates the gravity vector.

Unit: \([Nm]\).

Parameters
[in]qJoint position.
[in]gravity_earthEarth's gravity vector. Unit: \(\frac{m}{s^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.
[out]g_neGravity vector. Unit: \([Nm]\).

Implemented in franka::RobotModel.

◆ mass()

virtual void RobotModelBase::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,
std::array< double, 49 > &  m_ne 
)
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]\).
[out]m_neVectorized 7x7 mass matrix, column-major.

Implemented in franka::RobotModel.


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