Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dynamicgraph::sot::SotJointTrajectoryEntity Class Reference

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

#include <joint-trajectory-entity.hh>

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

Public Types

typedef size_type Dummy
 
- 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

 DYNAMIC_GRAPH_ENTITY_DECL ()
 
dynamicgraph::VectorgetNextCoM (dynamicgraph::Vector &com, const sigtime_t &time)
 Return the next com. More...
 
dynamicgraph::VectorgetNextCoP (dynamicgraph::Vector &cop, const sigtime_t &time)
 Return the next cop. More...
 
dynamicgraph::VectorgetNextPosition (dynamicgraph::Vector &pos, const sigtime_t &time)
 Return the next pose for the legs. More...
 
sot::MatrixHomogeneousgetNextWaist (sot::MatrixHomogeneous &waist, const sigtime_t &time)
 Return the next waist. More...
 
std::size_t & getSeqId (std::size_t &seqid, const sigtime_t &time)
 Return the current seq identified of the current trajectory. More...
 
void loadFile (const std::string &name)
 
size_typeOneStepOfUpdate (size_type &dummy, const sigtime_t &time)
 Perform one update of the signals. More...
 
 SotJointTrajectoryEntity (const std::string &name)
 Constructor. More...
 
sot::MatrixHomogeneous XYZThetaToMatrixHomogeneous (const dynamicgraph::Vector &xyztheta)
 Convert a xyztheta vector into an homogeneous matrix. More...
 
virtual ~SotJointTrajectoryEntity ()
 
- Public Member Functions inherited from dynamicgraph::Entity
std::ostream & displaySignalList (std::ostream &os) const
 
 Entity (const std::string &name)
 
virtual const std::string & getClassName () const
 
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

Signals

Internal signal for synchronisation.

dynamicgraph::SignalTimeDependent< size_type, sigtime_trefresherSINTERN
 
SignalTimeDependent< Dummy, sigtime_tOneStepOfUpdateS
 Internal signal to trigger one step of the algorithm. More...
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, sigtime_tpositionSOUT
 Publish pose for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, sigtime_tcomSOUT
 Publish com for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, sigtime_tzmpSOUT
 Publish zmp for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< sot::MatrixHomogeneous, sigtime_twaistSOUT
 Publish waist for each evaluation of the graph. More...
 
dynamicgraph::SignalTimeDependent< std::size_t, sigtime_tseqIdSOUT
 Publish ID of the trajectory currently realized. More...
 
dynamicgraph::SignalPtr< Trajectory, sigtime_ttrajectorySIN
 Read a trajectory. More...
 

Protected Member Functions

void setInitTraj (const std::string &os)
 Implements the parsing and the affectation of initial trajectory. More...
 
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...
 
- 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)
 

Protected Attributes

dynamicgraph::Vector com_
 Store the center of mass. More...
 
dynamicgraph::Vector cop_
 Store the center of pressure ZMP. More...
 
std::deque< sot::Trajectorydeque_traj_
 Queue of trajectories. More...
 
std::deque< sot::Trajectory >::size_type index_
 Index on the point along the trajectory. More...
 
sot::Trajectory init_traj_
 Initial state of the trajectory. More...
 
dynamicgraph::Vector pose_
 Store the pos;. More...
 
std::size_t seqid_
 Store the current seq identifier. More...
 
timestamp traj_timestamp_
 Keep the starting time as an identifier of the trajector. More...
 
sot::MatrixHomogeneous waist_
 Store the waist position. More...
 
- Protected Attributes inherited from dynamicgraph::Entity
CommandMap_t commandMap
 
Logger logger_
 
std::string name
 
SignalMap signalMap
 

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.

Definition at line 47 of file joint-trajectory-entity.hh.

Member Typedef Documentation

◆ Dummy

Definition at line 96 of file joint-trajectory-entity.hh.

Constructor & Destructor Documentation

◆ SotJointTrajectoryEntity()

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

Constructor.

Definition at line 36 of file joint-trajectory-entity.cpp.

◆ ~SotJointTrajectoryEntity()

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

Definition at line 54 of file joint-trajectory-entity.hh.

Member Function Documentation

◆ display()

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

Reimplemented from dynamicgraph::Entity.

Definition at line 295 of file joint-trajectory-entity.cpp.

◆ DYNAMIC_GRAPH_ENTITY_DECL()

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

◆ getNextCoM()

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

Return the next com.

Definition at line 253 of file joint-trajectory-entity.cpp.

◆ getNextCoP()

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

Return the next cop.

Definition at line 262 of file joint-trajectory-entity.cpp.

◆ getNextPosition()

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

Return the next pose for the legs.

Definition at line 243 of file joint-trajectory-entity.cpp.

◆ getNextWaist()

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

Return the next waist.

Definition at line 271 of file joint-trajectory-entity.cpp.

◆ getSeqId()

std::size_t & SotJointTrajectoryEntity::getSeqId ( std::size_t &  seqid,
const sigtime_t time 
)

Return the current seq identified of the current trajectory.

Definition at line 280 of file joint-trajectory-entity.cpp.

◆ loadFile()

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

Definition at line 289 of file joint-trajectory-entity.cpp.

◆ OneStepOfUpdate()

size_type & SotJointTrajectoryEntity::OneStepOfUpdate ( size_type dummy,
const sigtime_t time 
)

Perform one update of the signals.

Definition at line 206 of file joint-trajectory-entity.cpp.

◆ setInitTraj()

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

Implements the parsing and the affectation of initial trajectory.

Definition at line 301 of file joint-trajectory-entity.cpp.

◆ UpdatePoint()

void SotJointTrajectoryEntity::UpdatePoint ( const JointTrajectoryPoint aJTP)
protected

Update the entity with the current point of the trajectory.

Definition at line 90 of file joint-trajectory-entity.cpp.

◆ UpdateTrajectory()

void SotJointTrajectoryEntity::UpdateTrajectory ( const Trajectory aTrajectory)
protected

Update the entity with the trajectory aTrajectory.

Definition at line 132 of file joint-trajectory-entity.cpp.

◆ XYZThetaToMatrixHomogeneous()

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

Convert a xyztheta vector into an homogeneous matrix.

Definition at line 228 of file joint-trajectory-entity.cpp.

Friends And Related Function Documentation

◆ operator<<

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

Definition at line 88 of file joint-trajectory-entity.hh.

Member Data Documentation

◆ com_

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

Store the center of mass.

Definition at line 138 of file joint-trajectory-entity.hh.

◆ comSOUT

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

Publish com for each evaluation of the graph.

Definition at line 111 of file joint-trajectory-entity.hh.

◆ cop_

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

Store the center of pressure ZMP.

Definition at line 141 of file joint-trajectory-entity.hh.

◆ deque_traj_

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

Queue of trajectories.

Definition at line 153 of file joint-trajectory-entity.hh.

◆ index_

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

Index on the point along the trajectory.

Definition at line 129 of file joint-trajectory-entity.hh.

◆ init_traj_

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

Initial state of the trajectory.

Definition at line 150 of file joint-trajectory-entity.hh.

◆ OneStepOfUpdateS

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

Internal signal to trigger one step of the algorithm.

Definition at line 104 of file joint-trajectory-entity.hh.

◆ pose_

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

Store the pos;.

Definition at line 135 of file joint-trajectory-entity.hh.

◆ positionSOUT

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

Publish pose for each evaluation of the graph.

Definition at line 108 of file joint-trajectory-entity.hh.

◆ refresherSINTERN

dynamicgraph::SignalTimeDependent<size_type, sigtime_t> dynamicgraph::sot::SotJointTrajectoryEntity::refresherSINTERN

Definition at line 101 of file joint-trajectory-entity.hh.

◆ seqid_

std::size_t dynamicgraph::sot::SotJointTrajectoryEntity::seqid_
protected

Store the current seq identifier.

Definition at line 147 of file joint-trajectory-entity.hh.

◆ seqIdSOUT

dynamicgraph::SignalTimeDependent<std::size_t, sigtime_t> dynamicgraph::sot::SotJointTrajectoryEntity::seqIdSOUT

Publish ID of the trajectory currently realized.

Definition at line 121 of file joint-trajectory-entity.hh.

◆ traj_timestamp_

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

Keep the starting time as an identifier of the trajector.

Definition at line 132 of file joint-trajectory-entity.hh.

◆ trajectorySIN

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

Read a trajectory.

Definition at line 124 of file joint-trajectory-entity.hh.

◆ waist_

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

Store the waist position.

Definition at line 144 of file joint-trajectory-entity.hh.

◆ waistSOUT

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

Publish waist for each evaluation of the graph.

Definition at line 118 of file joint-trajectory-entity.hh.

◆ zmpSOUT

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

Publish zmp for each evaluation of the graph.

Definition at line 114 of file joint-trajectory-entity.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