SotLoader Class Reference

#include <dynamic_graph_bridge/sot_loader.hh>

Inheritance diagram for SotLoader:
[legend]
Collaboration diagram for SotLoader:
[legend]

List of all members.

Public Member Functions

 SotLoader ()
 ~SotLoader ()
void initializeRosNode (int argc, char *argv[])
void oneIteration ()
void fillSensors (std::map< std::string, dgs::SensorValues > &sensorsIn)
void readControl (std::map< std::string, dgs::ControlValues > &controlValues)
void setup ()

Protected Member Functions

virtual void startControlLoop ()

Protected Attributes

std::map< std::string,
dgs::SensorValues > 
sensorsIn_
 Map of sensor readings.
std::map< std::string,
dgs::ControlValues > 
controlValues_
 Map of control values.
std::vector< double > angleEncoder_
 Angular values read by encoders.
std::vector< double > angleControl_
 Angular values sent to motors.
std::vector< double > forces_
 Forces read by force sensors.
std::vector< double > torques_
 Torques.
std::vector< double > baseAtt_
 Attitude of the robot computed by extended Kalman filter.
std::vector< double > accelerometer_
 Accelerations read by Accelerometers.
std::vector< double > gyrometer_
 Angular velocity read by gyrometers.
std::string robot_desc_string_
 URDF string description of the robot.
tf::TransformBroadcaster freeFlyerPublisher_
tf::Transform freeFlyerPose_

Constructor & Destructor Documentation

SotLoader::SotLoader ( )
SotLoader::~SotLoader ( ) [inline]

Member Function Documentation

void SotLoader::fillSensors ( std::map< std::string, dgs::SensorValues > &  sensorsIn)
void SotLoader::initializeRosNode ( int  argc,
char *  argv[] 
) [virtual]

Reimplemented from SotLoaderBasic.

void SotLoader::oneIteration ( )
void SotLoader::readControl ( std::map< std::string, dgs::ControlValues > &  controlValues)
void SotLoader::setup ( )
virtual void SotLoader::startControlLoop ( ) [protected, virtual]

Member Data Documentation

std::vector<double> SotLoader::accelerometer_ [protected]

Accelerations read by Accelerometers.

std::vector<double> SotLoader::angleControl_ [protected]

Angular values sent to motors.

std::vector<double> SotLoader::angleEncoder_ [protected]

Angular values read by encoders.

std::vector<double> SotLoader::baseAtt_ [protected]

Attitude of the robot computed by extended Kalman filter.

std::map<std::string,dgs::ControlValues> SotLoader::controlValues_ [protected]

Map of control values.

std::vector<double> SotLoader::forces_ [protected]

Forces read by force sensors.

tf::Transform SotLoader::freeFlyerPose_ [protected]
tf::TransformBroadcaster SotLoader::freeFlyerPublisher_ [protected]
std::vector<double> SotLoader::gyrometer_ [protected]

Angular velocity read by gyrometers.

std::string SotLoader::robot_desc_string_ [protected]

URDF string description of the robot.

std::map<std::string,dgs::SensorValues> SotLoader::sensorsIn_ [protected]

Map of sensor readings.

std::vector<double> SotLoader::torques_ [protected]

Torques.