tinyrobotics
Loading...
Searching...
No Matches
tr::model::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 () 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 = ""
 Name of the model.
 
int n_links = 0
 Number of links in the model.
 
int n_joints = 0
 Number of joints in the model.
 
int n_q = 0
 Number of configuration coordinates (degrees of freedom) in the model.
 
std::vector< Link< Scalar > > links = {}
 Vector of links in the model.
 
int base_link_idx = -1
 Index of the base link in the models links vector.
 
std::vector< int > q_idx = {}
 Vector of indices of links in the models link vector that have a non-fixed joint.
 
std::vector< int > parent = {}
 Vector of parent link indices of the links which are non-fixed.
 
std::vector< Joint< Scalar > > joints = {}
 Vector of joints in the model.
 
Eigen::Matrix< Scalar, 3, 1 > gravity = {0, 0, -9.81}
 Gravitational acceleration experienced by model.
 
Data< Scalar, nq > data
 Stores the results of the models algorithms.
 

Detailed Description

template<typename Scalar, int nq>
struct tr::model::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 > tr::model::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 > tr::model::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 > tr::model::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 > tr::model::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 > tr::model::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 > tr::model::Model< Scalar, nq >::random_configuration ( ) const
inline

Get a random configuration vector for the model.

Returns
Random configuration vector.

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