Go to the documentation of this file.00001
00009
00010
00011
00012
00013 #ifndef KOBUKI_HPP_
00014 #define KOBUKI_HPP_
00015
00016
00017
00018
00019
00020 #include <string>
00021 #include <iomanip>
00022 #include <ecl/threads.hpp>
00023 #include <ecl/devices.hpp>
00024 #include <ecl/threads/mutex.hpp>
00025 #include <ecl/exceptions/standard_exception.hpp>
00026 #include "version_info.hpp"
00027 #include "parameters.hpp"
00028 #include "event_manager.hpp"
00029 #include "command.hpp"
00030 #include "modules.hpp"
00031 #include "packets.hpp"
00032 #include "packet_handler/packet_finder.hpp"
00033
00034
00035
00036
00037
00038 namespace kobuki
00039 {
00040
00041
00042
00043
00044
00045 union union_sint16
00046 {
00047 short word;
00048 unsigned char byte[2];
00049 };
00050
00051
00052
00053
00054
00055 class PacketFinder : public PacketFinderBase
00056 {
00057 public:
00058 virtual ~PacketFinder() {}
00059 bool checkSum();
00060 };
00061
00062
00063
00064
00070 class Kobuki
00071 {
00072 public:
00073 Kobuki();
00074 ~Kobuki();
00075
00076
00077
00078
00079 void init(Parameters ¶meters) throw (ecl::StandardException);
00080 bool isAlive() const { return is_alive; }
00081 bool isShutdown() const { return shutdown_requested; }
00082 bool isEnabled() const { return is_enabled; }
00083 bool enable();
00084 bool disable();
00085 void shutdown() { shutdown_requested = true; }
00086 void spin();
00087
00088
00089
00090
00091 ecl::Angle<double> getHeading() const;
00092 double getAngularVelocity() const;
00093 VersionInfo versionInfo() const { return VersionInfo(firmware.data.version, hardware.data.version, unique_device_id.data.udid0, unique_device_id.data.udid1, unique_device_id.data.udid2); }
00094 Battery batteryStatus() const { return Battery(core_sensors.data.battery, core_sensors.data.charger); }
00095
00096
00097
00098
00099 CoreSensors::Data getCoreSensorData() const { return core_sensors.data; }
00100 DockIR::Data getDockIRData() const { return dock_ir.data; }
00101 Cliff::Data getCliffData() const { return cliff.data; }
00102 Current::Data getCurrentData() const { return current.data; }
00103 Inertia::Data getInertiaData() const { return inertia.data; }
00104 GpInput::Data getGpInputData() const { return gp_input.data; }
00105 ThreeAxisGyro::Data getRawInertiaData() const { return three_axis_gyro.data; }
00106
00107
00108
00109
00110 void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate,
00111 double &wheel_right_angle, double &wheel_right_angle_rate);
00112 void updateOdometry(ecl::Pose2D<double> &pose_update,
00113 ecl::linear_algebra::Vector3d &pose_update_rates);
00114
00115
00116
00117
00118 void resetOdometry();
00119
00120
00121
00122
00123 void setBaseControl(const double &linear_velocity, const double &angular_velocity);
00124 void setLed(const enum LedNumber &number, const enum LedColour &colour);
00125 void setDigitalOutput(const DigitalOutput &digital_output);
00126 void setExternalPower(const DigitalOutput &digital_output);
00127 void playSoundSequence(const enum SoundSequences &number);
00128
00129
00130
00131
00132 void printSigSlotConnections() const;
00133
00134 private:
00135
00136
00137
00138 ecl::Thread thread;
00139 bool shutdown_requested;
00140
00141
00142
00143
00144 DiffDrive diff_drive;
00145 bool is_enabled;
00146
00147
00148
00149
00150 Parameters parameters;
00151 bool is_connected;
00152
00153
00154
00155
00156 AccelerationLimiter acceleration_limiter;
00157
00158
00159
00160
00161 CoreSensors core_sensors;
00162 Inertia inertia;
00163 DockIR dock_ir;
00164 Cliff cliff;
00165 Current current;
00166 GpInput gp_input;
00167 Hardware hardware;
00168 Firmware firmware;
00169 UniqueDeviceID unique_device_id;
00170 ThreeAxisGyro three_axis_gyro;
00171
00172 ecl::Serial serial;
00173 PacketFinder packet_finder;
00174 PacketFinder::BufferType data_buffer;
00175 bool is_alive;
00176
00177 int version_info_reminder;
00178
00179
00180
00181
00182 void sendBaseControlCommand();
00183 void sendCommand(Command command);
00184 ecl::Mutex command_mutex;
00185 Command kobuki_command;
00186 Command::Buffer command_buffer;
00187
00188
00189
00190
00191 EventManager event_manager;
00192
00193
00194
00195
00196 ecl::Signal<> sig_stream_data;
00197 ecl::Signal<const VersionInfo&> sig_version_info;
00198 ecl::Signal<const std::string&> sig_debug, sig_info, sig_warn, sig_error;
00199 ecl::Signal<Command::Buffer&> sig_raw_data_command;
00200 ecl::Signal<PacketFinder::BufferType&> sig_raw_data_stream;
00201 };
00202
00203 }
00204
00205 #endif