Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
tsid::robots::RobotWrapper Class Reference

Wrapper for a robot based on pinocchio. More...

#include <robot-wrapper.hpp>

Public Types

typedef math::ConstRefVector ConstRefVector
 
typedef pinocchio::Data Data
 
enum  e_RootJointType { FIXED_BASE_SYSTEM = 0, FLOATING_BASE_SYSTEM = 1 }
 
typedef pinocchio::Frame Frame
 
typedef math::Matrix Matrix
 
typedef math::Matrix3x Matrix3x
 
typedef pinocchio::Model Model
 
typedef pinocchio::Motion Motion
 
typedef math::RefVector RefVector
 
typedef enum tsid::robots::RobotWrapper::e_RootJointType RootJointType
 
typedef pinocchio::SE3 SE3
 
typedef math::Vector Vector
 
typedef math::Vector3 Vector3
 
typedef math::Vector6 Vector6
 

Public Member Functions

const Motionacceleration (const Data &data, const Model::JointIndex index) const
 
Vector3 angularMomentumTimeVariation (const Data &data) const
 
const Vector3com (const Data &data) const
 
void com (const Data &data, RefVector com_pos, RefVector com_vel, RefVector com_acc) const
 
const Vector3com_acc (const Data &data) const
 
const Vector3com_vel (const Data &data) const
 
void computeAllTerms (Data &data, const Vector &q, const Vector &v) const
 
Motion frameAcceleration (const Data &data, const Model::FrameIndex index) const
 
void frameAcceleration (const Data &data, const Model::FrameIndex index, Motion &frameAcceleration) const
 
Motion frameAccelerationWorldOriented (const Data &data, const Model::FrameIndex index) const
 
Motion frameClassicAcceleration (const Data &data, const Model::FrameIndex index) const
 
void frameClassicAcceleration (const Data &data, const Model::FrameIndex index, Motion &frameAcceleration) const
 
Motion frameClassicAccelerationWorldOriented (const Data &data, const Model::FrameIndex index) const
 
void frameJacobianLocal (Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
 
void frameJacobianWorld (Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
 
SE3 framePosition (const Data &data, const Model::FrameIndex index) const
 
void framePosition (const Data &data, const Model::FrameIndex index, SE3 &framePosition) const
 
Motion frameVelocity (const Data &data, const Model::FrameIndex index) const
 
void frameVelocity (const Data &data, const Model::FrameIndex index, Motion &frameVelocity) const
 
Motion frameVelocityWorldOriented (const Data &data, const Model::FrameIndex index) const
 
const Vectorgear_ratios () const
 
bool gear_ratios (ConstRefVector gear_ratios)
 
virtual bool is_fixed_base () const
 
void jacobianLocal (const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const
 
void jacobianWorld (const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const
 
const Matrix3xJcom (const Data &data) const
 
const Matrixmass (const Data &data)
 
Modelmodel ()
 
const Modelmodel () const
 Accessor to model. More...
 
const Data::Matrix6xmomentumJacobian (const Data &data) const
 
virtual int na () const
 
const VectornonLinearEffects (const Data &data) const
 
virtual int nq () const
 
virtual int nq_actuated () const
 
virtual int nv () const
 
const SE3position (const Data &data, const Model::JointIndex index) const
 
TSID_DEPRECATED RobotWrapper (const Model &m, bool verbose=false)
 
 RobotWrapper (const Model &m, RootJointType rootJoint, bool verbose=false)
 
 RobotWrapper (const std::string &filename, const std::vector< std::string > &package_dirs, bool verbose=false)
 
 RobotWrapper (const std::string &filename, const std::vector< std::string > &package_dirs, const pinocchio::JointModelVariant &rootJoint, bool verbose=false)
 
const Vectorrotor_inertias () const
 
bool rotor_inertias (ConstRefVector rotor_inertias)
 
void setGravity (const Motion &gravity)
 
const Motionvelocity (const Data &data, const Model::JointIndex index) const
 
virtual ~RobotWrapper ()=default
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Scalar Scalar
 

Protected Member Functions

void init ()
 
void updateMd ()
 

Protected Attributes

Vector m_gear_ratios
 
bool m_is_fixed_base
 
Matrix m_M
 diagonal part of inertia matrix due to rotor inertias More...
 
Vector m_Md
 
Model m_model
 Robot model. More...
 
std::string m_model_filename
 
int m_na
 
int m_nq_actuated
 
Vector m_rotor_inertias
 
bool m_verbose
 

Detailed Description

Wrapper for a robot based on pinocchio.

Definition at line 37 of file robots/robot-wrapper.hpp.

Member Typedef Documentation

◆ ConstRefVector

typedef math::ConstRefVector tsid::robots::RobotWrapper::ConstRefVector

Definition at line 53 of file robots/robot-wrapper.hpp.

◆ Data

Definition at line 43 of file robots/robot-wrapper.hpp.

◆ Frame

Definition at line 45 of file robots/robot-wrapper.hpp.

◆ Matrix

Definition at line 50 of file robots/robot-wrapper.hpp.

◆ Matrix3x

Definition at line 51 of file robots/robot-wrapper.hpp.

◆ Model

Definition at line 42 of file robots/robot-wrapper.hpp.

◆ Motion

Definition at line 44 of file robots/robot-wrapper.hpp.

◆ RefVector

Definition at line 52 of file robots/robot-wrapper.hpp.

◆ RootJointType

◆ SE3

Definition at line 46 of file robots/robot-wrapper.hpp.

◆ Vector

Definition at line 47 of file robots/robot-wrapper.hpp.

◆ Vector3

Definition at line 48 of file robots/robot-wrapper.hpp.

◆ Vector6

Definition at line 49 of file robots/robot-wrapper.hpp.

Member Enumeration Documentation

◆ e_RootJointType

Enumerator
FIXED_BASE_SYSTEM 
FLOATING_BASE_SYSTEM 

Definition at line 56 of file robots/robot-wrapper.hpp.

Constructor & Destructor Documentation

◆ RobotWrapper() [1/4]

tsid::robots::RobotWrapper::RobotWrapper ( const std::string &  filename,
const std::vector< std::string > &  package_dirs,
bool  verbose = false 
)

Definition at line 34 of file src/robots/robot-wrapper.cpp.

◆ RobotWrapper() [2/4]

tsid::robots::RobotWrapper::RobotWrapper ( const std::string &  filename,
const std::vector< std::string > &  package_dirs,
const pinocchio::JointModelVariant rootJoint,
bool  verbose = false 
)

◆ RobotWrapper() [3/4]

tsid::robots::RobotWrapper::RobotWrapper ( const Model m,
bool  verbose = false 
)

Definition at line 58 of file src/robots/robot-wrapper.cpp.

◆ RobotWrapper() [4/4]

tsid::robots::RobotWrapper::RobotWrapper ( const Model m,
RootJointType  rootJoint,
bool  verbose = false 
)

Definition at line 68 of file src/robots/robot-wrapper.cpp.

◆ ~RobotWrapper()

virtual tsid::robots::RobotWrapper::~RobotWrapper ( )
virtualdefault

Member Function Documentation

◆ acceleration()

const Motion & tsid::robots::RobotWrapper::acceleration ( const Data data,
const Model::JointIndex  index 
) const

Definition at line 190 of file src/robots/robot-wrapper.cpp.

◆ angularMomentumTimeVariation()

Vector3 tsid::robots::RobotWrapper::angularMomentumTimeVariation ( const Data data) const

Definition at line 350 of file src/robots/robot-wrapper.cpp.

◆ com() [1/2]

const Vector3 & tsid::robots::RobotWrapper::com ( const Data data) const

Definition at line 152 of file src/robots/robot-wrapper.cpp.

◆ com() [2/2]

void tsid::robots::RobotWrapper::com ( const Data data,
RefVector  com_pos,
RefVector  com_vel,
RefVector  com_acc 
) const

Definition at line 145 of file src/robots/robot-wrapper.cpp.

◆ com_acc()

const Vector3 & tsid::robots::RobotWrapper::com_acc ( const Data data) const

Definition at line 158 of file src/robots/robot-wrapper.cpp.

◆ com_vel()

const Vector3 & tsid::robots::RobotWrapper::com_vel ( const Data data) const

Definition at line 154 of file src/robots/robot-wrapper.cpp.

◆ computeAllTerms()

void tsid::robots::RobotWrapper::computeAllTerms ( Data data,
const Vector q,
const Vector v 
) const

Definition at line 105 of file src/robots/robot-wrapper.cpp.

◆ frameAcceleration() [1/2]

Motion tsid::robots::RobotWrapper::frameAcceleration ( const Data data,
const Model::FrameIndex  index 
) const

Definition at line 265 of file src/robots/robot-wrapper.cpp.

◆ frameAcceleration() [2/2]

void tsid::robots::RobotWrapper::frameAcceleration ( const Data data,
const Model::FrameIndex  index,
Motion frameAcceleration 
) const

Definition at line 274 of file src/robots/robot-wrapper.cpp.

◆ frameAccelerationWorldOriented()

Motion tsid::robots::RobotWrapper::frameAccelerationWorldOriented ( const Data data,
const Model::FrameIndex  index 
) const

Definition at line 284 of file src/robots/robot-wrapper.cpp.

◆ frameClassicAcceleration() [1/2]

Motion tsid::robots::RobotWrapper::frameClassicAcceleration ( const Data data,
const Model::FrameIndex  index 
) const

Definition at line 295 of file src/robots/robot-wrapper.cpp.

◆ frameClassicAcceleration() [2/2]

void tsid::robots::RobotWrapper::frameClassicAcceleration ( const Data data,
const Model::FrameIndex  index,
Motion frameAcceleration 
) const

Definition at line 307 of file src/robots/robot-wrapper.cpp.

◆ frameClassicAccelerationWorldOriented()

Motion tsid::robots::RobotWrapper::frameClassicAccelerationWorldOriented ( const Data data,
const Model::FrameIndex  index 
) const

Definition at line 319 of file src/robots/robot-wrapper.cpp.

◆ frameJacobianLocal()

void tsid::robots::RobotWrapper::frameJacobianLocal ( Data data,
const Model::FrameIndex  index,
Data::Matrix6x J 
) const

Definition at line 338 of file src/robots/robot-wrapper.cpp.

◆ frameJacobianWorld()

void tsid::robots::RobotWrapper::frameJacobianWorld ( Data data,
const Model::FrameIndex  index,
Data::Matrix6x J 
) const

Definition at line 330 of file src/robots/robot-wrapper.cpp.

◆ framePosition() [1/2]

SE3 tsid::robots::RobotWrapper::framePosition ( const Data data,
const Model::FrameIndex  index 
) const

Definition at line 216 of file src/robots/robot-wrapper.cpp.

◆ framePosition() [2/2]

void tsid::robots::RobotWrapper::framePosition ( const Data data,
const Model::FrameIndex  index,
SE3 framePosition 
) const

Definition at line 225 of file src/robots/robot-wrapper.cpp.

◆ frameVelocity() [1/2]

Motion tsid::robots::RobotWrapper::frameVelocity ( const Data data,
const Model::FrameIndex  index 
) const

Definition at line 235 of file src/robots/robot-wrapper.cpp.

◆ frameVelocity() [2/2]

void tsid::robots::RobotWrapper::frameVelocity ( const Data data,
const Model::FrameIndex  index,
Motion frameVelocity 
) const

Definition at line 244 of file src/robots/robot-wrapper.cpp.

◆ frameVelocityWorldOriented()

Motion tsid::robots::RobotWrapper::frameVelocityWorldOriented ( const Data data,
const Model::FrameIndex  index 
) const

Definition at line 254 of file src/robots/robot-wrapper.cpp.

◆ gear_ratios() [1/2]

const Vector & tsid::robots::RobotWrapper::gear_ratios ( ) const

Definition at line 120 of file src/robots/robot-wrapper.cpp.

◆ gear_ratios() [2/2]

bool tsid::robots::RobotWrapper::gear_ratios ( ConstRefVector  gear_ratios)

Definition at line 131 of file src/robots/robot-wrapper.cpp.

◆ init()

void tsid::robots::RobotWrapper::init ( )
protected

Definition at line 89 of file src/robots/robot-wrapper.cpp.

◆ is_fixed_base()

bool tsid::robots::RobotWrapper::is_fixed_base ( ) const
virtual

Definition at line 100 of file src/robots/robot-wrapper.cpp.

◆ jacobianLocal()

void tsid::robots::RobotWrapper::jacobianLocal ( const Data data,
const Model::JointIndex  index,
Data::Matrix6x J 
) const

Definition at line 207 of file src/robots/robot-wrapper.cpp.

◆ jacobianWorld()

void tsid::robots::RobotWrapper::jacobianWorld ( const Data data,
const Model::JointIndex  index,
Data::Matrix6x J 
) const

Definition at line 198 of file src/robots/robot-wrapper.cpp.

◆ Jcom()

const Matrix3x & tsid::robots::RobotWrapper::Jcom ( const Data data) const

Definition at line 162 of file src/robots/robot-wrapper.cpp.

◆ mass()

const Matrix & tsid::robots::RobotWrapper::mass ( const Data data)

Definition at line 164 of file src/robots/robot-wrapper.cpp.

◆ model() [1/2]

Model& tsid::robots::RobotWrapper::model ( )

◆ model() [2/2]

Model & tsid::robots::RobotWrapper::model ( ) const

Accessor to model.

Returns
a const reference on the model.

Definition at line 102 of file src/robots/robot-wrapper.cpp.

◆ momentumJacobian()

const Data::Matrix6x & tsid::robots::RobotWrapper::momentumJacobian ( const Data data) const

Definition at line 346 of file src/robots/robot-wrapper.cpp.

◆ na()

int tsid::robots::RobotWrapper::na ( ) const
virtual

Definition at line 98 of file src/robots/robot-wrapper.cpp.

◆ nonLinearEffects()

const Vector & tsid::robots::RobotWrapper::nonLinearEffects ( const Data data) const

Definition at line 170 of file src/robots/robot-wrapper.cpp.

◆ nq()

int tsid::robots::RobotWrapper::nq ( ) const
virtual

Definition at line 96 of file src/robots/robot-wrapper.cpp.

◆ nq_actuated()

int tsid::robots::RobotWrapper::nq_actuated ( ) const
virtual

Definition at line 99 of file src/robots/robot-wrapper.cpp.

◆ nv()

int tsid::robots::RobotWrapper::nv ( ) const
virtual

Definition at line 97 of file src/robots/robot-wrapper.cpp.

◆ position()

const SE3 & tsid::robots::RobotWrapper::position ( const Data data,
const Model::JointIndex  index 
) const

Definition at line 174 of file src/robots/robot-wrapper.cpp.

◆ rotor_inertias() [1/2]

const Vector & tsid::robots::RobotWrapper::rotor_inertias ( ) const

Definition at line 119 of file src/robots/robot-wrapper.cpp.

◆ rotor_inertias() [2/2]

bool tsid::robots::RobotWrapper::rotor_inertias ( ConstRefVector  rotor_inertias)

Definition at line 122 of file src/robots/robot-wrapper.cpp.

◆ setGravity()

void tsid::robots::RobotWrapper::setGravity ( const Motion gravity)

Definition at line 356 of file src/robots/robot-wrapper.cpp.

◆ updateMd()

void tsid::robots::RobotWrapper::updateMd ( )
protected

Definition at line 140 of file src/robots/robot-wrapper.cpp.

◆ velocity()

const Motion & tsid::robots::RobotWrapper::velocity ( const Data data,
const Model::JointIndex  index 
) const

Definition at line 182 of file src/robots/robot-wrapper.cpp.

Member Data Documentation

◆ m_gear_ratios

Vector tsid::robots::RobotWrapper::m_gear_ratios
protected

Definition at line 185 of file robots/robot-wrapper.hpp.

◆ m_is_fixed_base

bool tsid::robots::RobotWrapper::m_is_fixed_base
protected

number of actuators (nv for fixed-based, nv-6 for floating-base robots)

Definition at line 183 of file robots/robot-wrapper.hpp.

◆ m_M

Matrix tsid::robots::RobotWrapper::m_M
protected

diagonal part of inertia matrix due to rotor inertias

Definition at line 187 of file robots/robot-wrapper.hpp.

◆ m_Md

Vector tsid::robots::RobotWrapper::m_Md
protected

Definition at line 186 of file robots/robot-wrapper.hpp.

◆ m_model

Model tsid::robots::RobotWrapper::m_model
protected

Robot model.

Definition at line 174 of file robots/robot-wrapper.hpp.

◆ m_model_filename

std::string tsid::robots::RobotWrapper::m_model_filename
protected

Definition at line 175 of file robots/robot-wrapper.hpp.

◆ m_na

int tsid::robots::RobotWrapper::m_na
protected

dimension of the configuration space of the actuated DoF (nq for fixed-based, nq-7 for floating-base robots)

Definition at line 181 of file robots/robot-wrapper.hpp.

◆ m_nq_actuated

int tsid::robots::RobotWrapper::m_nq_actuated
protected

Definition at line 178 of file robots/robot-wrapper.hpp.

◆ m_rotor_inertias

Vector tsid::robots::RobotWrapper::m_rotor_inertias
protected

Definition at line 184 of file robots/robot-wrapper.hpp.

◆ m_verbose

bool tsid::robots::RobotWrapper::m_verbose
protected

Definition at line 176 of file robots/robot-wrapper.hpp.

◆ Scalar

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Scalar tsid::robots::RobotWrapper::Scalar

Definition at line 41 of file robots/robot-wrapper.hpp.


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


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17