20 #include <ecl/config.hpp>    21 #include <ecl/devices.hpp>    22 #include <ecl/exceptions/standard_exception.hpp>    23 #include <ecl/threads.hpp>    24 #include <ecl/threads/mutex.hpp>    64   unsigned char byte[2];
   102     return shutdown_requested;
   110     shutdown_requested = 
true;
   112   void resetXbotState();
   136   void base_lockDataAccess();
   137   void base_unlockDataAccess();
   143   void sensor_lockDataAccess();
   144   void sensor_unlockDataAccess();
   153   double getHeading() 
const;
   155   int getDebugSensors() 
const;
   157   double getAngularVelocity() 
const;
   159   unsigned char getYawPlatformDegree() 
const;
   161   unsigned char getPitchPlatformDegree() 
const;
   163   bool getStopButtonState() 
const;
   181   void getWheelJointStates(
float &wheel_left_angle,
   182                            float &wheel_left_angle_rate,
   183                            float &wheel_right_angle,
   184                            float &wheel_right_angle_rate);
   187                       ecl::linear_algebra::Vector3d &pose_update_rates);
   192   void resetOdometry();
   198   void setBaseControl(
const float &linear_velocity,
   199                       const float &angular_velocity);
   201   void setLiftControl(
const unsigned char &height_percent);
   203   void setYawPlatformControl(
const int &yaw_degree);
   205   void setPitchPlatformControl(
const int &pitch_degree);
   207   void setPowerControl(
const bool &power);
   209   void setSoundEnableControl(
const bool &sound);
   211   void setLedControl(
const char &led);
   278   void sendBaseControlCommand();
   279   void sendCommand(
Command command);
 
ecl::Serial sensor_serial
ecl::Signal< PacketFinder::BufferType & > base_sig_raw_data_stream
Parameter list and validator for the xbot. 
bool is_sensor_connected() const 
bool is_base_connected() const 
AccelerationLimiter acceleration_limiter
bool sensor_isAlive() const 
ecl::Mutex sensor_command_mutex
An acceleration limiter for the xbot. 
Standard exception type, provides code location and error string. 
bool base_isAlive() const 
unsigned char HeightPercent
ecl::Signal< PacketFinder::BufferType & > sensor_sig_raw_data_stream
ecl::Signal sensor_sig_stream_data
Convenience header for modules. 
Command::Buffer command_buffer
CoreSensors::Data getCoreSensorData() const 
Provides simple packet finder which may be consist of stx, etx, payload, ... 
PacketFinder::BufferType base_data_buffer
The sigslots connection manager. 
ecl::Thread sensor_thread
ecl::Signal< const std::string & > sig_warn
PacketFinder::BufferType sensor_data_buffer
ecl::Mutex sensor_data_mutex
ecl::Signal base_sig_stream_data
ecl::Mutex base_data_mutex
ecl::Signal< Command::Buffer & > sensor_sig_raw_data_command
Packets convenience header. 
Signalling component of a callback system. 
ecl::Mutex base_command_mutex
PacketFinder base_packet_finder
Parameter configuration for the xbot. 
The core xbot driver class. 
PacketFinder sensor_packet_finder
ecl::Signal< Command::Buffer & > base_sig_raw_data_command
Sensors::Data getExtraSensorsData() const