sot-core  4.11.8
Hierarchical task solver plug-in for dynamic-graph.
dynamicgraph::sot::SotJointTrajectoryEntity Class Reference

This object handles trajectory of quantities and publish them as signals. More...

#include <sot/core/joint-trajectory-entity.hh>

Inheritance diagram for dynamicgraph::sot::SotJointTrajectoryEntity:

Public Types

typedef int Dummy
 

Public Member Functions

 DYNAMIC_GRAPH_ENTITY_DECL ()
 
 SotJointTrajectoryEntity (const std::string &name)
 Constructor. More...
 
virtual ~SotJointTrajectoryEntity ()
 
void loadFile (const std::string &name)
 
dynamicgraph::Vector & getNextPosition (dynamicgraph::Vector &pos, const int &time)
 Return the next pose for the legs. More...
 
dynamicgraph::Vector & getNextCoM (dynamicgraph::Vector &com, const int &time)
 Return the next com. More...
 
dynamicgraph::Vector & getNextCoP (dynamicgraph::Vector &cop, const int &time)
 Return the next cop. More...
 
sot::MatrixHomogeneousgetNextWaist (sot::MatrixHomogeneous &waist, const int &time)
 Return the next waist. More...
 
unsigned int & getSeqId (unsigned int &seqid, const int &time)
 Return the current seq identified of the current trajectory. More...
 
sot::MatrixHomogeneous XYZThetaToMatrixHomogeneous (const dynamicgraph::Vector &xyztheta)
 Convert a xyztheta vector into an homogeneous matrix. More...
 
int & OneStepOfUpdate (int &dummy, const int &time)
 Perform one update of the signals. More...
 

Public Attributes

Signals

Internal signal for synchronisation.

dynamicgraph::SignalTimeDependent< int, int > refresherSINTERN
 
SignalTimeDependent< Dummy, int > OneStepOfUpdateS
 Internal signal to trigger one step of the algorithm. More...
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, int > positionSOUT
 Publish pose for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, int > comSOUT
 Publish com for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, int > zmpSOUT
 Publish zmp for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< sot::MatrixHomogeneous, int > waistSOUT
 Publish waist for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< unsigned int, int > seqIdSOUT
 Publish ID of the trajectory currently realized. More...
 
dynamicgraph::SignalPtr< Trajectory, int > trajectorySIN
 Read a trajectory. More...
 

Protected Member Functions

void UpdatePoint (const JointTrajectoryPoint &aJTP)
 Update the entity with the current point of the trajectory. More...
 
void UpdateTrajectory (const Trajectory &aTrajectory)
 Update the entity with the trajectory aTrajectory. More...
 
void setInitTraj (const std::string &os)
 Implements the parsing and the affectation of initial trajectory. More...
 

Protected Attributes

std::deque< sot::Trajectory >::size_type index_
 Index on the point along the trajectory. More...
 
timestamp traj_timestamp_
 Keep the starting time as an identifier of the trajector. More...
 
dynamicgraph::Vector pose_
 Store the pos;. More...
 
dynamicgraph::Vector com_
 Store the center of mass. More...
 
dynamicgraph::Vector cop_
 Store the center of pressure ZMP. More...
 
sot::MatrixHomogeneous waist_
 Store the waist position. More...
 
unsigned int seqid_
 Store the current seq identifier. More...
 
sot::Trajectory init_traj_
 Initial state of the trajectory. More...
 
std::deque< sot::Trajectorydeque_traj_
 Queue of trajectories. More...
 

Display

virtual void display (std::ostream &os) const
 
SOTJOINT_TRAJECTORY_ENTITY_EXPORT friend std::ostream & operator<< (std::ostream &os, const SotJointTrajectoryEntity &r)
 

Detailed Description

This object handles trajectory of quantities and publish them as signals.

Member Typedef Documentation

◆ Dummy

Constructor & Destructor Documentation

◆ SotJointTrajectoryEntity()

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

Constructor.

◆ ~SotJointTrajectoryEntity()

virtual dynamicgraph::sot::SotJointTrajectoryEntity::~SotJointTrajectoryEntity ( )
inlinevirtual

Member Function Documentation

◆ display()

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

◆ DYNAMIC_GRAPH_ENTITY_DECL()

dynamicgraph::sot::SotJointTrajectoryEntity::DYNAMIC_GRAPH_ENTITY_DECL ( )

◆ getNextCoM()

dynamicgraph::Vector& dynamicgraph::sot::SotJointTrajectoryEntity::getNextCoM ( dynamicgraph::Vector &  com,
const int &  time 
)

Return the next com.

◆ getNextCoP()

dynamicgraph::Vector& dynamicgraph::sot::SotJointTrajectoryEntity::getNextCoP ( dynamicgraph::Vector &  cop,
const int &  time 
)

Return the next cop.

◆ getNextPosition()

dynamicgraph::Vector& dynamicgraph::sot::SotJointTrajectoryEntity::getNextPosition ( dynamicgraph::Vector &  pos,
const int &  time 
)

Return the next pose for the legs.

◆ getNextWaist()

sot::MatrixHomogeneous& dynamicgraph::sot::SotJointTrajectoryEntity::getNextWaist ( sot::MatrixHomogeneous waist,
const int &  time 
)

Return the next waist.

◆ getSeqId()

unsigned int& dynamicgraph::sot::SotJointTrajectoryEntity::getSeqId ( unsigned int &  seqid,
const int &  time 
)

Return the current seq identified of the current trajectory.

◆ loadFile()

void dynamicgraph::sot::SotJointTrajectoryEntity::loadFile ( const std::string &  name)

◆ OneStepOfUpdate()

int& dynamicgraph::sot::SotJointTrajectoryEntity::OneStepOfUpdate ( int &  dummy,
const int &  time 
)

Perform one update of the signals.

◆ setInitTraj()

void dynamicgraph::sot::SotJointTrajectoryEntity::setInitTraj ( const std::string &  os)
protected

Implements the parsing and the affectation of initial trajectory.

◆ UpdatePoint()

void dynamicgraph::sot::SotJointTrajectoryEntity::UpdatePoint ( const JointTrajectoryPoint aJTP)
protected

Update the entity with the current point of the trajectory.

◆ UpdateTrajectory()

void dynamicgraph::sot::SotJointTrajectoryEntity::UpdateTrajectory ( const Trajectory aTrajectory)
protected

Update the entity with the trajectory aTrajectory.

◆ XYZThetaToMatrixHomogeneous()

sot::MatrixHomogeneous dynamicgraph::sot::SotJointTrajectoryEntity::XYZThetaToMatrixHomogeneous ( const dynamicgraph::Vector &  xyztheta)

Convert a xyztheta vector into an homogeneous matrix.

Friends And Related Function Documentation

◆ operator<<

SOTJOINT_TRAJECTORY_ENTITY_EXPORT friend std::ostream& operator<< ( std::ostream &  os,
const SotJointTrajectoryEntity r 
)
friend

Member Data Documentation

◆ com_

dynamicgraph::Vector dynamicgraph::sot::SotJointTrajectoryEntity::com_
protected

Store the center of mass.

◆ comSOUT

dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::SotJointTrajectoryEntity::comSOUT

Publish com for each evaluation of the graph.

◆ cop_

dynamicgraph::Vector dynamicgraph::sot::SotJointTrajectoryEntity::cop_
protected

Store the center of pressure ZMP.

◆ deque_traj_

std::deque<sot::Trajectory> dynamicgraph::sot::SotJointTrajectoryEntity::deque_traj_
protected

Queue of trajectories.

◆ index_

std::deque<sot::Trajectory>::size_type dynamicgraph::sot::SotJointTrajectoryEntity::index_
protected

Index on the point along the trajectory.

◆ init_traj_

sot::Trajectory dynamicgraph::sot::SotJointTrajectoryEntity::init_traj_
protected

Initial state of the trajectory.

◆ OneStepOfUpdateS

SignalTimeDependent<Dummy, int> dynamicgraph::sot::SotJointTrajectoryEntity::OneStepOfUpdateS

Internal signal to trigger one step of the algorithm.

◆ pose_

dynamicgraph::Vector dynamicgraph::sot::SotJointTrajectoryEntity::pose_
protected

Store the pos;.

◆ positionSOUT

dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::SotJointTrajectoryEntity::positionSOUT

Publish pose for each evaluation of the graph.

◆ refresherSINTERN

dynamicgraph::SignalTimeDependent<int, int> dynamicgraph::sot::SotJointTrajectoryEntity::refresherSINTERN

◆ seqid_

unsigned int dynamicgraph::sot::SotJointTrajectoryEntity::seqid_
protected

Store the current seq identifier.

◆ seqIdSOUT

dynamicgraph::SignalTimeDependent<unsigned int, int> dynamicgraph::sot::SotJointTrajectoryEntity::seqIdSOUT

Publish ID of the trajectory currently realized.

◆ traj_timestamp_

timestamp dynamicgraph::sot::SotJointTrajectoryEntity::traj_timestamp_
protected

Keep the starting time as an identifier of the trajector.

◆ trajectorySIN

dynamicgraph::SignalPtr<Trajectory, int> dynamicgraph::sot::SotJointTrajectoryEntity::trajectorySIN

Read a trajectory.

◆ waist_

sot::MatrixHomogeneous dynamicgraph::sot::SotJointTrajectoryEntity::waist_
protected

Store the waist position.

◆ waistSOUT

dynamicgraph::SignalTimeDependent<sot::MatrixHomogeneous, int> dynamicgraph::sot::SotJointTrajectoryEntity::waistSOUT

Publish waist for each evaluation of the graph.

◆ zmpSOUT

dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::SotJointTrajectoryEntity::zmpSOUT

Publish zmp for each evaluation of the graph.


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