#include <dynamic_graph_bridge/sot_loader.hh>


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. | |
| void | CleanUp () |
| Unload the library which handles the robot device. | |
| 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. | |
| 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. | |
| boost::thread | thread_ |
| The thread running dynamic graph. | |
| tf2_ros::TransformBroadcaster | freeFlyerPublisher_ |
| geometry_msgs::TransformStamped | freeFlyerPose_ |
Protected Attributes inherited from SotLoaderBasic | |
| bool | dynamic_graph_stopped_ |
| dgs::AbstractSotExternalInterface * | sotController_ |
| the sot-hrp2 controller | |
| po::variables_map | vm_ |
| std::string | dynamicLibraryName_ |
| void * | sotRobotControllerLibrary_ |
| Handle on the SoT library. | |
| 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::ServiceServer | service_start_ |
| Advertises start_dynamic_graph services. | |
| ros::ServiceServer | service_stop_ |
| Advertises stop_dynamic_graph services. | |
| 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. | |
| SotLoader::SotLoader | ( | ) |
| SotLoader::~SotLoader | ( | ) |
| void SotLoader::fillSensors | ( | std::map< std::string, dgs::SensorValues > & | sensorsIn | ) |
|
virtual |
Reimplemented from SotLoaderBasic.
| void SotLoader::oneIteration | ( | ) |
| void SotLoader::readControl | ( | std::map< std::string, dgs::ControlValues > & | controlValues | ) |
| void SotLoader::setup | ( | ) |
|
protectedvirtual |
|
protected |
Accelerations read by Accelerometers.
|
protected |
Angular values sent to motors.
|
protected |
Angular values read by encoders.
|
protected |
Attitude of the robot computed by extended Kalman filter.
|
protected |
Map of control values.
|
protected |
Forces read by force sensors.
|
protected |
|
protected |
|
protected |
Angular velocity read by gyrometers.
|
protected |
URDF string description of the robot.
|
protected |
Map of sensor readings.
|
protected |
The thread running dynamic graph.
|
protected |
Torques.