libfranka 0.18.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 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 std::array< double, 3 > &g_earth, std::array< double, 7 > &c_ne)=0
 Calculates the Coriolis force vector with configurable gravity (recommended implementation).
 
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 inertia matrix.
 
virtual std::array< double, 16 > pose (const std::array< double, 7 > &q, int joint_index)=0
 Calculates the homogeneous transformation matrix for the specified joint or link.
 
virtual std::array< double, 16 > poseEe (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee)=0
 Calculates the homogeneous transformation matrix for the end effector, applying the end effector transformation.
 
virtual std::array< double, 16 > poseFlange (const std::array< double, 7 > &q)=0
 Calculates the homogeneous transformation matrix for the flange.
 
virtual std::array< double, 16 > poseStiffness (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee, const std::array< double, 16 > &ee_t_k)=0
 Calculates the homogeneous transformation matrix for the stiffness frame.
 
virtual std::array< double, 42 > bodyJacobian (const std::array< double, 7 > &q, int joint_index)=0
 Calculates the 6x7 body Jacobian for the given joint, relative to that joint's frame.
 
virtual std::array< double, 42 > bodyJacobianFlange (const std::array< double, 7 > &q)=0
 Calculates the 6x7 body Jacobian for the flange frame, relative to that frame.
 
virtual std::array< double, 42 > bodyJacobianEe (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee)=0
 Calculates the 6x7 body Jacobian for the end effector frame, relative to that frame.
 
virtual std::array< double, 42 > bodyJacobianStiffness (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee, const std::array< double, 16 > &ee_t_k)=0
 Calculates the 6x7 body Jacobian for the stiffness frame, relative to that frame.
 
virtual std::array< double, 42 > zeroJacobian (const std::array< double, 7 > &q, int joint_index)=0
 Calculates the 6x7 zero Jacobian for the given joint, relative to the base frame.
 
virtual std::array< double, 42 > zeroJacobianFlange (const std::array< double, 7 > &q)=0
 Calculates the 6x7 zero Jacobian for the flange frame, relative to the base frame.
 
virtual std::array< double, 42 > zeroJacobianEe (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee)=0
 Calculates the 6x7 zero Jacobian for the end effector frame, relative to the base frame.
 
virtual std::array< double, 42 > zeroJacobianStiffness (const std::array< double, 7 > &q, const std::array< double, 16 > &f_t_ee, const std::array< double, 16 > &ee_t_k)=0
 Calculates the 6x7 zero Jacobian for the stiffness frame, relative to the base frame.
 

Detailed Description

Robot dynamic parameters computed from the URDF model with Pinocchio.

Member Function Documentation

◆ bodyJacobian()

virtual std::array< double, 42 > RobotModelBase::bodyJacobian ( const std::array< double, 7 > &  q,
int  joint_index 
)
pure virtual

Calculates the 6x7 body Jacobian for the given joint, relative to that joint's frame.

Parameters
[in]qJoint position.
[in]joint_indexThe index of the joint/link for which to calculate the Jacobian.
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.

◆ bodyJacobianEe()

virtual std::array< double, 42 > RobotModelBase::bodyJacobianEe ( const std::array< double, 7 > &  q,
const std::array< double, 16 > &  f_t_ee 
)
pure virtual

Calculates the 6x7 body Jacobian for the end effector frame, relative to that frame.

Parameters
[in]qJoint position.
[in]f_t_eeThe transformation from flange to end effector (4x4 matrix, column-major).
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.

◆ bodyJacobianFlange()

virtual std::array< double, 42 > RobotModelBase::bodyJacobianFlange ( const std::array< double, 7 > &  q)
pure virtual

Calculates the 6x7 body Jacobian for the flange frame, relative to that frame.

Parameters
[in]qJoint position.
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.

◆ bodyJacobianStiffness()

virtual std::array< double, 42 > RobotModelBase::bodyJacobianStiffness ( const std::array< double, 7 > &  q,
const std::array< double, 16 > &  f_t_ee,
const std::array< double, 16 > &  ee_t_k 
)
pure virtual

Calculates the 6x7 body Jacobian for the stiffness frame, relative to that frame.

Parameters
[in]qJoint position.
[in]f_t_eeThe transformation from flange to end effector (4x4 matrix, column-major).
[in]ee_t_kThe transformation from end effector to stiffness frame (4x4 matrix, column-major).
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.

◆ coriolis() [1/2]

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,
const std::array< double, 3 > &  g_earth,
std::array< double, 7 > &  c_ne 
)
pure virtual

Calculates the Coriolis force vector with configurable gravity (recommended implementation).

Unit: \([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]\).
[in]g_earthEarth's gravity vector. Unit: \(\frac{m}{s^2}\).
[out]c_neCoriolis force vector. Unit: \([Nm]\).

Implemented in franka::RobotModel.

◆ coriolis() [2/2]

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 inertia 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 inertia matrix, column-major.

Implemented in franka::RobotModel.

◆ pose()

virtual std::array< double, 16 > RobotModelBase::pose ( const std::array< double, 7 > &  q,
int  joint_index 
)
pure virtual

Calculates the homogeneous transformation matrix for the specified joint or link.

Parameters
[in]qJoint position.
[in]joint_indexThe index of the joint/link for which to calculate the pose.
Returns
Homogeneous transformation matrix (4x4) in column-major order.

Implemented in franka::RobotModel.

◆ poseEe()

virtual std::array< double, 16 > RobotModelBase::poseEe ( const std::array< double, 7 > &  q,
const std::array< double, 16 > &  f_t_ee 
)
pure virtual

Calculates the homogeneous transformation matrix for the end effector, applying the end effector transformation.

Parameters
[in]qJoint position.
[in]f_t_eeThe transformation from flange to end effector (4x4 matrix, column-major).
Returns
Homogeneous transformation matrix (4x4) in column-major order.

Implemented in franka::RobotModel.

◆ poseFlange()

virtual std::array< double, 16 > RobotModelBase::poseFlange ( const std::array< double, 7 > &  q)
pure virtual

Calculates the homogeneous transformation matrix for the flange.

Parameters
[in]qJoint position.
Returns
Homogeneous transformation matrix (4x4) in column-major order.

Implemented in franka::RobotModel.

◆ poseStiffness()

virtual std::array< double, 16 > RobotModelBase::poseStiffness ( const std::array< double, 7 > &  q,
const std::array< double, 16 > &  f_t_ee,
const std::array< double, 16 > &  ee_t_k 
)
pure virtual

Calculates the homogeneous transformation matrix for the stiffness frame.

Parameters
[in]qJoint position.
[in]f_t_eeThe transformation from flange to end effector (4x4 matrix, column-major).
[in]ee_t_kThe transformation from end effector to stiffness frame (4x4 matrix, column-major).
Returns
Homogeneous transformation matrix (4x4) in column-major order.

Implemented in franka::RobotModel.

◆ zeroJacobian()

virtual std::array< double, 42 > RobotModelBase::zeroJacobian ( const std::array< double, 7 > &  q,
int  joint_index 
)
pure virtual

Calculates the 6x7 zero Jacobian for the given joint, relative to the base frame.

Parameters
[in]qJoint position.
[in]joint_indexThe index of the joint/link for which to calculate the Jacobian.
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.

◆ zeroJacobianEe()

virtual std::array< double, 42 > RobotModelBase::zeroJacobianEe ( const std::array< double, 7 > &  q,
const std::array< double, 16 > &  f_t_ee 
)
pure virtual

Calculates the 6x7 zero Jacobian for the end effector frame, relative to the base frame.

Parameters
[in]qJoint position.
[in]f_t_eeThe transformation from flange to end effector (4x4 matrix, column-major).
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.

◆ zeroJacobianFlange()

virtual std::array< double, 42 > RobotModelBase::zeroJacobianFlange ( const std::array< double, 7 > &  q)
pure virtual

Calculates the 6x7 zero Jacobian for the flange frame, relative to the base frame.

Parameters
[in]qJoint position.
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.

◆ zeroJacobianStiffness()

virtual std::array< double, 42 > RobotModelBase::zeroJacobianStiffness ( const std::array< double, 7 > &  q,
const std::array< double, 16 > &  f_t_ee,
const std::array< double, 16 > &  ee_t_k 
)
pure virtual

Calculates the 6x7 zero Jacobian for the stiffness frame, relative to the base frame.

Parameters
[in]qJoint position.
[in]f_t_eeThe transformation from flange to end effector (4x4 matrix, column-major).
[in]ee_t_kThe transformation from end effector to stiffness frame (4x4 matrix, column-major).
Returns
Vectorized 6x7 Jacobian, column-major.

Implemented in franka::RobotModel.


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