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


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Thu Jun 6 2019 20:24:37