SotLoader Class Reference

#include <dynamic_graph_bridge/sot_loader.hh>

Collaboration diagram for SotLoader:
[legend]

List of all members.

Public Member Functions

 SotLoader ()
 ~SotLoader ()
int parseOptions (int argc, char *argv[])
void Initialization ()
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 ()
bool start_dg (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool stop_dg (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
int readSotVectorStateParam ()
int initPublication ()
bool isDynamicGraphStopped ()
void setDynamicLibraryName (std::string &afilename)

Protected Types

typedef std::vector< int > parallel_joints_to_state_vector_t
 List of parallel joints from the state vector.

Protected Member Functions

virtual void startControlLoop ()

Protected Attributes

bool dynamic_graph_stopped_
dgs::AbstractSotExternalInterface * sotController_
 the sot-hrp2 controller
po::variables_map vm_
std::string dynamicLibraryName_
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.
XmlRpc::XmlRpcValue stateVectorMap_
 Map between SoT state vector and some joint_state_links.
parallel_joints_to_state_vector_t parallel_joints_to_state_vector_
std::vector< double > coefficient_parallel_joints_
 Coefficient between parallel joints and the state vector.
ros::Publisher joint_pub_
sensor_msgs::JointState joint_state_
int nbOfJoints_
parallel_joints_to_state_vector_t::size_type nbOfParallelJoints_
tf::TransformBroadcaster freeFlyerPublisher_
tf::Transform freeFlyerPose_

Member Typedef Documentation

typedef std::vector<int> SotLoader::parallel_joints_to_state_vector_t [protected]

List of parallel joints from the state vector.


Constructor & Destructor Documentation

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

Member Function Documentation

void SotLoader::fillSensors ( std::map< std::string, dgs::SensorValues > &  sensorsIn)
void SotLoader::Initialization ( )
void SotLoader::initializeRosNode ( int  argc,
char *  argv[] 
)
int SotLoader::initPublication ( )
bool SotLoader::isDynamicGraphStopped ( ) [inline]
void SotLoader::oneIteration ( )
int SotLoader::parseOptions ( int  argc,
char *  argv[] 
)
void SotLoader::readControl ( std::map< std::string, dgs::ControlValues > &  controlValues)
int SotLoader::readSotVectorStateParam ( )
void SotLoader::setDynamicLibraryName ( std::string &  afilename)
void SotLoader::setup ( )
bool SotLoader::start_dg ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
virtual void SotLoader::startControlLoop ( ) [protected, virtual]
bool SotLoader::stop_dg ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

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::vector<double> SotLoader::coefficient_parallel_joints_ [protected]

Coefficient between parallel joints and the state vector.

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

Map of control values.

std::string SotLoader::dynamicLibraryName_ [protected]
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.

ros::Publisher SotLoader::joint_pub_ [protected]
sensor_msgs::JointState SotLoader::joint_state_ [protected]
int SotLoader::nbOfJoints_ [protected]
parallel_joints_to_state_vector_t::size_type SotLoader::nbOfParallelJoints_ [protected]
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.

dgs::AbstractSotExternalInterface* SotLoader::sotController_ [protected]

the sot-hrp2 controller

XmlRpc::XmlRpcValue SotLoader::stateVectorMap_ [protected]

Map between SoT state vector and some joint_state_links.

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

Torques.

po::variables_map SotLoader::vm_ [protected]