Public Member Functions | Private Member Functions | Private Attributes
kobuki::Kobuki Class Reference

The core kobuki driver class. More...

#include <kobuki.hpp>

List of all members.

Public Member Functions

Battery batteryStatus () const
bool disable ()
bool enable ()
double getAngularVelocity () const
Cliff::Data getCliffData () const
CoreSensors::Data getCoreSensorData () const
Current::Data getCurrentData () const
DockIR::Data getDockIRData () const
GpInput::Data getGpInputData () const
ecl::Angle< double > getHeading () const
Inertia::Data getInertiaData () const
ThreeAxisGyro::Data getRawInertiaData () const
void getWheelJointStates (double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
void init (Parameters &parameters) throw (ecl::StandardException)
bool isAlive () const
bool isEnabled () const
bool isShutdown () const
 Kobuki ()
void playSoundSequence (const enum SoundSequences &number)
void printSigSlotConnections () const
 Print a list of all relevant sigslot connections.
void resetOdometry ()
void setBaseControl (const double &linear_velocity, const double &angular_velocity)
void setDigitalOutput (const DigitalOutput &digital_output)
void setExternalPower (const DigitalOutput &digital_output)
void setLed (const enum LedNumber &number, const enum LedColour &colour)
void shutdown ()
void spin ()
 Performs a scan looking for incoming data packets.
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.
VersionInfo versionInfo () const
 ~Kobuki ()

Private Member Functions

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

Private Attributes

AccelerationLimiter acceleration_limiter
Cliff cliff
Command::Buffer command_buffer
ecl::Mutex command_mutex
CoreSensors core_sensors
Current current
PacketFinder::BufferType data_buffer
DiffDrive diff_drive
DockIR dock_ir
EventManager event_manager
Firmware firmware
GpInput gp_input
Hardware hardware
Inertia inertia
bool is_alive
bool is_connected
bool is_enabled
Command kobuki_command
PacketFinder packet_finder
Parameters parameters
ecl::Serial serial
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< Command::Buffer & > sig_raw_data_command
ecl::Signal
< PacketFinder::BufferType & > 
sig_raw_data_stream
ecl::Signal sig_stream_data
ecl::Signal< const VersionInfo & > sig_version_info
ecl::Signal< const std::string & > sig_warn
ecl::Thread thread
ThreeAxisGyro three_axis_gyro
UniqueDeviceID unique_device_id
int version_info_reminder

Detailed Description

The core kobuki driver class.

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

Definition at line 70 of file kobuki.hpp.


Constructor & Destructor Documentation

Definition at line 50 of file kobuki.cpp.

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

Definition at line 62 of file kobuki.cpp.


Member Function Documentation

Definition at line 94 of file kobuki.hpp.

Disable power to the motors.

Definition at line 504 of file kobuki.cpp.

Enable power to the motors.

Definition at line 498 of file kobuki.cpp.

Definition at line 376 of file kobuki.cpp.

Definition at line 101 of file kobuki.hpp.

Definition at line 99 of file kobuki.hpp.

Definition at line 102 of file kobuki.hpp.

Definition at line 100 of file kobuki.hpp.

Definition at line 104 of file kobuki.hpp.

Definition at line 368 of file kobuki.cpp.

Definition at line 103 of file kobuki.hpp.

Definition at line 105 of file kobuki.hpp.

void kobuki::Kobuki::getWheelJointStates ( double &  wheel_left_angle,
double &  wheel_left_angle_rate,
double &  wheel_right_angle,
double &  wheel_right_angle_rate 
)

Definition at line 391 of file kobuki.cpp.

void kobuki::Kobuki::init ( Parameters parameters) throw (ecl::StandardException)

Definition at line 70 of file kobuki.cpp.

bool kobuki::Kobuki::isAlive ( ) const [inline]

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

Definition at line 80 of file kobuki.hpp.

bool kobuki::Kobuki::isEnabled ( ) const [inline]

Whether the motor power is enabled or disabled.

Definition at line 82 of file kobuki.hpp.

bool kobuki::Kobuki::isShutdown ( ) const [inline]

Whether the worker thread is alive or not.

Definition at line 81 of file kobuki.hpp.

void kobuki::Kobuki::playSoundSequence ( const enum SoundSequences number)

Definition at line 436 of file kobuki.cpp.

Print a list of all relevant sigslot connections.

This includes both the kobuki driver signals as well as externally connected slots. Useful for when you need to check if any of your connections are dangling (often happens when you typo the name of the sigslots connection).

Definition at line 520 of file kobuki.cpp.

Definition at line 386 of file kobuki.cpp.

Definition at line 446 of file kobuki.cpp.

void kobuki::Kobuki::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 kobuki_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 468 of file kobuki.cpp.

void kobuki::Kobuki::setBaseControl ( const double &  linear_velocity,
const double &  angular_velocity 
)

Definition at line 441 of file kobuki.cpp.

void kobuki::Kobuki::setDigitalOutput ( const DigitalOutput digital_output)

Definition at line 423 of file kobuki.cpp.

void kobuki::Kobuki::setExternalPower ( const DigitalOutput digital_output)

Definition at line 427 of file kobuki.cpp.

void kobuki::Kobuki::setLed ( const enum LedNumber number,
const enum LedColour colour 
)

Definition at line 418 of file kobuki.cpp.

void kobuki::Kobuki::shutdown ( ) [inline]

Gently terminate the worker thread.

Definition at line 85 of file kobuki.hpp.

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 146 of file kobuki.cpp.

void kobuki::Kobuki::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 408 of file kobuki.cpp.

Definition at line 93 of file kobuki.hpp.


Member Data Documentation

Definition at line 156 of file kobuki.hpp.

Definition at line 164 of file kobuki.hpp.

Definition at line 186 of file kobuki.hpp.

ecl::Mutex kobuki::Kobuki::command_mutex [private]

Definition at line 184 of file kobuki.hpp.

Definition at line 161 of file kobuki.hpp.

Definition at line 165 of file kobuki.hpp.

Definition at line 174 of file kobuki.hpp.

Definition at line 144 of file kobuki.hpp.

Definition at line 163 of file kobuki.hpp.

Definition at line 191 of file kobuki.hpp.

Definition at line 168 of file kobuki.hpp.

Definition at line 166 of file kobuki.hpp.

Definition at line 167 of file kobuki.hpp.

Definition at line 162 of file kobuki.hpp.

bool kobuki::Kobuki::is_alive [private]

Definition at line 175 of file kobuki.hpp.

Definition at line 151 of file kobuki.hpp.

Definition at line 145 of file kobuki.hpp.

Definition at line 185 of file kobuki.hpp.

Definition at line 173 of file kobuki.hpp.

Definition at line 150 of file kobuki.hpp.

ecl::Serial kobuki::Kobuki::serial [private]

Definition at line 172 of file kobuki.hpp.

Definition at line 139 of file kobuki.hpp.

ecl::Signal<const std::string&> kobuki::Kobuki::sig_debug [private]

Definition at line 198 of file kobuki.hpp.

ecl::Signal<const std::string&> kobuki::Kobuki::sig_error [private]

Definition at line 198 of file kobuki.hpp.

ecl::Signal<const std::string&> kobuki::Kobuki::sig_info [private]

Definition at line 198 of file kobuki.hpp.

Definition at line 199 of file kobuki.hpp.

Definition at line 200 of file kobuki.hpp.

Definition at line 196 of file kobuki.hpp.

Definition at line 197 of file kobuki.hpp.

ecl::Signal<const std::string&> kobuki::Kobuki::sig_warn [private]

Definition at line 198 of file kobuki.hpp.

ecl::Thread kobuki::Kobuki::thread [private]

Definition at line 138 of file kobuki.hpp.

Definition at line 170 of file kobuki.hpp.

Definition at line 169 of file kobuki.hpp.

Definition at line 177 of file kobuki.hpp.


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


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Mon Oct 6 2014 01:31:10