Public Member Functions | Private Member Functions | Private Attributes | List of all members
xbot::Xbot Class Reference

The core xbot driver class. More...

#include <xbot.hpp>

Public Member Functions

void base_fixPayload (ecl::PushAndPop< unsigned char > &byteStream)
 
bool base_isAlive () const
 
void base_lockDataAccess ()
 
void base_spin ()
 Performs a scan looking for incoming data packets. More...
 
void base_unlockDataAccess ()
 
bool disable ()
 
bool enable ()
 
double getAngularVelocity () const
 
CoreSensors::Data getCoreSensorData () const
 
int getDebugSensors () const
 
Sensors::Data getExtraSensorsData () const
 
double getHeading () const
 
unsigned char getPitchPlatformDegree () const
 
bool getPowerState ()
 
bool getStopButtonState () const
 
void getWheelJointStates (float &wheel_left_angle, float &wheel_left_angle_rate, float &wheel_right_angle, float &wheel_right_angle_rate)
 
unsigned char getYawPlatformDegree () const
 
void init (Parameters &parameters) throw (ecl::StandardException)
 
bool is_base_connected () const
 
bool is_sensor_connected () const
 
bool isEnabled () const
 
bool isShutdown () const
 
void resetOdometry ()
 
void resetXbot ()
 
void resetXbotState ()
 
void sensor_fixPayload (ecl::PushAndPop< unsigned char > &byteStream)
 
bool sensor_isAlive () const
 
void sensor_lockDataAccess ()
 
void sensor_spin ()
 
void sensor_unlockDataAccess ()
 
void setBaseControl (const float &linear_velocity, const float &angular_velocity)
 
void setLedControl (const char &led)
 
void setLiftControl (const unsigned char &height_percent)
 
void setPitchPlatformControl (const int &pitch_degree)
 
void setPowerControl (const bool &power)
 
void setSoundEnableControl (const bool &sound)
 
void setYawPlatformControl (const int &yaw_degree)
 
void shutdown ()
 
void updateOdometry (ecl::Pose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
 Use the current sensor data (encoders and gyro) to calculate an update for the odometry. More...
 
 Xbot ()
 
 ~Xbot ()
 

Private Member Functions

void sendBaseControlCommand ()
 
void sendCommand (Command command)
 Send the prepared command to the serial port. More...
 

Private Attributes

AccelerationLimiter acceleration_limiter
 
ecl::Mutex base_command_mutex
 
PacketFinder::BufferType base_data_buffer
 
ecl::Mutex base_data_mutex
 
bool base_is_alive
 
bool base_is_connected
 
PacketFinder base_packet_finder
 
ecl::Serial base_serial
 
ecl::Signal< Command::Buffer & > base_sig_raw_data_command
 
ecl::Signal< PacketFinder::BufferType & > base_sig_raw_data_stream
 
ecl::Signal base_sig_stream_data
 
ecl::Thread base_thread
 
Command::Buffer command_buffer
 
CoreSensors core_sensors
 
DiffDrive diff_drive
 
double heading_offset
 
unsigned char HeightPercent
 
bool is_enabled
 
Parameters parameters
 
bool Power
 
ecl::Mutex sensor_command_mutex
 
PacketFinder::BufferType sensor_data_buffer
 
ecl::Mutex sensor_data_mutex
 
bool sensor_is_alive
 
bool sensor_is_connected
 
PacketFinder sensor_packet_finder
 
ecl::Serial sensor_serial
 
ecl::Signal< Command::Buffer & > sensor_sig_raw_data_command
 
ecl::Signal< PacketFinder::BufferType & > sensor_sig_raw_data_stream
 
ecl::Signal sensor_sig_stream_data
 
ecl::Thread sensor_thread
 
Sensors sensors
 
bool shutdown_requested
 
ecl::Signal< const std::string & > sig_debug
 
ecl::Signal< const std::string & > sig_error
 
ecl::Signal< const std::string & > sig_info
 
ecl::Signal< const std::string & > sig_warn
 
Command xbot_command
 

Detailed Description

The core xbot driver class.

This connects to the outside world via sigslots and get accessors.

Definition at line 86 of file xbot.hpp.

Constructor & Destructor Documentation

xbot::Xbot::Xbot ( )

Definition at line 49 of file xbot.cpp.

xbot::Xbot::~Xbot ( )

Shutdown the driver - make sure we wait for the thread to finish.

Definition at line 64 of file xbot.cpp.

Member Function Documentation

void xbot::Xbot::base_fixPayload ( ecl::PushAndPop< unsigned char > &  byteStream)

Definition at line 307 of file xbot.cpp.

bool xbot::Xbot::base_isAlive ( ) const
inline

Whether the connection to the robot is alive and currently streaming.

Definition at line 96 of file xbot.hpp.

void xbot::Xbot::base_lockDataAccess ( )

Usually you should call the getXXX functions from within slot callbacks connected to this driver's signals. This ensures that data is not overwritten inbetween getXXX calls as it all happens in the serial device's reading thread (aye, convoluted - apologies for the multiple robot and multiple developer adhoc hacking over 4-5 years for hasty demos on pre-xbot robots. This has generated such wonderful spaghetti ;).

If instead you just want to poll xbot, then you should lock and unlock the data access around any getXXX calls.

Definition at line 169 of file xbot.cpp.

void xbot::Xbot::base_spin ( )

Performs a scan looking for incoming data packets.

Sits on the device waiting for incoming and then parses it, and signals that an update has occured.

Or, if in simulation, just loopsback the motor devices.

Definition at line 190 of file xbot.cpp.

void xbot::Xbot::base_unlockDataAccess ( )

Unlock a previously locked data access privilege.

See also
lockDataAccess()

Definition at line 175 of file xbot.cpp.

bool xbot::Xbot::disable ( )

Disable power to the motors.

Definition at line 719 of file xbot.cpp.

bool xbot::Xbot::enable ( )

Enable power to the motors.

Definition at line 713 of file xbot.cpp.

double xbot::Xbot::getAngularVelocity ( ) const

Definition at line 505 of file xbot.cpp.

CoreSensors::Data xbot::Xbot::getCoreSensorData ( ) const
inline

Definition at line 174 of file xbot.hpp.

int xbot::Xbot::getDebugSensors ( ) const

Definition at line 502 of file xbot.cpp.

Sensors::Data xbot::Xbot::getExtraSensorsData ( ) const
inline

Definition at line 176 of file xbot.hpp.

double xbot::Xbot::getHeading ( ) const

Definition at line 491 of file xbot.cpp.

unsigned char xbot::Xbot::getPitchPlatformDegree ( ) const
bool xbot::Xbot::getPowerState ( )
inline

Definition at line 165 of file xbot.hpp.

bool xbot::Xbot::getStopButtonState ( ) const
void xbot::Xbot::getWheelJointStates ( float &  wheel_left_angle,
float &  wheel_left_angle_rate,
float &  wheel_right_angle,
float &  wheel_right_angle_rate 
)

Definition at line 529 of file xbot.cpp.

unsigned char xbot::Xbot::getYawPlatformDegree ( ) const
void xbot::Xbot::init ( Parameters parameters)
throw (ecl::StandardException
)

Definition at line 77 of file xbot.cpp.

bool xbot::Xbot::is_base_connected ( ) const
inline

Definition at line 113 of file xbot.hpp.

bool xbot::Xbot::is_sensor_connected ( ) const
inline

Definition at line 114 of file xbot.hpp.

bool xbot::Xbot::isEnabled ( ) const
inline

Whether the motor power is enabled or disabled.

Definition at line 104 of file xbot.hpp.

bool xbot::Xbot::isShutdown ( ) const
inline

Whether the worker thread is alive or not.

Definition at line 101 of file xbot.hpp.

void xbot::Xbot::resetOdometry ( )

Definition at line 521 of file xbot.cpp.

void xbot::Xbot::resetXbot ( )

Definition at line 593 of file xbot.cpp.

void xbot::Xbot::resetXbotState ( )

Definition at line 510 of file xbot.cpp.

void xbot::Xbot::sendBaseControlCommand ( )
private

Definition at line 601 of file xbot.cpp.

void xbot::Xbot::sendCommand ( Command  command)
private

Send the prepared command to the serial port.

Need to be a bit careful here, because we have no control over how the user is calling this - they may be calling from different threads (this is so for xbot_node), so we mutex protect it here rather than relying on the user to do so above.

Parameters
command: prepared command template (see Command's static member functions).

Definition at line 636 of file xbot.cpp.

void xbot::Xbot::sensor_fixPayload ( ecl::PushAndPop< unsigned char > &  byteStream)

Definition at line 456 of file xbot.cpp.

bool xbot::Xbot::sensor_isAlive ( ) const
inline

Definition at line 100 of file xbot.hpp.

void xbot::Xbot::sensor_lockDataAccess ( )

Definition at line 177 of file xbot.cpp.

void xbot::Xbot::sensor_spin ( )

Definition at line 339 of file xbot.cpp.

void xbot::Xbot::sensor_unlockDataAccess ( )

Definition at line 179 of file xbot.cpp.

void xbot::Xbot::setBaseControl ( const float &  linear_velocity,
const float &  angular_velocity 
)

Definition at line 563 of file xbot.cpp.

void xbot::Xbot::setLedControl ( const char &  led)

Definition at line 590 of file xbot.cpp.

void xbot::Xbot::setLiftControl ( const unsigned char &  height_percent)

Definition at line 573 of file xbot.cpp.

void xbot::Xbot::setPitchPlatformControl ( const int &  pitch_degree)

Definition at line 582 of file xbot.cpp.

void xbot::Xbot::setPowerControl ( const bool &  power)

Definition at line 568 of file xbot.cpp.

void xbot::Xbot::setSoundEnableControl ( const bool &  sound)

Definition at line 586 of file xbot.cpp.

void xbot::Xbot::setYawPlatformControl ( const int &  yaw_degree)

Definition at line 578 of file xbot.cpp.

void xbot::Xbot::shutdown ( )
inline

Gently terminate the worker thread.

Definition at line 109 of file xbot.hpp.

void xbot::Xbot::updateOdometry ( ecl::Pose2D< double > &  pose_update,
ecl::linear_algebra::Vector3d &  pose_update_rates 
)

Use the current sensor data (encoders and gyro) to calculate an update for the odometry.

This fuses current sensor data with the last updated odometry state to produce the new odometry state. This will be usually done in the slot callback to the stream_data signal.

It is important that this is called every time a data packet is received from the robot.

Parameters
pose_update: return the pose updates in this variable.
pose_update_rates: return the pose update rates in this variable.

Definition at line 552 of file xbot.cpp.

Member Data Documentation

AccelerationLimiter xbot::Xbot::acceleration_limiter
private

Definition at line 256 of file xbot.hpp.

ecl::Mutex xbot::Xbot::base_command_mutex
private

Definition at line 280 of file xbot.hpp.

PacketFinder::BufferType xbot::Xbot::base_data_buffer
private

Definition at line 266 of file xbot.hpp.

ecl::Mutex xbot::Xbot::base_data_mutex
private

Definition at line 282 of file xbot.hpp.

bool xbot::Xbot::base_is_alive
private

Definition at line 272 of file xbot.hpp.

bool xbot::Xbot::base_is_connected
private

Definition at line 249 of file xbot.hpp.

PacketFinder xbot::Xbot::base_packet_finder
private

Definition at line 265 of file xbot.hpp.

ecl::Serial xbot::Xbot::base_serial
private

Definition at line 264 of file xbot.hpp.

ecl::Signal<Command::Buffer &> xbot::Xbot::base_sig_raw_data_command
private

Definition at line 297 of file xbot.hpp.

ecl::Signal<PacketFinder::BufferType &> xbot::Xbot::base_sig_raw_data_stream
private

Definition at line 305 of file xbot.hpp.

ecl::Signal xbot::Xbot::base_sig_stream_data
private

Definition at line 294 of file xbot.hpp.

ecl::Thread xbot::Xbot::base_thread
private

Definition at line 221 of file xbot.hpp.

Command::Buffer xbot::Xbot::command_buffer
private

Definition at line 289 of file xbot.hpp.

CoreSensors xbot::Xbot::core_sensors
private

Definition at line 261 of file xbot.hpp.

DiffDrive xbot::Xbot::diff_drive
private

Definition at line 235 of file xbot.hpp.

double xbot::Xbot::heading_offset
private

Definition at line 242 of file xbot.hpp.

unsigned char xbot::Xbot::HeightPercent
private

Definition at line 229 of file xbot.hpp.

bool xbot::Xbot::is_enabled
private

Definition at line 236 of file xbot.hpp.

Parameters xbot::Xbot::parameters
private

Definition at line 247 of file xbot.hpp.

bool xbot::Xbot::Power
private

Definition at line 230 of file xbot.hpp.

ecl::Mutex xbot::Xbot::sensor_command_mutex
private

Definition at line 284 of file xbot.hpp.

PacketFinder::BufferType xbot::Xbot::sensor_data_buffer
private

Definition at line 271 of file xbot.hpp.

ecl::Mutex xbot::Xbot::sensor_data_mutex
private

Definition at line 285 of file xbot.hpp.

bool xbot::Xbot::sensor_is_alive
private

Definition at line 273 of file xbot.hpp.

bool xbot::Xbot::sensor_is_connected
private

Definition at line 251 of file xbot.hpp.

PacketFinder xbot::Xbot::sensor_packet_finder
private

Definition at line 270 of file xbot.hpp.

ecl::Serial xbot::Xbot::sensor_serial
private

Definition at line 269 of file xbot.hpp.

ecl::Signal<Command::Buffer &> xbot::Xbot::sensor_sig_raw_data_command
private

Definition at line 303 of file xbot.hpp.

ecl::Signal<PacketFinder::BufferType &> xbot::Xbot::sensor_sig_raw_data_stream
private

Definition at line 308 of file xbot.hpp.

ecl::Signal xbot::Xbot::sensor_sig_stream_data
private

Definition at line 295 of file xbot.hpp.

ecl::Thread xbot::Xbot::sensor_thread
private

Definition at line 223 of file xbot.hpp.

Sensors xbot::Xbot::sensors
private

Definition at line 262 of file xbot.hpp.

bool xbot::Xbot::shutdown_requested
private

Definition at line 224 of file xbot.hpp.

ecl::Signal<const std::string &> xbot::Xbot::sig_debug
private

Definition at line 296 of file xbot.hpp.

ecl::Signal<const std::string &> xbot::Xbot::sig_error
private

Definition at line 296 of file xbot.hpp.

ecl::Signal<const std::string &> xbot::Xbot::sig_info
private

Definition at line 296 of file xbot.hpp.

ecl::Signal<const std::string &> xbot::Xbot::sig_warn
private

Definition at line 296 of file xbot.hpp.

Command xbot::Xbot::xbot_command
private

Definition at line 288 of file xbot.hpp.


The documentation for this class was generated from the following files:


xbot_driver
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:27:38