kobuki.hpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10  ** Ifdefs
11  *****************************************************************************/
12 
13 #ifndef KOBUKI_HPP_
14 #define KOBUKI_HPP_
15 
16 /*****************************************************************************
17  ** Includes
18  *****************************************************************************/
19 
20 #include <string>
21 #include <iomanip>
22 #include <ecl/config.hpp>
23 #include <ecl/threads.hpp>
24 #include <ecl/devices.hpp>
25 #include <ecl/threads/mutex.hpp>
28 #include "version_info.hpp"
29 #include "parameters.hpp"
30 #include "event_manager.hpp"
31 #include "command.hpp"
32 #include "modules.hpp"
33 #include "packets.hpp"
35 #include "macros.hpp"
36 
37 /*****************************************************************************
38 ** Extern Templates
39 *****************************************************************************/
40 
41 #ifdef ECL_IS_WIN32
42  /* Help windows create common instances of sigslots across kobuki dll
43  * and end user program (otherwise it creates two separate variables!) */
49 #endif
50 
51 /*****************************************************************************
52  ** Namespaces
53  *****************************************************************************/
54 
55 namespace kobuki
56 {
57 
58 /*****************************************************************************
59  ** Definitions
60  *****************************************************************************/
61 
63 {
64  short word;
65  unsigned char byte[2];
66 };
67 
68 /*****************************************************************************
69 ** Parent Interface
70 *****************************************************************************/
71 
73 {
74 public:
75  virtual ~PacketFinder() {}
76  bool checkSum();
77 };
78 
79 /*****************************************************************************
80  ** Interface [Kobuki]
81  *****************************************************************************/
88 {
89 public:
90  Kobuki();
91  ~Kobuki();
92 
93  /*********************
94  ** Configuration
95  **********************/
96  void init(Parameters &parameters);
97  bool isAlive() const { return is_alive; }
98  bool isShutdown() const { return shutdown_requested; }
99  bool isEnabled() const { return is_enabled; }
100  bool enable();
101  bool disable();
102  void shutdown() { shutdown_requested = true; }
104  /******************************************
105  ** Packet Processing
106  *******************************************/
107  void spin();
108  void fixPayload(ecl::PushAndPop<unsigned char> & byteStream);
109 
110  /******************************************
111  ** Getters - Data Protection
112  *******************************************/
113  void lockDataAccess();
114  void unlockDataAccess();
115 
116  /******************************************
117  ** Getters - User Friendly Api
118  *******************************************/
119  /* Be sure to lock/unlock the data access (lockDataAccess and unlockDataAccess)
120  * around any getXXX calls - see the doxygen notes for lockDataAccess. */
121  ecl::Angle<double> getHeading() const;
122  double getAngularVelocity() const;
123  VersionInfo versionInfo() const { return VersionInfo(firmware.version(), hardware.data.version, unique_device_id.data.udid0, unique_device_id.data.udid1, unique_device_id.data.udid2); }
124  Battery batteryStatus() const { return Battery(core_sensors.data.battery, core_sensors.data.charger); }
125 
126  /******************************************
127  ** Getters - Raw Data Api
128  *******************************************/
129  /* Be sure to lock/unlock the data access (lockDataAccess and unlockDataAccess)
130  * around any getXXX calls - see the doxygen notes for lockDataAccess. */
131  CoreSensors::Data getCoreSensorData() const { return core_sensors.data; }
132  DockIR::Data getDockIRData() const { return dock_ir.data; }
133  Cliff::Data getCliffData() const { return cliff.data; }
134  Current::Data getCurrentData() const { return current.data; }
135  Inertia::Data getInertiaData() const { return inertia.data; }
136  GpInput::Data getGpInputData() const { return gp_input.data; }
137  ThreeAxisGyro::Data getRawInertiaData() const { return three_axis_gyro.data; }
138  ControllerInfo::Data getControllerInfoData() const { return controller_info.data; }
139 
140  /*********************
141  ** Feedback
142  **********************/
143  void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate,
144  double &wheel_right_angle, double &wheel_right_angle_rate);
145  void updateOdometry(ecl::LegacyPose2D<double> &pose_update,
146  ecl::linear_algebra::Vector3d &pose_update_rates);
147 
148  /*********************
149  ** Soft Commands
150  **********************/
151  void resetOdometry();
152 
153  /*********************
154  ** Hard Commands
155  **********************/
156  void setBaseControl(const double &linear_velocity, const double &angular_velocity);
157  void setLed(const enum LedNumber &number, const enum LedColour &colour);
158  void setDigitalOutput(const DigitalOutput &digital_output);
159  void setExternalPower(const DigitalOutput &digital_output);
160  void playSoundSequence(const enum SoundSequences &number);
161  bool setControllerGain(const unsigned char &type, const unsigned int &p_gain,
162  const unsigned int &i_gain, const unsigned int &d_gain);
163  bool getControllerGain();
164 
165  /*********************
166  ** Debugging
167  **********************/
168  void printSigSlotConnections() const;
169 
170 private:
171  /*********************
172  ** Thread
173  **********************/
174  ecl::Thread thread;
175  bool shutdown_requested; // helper to shutdown the worker thread.
176 
177  /*********************
178  ** Odometry
179  **********************/
182 
183  /*********************
184  ** Inertia
185  **********************/
187 
188  /*********************
189  ** Driver Paramters
190  **********************/
193 
194  /*********************
195  ** Acceleration Limiter
196  **********************/
198 
199  /*********************
200  ** Packet Handling
201  **********************/
208  Hardware hardware; // requestable
209  Firmware firmware; // requestable
213 
214  ecl::Serial serial;
216  PacketFinder::BufferType data_buffer;
217  bool is_alive; // used as a flag set by the data stream watchdog
218 
221 
222  /*********************
223  ** Commands
224  **********************/
225  void sendBaseControlCommand();
226  void sendCommand(Command command);
227  ecl::Mutex command_mutex; // protection against the user calling the command functions from multiple threads
228  // data_mutex is protection against reading and writing data structures simultaneously as well as
229  // ensuring multiple get*** calls are synchronised to the same data update
230  // refer to https://github.com/yujinrobot/kobuki/issues/240
231  ecl::Mutex data_mutex;
232  Command kobuki_command; // used to maintain some state about the command history
234  std::vector<short> velocity_commands_debug;
235 
236  /*********************
237  ** Events
238  **********************/
240 
241  /*********************
242  ** Logging
243  **********************/
244  std::vector<std::string> log(std::string msg) { return log("", "", msg); }
245  std::vector<std::string> log(std::string level, std::string msg) { return log(level, "", msg); }
246  std::vector<std::string> log(std::string level, std::string name, std::string msg) {
247  std::vector<std::string> ret;
248  if( level != "" ) ret.push_back(level);
249  if( name != "" ) ret.push_back(name);
250  if( msg != "" ) ret.push_back(msg);
251  return ret;
252  }
253 
254  /*********************
255  ** Signals
256  **********************/
257  ecl::Signal<> sig_stream_data, sig_controller_info;
259  ecl::Signal<const std::string&> sig_debug, sig_info, sig_warn, sig_error;
261  ecl::Signal<Command::Buffer&> sig_raw_data_command; // should be const, but pushnpop is not fully realised yet for const args in the formatters.
262  ecl::Signal<PacketFinder::BufferType&> sig_raw_data_stream; // should be const, but pushnpop is not fully realised yet for const args in the formatters.
264 };
265 
266 } // namespace kobuki
267 
268 #endif /* KOBUKI_HPP_ */
std::vector< std::string > log(std::string msg)
Definition: kobuki.hpp:244
ecl::Signal< PacketFinder::BufferType & > sig_raw_data_stream
Definition: kobuki.hpp:262
SoundSequences
Definition: sound.hpp:30
ControllerInfo controller_info
Definition: kobuki.hpp:212
AccelerationLimiter acceleration_limiter
Definition: kobuki.hpp:197
Current::Data getCurrentData() const
Definition: kobuki.hpp:134
EventManager event_manager
Definition: kobuki.hpp:239
Current current
Definition: kobuki.hpp:206
virtual ~PacketFinder()
Definition: kobuki.hpp:75
Command::Buffer command_buffer
Definition: kobuki.hpp:233
ecl::Thread thread
Definition: kobuki.hpp:174
void shutdown()
Definition: kobuki.hpp:102
Battery batteryStatus() const
Definition: kobuki.hpp:124
DiffDrive diff_drive
Definition: kobuki.hpp:180
bool is_enabled
Definition: kobuki.hpp:181
int controller_info_reminder
Definition: kobuki.hpp:220
Firmware firmware
Definition: kobuki.hpp:209
ecl::Serial serial
Definition: kobuki.hpp:214
Simple packet finder.
The event manager - sigslot interface.
ecl::Signal< const std::vector< short > & > sig_raw_control_command
Definition: kobuki.hpp:263
Command kobuki_command
Definition: kobuki.hpp:232
ecl::Signal< const VersionInfo & > sig_version_info
Definition: kobuki.hpp:258
Provides simple packet finder which may be consist of stx, etx, payload, ...
GpInput::Data getGpInputData() const
Definition: kobuki.hpp:136
bool shutdown_requested
Definition: kobuki.hpp:175
bool isShutdown() const
Definition: kobuki.hpp:98
Inertia inertia
Definition: kobuki.hpp:203
#define kobuki_PUBLIC
Definition: macros.hpp:39
UniqueDeviceID unique_device_id
Definition: kobuki.hpp:210
ecl::Signal< Command::Buffer & > sig_raw_data_command
Definition: kobuki.hpp:261
Parameter list and validator for the kobuki.
Definition: parameters.hpp:36
double heading_offset
Definition: kobuki.hpp:186
Convenience header for modules.
int version_info_reminder
Definition: kobuki.hpp:219
Command structure.
DockIR::Data getDockIRData() const
Definition: kobuki.hpp:132
Macros for kobuki_driver.
DockIR dock_ir
Definition: kobuki.hpp:204
ecl::Mutex data_mutex
Definition: kobuki.hpp:231
Parameters parameters
Definition: kobuki.hpp:191
ThreeAxisGyro::Data getRawInertiaData() const
Definition: kobuki.hpp:137
VersionInfo versionInfo() const
Definition: kobuki.hpp:123
The core kobuki driver class.
Definition: kobuki.hpp:87
Inertia::Data getInertiaData() const
Definition: kobuki.hpp:135
std::vector< std::string > log(std::string level, std::string name, std::string msg)
Definition: kobuki.hpp:246
ThreeAxisGyro three_axis_gyro
Definition: kobuki.hpp:211
Hardware hardware
Definition: kobuki.hpp:208
Version info for the kobuki driver.
CoreSensors core_sensors
Definition: kobuki.hpp:202
ecl::Mutex command_mutex
Definition: kobuki.hpp:227
bool isEnabled() const
Definition: kobuki.hpp:99
GpInput gp_input
Definition: kobuki.hpp:207
Battery level module.
Definition: battery.hpp:40
Cliff::Data getCliffData() const
Definition: kobuki.hpp:133
bool isAlive() const
Definition: kobuki.hpp:97
ecl::Signal< const std::string & > sig_warn
Definition: kobuki.hpp:259
unsigned short data[MAX_DATA_SIZE]
Packets convenience header.
ecl::Signal< const std::vector< std::string > & > sig_named
Definition: kobuki.hpp:260
An acceleration limiter for the kobuki.
PacketFinder packet_finder
Definition: kobuki.hpp:215
CoreSensors::Data getCoreSensorData() const
Definition: kobuki.hpp:131
Parameter configuration for the kobuki.
bool is_connected
Definition: kobuki.hpp:192
#define EXP_TEMPLATE
Definition: macros.hpp:41
std::vector< std::string > log(std::string level, std::string msg)
Definition: kobuki.hpp:245
std::vector< short > velocity_commands_debug
Definition: kobuki.hpp:234
ControllerInfo::Data getControllerInfoData() const
Definition: kobuki.hpp:138
ecl::Signal sig_stream_data
Definition: kobuki.hpp:257
PacketFinder::BufferType data_buffer
Definition: kobuki.hpp:216


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Fri Sep 18 2020 03:22:02