mc_tvm::CoM Struct Reference

#include <mc_tvm/CoM.h>

Inheritance diagram for mc_tvm::CoM:
Collaboration diagram for mc_tvm::CoM:

Public Member Functions

 CoM (NewCoMToken, Robot &robot)
 
const Eigen::Vector3d & com () const noexcept
 
const Eigen::Vector3d & velocity () const noexcept
 
const Eigen::Vector3d & normalAcceleration () const noexcept
 
const Eigen::Vector3d & acceleration () const noexcept
 
const Eigen::MatrixXd & jacobian () const noexcept
 
const Eigen::MatrixXd & JDot () const noexcept
 
const Robotrobot () const noexcept
 
Robotrobot () noexcept
 
const rbd::CoMJacobian & comJacobian () const noexcept
 

Friends

struct Robot
 

Detailed Description

Center of mass (CoM) of a Robot and related quantities

Provides the frame position, jacobian, velocity and normal acceleration. These signals are correctly initialized on the object's creation.

Outputs:

  • Position: position of the CoM in world coordinates
  • Jacobian: jacobian of the CoM in world coordinates
  • Velocity: velocity of the CoM in world coordinates
  • NormalAcceleration: normal acceleration of the CoM in world coordinates
  • Acceleration: acceleration of the CoM in world coordinates
  • JDot: derivative of the jacobian of the CoM in world coordinates

Constructor & Destructor Documentation

◆ CoM()

mc_tvm::CoM::CoM ( NewCoMToken  ,
Robot robot 
)

Constructor

Creates the CoM algorithm for a robot

Parameters
robotRobot to which the frame is attached

Member Function Documentation

◆ acceleration()

const Eigen::Vector3d& mc_tvm::CoM::acceleration ( ) const
inlinenoexcept

◆ com()

const Eigen::Vector3d& mc_tvm::CoM::com ( ) const
inlinenoexcept

◆ comJacobian()

const rbd::CoMJacobian& mc_tvm::CoM::comJacobian ( ) const
inlinenoexcept

Access the underlying CoMJacobian object to perform computations

◆ jacobian()

const Eigen::MatrixXd& mc_tvm::CoM::jacobian ( ) const
inlinenoexcept

◆ JDot()

const Eigen::MatrixXd& mc_tvm::CoM::JDot ( ) const
inlinenoexcept

◆ normalAcceleration()

const Eigen::Vector3d& mc_tvm::CoM::normalAcceleration ( ) const
inlinenoexcept

◆ robot() [1/2]

const Robot& mc_tvm::CoM::robot ( ) const
inlinenoexcept

◆ robot() [2/2]

Robot& mc_tvm::CoM::robot ( )
inlinenoexcept

◆ velocity()

const Eigen::Vector3d& mc_tvm::CoM::velocity ( ) const
inlinenoexcept

Friends And Related Function Documentation

◆ Robot

friend struct Robot
friend

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