TVM  0.9.4
tvm::Robot Class Reference

#include <tvm/Robot.h>

Inheritance diagram for tvm::Robot:
Collaboration diagram for tvm::Robot:

Public Member Functions

 Robot (Clock &clock, const std::string &name, rbd::MultiBodyGraph &mbg, rbd::MultiBody mb, rbd::MultiBodyConfig mbc, const rbd::parsers::Limits &limits={{}, {}, {}, {}})
 
const std::string & name () const
 
double mass () const
 
const VariableVectorq () const
 
VariableVectorq ()
 
const VariablePtrqFreeFlyer () const
 
VariablePtrqFreeFlyer ()
 
const VariablePtrqJoints () const
 
VariablePtrqJoints ()
 
const VariablePtrtau () const
 
VariablePtrtau ()
 
const rbd::MultiBody & mb () const
 
rbd::MultiBody & mb ()
 
const rbd::MultiBodyConfig & mbc () const
 
rbd::MultiBodyConfig & mbc ()
 
const std::vector< sva::MotionVecd > & normalAccB () const
 
std::vector< sva::MotionVecd > & normalAccB ()
 
const Eigen::VectorXd & lQBound () const
 
Eigen::VectorXd & lQBound ()
 
const Eigen::VectorXd & uQBound () const
 
Eigen::VectorXd & uQBound ()
 
const Eigen::VectorXd & lVelBound () const
 
Eigen::VectorXd & lVelBound ()
 
const Eigen::VectorXd & uVelBound () const
 
Eigen::VectorXd & uVelBound ()
 
const Eigen::VectorXd & lTauBound () const
 
Eigen::VectorXd & lTauBound ()
 
const Eigen::VectorXd & uTauBound () const
 
Eigen::VectorXd & uTauBound ()
 
const Eigen::MatrixXd & H () const
 
const Eigen::VectorXd & C () const
 
const Eigen::Vector3d & com () const
 
const sva::PTransformd & bodyTransform (const std::string &b) const
 
- Public Member Functions inherited from tvm::graph::internal::AbstractNode
template<typename EnumT >
bool isUpdateEnabled (EnumT e) const
 
virtual bool isUpdateStaticallyEnabled (int) const
 
virtual bool isUpdateCustomEnabled (int) const
 
virtual ~AbstractNode ()=default
 
void update (int i)
 
- Public Member Functions inherited from tvm::graph::internal::Inputs
virtual ~Inputs ()=default
 
template<typename T , typename EnumI , typename... Args>
void addInput (std::shared_ptr< T > source, EnumI i, Args... args)
 
template<typename T , typename EnumI , typename... Args, typename std::enable_if< std::is_base_of< abstract::Outputs, T >::value, int >::type = 0>
void addInput (T &source, EnumI i, Args... args)
 
template<typename T >
void removeInput (T *source)
 
template<typename T , typename... Args>
void removeInput (T *source, Args... args)
 
template<typename T >
Iterator getInput (T *source)
 
template<typename T >
Iterator getInput (const std::shared_ptr< T > &source)
 
- Public Member Functions inherited from tvm::graph::abstract::Outputs
virtual ~Outputs ()=default
 
template<typename EnumT >
bool isOutputEnabled (EnumT e) const
 
bool isOutputEnabled (int i) const
 
virtual bool isOutputStaticallyEnabled (int) const
 
virtual bool isOutputCustomEnabled (int) const
 

Additional Inherited Members

- Public Types inherited from tvm::graph::internal::AbstractNode
enum class  Update_
 
using UpdateParent = AbstractNode
 
using UpdateBase = AbstractNode
 
- Public Types inherited from tvm::graph::internal::Inputs
using inputs_t = std::unordered_map< abstract::Outputs *, std::set< int > >
 
using store_t = std::unordered_set< std::shared_ptr< abstract::Outputs > >
 
- Public Types inherited from tvm::graph::abstract::Outputs
enum class  Output_
 
using OutputParent = Outputs
 
using OutputBase = Outputs
 
- Static Public Member Functions inherited from tvm::graph::internal::AbstractNode
static constexpr const char * UpdateName (Update_)
 
template<typename EnumT >
static constexpr bool UpdateStaticallyEnabled (EnumT)
 
- Static Public Member Functions inherited from tvm::graph::abstract::Outputs
static constexpr const char * OutputName (Output_)
 
template<typename EnumT >
static constexpr bool OutputStaticallyEnabled (EnumT)
 
- Static Public Attributes inherited from tvm::graph::internal::AbstractNode
static constexpr unsigned int UpdateSize = 0
 
static constexpr auto UpdateBaseName = "AbstractNode"
 
- Static Public Attributes inherited from tvm::graph::abstract::Outputs
static constexpr unsigned int OutputSize = 0
 
static constexpr auto OutputBaseName = "Outputs"
 
- Protected Types inherited from tvm::graph::internal::AbstractNode
using input_dependency_t = std::map< Outputs *, std::set< int > >
 
- Protected Member Functions inherited from tvm::graph::abstract::Node< Robot >
void registerUpdates (EnumT u, void(U::*fn)(), Args... args)
 
void registerUpdates (EnumT u, void(U::*fn)())
 
void addOutputDependency (EnumO o, EnumU u)
 
void addOutputDependency (std::initializer_list< EnumO > os, EnumU u)
 
void addInternalDependency (EnumU1 uDependent, EnumU2 u)
 
void addInputDependency (EnumU u, std::shared_ptr< S > source, EnumO i, Args... args)
 
void addInputDependency (EnumU u, S &source, EnumO i, Args... args)
 
void addDirectDependency (EnumO o, std::shared_ptr< S > source, EnumI i)
 
void addDirectDependency (EnumO o, S &source, EnumI i)
 
- Protected Attributes inherited from tvm::graph::internal::AbstractNode
std::map< int, std::function< void(AbstractNode &)> > updates_
 
std::map< int, std::vector< int > > outputDependencies_
 
std::map< int, std::vector< int > > internalDependencies_
 
std::map< int, input_dependency_tinputDependencies_
 
std::map< int, std::pair< Outputs *, int > > directDependencies_
 
- Protected Attributes inherited from tvm::graph::abstract::Outputs
bool is_node_ = false
 

Detailed Description

Represent a Robot

A robot is constructed by providing instances of MultiBodyGraph, MultiBody and MultiBodyConfig that are created from each other. It provides signals that are relevant for computing quantities related to a robot.

Variables:

  • q (split between free-flyer and joints)
  • tau (see Outputs)

Individual outputs:

  • FK: forward kinematics (computed by RBDyn::FK)
  • FV: forward velocity (computed by RBDyn::FV), depends on FK
  • FA: forward acceleration (computed by RBDyn::FA), depends on FV
  • NormalAcceleration: update bodies' normal acceleration, depends on FA
  • tau: generalized torque vector, this output isn't currently linked to any computation
  • CoM: center of mass signal, depends on FK
  • H: inertia matrix signal, depends on FV
  • C: non-linear effect vector signal (Coriolis, gravity, external forces), depends on FV

Meta outputs: These outputs are provided for convenience sake

  • Geometry: depends on CoM (i.e. CoM + FK)
  • Dynamics: depends on FA + normalAcceleration (i.e. everything)

Constructor & Destructor Documentation

◆ Robot()

tvm::Robot::Robot ( Clock clock,
const std::string &  name,
rbd::MultiBodyGraph &  mbg,
rbd::MultiBody  mb,
rbd::MultiBodyConfig  mbc,
const rbd::parsers::Limits &  limits = {{}, {}, {}, {}} 
)

Constructor

Parameters
clockClock used in the ControlProblem
nameName of the robot
mbgMultiBodyGraph used to create mb/mbc
mbMultiBody representing the robot's kinematic structure
mbcMultiBodyConfig giving the robot's initial configuration
limitsJoint limits

Member Function Documentation

◆ bodyTransform()

const sva::PTransformd& tvm::Robot::bodyTransform ( const std::string &  b) const
inline

Access the transformation that allows to retrieve the original base of a body

◆ C()

const Eigen::VectorXd& tvm::Robot::C ( ) const
inline

Access the non-linear effect vector Access the non-linear effect vector (Coriolis, gravity, external force).

◆ com()

const Eigen::Vector3d& tvm::Robot::com ( ) const
inline

Access the CoM position

◆ H()

const Eigen::MatrixXd& tvm::Robot::H ( ) const
inline

Access the inertia matrix

◆ lQBound() [1/2]

Eigen::VectorXd& tvm::Robot::lQBound ( )
inline

Access the joints' lower position limit

◆ lQBound() [2/2]

const Eigen::VectorXd& tvm::Robot::lQBound ( ) const
inline

Access the joints' lower position limit (const)

◆ lTauBound() [1/2]

Eigen::VectorXd& tvm::Robot::lTauBound ( )
inline

Access the robot's lower torque limit

◆ lTauBound() [2/2]

const Eigen::VectorXd& tvm::Robot::lTauBound ( ) const
inline

Access the robot's lower torque limit (const)

◆ lVelBound() [1/2]

Eigen::VectorXd& tvm::Robot::lVelBound ( )
inline

Access the joints' lower velocity limit

◆ lVelBound() [2/2]

const Eigen::VectorXd& tvm::Robot::lVelBound ( ) const
inline

Access the joints' lower velocity limit (const)

◆ mass()

double tvm::Robot::mass ( ) const
inline

Returns the robot's mass

◆ mb() [1/2]

rbd::MultiBody& tvm::Robot::mb ( )
inline

Access the robot's related rbd::MultiBody

◆ mb() [2/2]

const rbd::MultiBody& tvm::Robot::mb ( ) const
inline

Access the robot's related rbd::MultiBody (const)

◆ mbc() [1/2]

rbd::MultiBodyConfig& tvm::Robot::mbc ( )
inline

Access the robot's related rbd::MultiBodyConfig

◆ mbc() [2/2]

const rbd::MultiBodyConfig& tvm::Robot::mbc ( ) const
inline

Access the robot's related rbd::MultiBodyConfig (const)

◆ name()

const std::string& tvm::Robot::name ( ) const
inline

Access the robot's name

◆ normalAccB() [1/2]

std::vector<sva::MotionVecd>& tvm::Robot::normalAccB ( )
inline

Access the vector of normal acceleration expressed in the body's frame

◆ normalAccB() [2/2]

const std::vector<sva::MotionVecd>& tvm::Robot::normalAccB ( ) const
inline

Access the vector of normal acceleration expressed in the body's frame (const)

◆ q() [1/2]

VariableVector& tvm::Robot::q ( )
inline

Access q variable

◆ q() [2/2]

const VariableVector& tvm::Robot::q ( ) const
inline

Access q variable (const)

◆ qFreeFlyer() [1/2]

VariablePtr& tvm::Robot::qFreeFlyer ( )
inline

Access free-flyer variable

◆ qFreeFlyer() [2/2]

const VariablePtr& tvm::Robot::qFreeFlyer ( ) const
inline

Access free-flyer variable (const)

◆ qJoints() [1/2]

VariablePtr& tvm::Robot::qJoints ( )
inline

Access joints variable

◆ qJoints() [2/2]

const VariablePtr& tvm::Robot::qJoints ( ) const
inline

Access joints variable (const)

◆ tau() [1/2]

VariablePtr& tvm::Robot::tau ( )
inline

Access tau variable

◆ tau() [2/2]

const VariablePtr& tvm::Robot::tau ( ) const
inline

Access tau variable (const)

◆ uQBound() [1/2]

Eigen::VectorXd& tvm::Robot::uQBound ( )
inline

Access the joints' upper position limit

◆ uQBound() [2/2]

const Eigen::VectorXd& tvm::Robot::uQBound ( ) const
inline

Access the joints' upper position limit (const)

◆ uTauBound() [1/2]

Eigen::VectorXd& tvm::Robot::uTauBound ( )
inline

Access the robot's upper torque limit

◆ uTauBound() [2/2]

const Eigen::VectorXd& tvm::Robot::uTauBound ( ) const
inline

Access the robot's upper torque limit (const)

◆ uVelBound() [1/2]

Eigen::VectorXd& tvm::Robot::uVelBound ( )
inline

Access the joints' upper velocity limit

◆ uVelBound() [2/2]

const Eigen::VectorXd& tvm::Robot::uVelBound ( ) const
inline

Access the joints' upper velocity limit (const)


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