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
- Committer:
- YosukeK
- Date:
- 2015-01-20
- Revision:
- 0:32eb0835b5a3
- Child:
- 1:aed433d882c9
File content as of revision 0:32eb0835b5a3:
#include "mbed.h"
#include "Roomba.h"
/**
* @bref コンストラクタ
* @param tx
* @param rx
*/
Roomba::Roomba(PinName tx, PinName rx, PinName led):
_s(tx, rx), _led(led){
count = 0;
timedOut = false;
_led = 0;
//_mode = Roomba::Mode::Off;
Roomba::mp = &Roomba::serialReceiveCallback;
_s.attach(this, Roomba::mp, Serial::RxIrq);
}
/**
* @bref コマンド送信インターフェースの実装
* @param e イベント引数
* @return true
*/
bool Roomba::send(EventArg e) {
_led != _led;
Roomba::start();
Roomba::mode(Roomba::Full);//(Roomba::Mode::Full); If write struct Mode and no name enum, Compiler say no sutable constructor conver to enum...
Roomba::drive(e.leftWheetVelocity, e.rightWheelVelocity);
return true;
}
/**
* @bref コマンド送信結果受信時のインターフェースの実装
* @param result コマンド送信結果
*/
void Roomba::notify(bool result) {
if (result == false) {
_led = 1;
} else {
_led = 0;
}
}
/**
* @bref 周期タイマのコールバックメソッド
* @param e イベント引数
*/
void Roomba::periodicCallback(EventArg e) {
count = count + 1;
if (count > 100) {
if (timedOut == false) {
timedOut = true;
Roomba::notify(timedOut);
}
}
_s.putc('1');
Roomba::send(e);
}
/**
* @bref シリアル受信時コールバックメソッド
*/
void Roomba::serialReceiveCallback() {
count = 0;
_s.putc('2');
if (timedOut) {
timedOut = false;
Roomba::notify(timedOut);
}
}
///**
// * @bref シリアル受信のアタッチ
// */
////継承先から操作できるようにしただけ
//void Roomba::attachSerialReceiveCallback() {
// Roomba::mp = &Roomba::serialReceiveCallback;
// _s.attach(this, Roomba::mp, Serial::RxIrq);
// //_s.attach(this, &Roomba::notify, Serial::RxIrq);
//}
/**
* @bref Start
* @return true
*/
bool Roomba::start() {
_s.putc('a');
_s.putc(128);
return true;
}
/**
* @bref 操作モード変更メソッド
* @param 操作モード
* @return true
*/
bool Roomba::mode(Roomba::Mode m) {
_s.putc('b');
_s.putc(132);//Full;
return true;
}
/**
* @bref Start
* @param true
*/
bool Roomba::drive(int rightWheelVelocity, int leftWheelVelocity) {
bool ret = false;
if ((-500 <= rightWheelVelocity && rightWheelVelocity <= 500)
&& (-500 <= leftWheelVelocity && leftWheelVelocity <= 500)) {
Roomba::command[0] = 145;
Roomba::command[1] = rightWheelVelocity & 0xFF00 >> 8; //MSB
Roomba::command[2] = rightWheelVelocity & 0xFF; //LSB
Roomba::command[3] = leftWheelVelocity & 0xFF00 >> 8; //MSB
Roomba::command[4] = leftWheelVelocity & 0xFF; //LSB
Roomba::command[5] = '\0';
for (int i = 0; Roomba::command[i] != '\0'; i++) {
_s.putc('c');
_s.putc(Roomba::command[i]);
}
ret = true;
}
return ret;
}
/**
* @bref バッテリ状態
* @param true
* @return
* @retval
*/
bool Roomba::battery(int* batteryCapacity) {
bool ret = false;
*batteryCapacity = 100;
return ret;
}