sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
SimpleStateIntegrator Class Reference

#include <sot/talos_balance/simple-state-integrator.hh>

Inheritance diagram for SimpleStateIntegrator:
Collaboration diagram for SimpleStateIntegrator:

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW SimpleStateIntegrator (const std::string &name)
 
 DECLARE_SIGNAL_IN (control, ::dynamicgraph::Vector)
 
 DECLARE_SIGNAL_OUT (state, ::dynamicgraph::Vector)
 
 DECLARE_SIGNAL_OUT (velocity, ::dynamicgraph::Vector)
 
virtual void display (std::ostream &os) const
 
void init (const double &step)
 
void setState (const ::dynamicgraph::Vector &st)
 
void setVelocity (const ::dynamicgraph::Vector &vel)
 

Protected Member Functions

void integrateRollPitchYaw (::dynamicgraph::Vector &state, const ::dynamicgraph::Vector &control, double dt)
 
void rotationMatrixToEuler (const Eigen::Matrix3d &rotationMatrix, Eigen::Vector3d &rollPitchYaw)
 

Protected Attributes

double timestep_
 Current integration step. More...
 
Vectors related to the state.

Position of the robot wrt pinocchio.

Eigen::VectorXd state_
 
Eigen::VectorXd velocity_
 Velocity of the robot wrt pinocchio. More...
 

Detailed Description

Definition at line 54 of file simple-state-integrator.hh.

Constructor & Destructor Documentation

◆ SimpleStateIntegrator()

SimpleStateIntegrator ( const std::string &  name)

Definition at line 56 of file simple-state-integrator.cpp.

Member Function Documentation

◆ DECLARE_SIGNAL_IN()

DECLARE_SIGNAL_IN ( control  ,
::dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_OUT() [1/2]

DECLARE_SIGNAL_OUT ( state  ,
::dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_OUT() [2/2]

DECLARE_SIGNAL_OUT ( velocity  ,
::dynamicgraph::Vector   
)

◆ display()

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

Definition at line 182 of file simple-state-integrator.cpp.

◆ init()

void init ( const double &  step)

Definition at line 91 of file simple-state-integrator.cpp.

◆ integrateRollPitchYaw()

void integrateRollPitchYaw ( ::dynamicgraph::Vector &  state,
const ::dynamicgraph::Vector &  control,
double  dt 
)
protected

Integrate the freeflyer state (to obtain position). Compute roll pitch yaw angles

Definition at line 103 of file simple-state-integrator.cpp.

◆ rotationMatrixToEuler()

void rotationMatrixToEuler ( const Eigen::Matrix3d &  rotationMatrix,
Eigen::Vector3d &  rollPitchYaw 
)
protected

Definition at line 132 of file simple-state-integrator.cpp.

◆ setState()

void setState ( const ::dynamicgraph::Vector &  st)

Definition at line 93 of file simple-state-integrator.cpp.

◆ setVelocity()

void setVelocity ( const ::dynamicgraph::Vector &  vel)

Definition at line 95 of file simple-state-integrator.cpp.

Member Data Documentation

◆ state_

Eigen::VectorXd state_
protected

Definition at line 65 of file simple-state-integrator.hh.

◆ timestep_

double timestep_
protected

Current integration step.

Definition at line 60 of file simple-state-integrator.hh.

◆ velocity_

Eigen::VectorXd velocity_
protected

Velocity of the robot wrt pinocchio.

Definition at line 67 of file simple-state-integrator.hh.


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