Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Roomba.cpp@0:32eb0835b5a3, 2015-01-20 (annotated)
- Committer:
- YosukeK
- Date:
- Tue Jan 20 15:58:19 2015 +0000
- Revision:
- 0:32eb0835b5a3
- Child:
- 1:aed433d882c9
First commit.
Who changed what in which revision?
| User | Revision | Line number | New contents of line | 
|---|---|---|---|
| YosukeK | 0:32eb0835b5a3 | 1 | #include "mbed.h" | 
| YosukeK | 0:32eb0835b5a3 | 2 | #include "Roomba.h" | 
| YosukeK | 0:32eb0835b5a3 | 3 | |
| YosukeK | 0:32eb0835b5a3 | 4 | /** | 
| YosukeK | 0:32eb0835b5a3 | 5 | * @bref コンストラクタ | 
| YosukeK | 0:32eb0835b5a3 | 6 | * @param tx | 
| YosukeK | 0:32eb0835b5a3 | 7 | * @param rx | 
| YosukeK | 0:32eb0835b5a3 | 8 | */ | 
| YosukeK | 0:32eb0835b5a3 | 9 | Roomba::Roomba(PinName tx, PinName rx, PinName led): | 
| YosukeK | 0:32eb0835b5a3 | 10 | _s(tx, rx), _led(led){ | 
| YosukeK | 0:32eb0835b5a3 | 11 | count = 0; | 
| YosukeK | 0:32eb0835b5a3 | 12 | timedOut = false; | 
| YosukeK | 0:32eb0835b5a3 | 13 | _led = 0; | 
| YosukeK | 0:32eb0835b5a3 | 14 | //_mode = Roomba::Mode::Off; | 
| YosukeK | 0:32eb0835b5a3 | 15 | Roomba::mp = &Roomba::serialReceiveCallback; | 
| YosukeK | 0:32eb0835b5a3 | 16 | _s.attach(this, Roomba::mp, Serial::RxIrq); | 
| YosukeK | 0:32eb0835b5a3 | 17 | } | 
| YosukeK | 0:32eb0835b5a3 | 18 | |
| YosukeK | 0:32eb0835b5a3 | 19 | |
| YosukeK | 0:32eb0835b5a3 | 20 | /** | 
| YosukeK | 0:32eb0835b5a3 | 21 | * @bref コマンド送信インターフェースの実装 | 
| YosukeK | 0:32eb0835b5a3 | 22 | * @param e イベント引数 | 
| YosukeK | 0:32eb0835b5a3 | 23 | * @return true | 
| YosukeK | 0:32eb0835b5a3 | 24 | */ | 
| YosukeK | 0:32eb0835b5a3 | 25 | bool Roomba::send(EventArg e) { | 
| YosukeK | 0:32eb0835b5a3 | 26 | _led != _led; | 
| YosukeK | 0:32eb0835b5a3 | 27 | Roomba::start(); | 
| YosukeK | 0:32eb0835b5a3 | 28 | Roomba::mode(Roomba::Full);//(Roomba::Mode::Full); If write struct Mode and no name enum, Compiler say no sutable constructor conver to enum... | 
| YosukeK | 0:32eb0835b5a3 | 29 | Roomba::drive(e.leftWheetVelocity, e.rightWheelVelocity); | 
| YosukeK | 0:32eb0835b5a3 | 30 | |
| YosukeK | 0:32eb0835b5a3 | 31 | return true; | 
| YosukeK | 0:32eb0835b5a3 | 32 | } | 
| YosukeK | 0:32eb0835b5a3 | 33 | |
| YosukeK | 0:32eb0835b5a3 | 34 | /** | 
| YosukeK | 0:32eb0835b5a3 | 35 | * @bref コマンド送信結果受信時のインターフェースの実装 | 
| YosukeK | 0:32eb0835b5a3 | 36 | * @param result コマンド送信結果 | 
| YosukeK | 0:32eb0835b5a3 | 37 | */ | 
| YosukeK | 0:32eb0835b5a3 | 38 | void Roomba::notify(bool result) { | 
| YosukeK | 0:32eb0835b5a3 | 39 | if (result == false) { | 
| YosukeK | 0:32eb0835b5a3 | 40 | _led = 1; | 
| YosukeK | 0:32eb0835b5a3 | 41 | } else { | 
| YosukeK | 0:32eb0835b5a3 | 42 | _led = 0; | 
| YosukeK | 0:32eb0835b5a3 | 43 | } | 
| YosukeK | 0:32eb0835b5a3 | 44 | } | 
| YosukeK | 0:32eb0835b5a3 | 45 | |
| YosukeK | 0:32eb0835b5a3 | 46 | |
| YosukeK | 0:32eb0835b5a3 | 47 | /** | 
| YosukeK | 0:32eb0835b5a3 | 48 | * @bref 周期タイマのコールバックメソッド | 
| YosukeK | 0:32eb0835b5a3 | 49 | * @param e イベント引数 | 
| YosukeK | 0:32eb0835b5a3 | 50 | */ | 
| YosukeK | 0:32eb0835b5a3 | 51 | void Roomba::periodicCallback(EventArg e) { | 
| YosukeK | 0:32eb0835b5a3 | 52 | |
| YosukeK | 0:32eb0835b5a3 | 53 | count = count + 1; | 
| YosukeK | 0:32eb0835b5a3 | 54 | |
| YosukeK | 0:32eb0835b5a3 | 55 | if (count > 100) { | 
| YosukeK | 0:32eb0835b5a3 | 56 | if (timedOut == false) { | 
| YosukeK | 0:32eb0835b5a3 | 57 | timedOut = true; | 
| YosukeK | 0:32eb0835b5a3 | 58 | Roomba::notify(timedOut); | 
| YosukeK | 0:32eb0835b5a3 | 59 | } | 
| YosukeK | 0:32eb0835b5a3 | 60 | } | 
| YosukeK | 0:32eb0835b5a3 | 61 | |
| YosukeK | 0:32eb0835b5a3 | 62 | _s.putc('1'); | 
| YosukeK | 0:32eb0835b5a3 | 63 | Roomba::send(e); | 
| YosukeK | 0:32eb0835b5a3 | 64 | |
| YosukeK | 0:32eb0835b5a3 | 65 | } | 
| YosukeK | 0:32eb0835b5a3 | 66 | |
| YosukeK | 0:32eb0835b5a3 | 67 | /** | 
| YosukeK | 0:32eb0835b5a3 | 68 | * @bref シリアル受信時コールバックメソッド | 
| YosukeK | 0:32eb0835b5a3 | 69 | */ | 
| YosukeK | 0:32eb0835b5a3 | 70 | void Roomba::serialReceiveCallback() { | 
| YosukeK | 0:32eb0835b5a3 | 71 | count = 0; | 
| YosukeK | 0:32eb0835b5a3 | 72 | |
| YosukeK | 0:32eb0835b5a3 | 73 | _s.putc('2'); | 
| YosukeK | 0:32eb0835b5a3 | 74 | |
| YosukeK | 0:32eb0835b5a3 | 75 | if (timedOut) { | 
| YosukeK | 0:32eb0835b5a3 | 76 | timedOut = false; | 
| YosukeK | 0:32eb0835b5a3 | 77 | Roomba::notify(timedOut); | 
| YosukeK | 0:32eb0835b5a3 | 78 | } | 
| YosukeK | 0:32eb0835b5a3 | 79 | } | 
| YosukeK | 0:32eb0835b5a3 | 80 | |
| YosukeK | 0:32eb0835b5a3 | 81 | ///** | 
| YosukeK | 0:32eb0835b5a3 | 82 | // * @bref シリアル受信のアタッチ | 
| YosukeK | 0:32eb0835b5a3 | 83 | // */ | 
| YosukeK | 0:32eb0835b5a3 | 84 | ////継承先から操作できるようにしただけ | 
| YosukeK | 0:32eb0835b5a3 | 85 | //void Roomba::attachSerialReceiveCallback() { | 
| YosukeK | 0:32eb0835b5a3 | 86 | // Roomba::mp = &Roomba::serialReceiveCallback; | 
| YosukeK | 0:32eb0835b5a3 | 87 | // _s.attach(this, Roomba::mp, Serial::RxIrq); | 
| YosukeK | 0:32eb0835b5a3 | 88 | // //_s.attach(this, &Roomba::notify, Serial::RxIrq); | 
| YosukeK | 0:32eb0835b5a3 | 89 | //} | 
| YosukeK | 0:32eb0835b5a3 | 90 | |
| YosukeK | 0:32eb0835b5a3 | 91 | /** | 
| YosukeK | 0:32eb0835b5a3 | 92 | * @bref Start | 
| YosukeK | 0:32eb0835b5a3 | 93 | * @return true | 
| YosukeK | 0:32eb0835b5a3 | 94 | */ | 
| YosukeK | 0:32eb0835b5a3 | 95 | bool Roomba::start() { | 
| YosukeK | 0:32eb0835b5a3 | 96 | |
| YosukeK | 0:32eb0835b5a3 | 97 | _s.putc('a'); | 
| YosukeK | 0:32eb0835b5a3 | 98 | |
| YosukeK | 0:32eb0835b5a3 | 99 | _s.putc(128); | 
| YosukeK | 0:32eb0835b5a3 | 100 | |
| YosukeK | 0:32eb0835b5a3 | 101 | return true; | 
| YosukeK | 0:32eb0835b5a3 | 102 | } | 
| YosukeK | 0:32eb0835b5a3 | 103 | |
| YosukeK | 0:32eb0835b5a3 | 104 | |
| YosukeK | 0:32eb0835b5a3 | 105 | /** | 
| YosukeK | 0:32eb0835b5a3 | 106 | * @bref 操作モード変更メソッド | 
| YosukeK | 0:32eb0835b5a3 | 107 | * @param 操作モード | 
| YosukeK | 0:32eb0835b5a3 | 108 | * @return true | 
| YosukeK | 0:32eb0835b5a3 | 109 | */ | 
| YosukeK | 0:32eb0835b5a3 | 110 | bool Roomba::mode(Roomba::Mode m) { | 
| YosukeK | 0:32eb0835b5a3 | 111 | |
| YosukeK | 0:32eb0835b5a3 | 112 | _s.putc('b'); | 
| YosukeK | 0:32eb0835b5a3 | 113 | |
| YosukeK | 0:32eb0835b5a3 | 114 | _s.putc(132);//Full; | 
| YosukeK | 0:32eb0835b5a3 | 115 | |
| YosukeK | 0:32eb0835b5a3 | 116 | return true; | 
| YosukeK | 0:32eb0835b5a3 | 117 | } | 
| YosukeK | 0:32eb0835b5a3 | 118 | |
| YosukeK | 0:32eb0835b5a3 | 119 | |
| YosukeK | 0:32eb0835b5a3 | 120 | /** | 
| YosukeK | 0:32eb0835b5a3 | 121 | * @bref Start | 
| YosukeK | 0:32eb0835b5a3 | 122 | * @param true | 
| YosukeK | 0:32eb0835b5a3 | 123 | */ | 
| YosukeK | 0:32eb0835b5a3 | 124 | bool Roomba::drive(int rightWheelVelocity, int leftWheelVelocity) { | 
| YosukeK | 0:32eb0835b5a3 | 125 | |
| YosukeK | 0:32eb0835b5a3 | 126 | |
| YosukeK | 0:32eb0835b5a3 | 127 | bool ret = false; | 
| YosukeK | 0:32eb0835b5a3 | 128 | |
| YosukeK | 0:32eb0835b5a3 | 129 | if ((-500 <= rightWheelVelocity && rightWheelVelocity <= 500) | 
| YosukeK | 0:32eb0835b5a3 | 130 | && (-500 <= leftWheelVelocity && leftWheelVelocity <= 500)) { | 
| YosukeK | 0:32eb0835b5a3 | 131 | |
| YosukeK | 0:32eb0835b5a3 | 132 | Roomba::command[0] = 145; | 
| YosukeK | 0:32eb0835b5a3 | 133 | Roomba::command[1] = rightWheelVelocity & 0xFF00 >> 8; //MSB | 
| YosukeK | 0:32eb0835b5a3 | 134 | Roomba::command[2] = rightWheelVelocity & 0xFF; //LSB | 
| YosukeK | 0:32eb0835b5a3 | 135 | Roomba::command[3] = leftWheelVelocity & 0xFF00 >> 8; //MSB | 
| YosukeK | 0:32eb0835b5a3 | 136 | Roomba::command[4] = leftWheelVelocity & 0xFF; //LSB | 
| YosukeK | 0:32eb0835b5a3 | 137 | Roomba::command[5] = '\0'; | 
| YosukeK | 0:32eb0835b5a3 | 138 | |
| YosukeK | 0:32eb0835b5a3 | 139 | for (int i = 0; Roomba::command[i] != '\0'; i++) { | 
| YosukeK | 0:32eb0835b5a3 | 140 | _s.putc('c'); | 
| YosukeK | 0:32eb0835b5a3 | 141 | _s.putc(Roomba::command[i]); | 
| YosukeK | 0:32eb0835b5a3 | 142 | } | 
| YosukeK | 0:32eb0835b5a3 | 143 | |
| YosukeK | 0:32eb0835b5a3 | 144 | ret = true; | 
| YosukeK | 0:32eb0835b5a3 | 145 | } | 
| YosukeK | 0:32eb0835b5a3 | 146 | |
| YosukeK | 0:32eb0835b5a3 | 147 | return ret; | 
| YosukeK | 0:32eb0835b5a3 | 148 | } | 
| YosukeK | 0:32eb0835b5a3 | 149 | |
| YosukeK | 0:32eb0835b5a3 | 150 | /** | 
| YosukeK | 0:32eb0835b5a3 | 151 | * @bref バッテリ状態 | 
| YosukeK | 0:32eb0835b5a3 | 152 | * @param true | 
| YosukeK | 0:32eb0835b5a3 | 153 | * @return | 
| YosukeK | 0:32eb0835b5a3 | 154 | * @retval | 
| YosukeK | 0:32eb0835b5a3 | 155 | */ | 
| YosukeK | 0:32eb0835b5a3 | 156 | bool Roomba::battery(int* batteryCapacity) { | 
| YosukeK | 0:32eb0835b5a3 | 157 | bool ret = false; | 
| YosukeK | 0:32eb0835b5a3 | 158 | |
| YosukeK | 0:32eb0835b5a3 | 159 | *batteryCapacity = 100; | 
| YosukeK | 0:32eb0835b5a3 | 160 | |
| YosukeK | 0:32eb0835b5a3 | 161 | return ret; | 
| YosukeK | 0:32eb0835b5a3 | 162 | } |