tinyrobotics
Loading...
Searching...
No Matches
tinyrobotics::Model< Scalar, nq > Struct Template Reference

A tinyrobotics model. More...

#include <model.hpp>

Public Member Functions

Link< Scalar > get_link (const std::string &name) const
 Get a link in the model by name.
 
Link< Scalar > get_parent_link (const std::string &name) const
 Get the parent link of a link in the model by name.
 
Joint< Scalar > get_joint (const std::string &name) const
 Get the joint in the model by name.
 
void show_details ()
 Display details of the model.
 
Eigen::Matrix< Scalar, nq, 1 > home_configuration () const
 Get a configuration vector for the model of all zeros.
 
Eigen::Matrix< Scalar, nq, 1 > random_configuration (Scalar range=M_PI) const
 Get a random configuration vector for the model.
 
template<typename NewScalar >
Model< NewScalar, nq > cast ()
 Casts the model to a new scalar type.
 

Public Attributes

std::string name = ""
 **************** Model Information ****************
 
int n_q = 0
 Number of configuration coordinates (degrees of freedom) in the model.
 
int base_link_idx = -1
 Index of the base link in the models links vector.
 
std::vector< int > q_map = {}
 Map to indices of links in the models link vector that have a non-fixed joints.
 
std::vector< int > parent = {}
 Vector of parent link indices of the links which have a non-fixed joints.
 
Eigen::Matrix< Scalar, 3, 1 > gravity = {0, 0, -9.81}
 Gravitational acceleration vector experienced by model.
 
Scalar mass = 0
 Total mass of the model.
 
std::vector< Link< Scalar > > links = {}
 Vector of links in the model.
 
Eigen::Matrix< Scalar, nq, nq > mass_matrix = Eigen::Matrix<Scalar, nq, nq>::Zero()
 **************** Pre-allcoated variables for kinematics algorithms ****************
 
Scalar potential_energy = 0
 Potential 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.
 
Eigen::Matrix< Scalar, 3, 1 > center_of_mass = Eigen::Matrix<Scalar, 3, 1>::Zero()
 center of mass position
 
std::vector< Eigen::Matrix< Scalar, 6, 6 > > Xup
 **************** Pre-allcoated variables for dynamics algorithms ****************
 
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::Matrix< Scalar, 6, 1 > vJ = Eigen::Matrix<Scalar, 6, 1>::Zero()
 Joint spatial velocities.
 
std::vector< Eigen::Matrix< Scalar, 6, 1 > > fvp
 Joint spatial forces.
 
Eigen::Matrix< Scalar, nq, 1 > C = Eigen::Matrix<Scalar, nq, 1>::Zero()
 Bias force vector.
 
Eigen::Matrix< Scalar, 6, 1 > fh = Eigen::Matrix<Scalar, 6, 1>::Zero()
 Force term for intermediately storing the result.
 
std::vector< Eigen::Matrix< Scalar, 6, 6 > > IC
 Articulated-body inertias.
 
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()
 Jacobian.
 
Eigen::Matrix< Scalar, nq, 1 > ddq = Eigen::Matrix<Scalar, nq, 1>::Zero()
 Joint acceleration.
 
Eigen::Matrix< Scalar, nq, 1 > tau = Eigen::Matrix<Scalar, nq, 1>::Zero()
 Joint torque/force.
 

Detailed Description

template<typename Scalar, int nq>
struct tinyrobotics::Model< Scalar, nq >

A tinyrobotics model.

A tinyrobotics model is a collection of links and joints that represents a robot.

Template Parameters
ScalarThe scalar type for the model.
nqThe number of configuration coordinates (number of degrees of freedom).

Member Function Documentation

◆ cast()

template<typename Scalar , int nq>
template<typename NewScalar >
Model< NewScalar, nq > tinyrobotics::Model< Scalar, nq >::cast ( )
inline

Casts the model to a new scalar type.

Template Parameters
NewScalarscalar type to cast the model to.
Returns
Model with new scalar type.

◆ get_joint()

template<typename Scalar , int nq>
Joint< Scalar > tinyrobotics::Model< Scalar, nq >::get_joint ( const std::string &  name) const
inline

Get the joint in the model by name.

Parameters
nameName of the joint.
Returns
Joint in the model.

◆ get_link()

template<typename Scalar , int nq>
Link< Scalar > tinyrobotics::Model< Scalar, nq >::get_link ( const std::string &  name) const
inline

Get a link in the model by name.

Parameters
nameName of the link.
Returns
Link in the model.

◆ get_parent_link()

template<typename Scalar , int nq>
Link< Scalar > tinyrobotics::Model< Scalar, nq >::get_parent_link ( const std::string &  name) const
inline

Get the parent link of a link in the model by name.

Parameters
link_idxIndex of the link in the model.
Returns
Parent link of the link.

◆ home_configuration()

template<typename Scalar , int nq>
Eigen::Matrix< Scalar, nq, 1 > tinyrobotics::Model< Scalar, nq >::home_configuration ( ) const
inline

Get a configuration vector for the model of all zeros.

Returns
Configuration vector of all zeros.

◆ random_configuration()

template<typename Scalar , int nq>
Eigen::Matrix< Scalar, nq, 1 > tinyrobotics::Model< Scalar, nq >::random_configuration ( Scalar  range = M_PI) const
inline

Get a random configuration vector for the model.

Parameters
rangeRange of the random values. Values will be between -range and range.
Returns
Configuration vector of random values between -pi and pi.

Member Data Documentation

◆ a

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Model< 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.

◆ c

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Model< 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::Model< Scalar, nq >::fvp
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 1>>(nq, Eigen::Matrix<Scalar, 6, 1>::Zero())

Joint spatial forces.

◆ IA

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 6> > tinyrobotics::Model< 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::Model< Scalar, nq >::IC
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 6>>(nq, Eigen::Matrix<Scalar, 6, 6>::Zero())

Articulated-body inertias.

◆ mass_matrix

template<typename Scalar , int nq>
Eigen::Matrix<Scalar, nq, nq> tinyrobotics::Model< Scalar, nq >::mass_matrix = Eigen::Matrix<Scalar, nq, nq>::Zero()

**************** Pre-allcoated variables for kinematics algorithms ****************

Mass matrix

◆ name

template<typename Scalar , int nq>
std::string tinyrobotics::Model< Scalar, nq >::name = ""

**************** Model Information ****************

Name of the model

◆ pA

template<typename Scalar , int nq>
std::vector<Eigen::Matrix<Scalar, 6, 1> > tinyrobotics::Model< 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::Model< 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::Model< 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::Model< 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::Model< Scalar, nq >::Xup
Initial value:
=
std::vector<Eigen::Matrix<Scalar, 6, 6>>(nq, Eigen::Matrix<Scalar, 6, 6>::Zero())

**************** Pre-allcoated variables for dynamics algorithms ****************

Spatial transforms from parent to child links


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