dynamicgraph::sot::StepObserver Class Reference

#include <sot/pattern-generator/step-observer.h>

Inheritance diagram for dynamicgraph::sot::StepObserver:
Collaboration diagram for dynamicgraph::sot::StepObserver:

Public Member Functions

virtual const std::string & getClassName (void) const
 
 StepObserver (const std::string &name)
 
SignalArray< int > getSignals (void)
 
 operator SignalArray< int > ()
 
MatrixHomogeneous & computeReferencePositionLeft (MatrixHomogeneous &res, int timeCurr)
 
MatrixHomogeneous & computeReferencePositionRight (MatrixHomogeneous &res, int timeCurr)
 
MatrixHomogeneous & computeReferencePositionWaist (MatrixHomogeneous &res, int timeCurr)
 
virtual void display (std::ostream &os) const
 
virtual void commandLine (const std::string &cmdLine, std::istringstream &cmdArgs, std::ostream &os)
 

Public Attributes

SignalPtr< MatrixHomogeneous, int > leftHandPositionSIN
 
SignalPtr< MatrixHomogeneous, int > rightHandPositionSIN
 
SignalPtr< MatrixHomogeneous, int > leftFootPositionSIN
 
SignalPtr< MatrixHomogeneous, int > rightFootPositionSIN
 
SignalPtr< MatrixHomogeneous, int > waistPositionSIN
 
SignalTimeDependent< MatrixHomogeneous, int > referencePositionLeftSOUT
 Reference frame in left foot coordinates. More...
 
SignalTimeDependent< MatrixHomogeneous, int > referencePositionRightSOUT
 Reference frame in right foot coordinates. More...
 
SignalTimeDependent< MatrixHomogeneous, int > referencePositionWaistSOUT
 Reference frame in the waist coordinates. More...
 

Static Public Attributes

static const std::string CLASS_NAME
 

Detailed Description

Computes a reference frame from the position of both hands and feet of the robot. The coordinates of the reference frames are computed both in the left and right foot frames, and in the waist frame.

Constructor & Destructor Documentation

◆ StepObserver()

dynamicgraph::sot::StepObserver::StepObserver ( const std::string &  name)

Member Function Documentation

◆ commandLine()

virtual void dynamicgraph::sot::StepObserver::commandLine ( const std::string &  cmdLine,
std::istringstream &  cmdArgs,
std::ostream &  os 
)
virtual

◆ computeReferencePositionLeft()

MatrixHomogeneous& dynamicgraph::sot::StepObserver::computeReferencePositionLeft ( MatrixHomogeneous &  res,
int  timeCurr 
)

◆ computeReferencePositionRight()

MatrixHomogeneous& dynamicgraph::sot::StepObserver::computeReferencePositionRight ( MatrixHomogeneous &  res,
int  timeCurr 
)

◆ computeReferencePositionWaist()

MatrixHomogeneous& dynamicgraph::sot::StepObserver::computeReferencePositionWaist ( MatrixHomogeneous &  res,
int  timeCurr 
)

◆ display()

virtual void dynamicgraph::sot::StepObserver::display ( std::ostream &  os) const
virtual

◆ getClassName()

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

◆ getSignals()

SignalArray<int> dynamicgraph::sot::StepObserver::getSignals ( void  )

◆ operator SignalArray< int >()

dynamicgraph::sot::StepObserver::operator SignalArray< int > ( )

Member Data Documentation

◆ CLASS_NAME

const std::string dynamicgraph::sot::StepObserver::CLASS_NAME
static

◆ leftFootPositionSIN

SignalPtr<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::leftFootPositionSIN

◆ leftHandPositionSIN

SignalPtr<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::leftHandPositionSIN

◆ referencePositionLeftSOUT

SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::referencePositionLeftSOUT

Reference frame in left foot coordinates.

◆ referencePositionRightSOUT

SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::referencePositionRightSOUT

Reference frame in right foot coordinates.

◆ referencePositionWaistSOUT

SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::referencePositionWaistSOUT

Reference frame in the waist coordinates.

◆ rightFootPositionSIN

SignalPtr<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::rightFootPositionSIN

◆ rightHandPositionSIN

SignalPtr<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::rightHandPositionSIN

◆ waistPositionSIN

SignalPtr<MatrixHomogeneous, int> dynamicgraph::sot::StepObserver::waistPositionSIN

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