mc_tvm::Robot Struct Reference

#include <mc_tvm/Robot.h>

Inheritance diagram for mc_tvm::Robot:
Collaboration diagram for mc_tvm::Robot:

Classes

struct  NewRobotToken
 

Public Types

using mimic_variables_t = std::pair< tvm::VariableVector, Eigen::VectorXd >
 

Public Member Functions

 Robot (NewRobotToken, const mc_rbdyn::Robot &robot)
 
 Robot (Robot &&)=delete
 
Robotoperator= (Robot &&)=delete
 
 Robot (const Robot &)=delete
 
Robotoperator= (const Robot &)=delete
 
const mc_rbdyn::Robotrobot () const
 
const Limitslimits () const noexcept
 
Limitslimits () noexcept
 
const tvm::VariablePtr & q () const noexcept
 
tvm::VariablePtr & q () noexcept
 
const tvm::VariablePtr & alpha () const noexcept
 
tvm::VariablePtr & alpha () noexcept
 
const tvm::VariablePtr & alphaD () const noexcept
 
tvm::VariablePtr & alphaD () noexcept
 
const tvm::VariablePtr & qFloatingBase () const noexcept
 
tvm::VariablePtr & qFloatingBase () noexcept
 
const tvm::VariablePtr & qJoints () const noexcept
 
tvm::VariablePtr & qJoints () noexcept
 
tvm::VariablePtr qJoint (size_t jIdx)
 
tvm::VariablePtr qJoint (const std::string &jName)
 
const std::map< tvm::VariablePtr, mimic_variables_t > & mimics () const noexcept
 
std::map< tvm::VariablePtr, mimic_variables_t > & mimics () noexcept
 
const tvm::VariablePtr & tau () const noexcept
 
tvm::VariablePtr & tau ()
 
const CoMcomAlgo () const noexcept
 
CoMcomAlgo () noexcept
 
const MomentummomentumAlgo () const noexcept
 
MomentummomentumAlgo () noexcept
 
const Eigen::MatrixXd & H () const noexcept
 
const Eigen::VectorXd & C () const noexcept
 
const std::vector< sva::MotionVecd > & normalAccB () const noexcept
 
Eigen::DenseIndex refJointIndexToQIndex (size_t jointIndex) const
 
Eigen::DenseIndex refJointIndexToQDotIndex (size_t jointIndex) const
 

Friends

struct mc_rbdyn::Robot
 

Detailed Description

Represent a robot managed by the optimization problem

It is created through an mc_rbdyn::Robot

It provides signals that are relevant for computing quantities related to the 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 FV
  • tau: generalized torque vector
  • 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 FK
  • Dynamics: depends on FA + normalAcceleration (i.e. everything)

Member Typedef Documentation

◆ mimic_variables_t

using mc_tvm::Robot::mimic_variables_t = std::pair<tvm::VariableVector, Eigen::VectorXd>

Constructor & Destructor Documentation

◆ Robot() [1/3]

mc_tvm::Robot::Robot ( NewRobotToken  ,
const mc_rbdyn::Robot robot 
)

◆ Robot() [2/3]

mc_tvm::Robot::Robot ( Robot &&  )
delete

◆ Robot() [3/3]

mc_tvm::Robot::Robot ( const Robot )
delete

Member Function Documentation

◆ alpha() [1/2]

const tvm::VariablePtr& mc_tvm::Robot::alpha ( ) const
inlinenoexcept

Access q first derivative (joint velocity) (const)

◆ alpha() [2/2]

tvm::VariablePtr& mc_tvm::Robot::alpha ( )
inlinenoexcept

Access q first derivative (joint velocity)

◆ alphaD() [1/2]

const tvm::VariablePtr& mc_tvm::Robot::alphaD ( ) const
inlinenoexcept

Access q second derivative (joint acceleration) (const)

◆ alphaD() [2/2]

tvm::VariablePtr& mc_tvm::Robot::alphaD ( )
inlinenoexcept

Access q second derivative (joint acceleration)

◆ C()

const Eigen::VectorXd& mc_tvm::Robot::C ( ) const
inlinenoexcept

Returns the non-linear dynamics component

◆ comAlgo() [1/2]

const CoM& mc_tvm::Robot::comAlgo ( ) const
inlinenoexcept

Returns the CoM algorithm associated to this robot (const)

◆ comAlgo() [2/2]

CoM& mc_tvm::Robot::comAlgo ( )
inlinenoexcept

Returns the CoM algorithm associated to this robot

◆ H()

const Eigen::MatrixXd& mc_tvm::Robot::H ( ) const
inlinenoexcept

Returns the mass matrix

◆ limits() [1/2]

const Limits& mc_tvm::Robot::limits ( ) const
inlinenoexcept

Retrieve the joint limits (const)

◆ limits() [2/2]

Limits& mc_tvm::Robot::limits ( )
inlinenoexcept

Retrieve the joint limits

◆ mimics() [1/2]

const std::map<tvm::VariablePtr, mimic_variables_t>& mc_tvm::Robot::mimics ( ) const
inlinenoexcept

Access mimics' variable map (const)

◆ mimics() [2/2]

std::map<tvm::VariablePtr, mimic_variables_t>& mc_tvm::Robot::mimics ( )
inlinenoexcept

Access mimics' variable map

◆ momentumAlgo() [1/2]

const Momentum& mc_tvm::Robot::momentumAlgo ( ) const
inlinenoexcept

Returns the momentum algorithm associated with this robot (const)

◆ momentumAlgo() [2/2]

Momentum& mc_tvm::Robot::momentumAlgo ( )
inlinenoexcept

Returns the momentum algorithm associated with this robot (const)

◆ normalAccB()

const std::vector<sva::MotionVecd>& mc_tvm::Robot::normalAccB ( ) const
inlinenoexcept

Vector of normal acceleration in body coordinates

◆ operator=() [1/2]

Robot& mc_tvm::Robot::operator= ( const Robot )
delete

◆ operator=() [2/2]

Robot& mc_tvm::Robot::operator= ( Robot &&  )
delete

◆ q() [1/2]

const tvm::VariablePtr& mc_tvm::Robot::q ( ) const
inlinenoexcept

Access q variable (const)

◆ q() [2/2]

tvm::VariablePtr& mc_tvm::Robot::q ( )
inlinenoexcept

Access q variable

◆ qFloatingBase() [1/2]

const tvm::VariablePtr& mc_tvm::Robot::qFloatingBase ( ) const
inlinenoexcept

Access floating-base variable (const)

◆ qFloatingBase() [2/2]

tvm::VariablePtr& mc_tvm::Robot::qFloatingBase ( )
inlinenoexcept

Access free-flyer variable

◆ qJoint() [1/2]

tvm::VariablePtr mc_tvm::Robot::qJoint ( const std::string &  jName)
inline

Given a joint name, returns the TVM variable it belongs to and the index of the joint in this variable

Parameters
jNameJoint name
Exceptions
Ifthe robot does not have such a joint or the joint is not actuated

◆ qJoint() [2/2]

tvm::VariablePtr mc_tvm::Robot::qJoint ( size_t  jIdx)

Given a joint index creates a TVM variable corresponding to this variable

Warning
This returns a different object (but the same variable from TVM pov) each time this function is called
Parameters
jIdxJoint index
Exceptions
Ifthe joint index is out of bounds or the joint is not actuated

◆ qJoints() [1/2]

const tvm::VariablePtr& mc_tvm::Robot::qJoints ( ) const
inlinenoexcept

Access joints variable (const)

◆ qJoints() [2/2]

tvm::VariablePtr& mc_tvm::Robot::qJoints ( )
inlinenoexcept

Access joints variable

◆ refJointIndexToQDotIndex()

Eigen::DenseIndex mc_tvm::Robot::refJointIndexToQDotIndex ( size_t  jointIndex) const
inline

Given a joint index in the reference joint order, returns the corresponding joint index in the q derivatives variable

Note
Joint indices can be -1 for joints present in refJointOrder but not in the robot's q (such as filtered joints in some robot modules)
Parameters
jointIndexJoint index in refJointOrder
Returns
joint index in q

◆ refJointIndexToQIndex()

Eigen::DenseIndex mc_tvm::Robot::refJointIndexToQIndex ( size_t  jointIndex) const
inline

Given a joint index in the reference joint order, returns the corresponding joint index in the q variable

Note
Joint indices can be -1 for joints present in refJointOrder but not in the robot's q (such as filtered joints in some robot modules)
Parameters
jointIndexJoint index in refJointOrder
Returns
joint index in q

◆ robot()

const mc_rbdyn::Robot& mc_tvm::Robot::robot ( ) const
inline

Retrieve the associated robot (const)

Exceptions
Ifthe original robot has been destroyed

◆ tau() [1/2]

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

Access tau variable

◆ tau() [2/2]

const tvm::VariablePtr& mc_tvm::Robot::tau ( ) const
inlinenoexcept

Access tau variable (const)

Friends And Related Function Documentation

◆ mc_rbdyn::Robot

friend struct mc_rbdyn::Robot
friend

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