LocomoはArduino互換のロボットプロトタイピングボードです。 無線制御の移動ロボットの開発を支援する目的で作られました。 Locomoを使えば、DCモータやサーボモータを無線制御するロボット・システムを手軽に作ることができます。

(公開:2013年10月31日/最終更新:2013年11月5日)

Locomoとは

Locomoは無線操縦のロボットのプロトタイピングのために作られたマイコンボードです。 Locomoという名前は「locomotion(移動)」に由来し、主にモータ駆動の移動ロボットをターゲットとしています。 通常そのようなロボットを作る場合、マイコンや無線モジュール、モータドライバなどの複数のパーツから構成される複雑な制御回路を自分で作る必要がありますが、それはなかなか負担の大きい作業です。 その工程をショートカットしてくれるのがこのLocomoです。

特徴




活用例

モータ駆動の玩具をLocomoで無線化した例

自作のテオヤンセン機構のロボット


右の動画は、リモコン操縦のロボット玩具(トリプルレンジャー MR-9102)をLocomoを使ってPCから無線コントロールできるようにした例です。 通信にはXBee Wi-Fiを使っており、PC以外にもスマートフォンからもコントール可能です。 このようにモータ駆動のモノを無線コントロールしたいときにLocomoは威力を発揮します。

ハードウェア





DCモータ端子

Locomoに接続できるモータは、タミヤの工作キットやおもちゃなどに使われている駆動電圧3Vの小型DCモータです。DCモータから伸びているコードを直接接続することできます。



タミヤから発売されているモータ&ギヤボックス各種

DCモータ端子にモータを接続した様子


DCモータの制御には3種類のピンを使用します。 ピンの割り当てと動作モードを以下の表に示します。 FWDとREVでモータの回転方向と停止の制御を行い、PWMによって速度制御を行います。 例えば、DCモータ1を正転させたければ、D2をHIGHに、D4をLOWにして、D3に0〜255の範囲でアナログ出力します。


FWDREVPWM
DCモータ1D2D4D3
DCモータ2D5D7D6
DCモータ3D12D13D11
FWDREVモータの動作
LOWLOWニュートラル(空転)
HIGHLOW正転
LOWHIGH逆転
HIGHHIGHブレーキ(停止)



サーボモータ端子

サーボモータ端子には5V駆動のサーボモータを合計2個接続することができます。 ピンの並びはフタバ製のサーボモータに準拠して「GND, 5V, PWM」の順になっています。 これとは異なるピン配置のサーボモータを利用するときは注意してください。 サーボモータを制御するときは、PWMピンであるD9またはD10に対してPWM出力します。 Arduinoには標準でサーボモータ用のライブラリ(Servo.h)がありますので、それを利用してプログラムを書いてください。



サーボモータを2個接続した様子
サーボモータ端子のピン配置
サーボモータ1GND, 5V, D9
サーボモータ2GND, 5V, D10



センサ端子

アナログピンA0〜A7に対して、電源供給のためにGNDと5Vをセットにして並べました。 センサ5とセンサ6にアナログピンが2個含まれているのは、ロータリエンコーダのような2個の入力端子を必要とするセンサの利用を想定しているためです。 なお、アナログピンA0〜A7はピン設定によってデジタル入出力端子としても利用可能です。



距離センサ(GP2Y0A21YK)を接続した様子
センサ端子のピン配置
センサ1GND, A0, 5V
センサ2GND, A1, 5V
センサ3GND, A2, 5V
センサ4GND, A3, 5V
センサ5GND, A4, A5, 5V
センサ6GND, A6, A7, 5V


XBeeエクスプローラモード

Locomoにはボード本体が「XBeeエクスプローラUSB」として動作するモードが搭載されています。 一般的にXBeeの通信設定を行う際には、XBeeエクスプローラUSBに代表されるXBee用USBアダプタを使いますが、それがなくてもLocomo単体で通信設定が行えます。



XBeeエクスプローラUSB

LocomoをXBeeエクスプローラモードにするときは、XBee端子の左にある3つのスイッチで切り替えます。 あとはXBeeエクスプローラUSBを使うときと同様の手順でXBeeの設定を行うことができます。



通常モード
3つのスイッチがすべて上側

XBeeエクスプローラモード
3つのスイッチがすべて下側


Locomo本体の側面にあるボタンスイッチは、XBeeエクスプローラモードで使用するリセットボタンです。 XBeeの設定作業中にリセットボタンを押す必要がでてきたときは、このボタンを押してください。



XBeeのリセットボタン


電力仕様


電源入力DC6〜12V
DCモータ出力電圧最大約3〜4V(入力電源により変動)
DCモータ出力電流それぞれ連続1A
サーボモータ出力電圧5V
サーボモータ出力電流合計連続1A
センサ端子出力電圧5V
センサ端子出力電流全ポート合計最大600mA
USB接続時にUSBから
給電される範囲
  • マイコン
  • XBee
  • センサ端子
※安全のため、DCモータとサーボモータにはUSBから給電されません。

プログラミング・チュートリアル

実際のプログラミングの手順について紹介します。 作例として、PCやスマートフォンから無線操縦できる移動ロボットを作ることを想定して、2個のモータをWiFi経由で制御するものを作ってみましょう。


動かすターゲット

Locomoにバッテリ(単三電池×6)と2個のDCモータ(タミヤのダブルギヤボックス)を接続しました。 左右の車輪が個別に回転することによって前後移動と左右への旋回ができる仕組みです。 また、WiFi通信するためにXBee端子にはXBee Wi-Fiが挿さっています。 車体はいつか作るとして、ここでは2個のDCモータを制御する仕組みの作り方を解説していきます。



PC、Locomo、電池、モータ&ギヤボックス


PCとの接続確認

PCとの接続はUSBケーブルで行います。 LocomoにはFTDI社のFT232Rというシリアル通信モジュールが搭載されており、PC側からはUSBシリアルポートとして認識されます。 Windows Vista以降であれば、PCに接続したタイミングでドライバが自動的にインストールされます。 ドライバが自動的にインストールされない場合やMacの場合は、こちらからドライバをダウンロードして手動インストールしてください。



モータをコントロールするプログラムを作る(Arduino)

LocomoにはArduinoと同じATMega328というマイコンが搭載されており、中にはArduinoのブートローダが書き込まれています。 つまりArduino IDEを使ってプログラミングを行うことができます。

プログラミングをはじめる前にArduino IDEで以下の2つの設定を行ってください。


サンプルプログラム

以下はシリアル通信で左右輪のモータをコントロールするプログラムです。 文字列の送信によって各モータの回転方向と速度を指定できるようになっています。 例えば「L100 R-100」のような文字列を受信すると、左モータを速度100で正転、右モータを速度100で逆転させます。 LとRがそれぞれ左右のモータを意味しており、後に続く数値が速度です。数値が負のときに逆転になります。

2個の車輪をシリアル通信でコントロールするプログラム
static int FWD_L = 2;  // 左モータのFWDピン
static int REV_L = 4;  // 左モータのREVピン
static int PWM_L = 3;  // 左モータのPWMピン

static int FWD_R = 5;  // 右モータのFWDピン
static int REV_R = 7;  // 右モータのFEVピン
static int PWM_R = 6;  // 右モータのPWMピン
 
int speed_L = 0; // 左モータの回転速度(0〜255)
int speed_R = 0; // 左モータの回転速度(0〜255)
 
void setup() {
  // 通信速度の設定
  Serial.begin(9600);
 
  // モータの制御ピンを出力に設定
  pinMode( FWD_L, OUTPUT );
  pinMode( REV_L, OUTPUT );
  pinMode( PWM_L, OUTPUT );
  pinMode( FWD_R, OUTPUT );
  pinMode( REV_R, OUTPUT );
  pinMode( PWM_R, OUTPUT );                       
}
 
void loop() {
    // 特に何もしない
}
 
// 通信イベント
void serialEvent() {
  if ( Serial.available() > 0 ) {
    int key = Serial.read();

    // LまたはRの後に続く数値を取得 
    if (key=='L') { speed_L = readIntValue(); }    
    if (key=='R') { speed_R = readIntValue(); }
     
    // 回転速度の設定
    analogWrite( PWM_L, abs(speed_L) );
    analogWrite( PWM_R, abs(speed_R) );
 
    // モータの回転制御
    if ( speed_L == 0 ) { motor_stop( FWD_L, REV_L ); }
    else if ( speed_L > 0 ) { motor_forward( FWD_L, REV_L ); }
    else if ( speed_L < 0 ) { motor_reverse( FWD_L, REV_L ); }
 
    if ( speed_R == 0 ) { motor_stop( FWD_R, REV_R ); }
    else if ( speed_R > 0 ) { motor_forward( FWD_R, REV_R ); }
    else if ( speed_R < 0 ) { motor_reverse( FWD_R, REV_R ); }
  }
}

// モータの正転
void motor_forward( int pin_fwd, int pin_rev ) {
  digitalWrite( pin_fwd, HIGH );
  digitalWrite( pin_rev, LOW );  
}

// モータの逆転
void motor_reverse( int pin_fwd, int pin_rev ) {
  digitalWrite( pin_fwd, LOW );
  digitalWrite( pin_rev, HIGH );  
}

// モータの停止
void motor_stop( int pin_fwd, int pin_rev ) {
  digitalWrite( pin_fwd, HIGH );
  digitalWrite( pin_rev, HIGH );  
}

// 数値を読み込む関数
int readIntValue() {
  int i = 0;
  char string[10];
  
  while ( i < sizeof(string) ) {
    if ( Serial.available() ) {
      char c = Serial.read();
      if ( (c>='0' && c<='9') || c=='-' ) {
        string[i] = c;
        i++;
      } else {
        string[i] = '\0';       
        break;
      }
    }
  }
  return atoi(string);
}


まずはUSB接続した状態で動作確認

プログラムをLocomoに書きこんだら、動作確認してみましょう。 LocomoではXBeeによる無線通信だけでなく、USB経由でのシリアル通信も可能です(XBeeは挿したままでOK)。 無線通信をやるときは接続上のトラブルが何かとつきものですので、XBeeでやる前にUSB経由でテストするのがおすすめです。 Locomoの電源スイッチをONにして、Arduino IDEのシリアルモニタを立ち上げたら、「L100 R100」とか「L-100 R-100」のように文字列を送ってみてください。 モータが意図通り回転したらOKです。もし、モータが逆方向に回転するようであれば、DCモータ端子に接続しているコードを入れ替えてみてください。



XBeeエクスプローラモードでXBee Wi-Fiの設定

次はXBee Wi-Fiを使ってWiFi経由での無線通信にトライしてみましょう。 Locomoに搭載されたモード切り替えスイッチ(3つのスイッチ)を切り替えて、XBeeエクスプローラモードにしてください。



XBeeエクスプローラモード:3つのスイッチがすべて下側


PCでの操作について説明します。 ここではターミナルからATコマンドを使って通信設定を行う方法を紹介します(なお、WindowsであればX-CTUというXBee設定ツールがありますので、そちらを使ってもOKです)。 WindowsではTeraTermなどの適当なターミナルソフト、Macではscreenコマンドを使ってシリアルポートにアクセスし、以下のコマンド入力操作を行ってください。

※黒文字があなたが入力する文字、赤文字がXBeeからの応答です。

+++OK ……ATコマンドによる設定開始
atid 無線LANのSSID ……接続先を設定
OK
atee 1 ……暗号化方式をWPA PSKに変更
OK
atpk 無線LANのパスワード ……無線LANへ接続するためのパスワードを設定
OK
atip 1 ……プロトコルをTCPに変更
OK
atc0 2616 ……ポート番号を16進数で設定。2616は10進数で9750(XBee Wi-Fiのデフォルトポート)
OK
atwr ……設定をXBeeに書き込み
OK
atai ……現在の接続状態を表示
0    ……0:接続成功 / 23:SSID未設定 / FF:検索中
atmy ……無線LANから割り当てられたIPアドレスを表示
192.168.100.102

設定が終わったら、モード切り替えスイッチを戻して通常モードにしてください。



通常モード:3つのスイッチがすべて上側


XBee Wi-Fiに割り当てられたIPアドレスを確認したら、Telnetで接続できるかチェックしてみましょう(ポート番号は9750)。 先ほどと同様に制御コマンド(例えば「L100 R100」)を送信してモータが反応すればOKです。



WiFi経由でコントロールするホスト側プログラムを作る

WiFi接続がきちんと動作するのが確認できたら、今度はWiFi経由でLocomoをコントロールするホスト側のプログラムを作ってみましょう。 ホスト側プログラムはTCPによるソケット通信ができる言語であれば、C++やJava、Processingなどなんでも良いです。 ここではProcessingでの作例を紹介します。


サンプルプログラム(Processing)

PCからTCP通信によってLocomoをコントロールするプログラムを以下に示します。 キーボード入力を行うと、Locomoに対してモータをコントロールする文字列が送信されます。 キーを押している間モータが回転し、キーを離すとモータが停止します。


ホスト側のプログラム(Processing)
import processing.net.*;
 
Client client;
int speed_L = 0;
int speed_R = 0;
 
void setup() {
  // Locomoに接続
  client = new Client(this, "192.168.100.102", 9750);
}
 
void draw() {
  // 特に何もしない
}

// キーが押された時の処理(モータ回転)
void keyPressed() {
  if ( keyCode==UP ) {
    speed_L = 255;
    speed_R = 255;
  }
  if ( keyCode==DOWN ) {
    speed_L = -255;
    speed_R = -255;
  }
  if ( keyCode==LEFT ) {
    speed_L = -255;
    speed_R = 255;
  }
  if ( keyCode==RIGHT ) {
    speed_L = 255;
    speed_R = -255;
  }
  client.write("L" + speed_L + " R" + speed_R + "\r");
}

// キーが離された時の処理(モータ停止)
void keyReleased() {
  speed_L = 0;
  speed_R = 0;
  client.write("L" + speed_L + " R" + speed_R + "\r");
}


きちんと動きましたでしょうか? ここで紹介したものはPCから操作するものでしたが、スマートフォンのアプリを作る場合でも基本は同じです。 Processingであれば、上で紹介したプログラムをベースにAndroidで動作するものも作れます。


以下のページにProessin、Java、Pythonによる通信プログラムのサンプルを用意しました。こちらも参考にしてください。

Locomoの販売について

Locomoは研究・教育・ホビーなどの用途で利用したい人のために、量産・販売することを予定しております。 「ウチで販売したい!」「学校の実験で使ってみたい!」「ここはこうしてほしい!」などのご意見・ご質問・コメント等ございましたら、ぜひぜひお寄せください。


お問い合わせ先:橋本直(明治大学/工学ナビ)

クレジット

LocomoはJST ERATO 五十嵐デザインインタフェースプロジェクトで開発されました。

開発メンバー
 橋本直(明治大学)
 神山洋一(慶應義塾大学)
 吉田成朗(東京大学)
 稲見昌彦(慶應義塾大学)
 五十嵐健夫(東京大学)