神戸支部の夜子まま氏がAndyLibというADKやBluetooth等の通信経路をひとくくりにできるAndroid側アプリに組み込んで使用する為の通信ライブラリを開発されています。その際に、通信プロトコルもそれぞれで統一されたものが良いということで、「メモリーマッププロトコル」というものを採用されることになりました。
メモリーマッププロトコルは、シンプルなプロトコルで、Andyで使用していた可変長のバイナリ通信をしてたプロトコルに似ています。このプロトコルはこのプロトコルで特徴があります。その辺はこれからご紹介してまいります。
なお、メモリーマッププロトコルはJS Robotics社さんが公開されているプロトコルとの事です。
さて、今回はこの通信プロトコルの紹介と、それをArduinoで簡単に使用するArduino用ライブラリを作成致しましたので、紹介させていただきたいと思います。
(詳細ドキュメントpdfを作成し、本記事の下にそのpdfへのリンクを置いています)
メモリーマッププロトコルの通信内容は大まかにはWrite Memory MapとRead Memory Mapというメッセージで主にやりとりしています。
例えば、Androidデバイスから、Andyのようなラジコンカーを動かす場合、例えばAndroidデバイス側をホスト、Andy側とデバイスにしたとすると、通信はホスト側から必ず発行されます。
この場合、仮にLEDの点滅指示をアドレス 0x30 に、そしてスイッチの開閉状態をアドレス 0x31 にマッピングしておいたとすると、ホスト側からLEDの点滅制御をする際には、アドレス 0x30 に Write Memory Map を行い、一方ホスト側がスイッチの開閉状態を知りたいときには、アドレス 0x31 に対して Read Memory Map を行うことになります。
この通信プロトコルのデバイス側を簡単に実現するのが Arduinoライブラリ MemoryMapLib です。Arduino IDEから簡単に利用できます。
では、MemoryMapLibが提供するインターフェースの紹介です。
int MemoryMap::registerMapAddressJob(unsigned char address,unsigned char RWOP,Job ptr); int MemoryMap::registerMapAddressVar(unsigned char address,unsigned char RWOP,unsigned char* ptr); int MemoryMap::registerMapAddressBlock(Command* ); int MemoryMap::removeMapAddress(unsigned char address); int MemoryMap::setStreamInterface(HardwareSerial* ); void MemoryMap::poll(void);インスタンス生成
MemoryMap mMemoryMap;
シリアルインターフェースの接続
Arduinoと外部機器が通信をする際の、インターフェースをMemoryMapLibに設定します。現在はUARTに対応させていますが、他のI/Fへの対応拡張は容易と思います。今回は主に、Bluetoothでの制御を実現する為、Bluetoothアダプタと直結できるUARTを使用しています。
void setup()
{
Serial.begin(9600);
mMemoryMap.setStreamInterface(&Serial);
}
上記例では、Serialを9600bpsに設定した後、mMemoryMapに渡してます。
アドレスへの動作のマッピング
このライブラリでは、任意のアドレスにアクセスがあった場合に、「変数の操作」または、「関数の実行」のどちらかを定義します。ここでアドレス値と対応する仕事を紐付ける為に使用するのが、registerMapAddressVarまたはregisterMapAddressJobです。
unsigned char var = 0;
void setup()
{
mMemoryMap.registerMapAddressJob(0x30,OPERATION_WRITE|OPERATION_READ,&jobLED);
mMemoryMap.registerMapAddressJob(0x31,OPERATION_READ,&jobSW);
mMemoryMap.registerMapAddressJob(0x32,OPERATION_READ|OPERATION_WRITE,&var);
}
ジョブ関数内の実装
MemoryMap::registerMapAddressJob()に渡す関数は、以下の形式です。
void (*jobFunction) (unsigend char RWOP,unsigned char address,unsigned char * value)RWOP[in] : Read(OPERATION_READ) or Write(OPERATION_WRITE)どちらのアクセスにより呼び出されたかが設定される。
address[in] : Read or Write対象のアドレス値が入る。例えば、registerMapAddressJobにより、複数のアドレスに同一の関数を定義した場合でも、ここに設定されるアドレス値を確認することで動作を切り替えることが出来る。
value[in/out] : Writeで呼び出された際には、設定内容のメモリーへのポインタがセットされるで、参照する。Readで呼び出された際には、ホストに送り返すバッファへのホインタがセットされるので、値をセットする。
このライブラリを使用して、Android制御ラジコンを作ったコード例です。以下のように、やりたい制御だけ記述すれば実現できますよ。
#include "MemoryMapLib.h"
#define PIN_MOTOR_L_VREF 6
#define PIN_MOTOR_R_VREF 5
#define PIN_MOTOR_L_CONTROL1 A0
#define PIN_MOTOR_L_CONTROL2 A1
#define PIN_MOTOR_R_CONTROL1 A3
#define PIN_MOTOR_R_CONTROL2 A2
#define MOTORTYPE_MOTOR_R 0
#define MOTORTYPE_MOTOR_L 1
MemoryMap mMemoryMap;
void setup()
{
pinMode(PIN_MOTOR_R_VREF,OUTPUT);
pinMode(PIN_MOTOR_L_VREF,OUTPUT);
pinMode(PIN_MOTOR_R_CONTROL1,OUTPUT);
pinMode(PIN_MOTOR_R_CONTROL2,OUTPUT);
pinMode(PIN_MOTOR_L_CONTROL1,OUTPUT);
pinMode(PIN_MOTOR_L_CONTROL2,OUTPUT);
digitalWrite(PIN_MOTOR_R_CONTROL1,LOW);
digitalWrite(PIN_MOTOR_R_CONTROL2,LOW);
digitalWrite(PIN_MOTOR_L_CONTROL1,LOW);
digitalWrite(PIN_MOTOR_L_CONTROL2,LOW);
analogWrite(PIN_MOTOR_R_VREF,0);
analogWrite(PIN_MOTOR_L_VREF,0);
Serial.begin(9600);
mMemoryMap.setStreamInterface(&Serial);
mMemoryMap.registerMapAddressJob(0x1b,OPERATION_WRITE,&jobMotor);
mMemoryMap.registerMapAddressJob(0x1c,OPERATION_WRITE,&jobMotor);
}
void loop()
{
mMemoryMap.poll();
}
void jobMotor(unsigned char RWOP,unsigned char addr,unsigned char* value)
{
struct S_MOTOR_BIT_FIELD {
unsigned char power :6;
unsigned char cont :2;
};
if(RWOP & OPERATION_WRITE){
unsigned char cont,power;
cont = ((struct S_MOTOR_BIT_FIELD*)value)->cont;
power = ((struct S_MOTOR_BIT_FIELD*)value)->power;
controlMotorPower(addr == 0x1b ? MOTORTYPE_MOTOR_R : MOTORTYPE_MOTOR_L,cont,power << 2);
}
}
void controlMotorPower(int motortype,int motoraction,int power)
{
int pinno_1;
int pinno_2;
int pinno_pwm;
const unsigned char cont[4][2] = {
{ LOW , LOW }, // STOP
{ LOW , HIGH }, // REVERSE
{ HIGH , LOW }, // FORWARD
{ HIGH , HIGH } // BRAKE
};
if(motortype == MOTORTYPE_MOTOR_R){
pinno_1 = PIN_MOTOR_R_CONTROL1;
pinno_2 = PIN_MOTOR_R_CONTROL2;
pinno_pwm = PIN_MOTOR_R_VREF;
} else {
pinno_1 = PIN_MOTOR_L_CONTROL1;
pinno_2 = PIN_MOTOR_L_CONTROL2;
pinno_pwm = PIN_MOTOR_L_VREF;
}
digitalWrite(pinno_1,cont[motoraction][0]);
digitalWrite(pinno_2,cont[motoraction][1]);
analogWrite(pinno_pwm,power);
}
上記ソースを実行した動画です。
以下のgithubにてソース公開しています。 https://github.com/yishii/Arduino_MemoryMapLib
または、以下でアーカイブダウンロード出来ます。
MemoryMapLib002.zip
詳細な資料はこちらです。ホスト側のプロトコルについても、こちらの資料に記載しています。
ArduinoMemoryMapLib.pdf




