Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Protected Attributes | Private Attributes | Friends | List of all members
dynamicgraph::sot::Device Class Reference

#include <device.hh>

Inheritance diagram for dynamicgraph::sot::Device:
Inheritance graph
[legend]

Public Types

enum  ForceSignalSource { FORCE_SIGNAL_RLEG, FORCE_SIGNAL_LLEG, FORCE_SIGNAL_RARM, FORCE_SIGNAL_LARM }
 
- Public Types inherited from dynamicgraph::Entity
typedef std::map< const std::string, command::Command * > CommandMap_t
 
typedef std::map< std::string, SignalBase< sigtime_t > * > SignalMap
 

Public Member Functions

virtual void cmdDisplay ()
 
 Device (const std::string &name)
 
virtual void display (std::ostream &os) const
 
virtual const std::string & getClassName (void) const
 
void getControl (std::map< std::string, ControlValues > &anglesOut, const double &period)
 
size_type getControlSize () const
 
virtual void setControlInputType (const std::string &cit)
 
void setControlSize (const size_type &size)
 
virtual void setNoIntegration ()
 
virtual void setRoot (const dynamicgraph::Matrix &root)
 
virtual void setRoot (const MatrixHomogeneous &worldMwaist)
 
virtual void setSecondOrderIntegration ()
 
virtual void setState (const dynamicgraph::Vector &st)
 
virtual void setStateSize (const size_type &size)
 
virtual void setVelocity (const dynamicgraph::Vector &vel)
 
void setVelocitySize (const size_type &size)
 
virtual ~Device ()
 
Sanity check parameterization
void setSanityCheck (const bool &enableCheck)
 
void setPositionBounds (const Vector &lower, const Vector &upper)
 
void setVelocityBounds (const Vector &lower, const Vector &upper)
 
void setTorqueBounds (const Vector &lower, const Vector &upper)
 
- Public Member Functions inherited from dynamicgraph::Entity
std::ostream & displaySignalList (std::ostream &os) const
 
 Entity (const std::string &name)
 
const std::string & getCommandList () const
 
virtual std::string getDocString () const
 
LoggerVerbosity getLoggerVerbosityLevel ()
 
LoggerVerbosity getLoggerVerbosityLevel ()
 
const std::string & getName () const
 
command::CommandgetNewStyleCommand (const std::string &cmdName)
 
CommandMap_t getNewStyleCommandMap ()
 
SignalBase< sigtime_t > & getSignal (const std::string &signalName)
 
const SignalBase< sigtime_t > & getSignal (const std::string &signalName) const
 
SignalMap getSignalMap () const
 
double getStreamPrintPeriod ()
 
double getStreamPrintPeriod ()
 
double getTimeSample ()
 
double getTimeSample ()
 
bool hasSignal (const std::string &signame) const
 
Loggerlogger ()
 
Loggerlogger ()
 
const Loggerlogger () const
 
const Loggerlogger () const
 
void sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const std::string &lineId="")
 
void sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const std::string &lineId="")
 
void setLoggerVerbosityLevel (LoggerVerbosity lv)
 
void setLoggerVerbosityLevel (LoggerVerbosity lv)
 
bool setStreamPrintPeriod (double t)
 
bool setStreamPrintPeriod (double t)
 
bool setTimeSample (double t)
 
bool setTimeSample (double t)
 
virtual SignalBase< sigtime_t > * test ()
 
virtual void test2 (SignalBase< sigtime_t > *)
 
virtual std::ostream & writeCompletionList (std::ostream &os) const
 
virtual std::ostream & writeGraph (std::ostream &os) const
 
virtual ~Entity ()
 

Public Attributes

dynamicgraph::SignalPtr< dynamicgraph::Vector, sigtime_tattitudeSIN
 
dynamicgraph::SignalPtr< dynamicgraph::Vector, sigtime_tcontrolSIN
 
dynamicgraph::SignalPtr< dynamicgraph::Vector, sigtime_tzmpSIN
 
Device current state.
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_tstateSOUT
 
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_tvelocitySOUT
 
dynamicgraph::Signal< MatrixRotation, sigtime_tattitudeSOUT
 
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_tmotorcontrolSOUT
 The current state of the robot from the command viewpoint. More...
 
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_tpreviousControlSOUT
 
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_tZMPPreviousControllerSOUT
 The ZMP reference send by the previous controller. More...
 
Real robot current state

This corresponds to the real encoders values and take into account the stabilization step. Therefore, this usually does not match the state control input signal.

Motor positions

dynamicgraph::Signal< dynamicgraph::Vector, sigtime_trobotState_
 
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_trobotVelocity_
 Motor velocities. More...
 
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_t > * forcesSOUT [4]
 The force torque sensors. More...
 
dynamicgraph::Signal< dynamicgraph::Vector, sigtime_tpseudoTorqueSOUT
 

Static Public Attributes

static const std::string CLASS_NAME = "Device"
 

Protected Attributes

ControlInput controlInputType_
 
bool sanityCheck_
 
dynamicgraph::Vector state_
 
double timestep_
 
dynamicgraph::Vector vel_control_
 
dynamicgraph::Vector velocity_
 
bool withForceSignals [4]
 
Robot bounds used for sanity checks
Vector upperPosition_
 
Vector upperVelocity_
 
Vector upperTorque_
 
Vector lowerPosition_
 
Vector lowerVelocity_
 
Vector lowerTorque_
 
- Protected Attributes inherited from dynamicgraph::Entity
CommandMap_t commandMap
 
Logger logger_
 
std::string name
 
SignalMap signalMap
 

Private Attributes

size_type controlSize_
 
dynamicgraph::Vector forceZero6
 
sigtime_t lastTimeControlWasRead_
 

Friends

SOT_CORE_EXPORT friend std::ostream & operator<< (std::ostream &os, const Device &r)
 

Additional Inherited Members

- Protected Member Functions inherited from dynamicgraph::Entity
void addCommand (const std::string &name, command::Command *command)
 
void entityDeregistration ()
 
void entityRegistration ()
 
void signalDeregistration (const std::string &name)
 
void signalRegistration (const SignalArray< sigtime_t > &signals)
 

Detailed Description

Definition at line 47 of file device.hh.

Member Enumeration Documentation

◆ ForceSignalSource

Enumerator
FORCE_SIGNAL_RLEG 
FORCE_SIGNAL_LLEG 
FORCE_SIGNAL_RARM 
FORCE_SIGNAL_LARM 

Definition at line 52 of file device.hh.

Constructor & Destructor Documentation

◆ Device()

Device::Device ( const std::string &  name)

Definition at line 78 of file device.cpp.

◆ ~Device()

Device::~Device ( )
virtual

Definition at line 72 of file device.cpp.

Member Function Documentation

◆ cmdDisplay()

void Device::cmdDisplay ( )
virtual

Definition at line 354 of file device.cpp.

◆ display()

void Device::display ( std::ostream &  os) const
virtual

Reimplemented from dynamicgraph::Entity.

Definition at line 348 of file device.cpp.

◆ getClassName()

virtual const std::string& dynamicgraph::sot::Device::getClassName ( void  ) const
inlinevirtual

Reimplemented from dynamicgraph::Entity.

Reimplemented in dynamicgraph::sot::RobotSimu.

Definition at line 50 of file device.hh.

◆ getControl()

void Device::getControl ( std::map< std::string, ControlValues > &  anglesOut,
const double period 
)

Definition at line 226 of file device.cpp.

◆ getControlSize()

size_type Device::getControlSize ( ) const

Definition at line 261 of file device.cpp.

◆ setControlInputType()

void Device::setControlInputType ( const std::string &  cit)
virtual

Definition at line 293 of file device.cpp.

◆ setControlSize()

void Device::setControlSize ( const size_type size)

Definition at line 259 of file device.cpp.

◆ setNoIntegration()

void Device::setNoIntegration ( )
virtual

Definition at line 291 of file device.cpp.

◆ setPositionBounds()

void Device::setPositionBounds ( const Vector lower,
const Vector upper 
)

Definition at line 297 of file device.cpp.

◆ setRoot() [1/2]

void Device::setRoot ( const dynamicgraph::Matrix root)
virtual

Definition at line 276 of file device.cpp.

◆ setRoot() [2/2]

void Device::setRoot ( const MatrixHomogeneous worldMwaist)
virtual

Definition at line 282 of file device.cpp.

◆ setSanityCheck()

void Device::setSanityCheck ( const bool &  enableCheck)

Definition at line 295 of file device.cpp.

◆ setSecondOrderIntegration()

void Device::setSecondOrderIntegration ( )
virtual

Definition at line 289 of file device.cpp.

◆ setState()

void Device::setState ( const dynamicgraph::Vector st)
virtual

Definition at line 269 of file device.cpp.

◆ setStateSize()

void Device::setStateSize ( const size_type size)
virtual

Definition at line 244 of file device.cpp.

◆ setTorqueBounds()

void Device::setTorqueBounds ( const Vector lower,
const Vector upper 
)

Definition at line 329 of file device.cpp.

◆ setVelocity()

void Device::setVelocity ( const dynamicgraph::Vector vel)
virtual

Definition at line 271 of file device.cpp.

◆ setVelocityBounds()

void Device::setVelocityBounds ( const Vector lower,
const Vector upper 
)

Definition at line 313 of file device.cpp.

◆ setVelocitySize()

void Device::setVelocitySize ( const size_type size)

Definition at line 263 of file device.cpp.

Friends And Related Function Documentation

◆ operator<<

SOT_CORE_EXPORT friend std::ostream& operator<< ( std::ostream &  os,
const Device r 
)
friend

Definition at line 108 of file device.hh.

Member Data Documentation

◆ attitudeSIN

dynamicgraph::SignalPtr<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::attitudeSIN

Definition at line 116 of file device.hh.

◆ attitudeSOUT

dynamicgraph::Signal<MatrixRotation, sigtime_t> dynamicgraph::sot::Device::attitudeSOUT

Definition at line 123 of file device.hh.

◆ CLASS_NAME

const std::string Device::CLASS_NAME = "Device"
static

Definition at line 49 of file device.hh.

◆ controlInputType_

ControlInput dynamicgraph::sot::Device::controlInputType_
protected

Definition at line 64 of file device.hh.

◆ controlSIN

dynamicgraph::SignalPtr<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::controlSIN

Definition at line 115 of file device.hh.

◆ controlSize_

size_type dynamicgraph::sot::Device::controlSize_
private

Definition at line 155 of file device.hh.

◆ forcesSOUT

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t>* dynamicgraph::sot::Device::forcesSOUT[4]

The force torque sensors.

Definition at line 142 of file device.hh.

◆ forceZero6

dynamicgraph::Vector dynamicgraph::sot::Device::forceZero6
private

Definition at line 157 of file device.hh.

◆ lastTimeControlWasRead_

sigtime_t dynamicgraph::sot::Device::lastTimeControlWasRead_
private

Definition at line 154 of file device.hh.

◆ lowerPosition_

Vector dynamicgraph::sot::Device::lowerPosition_
protected

Definition at line 73 of file device.hh.

◆ lowerTorque_

Vector dynamicgraph::sot::Device::lowerTorque_
protected

Definition at line 75 of file device.hh.

◆ lowerVelocity_

Vector dynamicgraph::sot::Device::lowerVelocity_
protected

Definition at line 74 of file device.hh.

◆ motorcontrolSOUT

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::motorcontrolSOUT

The current state of the robot from the command viewpoint.

Definition at line 125 of file device.hh.

◆ previousControlSOUT

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::previousControlSOUT

Definition at line 126 of file device.hh.

◆ pseudoTorqueSOUT

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::pseudoTorqueSOUT

Motor torques

Todo:
why pseudo ?

Definition at line 145 of file device.hh.

◆ robotState_

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::robotState_

Definition at line 138 of file device.hh.

◆ robotVelocity_

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::robotVelocity_

Motor velocities.

Definition at line 140 of file device.hh.

◆ sanityCheck_

bool dynamicgraph::sot::Device::sanityCheck_
protected

Definition at line 62 of file device.hh.

◆ state_

dynamicgraph::Vector dynamicgraph::sot::Device::state_
protected

Definition at line 60 of file device.hh.

◆ stateSOUT

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::stateSOUT

Definition at line 121 of file device.hh.

◆ timestep_

double dynamicgraph::sot::Device::timestep_
protected

Definition at line 66 of file device.hh.

◆ upperPosition_

Vector dynamicgraph::sot::Device::upperPosition_
protected

Definition at line 70 of file device.hh.

◆ upperTorque_

Vector dynamicgraph::sot::Device::upperTorque_
protected

Definition at line 72 of file device.hh.

◆ upperVelocity_

Vector dynamicgraph::sot::Device::upperVelocity_
protected

Definition at line 71 of file device.hh.

◆ vel_control_

dynamicgraph::Vector dynamicgraph::sot::Device::vel_control_
protected

Definition at line 63 of file device.hh.

◆ velocity_

dynamicgraph::Vector dynamicgraph::sot::Device::velocity_
protected

Definition at line 61 of file device.hh.

◆ velocitySOUT

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::velocitySOUT

Definition at line 122 of file device.hh.

◆ withForceSignals

bool dynamicgraph::sot::Device::withForceSignals[4]
protected

Definition at line 65 of file device.hh.

◆ ZMPPreviousControllerSOUT

dynamicgraph::Signal<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::ZMPPreviousControllerSOUT

The ZMP reference send by the previous controller.

Definition at line 129 of file device.hh.

◆ zmpSIN

dynamicgraph::SignalPtr<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::Device::zmpSIN

Definition at line 117 of file device.hh.


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


sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Tue Oct 24 2023 02:26:32