Roomba
Roomba.h
1 // Roomba.h
2 //
3 ///
4 /// \mainpage Roomba library for Arduino
5 ///
6 /// This is the Arduino Roomba library.
7 /// It provides an object-oriented interface for talking to iRobot Roomba and Create robots
8 /// via a serial port.
9 /// The Roomba is the original device from iRobot. It has a serial port DIN socket on the side.
10 /// The Create is a more full-featured robot platform for hobbyists. It has both the DIN socket and a DB25
11 /// connector called the CArgo Bay Connector
12 ///
13 /// The Create understands a superset of the Roomba commands. This library supports both devices. Where
14 /// comands are only available on one or the other platform it is noted.
15 ///
16 /// The version of the package that this documentation refers to can be downloaded
17 /// from http://www.airspayce.com/mikem/arduino/Roomba/Roomba-1.4.zip
18 /// You can find the latest version at http://www.airspayce.com/mikem/arduino/Roomba
19 ///
20 /// tested on Arduino 1.8.1 with ESP8266
21 ///
22 /// A number of example programs are included that work with the iRobot Create:
23 /// \li TestSuite Runs on a Mega and exercises a number of the functions, checking for correct operation
24 /// \li RoombaTest1 Runs in any Arduino, checks that sensors can be read from Create using the stream() command
25 /// \li RoombaRCRx OBSOLETE
26 /// \li RoombaRCRxESP8266Demo program that shows how to control a Create using the RCRx Arduino library,
27 /// an ESP8266 with built-in WiFi and the RCTx
28 /// iPhone app. Control a Create from your iPhone!
29 ///
30 /// A video domonstating this library (along with the http://www.airspayce.com/mikem/arduino/RCKit library)
31 /// being used to control a Create from an iPhone or iPad can be found at http://www.youtube.com/watch?v=Qv-5ZOb5WW4
32 ///
33 /// \par Installation
34 /// Install in the usual way: unzip the distribution zip file to the libraries
35 /// sub-folder of your sketchbook.
36 ///
37 /// \par Prerequisites
38 /// Install the RCRx library verison 2.6 or later from http://www.airspayce.com/mikem/arduino/RCKit/
39 ///
40 /// This software is Copyright (C) 2010 Mike McCauley. Use is subject to license
41 /// conditions. The main licensing options available are GPL V2 or Commercial:
42 ///
43 /// \par Open Source Licensing GPL V2
44 /// This is the appropriate option if you want to share the source code of your
45 /// application with everyone you distribute it to, and you also want to give them
46 /// the right to share who uses it. If you wish to use this software under Open
47 /// Source Licensing, you must contribute all your source code to the open source
48 /// community in accordance with the GPL Version 2 when your application is
49 /// distributed. See http://www.gnu.org/copyleft/gpl.html
50 ///
51 /// \par Commercial Licensing
52 /// This is the appropriate option if you are creating proprietary applications
53 /// and you are not prepared to distribute and share the source code of your
54 /// application. Contact info@airspayce.com for details.
55 ///
56 /// \par Revision History
57 /// \version 1.0 Initial release
58 /// \version 1.1 Updated docs, added Youtube video
59 /// \version 1.2 Compiles under Arduino 1.0
60 /// \version 1.3 Updated author and distribution location details to airspayce.com
61 /// \version 1.4 2018-09-19 Added RoombaRCRxESP8266.ino example. RoombaRCRx.pde
62 /// is now obsolete.
63 ///
64 /// \author Mike McCauley (mikem@airspayce.com)
65 // Copyright (C) 2010 Mike McCauley
66 // $Id: Roomba.h,v 1.1 2010/09/27 21:58:32 mikem Exp mikem $
67 
68 #ifndef Roomba_h
69 #define Roomba_h
70 
71 #if (ARDUINO < 100)
72 #include "WProgram.h"
73 #else
74 #include <Arduino.h>
75 #endif
76 
77 /// Masks for LEDs in leds()
78 #define ROOMBA_MASK_LED_NONE 0
79 #define ROOMBA_MASK_LED_PLAY 0x2
80 #define ROOMBA_MASK_LED_ADVANCE 0x8
81 
82 /// Masks for digitalOut()
83 #define ROOMBA_MASK_DIGITAL_OUT_0 0x1
84 #define ROOMBA_MASK_DIGITAL_OUT_1 0x2
85 #define ROOMBA_MASK_DIGITAL_OUT_2 0x4
86 
87 /// Masks for drivers()
88 #define ROOMBA_MASK_DRIVER_0 0x1
89 #define ROOMBA_MASK_DRIVER_1 0x2
90 #define ROOMBA_MASK_DRIVER_2 0x4
91 /// Roomba only:
92 #define ROOMBA_MASK_SIDE_BRUSH 0x1
93 #define ROOMBA_MASK_VACUUM 0x2
94 #define ROOMBA_MASK_MAIN_BRUSH 0x4
95 
96 /// Masks for bumps and wheedrops sensor packet id 7
97 #define ROOMBA_MASK_BUMP_RIGHT 0x1
98 #define ROOMBA_MASK_BUMP_LEFT 0x2
99 #define ROOMBA_MASK_WHEELDROP_RIGHT 0x4
100 #define ROOMBA_MASK_WHEELDROP_LEFT 0x8
101 #define ROOMBA_MASK_WHEELDROP_CASTER 0x10
102 
103 /// Masks for driver overcurrents Packet ID 13
104 #define ROOMBA_MASK_LD1 0x1
105 #define ROOMBA_MASK_LD0 0x2
106 #define ROOMBA_MASK_LD2 0x4
107 #define ROOMBA_MASK_RIGHT_WHEEL 0x8
108 #define ROOMBA_MASK_LEFT_WHEEL 0x10
109 // Roomba, use ROOMBA_MASK_SIDE_BRUSH, ROOMBA_MASK_VACUUM, ROOMBA_MASK_MAIN_BRUSH
110 
111 /// Masks for buttons sensor packet ID 18
112 /// Create
113 #define ROOMBA_MASK_BUTTON_PLAY 0x1
114 #define ROOMBA_MASK_BUTTON_ADVANCE 0x4
115 /// Roomba
116 #define ROOMBA_MASK_BUTTON_MAX 0x1
117 #define ROOMBA_MASK_BUTTON_CLEAN 0x2
118 #define ROOMBA_MASK_BUTTON_SPOT 0x4
119 #define ROOMBA_MASK_BUTTON_POWER 0x8
120 
121 /// Masks for digital inputs sensor packet ID 32
122 #define ROOMBA_MASK_DIGITAL_IN_0 0x1
123 #define ROOMBA_MASK_DIGITAL_IN_1 0x2
124 #define ROOMBA_MASK_DIGITAL_IN_2 0x4
125 #define ROOMBA_MASK_DIGITAL_IN_3 0x8
126 #define ROOMBA_MASK_DIGITAL_IN_DEVICE_DETECT 0x10
127 
128 /// Masks for charging sources sensor packet ID 34
129 #define ROOMBA_MASK_INTERNAL_CHARGER 0x1
130 #define ROOMBA_MASK_HOME_BASE 0x2
131 
132 /// \def ROOMBA_READ_TIMEOUT
133 /// Read timeout in milliseconds.
134 /// If we have to wait more than this to read a char when we are expecting one, then something is wrong.
135 #define ROOMBA_READ_TIMEOUT 200
136 
137 // You may be able to set this so you can use Roomba with NewSoftSerial
138 // instead of HardwareSerial
139 //#define HardwareSerial NewSoftSerial
140 
141 /////////////////////////////////////////////////////////////////////
142 /// \class Roomba Roomba.h <Roomba.h>
143 /// \brief Support for iRobot Roomba and Create platforms via serial port using the iRobot Open Interface (OI)
144 /// protocol.
145 ///
146 /// The iRobot Roomba and Create platforms support a serial port through which you can control and
147 /// interrogate the device. The protocol implemented here conforms to the Open Interface protocol described in the
148 /// iRobot Open Interface Command Reference. Not all commands are supported on both platforms. Differences are
149 /// noted in the API
150 ///
151 /// The Roomba and Create is equipped with a min-din serial port socket, while the Create
152 /// is also equipped with a 25-pin D connector called the Cargo Bay Connector. The
153 /// pins on the Cargo Bay Connector include the serial port, battery, digital inputs and
154 /// outputs, and an analog input.
155 ///
156 /// In order to communicate with a Roomba, you must create an instance of the Roomba class and then call its
157 /// instance methods to send commmands and receive sensor messages. You can also request continuous
158 /// streams of sensor data to be sent by the Roomba. The Roomba also emits messages on its
159 /// serial port from time to time as described below.
160 ///
161 /// \par Electrical Considerations
162 ///
163 /// The serial port output TXD from the Roomba/Create is too weak to drive the RX serial port input
164 /// of an Arduino properly.
165 /// This is because of the USB-Serial converter on the Arduino: it also tries to drive the RX serial port input
166 /// via a pullup resistor,
167 /// but the Roomba does not have enough drive to pull the RX down below about 2.5 volts, which is insufficient
168 /// to be reliably detected as a TTL serial input of 0.
169 ///
170 /// \note Note that this problem does not affect the Serial1 Serial2 or Serial3 ports on the Mega: these ports do not
171 /// have other circuitry connected to them and the Roomba can drive the serial port inputs of these ports
172 /// without a problem. Its only the RX Serial port (ie the first Serial port) that is affected by this problem.
173 ///
174 /// What this means is that if you intend to connect a Roomba to the standard (first) RX/TX serial port on an Arduino
175 /// you \a MUST have additional circuitry to help drive RX on the Arduino low enough.
176 /// We use a simple PNP emitter follower. Almost any small signal low power PNP will do.
177 /// See the <a href="Create-Arduino.pdf">example circuit diagram</a>. This will ensure the RX serial
178 /// port input on the Arduino is pulled down to about 0.6V for reliable comms.
179 ///
180 /// \par Other Roomba messages
181 ///
182 /// When iRobot Create powers up and after a reset, it sends a message like this on its serial port:
183 /// \code
184 /// bl-start
185 /// 2006-09-12-1137-L
186 /// RDK by iRobot!
187 /// MC9S12E128
188 /// 2006-11-20-1731-L
189 /// battery-current-quiescent-raw 524 battery-current-zero 510
190 ///
191 /// 2006-11-20-1731-L
192 /// \endcode
193 ///
194 /// While charging it will send a message like this each second:
195 /// \code
196 /// bat: min 3 sec 21 mV 15558 mA 1491 deg-C 24
197 /// \endcode
198 ///
199 /// To enter the factory test menu for the IRobot Create, hold down the (>) and (>>|)
200 /// buttons then press and hold the Power button until the assending and descending tones play and then stop.
201 /// You wil see some messages emitted on teh serial port.
202 /// Press the right-right arrow button to cycle through the tests.
203 ///
204 class Roomba
205 {
206 public:
207  /// \enum Baud
208  /// Demo types to pass to Roomba::baud()
209  typedef enum
210  {
211  Baud300 = 0,
212  Baud600 = 1,
213  Baud1200 = 2,
214  Baud2400 = 3,
215  Baud4800 = 4,
216  Baud9600 = 5,
217  Baud14400 = 6,
218  Baud19200 = 7,
219  Baud28800 = 8,
220  Baud38400 = 9,
221  Baud57600 = 10,
222  Baud115200 = 11,
223  } Baud;
224 
225  /// \enum Demo
226  /// Demo types to pass to Roomba::demo()
227  typedef enum
228  {
229  DemoAbort = -1,
230  DemoCover = 0,
231  DemoCoverAndDock = 1,
232  DemoSpotCover = 2,
233  DemoMouse = 3,
234  DemoDriveFigureEight = 4,
235  DemoWimp = 5,
236  DemoHome = 6,
237  DemoTag = 7,
238  DemoPachelbel = 8,
239  DemoBanjo = 9,
240  } Demo;
241 
242  /// \enum Drive
243  /// Special values for radius in Roomba::drive()
244  typedef enum
245  {
246  DriveStraight = 0x8000,
247  DriveInPlaceClockwise = 0xFFFF,
248  DriveInPlaceCounterClockwise = 0x0001,
249  } Drive;
250 
251  /// \enum StreamCommand
252  /// Values to pass to Roomba::streamCommand()
253  typedef enum
254  {
255  StreamCommandPause = 0,
256  StreamCommandResume = 1,
257  } StreamCommand;
258 
259  /// \enum EventType
260  /// Values to pass to Roomba::waitEvent()
261  typedef enum
262  {
263  EventTypeWheelDrop = 1,
264  EventTypeFronWheelDrop = 2,
265  EventTypeLeftWheelDrop = 3,
266  EventTypeRightWheelDrop = 4,
267  EventTypeBump = 5,
268  EventTypeLeftBump = 6,
269  EventTypeRightBump = 7,
270  EventTypeVirtualWall = 8,
271  EventTypeWall = 9,
272  EventTypeCliff = 10,
273  EventTypeLeftCliff = 11,
274  EventTypeFrontLeftCliff = 12,
275  EventTypeFrontRightCliff = 13,
276  EventTypeRightCliff = 14,
277  EventTypeHomeBase = 15,
278  EventTypeAdvanceButton = 16,
279  EventTypePlayButton = 17,
280  EventTypeDigitalInput0 = 18,
281  EventTypeDigitalInput1 = 19,
282  EventTypeDigitalInput2 = 20,
283  EventTypeDigitalInput3 = 21,
284  EventTypeModePassive = 22,
285  } EventType;
286 
287  /// \enum IRCommand
288  /// Values for sensor packet ID 27
289  typedef enum
290  {
291  // Remote control:
292  IRCommandLeft = 129,
293  IRCommandForward = 130,
294  IRCommandRight = 131,
295  IRCommandSpot = 132,
296  IRCommandMax = 133,
297  IRCommandSmall = 134,
298  IRCommandMedium = 135,
299  IRCommandLargeClean = 136,
300  IRCommandPause = 137,
301  IRCommandPower = 138,
302  IRCommandArcForwardLeft = 139,
303  IRCommandArcForwardRight = 140,
304  IRCommandDriveStop = 141,
305  // Scheduling Remote:
306  IRCommandSendAll = 142,
307  IRCommandSeekDock = 143,
308  // Home Base:
309  IRCommandReserved1 = 240,
310  IRCommandRedBuoy = 248,
311  IRCommandGreenBuoy = 244,
312  IRCommandForceField = 242,
313  IRCommandRedGreenBuoy = 252,
314  IRCommandRedBuoyForceField = 250,
315  IRCommandGreenBuoyForceField = 246,
316  IRCommandRedGreenBuoyForceField = 254,
317  } IRCommand;
318 
319  /// \enum ChargeState
320  /// Values for sensor packet ID 21
321  typedef enum
322  {
323  ChargeStateNotCharging = 0,
324  ChargeStateReconditioningCharging = 1,
325  ChargeStateFullChanrging = 2,
326  ChargeStateTrickleCharging = 3,
327  ChargeStateWaiting = 4,
328  ChargeStateFault = 5,
329  } ChargeState;
330 
331  /// \enum Mode
332  /// Values for sensor packet ID 35
333  typedef enum
334  {
335  ModeOff = 0,
336  ModePassive = 1,
337  ModeSafe = 2,
338  ModeFull = 3,
339  } Mode;
340 
341  /// \enum Sensor
342  /// Values for sensor packet IDs to pass to getSensors() and getSensorsList()
343  typedef enum
344  {
345  Sensors7to26 = 0,
346  Sensors7to16 = 1,
347  Sensors17to20 = 2,
348  Sensors21to26 = 3,
349  Sensors27to34 = 4,
350  Sensors35to42 = 5,
351  Sensors7to42 = 6,
352  SensorBumpsAndWheelDrops = 7,
353  SensorWall = 8,
354  SensorCliffLeft = 9,
355  SensorCliffFrontLeft = 10,
356  SensorCliffFrontRight = 11,
357  SensorCliffRight = 12,
358  SensorVirtualWall = 13,
359  SensorOvercurrents = 14,
360 // SensorUnused1 = 15,
361 // SensorUnused2 = 16,
362  SensorIRByte = 17,
363  SensorButtons = 18,
364  SensorDistance = 19,
365  SensorAngle = 20,
366  SensorChargingState = 21,
367  SensorVoltage = 22,
368  SensorCurrent = 23,
369  SensorBatteryTemperature = 24,
370  SensorBatteryCharge = 25,
371  SensorBatteryCapacity = 26,
372  SensorWallSignal = 27,
373  SensoCliffLeftSignal = 28,
374  SensoCliffFrontLeftSignal = 29,
375  SensoCliffFrontRightSignal = 30,
376  SensoCliffRightSignal = 31,
377  SensorUserDigitalInputs = 32,
378  SensorUserAnalogInput = 33,
379  SensorChargingSourcesAvailable = 34,
380  SensorOIMode = 35,
381  SensorSongNumber = 36,
382  SensorSongPlaying = 37,
383  SensorNumberOfStreamPackets = 38,
384  SensorVelocity = 39,
385  SensorRadius = 40,
386  SensorRightVelocity = 41,
387  SensorLeftVelocity = 42,
388  } Sensor;
389 
390  /// Constructor. You can have multiple simultaneous Roomba if that makes sense.
391  /// \param[in] serial POinter to the HardwareSerial port to use to communicate with the Roomba.
392  /// Defaults to &Serial
393  /// \param[in] baud the baud rate to use on the serial port. Defaults to 57600, the default for the Roomba.
394  Roomba(HardwareSerial* serial = &Serial, Baud baud = Baud57600);
395 
396  /// Resets the Roomba.
397  /// It will emit its startup message
398  /// Caution, this may take several seconds to complete
399  void reset();
400 
401  /// Starts the Open Interface and sets the mode to Passive.
402  /// You must send this before sending any other commands.
403  /// Initialises the serial port to the baud rate given in the constructor
404  void start();
405 
406  /// Converts the specified baud code into a baud rate in bits per second
407  /// \param[in] baud Baud code, one of Roomba::Baud
408  /// \return baud rate in bits per second
409  uint32_t baudCodeToBaudRate(Baud baud);
410 
411  /// Changes the baud rate
412  /// Baud is on of the Roomba::Baud enums
413  void baud(Baud baud);
414 
415  /// Sets the OI to Safe mode.
416  /// In Safe mode, the cliff and wheel drop detectors work to prevent Roomba driving off a cliff
417  void safeMode();
418 
419  /// Sets the OI to Full mode.
420  /// In Full mode, the cliff and wheel drop detectors do not stop the motors: you are responsible
421  // for full control of the Roomba
422  void fullMode();
423 
424  /// Puts a Roomba in sleep mode.
425  /// Roomba only, no equivalent for Create.
426  void power();
427 
428  /// Causes roomba to immediately
429  /// seek the docking station.
430  /// No equivalent for Create.
431  void dock();
432 
433  /// Starts the requirested built-in demo
434  /// \param[in] demo The demo number. One of Roomba::Demo
435  void demo(Demo demo);
436 
437  /// Starts the Cover demo
438  /// Changes mode to Passive
439  void cover();
440 
441  /// Starts the Cover and Dock demo
442  /// Changes mode to Passive
443  void coverAndDock();
444 
445  /// Starts the Spot Cover demo
446  /// Changes mode to Passive
447  void spot();
448 
449  /// Starts the Roomba driving with a specified wheel velocity and radius of turn
450  /// \param[in] velocity Speed in mm/s (-500 to 500 mm/s)
451  /// \param[in] radius Radius of the turn in mm. (-2000 to 2000 mm).
452  /// Any of the special values in enum Roomba::Drive may be used instead of a radius value
453  void drive(int16_t velocity, int16_t radius);
454 
455  /// Starts the Roomba driving with a specified velocity for each wheel
456  /// Create only. No equivalent on Roomba.
457  /// \param[in] leftVelocity Left wheel velocity in mm/s (-500 to 500 mm/s)
458  /// \param[in] rightVelocity Right wheel velocity in mm/s (-500 to 500 mm/s)
459  void driveDirect(int16_t leftVelocity, int16_t rightVelocity);
460 
461  /// Controls the LEDs on the Create
462  /// \param[in] leds Bitmask specifying which LEDs to activate. ORed combination of ROOMBA_MASK_LED_*
463  /// \param[in] powerColour The colour of the Power LED. 0 to 255. 0 = green, 255 = red,
464  /// intermediate values are intermediate colours
465  /// \param[in] powerIntensity Power LED intensity. 0 to 255. 0 = off, 255 = full intensity
466  void leds(uint8_t leds, uint8_t powerColour, uint8_t powerIntensity);
467 
468  /// Sets the digital output pins on the Cargo Bay Connector of the Create
469  /// Create only. No equivalent on Roomba.
470  /// \param[in] out Mask specifiying which outputs to enable. ORed value ROOMBA_MASK_DIGITAL_OUT_*
471  void digitalOut(uint8_t out);
472 
473  /// Sets the duty cycle for PWM outputs on the low side drivers. These can be use for PWM driving of
474  /// motors, lights etc.
475  /// Create only. No equivalent on Roomba.
476  /// \param[in] dutyCycle0 Duty cycle for low side driver 0. 0 to 128.
477  /// \param[in] dutyCycle1 Duty cycle for low side driver 1. 0 to 128.
478  /// \param[in] dutyCycle2 Duty cycle for low side driver 2. 0 to 128.
479  void pwmDrivers(uint8_t dutyCycle0, uint8_t dutyCycle1, uint8_t dutyCycle2);
480 
481  /// Sets the low side drivers on or off. On the Romba, these control the 3 motors.
482  /// \param[in] out Bitmask of putputs to enable. ORed value ROOMBA_MASK_DRIVER_*
483  void drivers(uint8_t out);
484 
485  /// Sends the requested byte out of the low side driver 1 (pin 23 on the Cargo Bay Connector).
486  /// low side driver 1 can be used to drive an IR transmitter to send commands to other Roombas and Creates.
487  /// Create only. No equivalent on Roomba.
488  /// \param[in] data Data byte to transmit
489  void sendIR(uint8_t data);
490 
491  /// Defines a song which can later be played with playSong()
492  /// \param[in] songNumber Song number for this song. 0 to 15
493  /// \param[in] notes Array of note/duration pairs. See Open Interface manual for details. 2 bytes per note,
494  /// first byte is the note and the second is the duration
495  /// \param[in] len Length of notes array in bytes, so this will be twice the number of notes in the song
496  void song(uint8_t songNumber, const uint8_t* notes, int len);
497 
498  /// Plays a song that has previously been defined by song()
499  /// \param[in] songNumber The song number to play. 0 to 15
500  void playSong(uint8_t songNumber);
501 
502  /// Requests that a stream of sensor data packets be sent by the Roomba.
503  /// See the Open Interface manual for details on the resutting data.
504  /// The packets will be sent every 15ms.
505  /// You can use pollSensors() to receive sensor data streams.
506  /// Create only. No equivalent on Roomba.
507  /// See the Open Interface maual for more details and limitations.
508  /// \param[in] packetIDs Array specifying sensor packet IDs from Roomba::Sensor to be sent.
509  /// \param[in] len Number of IDs in packetIDs
510  void stream(const uint8_t* packetIDs, int len);
511 
512  /// Pause or resume a stream of sensor data packets previously requested by stream()
513  /// Create only. No equivalent on Roomba.
514  /// \param[in] command One of Roomba::StreamCommand
515  void streamCommand(StreamCommand command);
516 
517  /// Defines a command script which can later be executed with playScript(). You can clear the script by calling
518  /// script(NULL, 0);
519  /// Create only. No equivalent on Roomba.
520  /// \param[in] script Array containing a sequence of Roomba OI commands.
521  /// \param[in] len Length of the script in bytes.
522  void script(const uint8_t* script, uint8_t len);
523 
524  /// Executes a previously defined script,
525  /// the last one specified by script()
526  /// Create only. No equivalent on Roomba.
527  void playScript();
528 
529  /// Tells the Roomba to wait for a specified time.
530  /// This command is intended for use in scripting only.
531  /// Create only. No equivalent on Roomba.
532  /// \param[in] ticks The number of ticks to wait. Each tick is 15ms
533  void wait(uint8_t ticks);
534 
535  /// Causes Roomba to wait until it has travelled the distance specified.
536  /// Roomba will not react to any inputs until the wait has completed.
537  /// Note that this does not cause the host arduino to wait, it only sends the wait comman to the Roomba
538  /// This command is intended for use in scripting only.
539  /// Create only. No equivalent on Roomba.
540  /// \param[in] mm Distance to wait for in mm
541  void waitDistance(int16_t mm);
542 
543  /// Causes Roomba to wait until it has rotated through the specified angle.
544  /// Roomba will not react to any inputs until the wait has completed.
545  /// Note that this does not cause the host arduino to wait, it only sends the wait comman to the Roomba
546  /// This command is intended for use in scripting only.
547  /// Create only. No equivalent on Roomba.
548  /// \param[in] degrees Angle to wait for in degrees
549  void waitAngle(int16_t degrees);
550 
551  /// Cause the Create to wait for a specified event.
552  /// Roomba will not react to any inputs until the wait has completed.
553  /// Note that this does not cause the host arduino to wait, it only sends the wait comman to the Roomba
554  /// Create only. No equivalent on Roomba.
555  /// \param[in] type Event type to wait for. One of Roomba::EventType
556  void waitEvent(EventType type);
557 
558  /// Low level funciton to read len bytes of data from the Roomba
559  /// Blocks untill all len bytes are read or a read timeout occurs.
560  /// \param[out] dest Destination where the read data is stored. Must have at least len bytes available.
561  /// \param[in] len Number of bytes to read
562  /// \return true if all len bytes were successfully read. Returns false in the case of a timeout
563  /// on reading any byte.
564  bool getData(uint8_t* dest, uint8_t len);
565 
566  /// Reads the sensor data for the specified sensor packet ID. Note that different sensor packets have
567  /// different lengths, and it is the callers responsibilty to make sure len agrees with the expected
568  /// length of the sensor data. See the Open Interface manual for details on sensor packet lengths.
569  /// Roomba.h defines various enums and defines for decoding sensor data.
570  /// Blocks untill all len bytes are read or a read timeout occurs.
571  /// \param[in] packetID The ID of the sensor packet to read from Roomba::Sensor
572  /// \param[out] dest Destination where the read data is stored. Must have at least len bytes available.
573  /// \param[in] len Number of sensor data bytes to read
574  /// \return true if all len bytes were successfully read. Returns false in the case of a timeout
575  /// on reading any byte.
576  bool getSensors(uint8_t packetID, uint8_t* dest, uint8_t len);
577 
578  /// Reads the sensor data for the specified set of sensor packet IDs. Note that different sensor packets have
579  /// different lengths, and it is the callers responsibilty to make sure len agrees with the expected
580  /// length of the sensor data. See the Open Interface manual for details on sensor packet lengths.
581  /// Blocks until all len bytes are read or a read timeout occurs.
582  /// Create only. No equivalent on Roomba.
583  /// \param[in] packetIDs Array of IDs from Roomba::Sensor of the sensor packets to read
584  /// \param[in] numPacketIDs number of IDs in the packetIDs array
585  /// \param[out] dest Destination where the read data is stored. Must have at least len bytes available.
586  /// \param[in] len Number of sensor data bytes to read and store to dest.
587  /// \return true if all len bytes were successfully read. Returns false in the case of a timeout
588  /// on reading any byte.
589  bool getSensorsList(uint8_t* packetIDs, uint8_t numPacketIDs, uint8_t* dest, uint8_t len);
590 
591  /// Polls the serial input for data belonging to a sensor data stream previously requested with stream().
592  /// As sensor data is read it is appended to dest until at most len bytes are stored there.
593  /// When a complete sensor stream has been read with a correct checksum, returns true.
594  /// See the Open Interface manual for details on how the sensor data will be encoded in dest.
595  /// Discards characters that are not part of a stream, such as the messages the Roomba
596  /// sends at startup and while charging.
597  /// Create only. No equivalent on Roomba.
598  /// \param[out] dest Destination where the read data is stored. Must have at least len bytes available.
599  /// \param[in] len Max number of sensor data bytes to store to dest
600  /// \return true when a complete stream has been read, and the checksum is correct. The sensor data
601  /// (at most len bytes) will have been stored into dest, ready for the caller to decode.
602  bool pollSensors(uint8_t* dest, uint8_t len);
603 
604  /// Reads a the contents of the script most recently specified by a call to script().
605  /// Create only. No equivalent on Roomba.
606  /// \param[out] dest Destination where the read data is stored. Must have at least len bytes available.
607  /// \param[in] len The maximum number of bytes to place in dest. If the script is actually longer than len
608  /// only len bytes will be written
609  /// \return The actual number of bytes in the script, even if this is more than len. By calling
610  /// getScript(NULL, 0), you can determine how many bytes would be required to store the script.
611  uint8_t getScript(uint8_t* dest, uint8_t len);
612 
613 private:
614  /// \enum PollState
615  /// Values for _pollState
616  typedef enum
617  {
618  PollStateIdle = 0,
619  PollStateWaitCount = 1,
620  PollStateWaitBytes = 2,
621  PollStateWaitChecksum = 3,
622  } PollState;
623 
624  /// The baud rate to use for the serial port
625  uint32_t _baud;
626 
627  /// The serial port to use to talk to the Roomba
628  HardwareSerial* _serial;
629 
630  /// Variables for keeping track of polling of data streams
631  uint8_t _pollState; /// Current state of polling, one of Roomba::PollState
632  uint8_t _pollSize; /// Expected size of the data stream in bytes
633  uint8_t _pollCount; /// Num of bytes read so far
634  uint8_t _pollChecksum; /// Running checksum counter of data bytes + count
635 
636 };
637 
638 /// @example RoombaRCRxESP8266/RoombaRCRxESP8266.ino
639 /// Sample RCRx RCOIP receiver for driving a Create
640 /// Receives RCOIP commmands on a ESP8266 and uses them to control the wheel motors on a Create
641 /// Uses the driveDirect command so cant be used on Roomba
642 
643 /// @example TestSuite/TestSuite.pde
644 /// Test suite for the Roomba class
645 
646 #endif
void waitAngle(int16_t degrees)
Definition: Roomba.cpp:225
void start()
Definition: Roomba.cpp:23
void script(const uint8_t *script, uint8_t len)
Definition: Roomba.cpp:199
void leds(uint8_t leds, uint8_t powerColour, uint8_t powerIntensity)
Definition: Roomba.cpp:130
void dock()
Definition: Roomba.cpp:86
void waitDistance(int16_t mm)
Definition: Roomba.cpp:218
uint32_t baudCodeToBaudRate(Baud baud)
Definition: Roomba.cpp:29
void digitalOut(uint8_t out)
Definition: Roomba.cpp:138
void fullMode()
Definition: Roomba.cpp:76
void stream(const uint8_t *packetIDs, int len)
Definition: Roomba.cpp:185
void sendIR(uint8_t data)
Definition: Roomba.cpp:162
uint8_t getScript(uint8_t *dest, uint8_t len)
Definition: Roomba.cpp:315
Demo
Definition: Roomba.h:227
void playSong(uint8_t songNumber)
Definition: Roomba.cpp:178
void power()
Definition: Roomba.cpp:81
void playScript()
Definition: Roomba.cpp:206
void waitEvent(EventType type)
Definition: Roomba.cpp:233
void baud(Baud baud)
Definition: Roomba.cpp:62
void coverAndDock()
Definition: Roomba.cpp:102
void drivers(uint8_t out)
Definition: Roomba.cpp:154
bool pollSensors(uint8_t *dest, uint8_t len)
Definition: Roomba.cpp:276
void reset()
Definition: Roomba.cpp:16
void streamCommand(StreamCommand command)
Definition: Roomba.cpp:192
void driveDirect(int16_t leftVelocity, int16_t rightVelocity)
Definition: Roomba.cpp:121
void safeMode()
Definition: Roomba.cpp:71
Sensor
Definition: Roomba.h:343
void drive(int16_t velocity, int16_t radius)
Definition: Roomba.cpp:112
EventType
Definition: Roomba.h:261
Support for iRobot Roomba and Create platforms via serial port using the iRobot Open Interface (OI) p...
Definition: Roomba.h:204
bool getSensorsList(uint8_t *packetIDs, uint8_t numPacketIDs, uint8_t *dest, uint8_t len)
Definition: Roomba.cpp:267
void song(uint8_t songNumber, const uint8_t *notes, int len)
Definition: Roomba.cpp:170
StreamCommand
Definition: Roomba.h:253
void cover()
Definition: Roomba.cpp:97
ChargeState
Definition: Roomba.h:321
void pwmDrivers(uint8_t dutyCycle0, uint8_t dutyCycle1, uint8_t dutyCycle2)
Definition: Roomba.cpp:145
bool getData(uint8_t *dest, uint8_t len)
Definition: Roomba.cpp:244
Roomba(HardwareSerial *serial=&Serial, Baud baud=Baud57600)
Definition: Roomba.cpp:8
void wait(uint8_t ticks)
Definition: Roomba.cpp:212
Mode
Definition: Roomba.h:333
Drive
Definition: Roomba.h:244
Baud
Definition: Roomba.h:209
void spot()
Definition: Roomba.cpp:107
bool getSensors(uint8_t packetID, uint8_t *dest, uint8_t len)
Definition: Roomba.cpp:260
IRCommand
Definition: Roomba.h:289
void demo(Demo demo)
Definition: Roomba.cpp:91