ON THE HAND

引っ越しました http://tech.andhandworks.com

スポンサーサイト

上記の広告は1ヶ月以上更新のないブログに表示されています。
新しい記事を書く事で広告が消せます。

このエントリーをはてなブックマークに追加

  1. --/--/--(--) --:--:--|
  2. スポンサー広告

WiiリモコンとArduinoでQuadcopterを飛ばす(5):安全装置

【ご注意】
ここで紹介する方法は飽くまで個々の技術を組み合わせた例です。
周囲に人や建物がある場所で飛ばすのはお奨めしません。
Wiiリモコンのセンサ等はラジコンに用いることを想定されておらず、
操作不能に陥り想定外の場所に暴走したり墜落することがあります。
安易な飛行は非常に危険ですので重々ご注意ください。


前回、Arduino から MultiWii への入力方法を説明しました。
今回は Wii リモコンをプロポにして Arduino を受信機として動作させ、MultiWii への入力と結合します。

・・・と言いたいところですが、安易に結合すると大惨事になるので、まずは安全装置を作ります。

Wii リモコンと Arduino の接続

以前紹介した「Wiiリモコン+Arduino+LEGO でラジコンを作る」と全く同じです。
過去ログをご参照ください。

安全装置その1:概要

Wiiリモコンの通信可能距離はせいぜい10m程度が限界です。
つまり、Quadcopterが10m以上遠くに飛んで行くと制御不能になります。
と言うか、暴走して明後日の方向に飛んで行きます。
そこで、Wiiリモコンからの操作を受け付ける前に安全装置を組み込んでおきます。

安全装置と言っても、MultiWii の FAILSAFE モードを起動するだけです。
FAILSAFE モードでは墜落しない程度にモーター出力を落として不時着を狙います。

MultiWii の FAILSAFE モードは、MultiWii の config.h で「#define FAILSAFE」の行の
コメントを外せば使えます。
MultiWii 動作中に FAILSAFE モードに落とすには前回説明した PPM 信号を
すべて LOW にすればOKです。

安全装置その1:実装

「ふーん、じゃぁ、Wiiリモコンの信号が切れたら PPM を LOW にすれば良いのね?」
と考えてしまいますが、そのように実装してテスト飛行すると大事故になります。


と言うのも、Arduino と Wii リモコンの間の Bluetooth が切れると、
Wii リモコンライブラリは最後に受信した値を吐き続けます。
そのため、切断されたのか同じ信号を受信しているのかの区別がつきません。

この問題を私なりに考えた結果
「Wiiリモコンの加速度センサ系の値(roll, pitch)は常に変動しているはず。
その値が同一のまま一定時間が経過したら通信が切れているのでは?」
という結論に達しました。

これを実装すると次のようになります。
roll と pitch の現在値を直前の値と比較し続け、同一の値が WII_TIMEOUT 以上
連続したら activate フラグを false にして PPM を LOW にします。
#include <Wii.h>
#include <usbhub.h>

USB Usb;
USBHub Hub1(&Usb);
BTD Btd(&Usb);
WII Wii(&Btd,PAIR);

float pp = 0.0;
float pr = 0.0;
unsigned int cc = 0;
#define WII_TIMEOUT 500

void loop() {
  Usb.Task();
  if(! Wii.wiimoteConnected || Wii.getButtonPress(HOME)){ activate = 0; return; }
  if( millis() > uptime ){
    // check connecition
    if( pp == Wii.getPitch() && pr == Wii.getRoll() ){ cc ++ ; }else{ cc = 0; }
    pp = Wii.getPitch();
    pr = Wii.getRoll();
          : (中略)
    uptime = millis() + SPAN;    
  }
  if ( cc > WII_TIMEOUT / SPAN ){ activate = 0; return; }
  activate = 1;
    : (中略)  
}
void isr_sendPulses() {
  digitalWrite(PIN_PPM, LOW);
  if( ! activate ){ return; }
    : (中略)  
}

安全装置その2:概要

そもそも通信が切れるかどうかに関係なく、危険な状態になったら不時着させたいケースがあります。
例えば、操縦し切れなくてとにかく着陸させたい場合です。
通信が切れなくても FAILSAFE にさせる操作が必要です。

安全装置その2:実装

この実装は非常に簡単です。
Wii リモコンのどれかのボタンを不時着ボタンとして割り当てて FAILSAFE を起動させるだけです。
下記の実装例では Wii リモコンの HOME ボタンを押すといきなり FAILSAFE になります。
void loop() {
  Usb.Task();
  if(! Wii.wiimoteConnected || Wii.getButtonPress(HOME)){ activate = 0; return; }
        : (後略)

安全装置その3:概要

FAILSAFE はモーター出力を落としてゆっくり着陸するのでかなり風に流されるケースがあります。
いまにも人や物に突っ込みそうな場合にはそんな悠長なことは言っていられません。

このようなケースでは Quadcopter を破壊してでも飛行を中断する必要があるため
強制的にモーターを停止する「撃墜モード」を用意しておきます。
高さがある場合は確実に Quadcopter が壊れますが、操作が遅れると被害が拡大するので
迷わず撃墜できる練習を積んでおくのも重要です。
その一方、上空で撃墜すると鉄の塊が降ってくる点が解決できないドローンの危険性の1つです。

安全装置その3:実装

撃墜モードについても先ほどと同様に Wii リモコンにモーター停止用のボタンを割り当てます。
ここではBボタンとマイナスボタンの同時押しを割り当てています。

ボタン1つだと何かに当たって誤動作する恐れがあります。
上空で撃墜モードが誤動作すると非常に危険なため、
Bボタン(リモコンの裏)とマイナス(表の小さいボタン)の同時押しという
偶然ではありえない組み合わせを割り当てました。

モーター停止には PPM で Throttle と Yaw を 1000 にします。
これは MultiWii に実装されている特殊コマンドで Disarm を意味します。
ちなみに、Throttle=1000, Yaw=2000 にすると Arm です。
void loop() {
          :(中略)
  if(Wii.getButtonPress(B)){
           :(中略)
    if(Wii.getButtonPress(PLUS)){
      // arm
      currentTh = 1000;
      y = 2000;
    }else if(Wii.getButtonPress(MINUS)){
      // disarm
      currentTh = y = 1000;
    }
  }

  setPulse(r,p,currentTh,y,a1,a2);
}


3重の安全装置を組み込みましたが、これでも安全対策は不十分です。
屋外飛行の前のデバッグ方法についても後日説明します。

このエントリーをはてなブックマークに追加

  1. 2015/10/04(日) 00:31:50|
  2. Quadcopter
  3. | コメント:0
関連記事
<<ルンバを修理する | ホーム | WiiリモコンとArduinoでQuadcopterを飛ばす(4):Arduinoを受信機にする>>

コメント

コメントの投稿


管理者にだけ表示を許可する

上記広告は1ヶ月以上更新のないブログに表示されています。新しい記事を書くことで広告を消せます。