kobuki.hpp
Go to the documentation of this file.
00001 
00009 /*****************************************************************************
00010  ** Ifdefs
00011  *****************************************************************************/
00012 
00013 #ifndef KOBUKI_HPP_
00014 #define KOBUKI_HPP_
00015 
00016 /*****************************************************************************
00017  ** Includes
00018  *****************************************************************************/
00019 
00020 #include <string>
00021 #include <iomanip>
00022 #include <ecl/config.hpp>
00023 #include <ecl/threads.hpp>
00024 #include <ecl/devices.hpp>
00025 #include <ecl/threads/mutex.hpp>
00026 #include <ecl/exceptions/standard_exception.hpp>
00027 #include "version_info.hpp"
00028 #include "parameters.hpp"
00029 #include "event_manager.hpp"
00030 #include "command.hpp"
00031 #include "modules.hpp"
00032 #include "packets.hpp"
00033 #include "packet_handler/packet_finder.hpp"
00034 #include "macros.hpp"
00035 
00036 /*****************************************************************************
00037 ** Extern Templates
00038 *****************************************************************************/
00039 
00040 #ifdef ECL_IS_WIN32
00041   /* Help windows create common instances of sigslots across kobuki dll
00042    * and end user program (otherwise it creates two separate variables!) */
00043   EXP_TEMPLATE template class kobuki_PUBLIC ecl::SigSlotsManager<>;
00044   EXP_TEMPLATE template class kobuki_PUBLIC ecl::SigSlotsManager<const kobuki::VersionInfo&>;
00045   EXP_TEMPLATE template class kobuki_PUBLIC ecl::SigSlotsManager<const std::string&>;
00046   EXP_TEMPLATE template class kobuki_PUBLIC ecl::SigSlotsManager<kobuki::Command::Buffer&>;
00047   EXP_TEMPLATE template class kobuki_PUBLIC ecl::SigSlotsManager<kobuki::PacketFinderBase::BufferType&>;
00048 #endif
00049 
00050 /*****************************************************************************
00051  ** Namespaces
00052  *****************************************************************************/
00053 
00054 namespace kobuki
00055 {
00056 
00057 /*****************************************************************************
00058  ** Definitions
00059  *****************************************************************************/
00060 
00061 union union_sint16
00062 {
00063   short word;
00064   unsigned char byte[2];
00065 };
00066 
00067 /*****************************************************************************
00068 ** Parent Interface
00069 *****************************************************************************/
00070 
00071 class PacketFinder : public PacketFinderBase
00072 {
00073 public:
00074   virtual ~PacketFinder() {}
00075   bool checkSum();
00076 };
00077 
00078 /*****************************************************************************
00079  ** Interface [Kobuki]
00080  *****************************************************************************/
00086 class kobuki_PUBLIC Kobuki
00087 {
00088 public:
00089   Kobuki();
00090   ~Kobuki();
00091 
00092   /*********************
00093    ** Configuration
00094    **********************/
00095   void init(Parameters &parameters) throw (ecl::StandardException);
00096   bool isAlive() const { return is_alive; } 
00097   bool isShutdown() const { return shutdown_requested; } 
00098   bool isEnabled() const { return is_enabled; } 
00099   bool enable(); 
00100   bool disable(); 
00101   void shutdown() { shutdown_requested = true; } 
00103   /******************************************
00104   ** Packet Processing
00105   *******************************************/
00106   void spin();
00107   void fixPayload(ecl::PushAndPop<unsigned char> & byteStream);
00108 
00109   /******************************************
00110   ** Getters - Data Protection
00111   *******************************************/
00112   void lockDataAccess();
00113   void unlockDataAccess();
00114 
00115   /******************************************
00116   ** Getters - User Friendly Api
00117   *******************************************/
00118   /* Be sure to lock/unlock the data access (lockDataAccess and unlockDataAccess)
00119    * around any getXXX calls - see the doxygen notes for lockDataAccess. */
00120   ecl::Angle<double> getHeading() const;
00121   double getAngularVelocity() const;
00122   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); }
00123   Battery batteryStatus() const { return Battery(core_sensors.data.battery, core_sensors.data.charger); }
00124 
00125   /******************************************
00126   ** Getters - Raw Data Api
00127   *******************************************/
00128   /* Be sure to lock/unlock the data access (lockDataAccess and unlockDataAccess)
00129    * around any getXXX calls - see the doxygen notes for lockDataAccess. */
00130   CoreSensors::Data getCoreSensorData() const { return core_sensors.data; }
00131   DockIR::Data getDockIRData() const { return dock_ir.data; }
00132   Cliff::Data getCliffData() const { return cliff.data; }
00133   Current::Data getCurrentData() const { return current.data; }
00134   Inertia::Data getInertiaData() const { return inertia.data; }
00135   GpInput::Data getGpInputData() const { return gp_input.data; }
00136   ThreeAxisGyro::Data getRawInertiaData() const { return three_axis_gyro.data; }
00137   ControllerInfo::Data getControllerInfoData() const { return controller_info.data; }
00138 
00139   /*********************
00140   ** Feedback
00141   **********************/
00142   void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate,
00143                            double &wheel_right_angle, double &wheel_right_angle_rate);
00144   void updateOdometry(ecl::Pose2D<double> &pose_update,
00145                       ecl::linear_algebra::Vector3d &pose_update_rates);
00146 
00147   /*********************
00148   ** Soft Commands
00149   **********************/
00150   void resetOdometry();
00151 
00152   /*********************
00153   ** Hard Commands
00154   **********************/
00155   void setBaseControl(const double &linear_velocity, const double &angular_velocity);
00156   void setLed(const enum LedNumber &number, const enum LedColour &colour);
00157   void setDigitalOutput(const DigitalOutput &digital_output);
00158   void setExternalPower(const DigitalOutput &digital_output);
00159   void playSoundSequence(const enum SoundSequences &number);
00160   bool setControllerGain(const unsigned char &type, const unsigned int &p_gain,
00161                          const unsigned int &i_gain, const unsigned int &d_gain);
00162   bool getControllerGain();
00163 
00164   /*********************
00165   ** Debugging
00166   **********************/
00167   void printSigSlotConnections() const;
00168 
00169 private:
00170   /*********************
00171   ** Thread
00172   **********************/
00173   ecl::Thread thread;
00174   bool shutdown_requested; // helper to shutdown the worker thread.
00175 
00176   /*********************
00177   ** Odometry
00178   **********************/
00179   DiffDrive diff_drive;
00180   bool is_enabled;
00181 
00182   /*********************
00183   ** Inertia
00184   **********************/
00185   double heading_offset;
00186 
00187   /*********************
00188   ** Driver Paramters
00189   **********************/
00190   Parameters parameters;
00191   bool is_connected;
00192 
00193   /*********************
00194   ** Acceleration Limiter
00195   **********************/
00196   AccelerationLimiter acceleration_limiter;
00197 
00198   /*********************
00199   ** Packet Handling
00200   **********************/
00201   CoreSensors core_sensors;
00202   Inertia inertia;
00203   DockIR dock_ir;
00204   Cliff cliff;
00205   Current current;
00206   GpInput gp_input;
00207   Hardware hardware; // requestable
00208   Firmware firmware; // requestable
00209   UniqueDeviceID unique_device_id; // requestable
00210   ThreeAxisGyro three_axis_gyro;
00211   ControllerInfo controller_info; // requestable
00212 
00213   ecl::Serial serial;
00214   PacketFinder packet_finder;
00215   PacketFinder::BufferType data_buffer;
00216   bool is_alive; // used as a flag set by the data stream watchdog
00217 
00218   int version_info_reminder;
00219   int controller_info_reminder;
00220 
00221   /*********************
00222   ** Commands
00223   **********************/
00224   void sendBaseControlCommand();
00225   void sendCommand(Command command);
00226   ecl::Mutex command_mutex; // protection against the user calling the command functions from multiple threads
00227   // data_mutex is protection against reading and writing data structures simultaneously as well as
00228   // ensuring multiple get*** calls are synchronised to the same data update
00229   // refer to https://github.com/yujinrobot/kobuki/issues/240
00230   ecl::Mutex data_mutex;
00231   Command kobuki_command; // used to maintain some state about the command history
00232   Command::Buffer command_buffer;
00233   std::vector<short> velocity_commands_debug;
00234 
00235   /*********************
00236   ** Events
00237   **********************/
00238   EventManager event_manager;
00239 
00240   /*********************
00241   ** Logging
00242   **********************/
00243   std::vector<std::string> log(std::string msg) { return log("", "", msg); } 
00244   std::vector<std::string> log(std::string level, std::string msg) { return log(level, "", msg); }
00245   std::vector<std::string> log(std::string level, std::string name, std::string msg) {
00246     std::vector<std::string> ret;
00247     if( level != "" ) ret.push_back(level);
00248     if( name != "" ) ret.push_back(name);
00249     if( msg != "" ) ret.push_back(msg);
00250     return ret;
00251   }
00252 
00253   /*********************
00254   ** Signals
00255   **********************/
00256   ecl::Signal<> sig_stream_data, sig_controller_info;
00257   ecl::Signal<const VersionInfo&> sig_version_info;
00258   ecl::Signal<const std::string&> sig_debug, sig_info, sig_warn, sig_error;
00259   ecl::Signal<const std::vector<std::string>&> sig_named;
00260   ecl::Signal<Command::Buffer&> sig_raw_data_command; // should be const, but pushnpop is not fully realised yet for const args in the formatters.
00261   ecl::Signal<PacketFinder::BufferType&> sig_raw_data_stream; // should be const, but pushnpop is not fully realised yet for const args in the formatters.
00262   ecl::Signal<const std::vector<short>&> sig_raw_control_command;
00263 };
00264 
00265 } // namespace kobuki
00266 
00267 #endif /* KOBUKI_HPP_ */


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Thu Aug 27 2015 13:43:58