tinyrobotics
Loading...
Searching...
No Matches
tr::data::Data< Scalar, nq > Struct Template Reference

A data struct for storing results of various model algorithms. More...

#include <Data.hpp>

Public Member Functions

template<typename NewScalar >
Data< NewScalar, nq > cast ()
 Casts the data to a new scalar type.
 

Public Attributes

Eigen::Matrix< Scalar, nq, 1 > q
 Joint configuration.
 
Eigen::Matrix< Scalar, nq, 1 > dq
 Joint velocity.
 
Eigen::Matrix< Scalar, nq, 1 > ddq
 Joint acceleration.
 
Eigen::Matrix< Scalar, nq, 1 > p
 Joint Momentum.
 
Eigen::Matrix< Scalar, nq, 1 > tau
 Joint torque.
 
Eigen::Matrix< Scalar, nq, nq > M = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Mass matrix.
 
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Mr
 
Eigen::Matrix< Scalar, nq, nq > Minv = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Inverse mass matrix.
 
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Mrinv
 
Eigen::Matrix< Scalar, nq, nq > C = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Coriolis matrix.
 
Eigen::Matrix< Scalar, nq, 1 > g
 Gravity torque vector.
 
Eigen::Matrix< Scalar, nq, nq > Gp = Eigen::Matrix<Scalar, nq, nq>::Identity()
 Input mapping matrix.
 
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Gr
 
Eigen::Matrix< Scalar, nq, nq > Dp = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Damping matrix.
 
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Dr
 
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Jc
 Constraint jacobian.
 
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Jcp
 Constraint jacobian left annihilator.
 
Scalar T = 0
 The kinetic co-energy.
 
Scalar V = 0
 The potential energy.
 
Scalar H = 0
 The hamiltonian (total energy).
 
Eigen::Matrix< Scalar, nq+nq, 1 > dx_dt
 The dynamics dx_dt.
 
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > FK = {}
 Vector of forward kinematics Data.
 
int nr = 0
 Number of reduced momentum states.
 
int nz = 0
 Vector of redundant momentum states.
 

Detailed Description

template<typename Scalar, int nq>
struct tr::data::Data< Scalar, nq >

A data struct for storing results of various model algorithms.

Template Parameters
ScalarScalar type of the associated model.
nqNumber of configuration coordinates (number of degrees of freedom)

Member Function Documentation

◆ cast()

template<typename Scalar , int nq>
template<typename NewScalar >
Data< NewScalar, nq > tr::data::Data< Scalar, nq >::cast ( )
inline

Casts the data to a new scalar type.

Template Parameters
NewScalarscalar type to cast the data to.
Returns
Data with new scalar type.

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