All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
SotLoader Class Reference

#include <dynamic_graph_bridge/sot_loader.hh>

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

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 ()
 
- Public Member Functions inherited from SotLoaderBasic
 SotLoaderBasic ()
 
 ~SotLoaderBasic ()
 
int parseOptions (int argc, char *argv[])
 
void Initialization ()
 Load the SoT device corresponding to the robot. More...
 
void CleanUp ()
 Unload the library which handles the robot device. More...
 
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 Member Functions

virtual void startControlLoop ()
 

Protected Attributes

std::map< std::string,
dgs::SensorValues
sensorsIn_
 Map of sensor readings. More...
 
std::map< std::string,
dgs::ControlValues
controlValues_
 Map of control values. More...
 
std::vector< double > angleEncoder_
 Angular values read by encoders. More...
 
std::vector< double > angleControl_
 Angular values sent to motors. More...
 
std::vector< double > forces_
 Forces read by force sensors. More...
 
std::vector< double > torques_
 Torques. More...
 
std::vector< double > baseAtt_
 Attitude of the robot computed by extended Kalman filter. More...
 
std::vector< double > accelerometer_
 Accelerations read by Accelerometers. More...
 
std::vector< double > gyrometer_
 Angular velocity read by gyrometers. More...
 
std::string robot_desc_string_
 URDF string description of the robot. More...
 
boost::thread thread_
 The thread running dynamic graph. More...
 
tf::TransformBroadcaster freeFlyerPublisher_
 
tf::Transform freeFlyerPose_
 
- Protected Attributes inherited from SotLoaderBasic
bool dynamic_graph_stopped_
 
dgs::AbstractSotExternalInterfacesotController_
 the sot-hrp2 controller More...
 
po::variables_map vm_
 
std::string dynamicLibraryName_
 
void * sotRobotControllerLibrary_
 Handle on the SoT library. More...
 
XmlRpc::XmlRpcValue stateVectorMap_
 Map between SoT state vector and some joint_state_links. More...
 
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. More...
 
ros::ServiceServer service_start_
 Advertises start_dynamic_graph services. More...
 
ros::ServiceServer service_stop_
 Advertises stop_dynamic_graph services. More...
 
ros::Publisher joint_pub_
 
sensor_msgs::JointState joint_state_
 
int nbOfJoints_
 
parallel_joints_to_state_vector_t::size_type nbOfParallelJoints_
 

Additional Inherited Members

- Protected Types inherited from SotLoaderBasic
typedef std::vector< int > parallel_joints_to_state_vector_t
 List of parallel joints from the state vector. More...
 

Constructor & Destructor Documentation

SotLoader::SotLoader ( )
SotLoader::~SotLoader ( )

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 ( )
protectedvirtual

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.

boost::thread SotLoader::thread_
protected

The thread running dynamic graph.

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

Torques.