tinyrobotics
Loading...
Searching...
No Matches
tinyrobotics::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 > tau
 Joint torque/force.
 
Eigen::Matrix< Scalar, nq, nq > mass_matrix = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Mass matrix.
 
Eigen::Matrix< Scalar, nq, nq > inv_mass_matrix = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Inverse mass matrix.
 
Eigen::Matrix< Scalar, nq, nq > coriolis = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Coriolis matrix.
 
Eigen::Matrix< Scalar, nq, 1 > gravity
 Gravity vector.
 
Eigen::Matrix< Scalar, nq, nq > input_mapping = Eigen::Matrix<Scalar, nq, nq>::Identity()
 Input mapping matrix.
 
Eigen::Matrix< Scalar, nq, nq > damping = Eigen::Matrix<Scalar, nq, nq>::Zero()
 Damping matrix.
 
Scalar kinetic_energy = 0
 Kinetic energy.
 
Scalar potential_energy = 0
 Potential energy.
 
Scalar total_energy = 0
 Total_energy.
 
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > forward_kinematics = {}
 Vector of forward kinematics Data.
 
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > forward_kinematics_com = {}
 Vector of forward kinematics com Data.
 
std::vector< Eigen::Matrix< Scalar, 6, 6 > > Xup
 Spatial transforms from parent to child links.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > S
 Motion subspace matrices for the joints.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > v
 Spatial velocities of the robot links.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > c
 Spatial acceleration bias terms for the robot links.
 
std::vector< Eigen::Matrix< Scalar, 6, 6 > > IA
 Articulated-body inertia matrices for the robot links.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > pA
 Articulated-body forces for the robot links.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > U
 Spatial force projections for the joints.
 
std::vector< Scalar > d = std::vector<Scalar>(nq, 0)
 Joint force inertia terms for the robot links.
 
std::vector< Scalar > u = std::vector<Scalar>(nq, 0)
 Joint force bias terms for the robot links.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > a
 Spatial accelerations of the robot links.
 
Eigen::Transform< Scalar, 3, Eigen::Isometry > T = Eigen::Transform<Scalar, 3, Eigen::Isometry>::Identity()
 Homogeneous transformation matrix.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > avp
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > fvp
 
Eigen::Matrix< Scalar, nq, 1 > C = Eigen::Matrix<Scalar, nq, 1>::Zero()
 
Eigen::Matrix< Scalar, 6, 1 > fh = Eigen::Matrix<Scalar, 6, 1>::Zero()
 
std::vector< Eigen::Matrix< Scalar, 6, 6 > > IC
 
Eigen::Matrix< Scalar, 6, 1 > spatial_gravity = Eigen::Matrix<Scalar, 6, 1>::Zero()
 Gravity vector in spatial coordinates.
 
Eigen::Matrix< Scalar, 6, nq > J = Eigen::Matrix<Scalar, 6, nq>::Zero()
 Geometric Jacobian.
 

Detailed Description

template<typename Scalar, int nq>
struct tinyrobotics::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 > tinyrobotics::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.

Member Data Documentation

◆ a

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::a
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

Spatial accelerations of the robot links.

◆ avp

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::avp
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

◆ c

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::c
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

Spatial acceleration bias terms for the robot links.

◆ fvp

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::fvp
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

◆ IA

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 6> > tinyrobotics::Data< Scalar, nq >::IA
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 6>>(nq, Eigen::Matrix<Scalar, 6, 6>::Zero())

Articulated-body inertia matrices for the robot links.

◆ IC

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 6> > tinyrobotics::Data< Scalar, nq >::IC
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 6>>(nq, Eigen::Matrix<Scalar, 6, 6>::Zero())

◆ pA

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::pA
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

Articulated-body forces for the robot links.

◆ S

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::S
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

Motion subspace matrices for the joints.

◆ U

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::U
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

Spatial force projections for the joints.

◆ v

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Data< Scalar, nq >::v
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

Spatial velocities of the robot links.

◆ Xup

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 6> > tinyrobotics::Data< Scalar, nq >::Xup
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 6>>(nq, Eigen::Matrix<Scalar, 6, 6>::Zero())

Spatial transforms from parent to child links.


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