唐突だが、
モーターで動く小さい台車にデジカメを乗せ、走り回らせて動画を撮りたい。虫の視点で動画を撮るわけだ。人の視点では思いもよらない、家の中のいろいろなものが写り込んで、面白いのではないだろうか。
Arduinoで制御し、手持ちの超音波センサで障害物を避けるようにしたい。
できるだけシンプルに作るため、操向装置を工夫する。普通ならサーボなどを用いて操向輪の向きを操作するのだろうが、ここを単純にしたい。
3輪の台車にし、後輪をキャスターのようなものにする。前進時はまっすぐに向くが、後退させるとモーメントがかかって後輪が傾き、左右どちらかに振れるようにする。そうすると、前進・後退の制御のみであちらこちらに台車を走行させることができるだろう。直進していって、ある程度まで壁などの障害物に近づくと、後退させる。後退させると、左右どちらかに向きが振れるので、超音波センサで測距しつつ後退させ、ある程度障害物が離れたらまた前進させる。
Arduinoでモーターを回すには、FETやトランジスタを用いる方法もあるが、前進・後退をさせるためには逆転ができた方がよい。それをFETなどを使ってスクラッチでやるのは面倒くさい。そこで、「モータードライバIC」を購入して、手っ取り早く済ませよう。
検索すると、よく売れていて入手しやすく、かつ他人の作例も多そうなものには東芝のTA7291Pというのがある。メーカーのサイトには生産終了予定と出ているものの、秋葉原へ行けば多分千石電商あたりに置かれているだろう。180円とか300円とか、そんな値段なので、どうってことはない。
このモータードライバに合うような模型用のモーターを選ぶ。スペックシートによるとTA7291Pは1A流せる。乾電池で台車を動かすとして、Arduinoには5Vがいるから、単3×4本の6Vとして、良さげなものをマブチのページで見繕う。
6Vだと電流が途端に2.9Aくらいにハネ上がり、モータードライバに合わない。しかも、急に1000円近くするので、趣味の工作にはちょっとどうかと思う。それで、電圧は3端子レギュレータを一つ買って落とすとして、3Vのものを見繕うと、「FA-130RA」というのに結局落ち着きそうだ。このモーターはよく使われているようで、他の方の作例にも良く出てくる。電圧は3Vまで、500mAだから、TA7291Pで動かすにはぴったりだ。
このモーターをタミヤあたりのギアボックスにうまく取り付ければいいだろう。
ギヤボックスを探すと、モーター込みのものも多くあるようだ。見ていると、このFA-130RA込みのギヤボックスがある。「タミヤ・3速クランクギヤーボックス」というやつだ。モーター込みで600円かそこらは安い。
最後に、ゴムの車輪を三つ、だな。まあ、これは何か、いいものがあるだろう。
休みなので、さっそく秋葉原へ行き、いろいろと買い込んでくる。秋葉原にはないものを、帰りに北千住の東急ハンズで買う。
まず、タミヤの「ミニモーター標準ギヤボックス」というのを買ってみた。モーター付きだが810円。安いかと言うと微妙なところだが、自力でギヤをいろいろやるとこれが結構大変なので、まあ、値段はこんなところだろう。
それから、走行させるためのゴムタイヤを買う。向きをうまく変えるための「キャスター」は東急ハンズで買う。
タイヤはさておき、この「キャスター」が、今回の私の工夫だ。前進・後退のみ、モーター1個の制御で、操向もしてしまおう、という工夫だ。このキャスターの変向角度を一定に制限し、後退する時だけランダムに向きが変わるようにするのだ。
それから東芝のモータードライバ「TA7291P」と、モーター用に電圧を落とす3端子レギュレータ。3端子レギュレータは3.3Vのものを探したが、なかったので、2.5Vのものを買った。これでだめなら、抵抗分圧で電圧を落とそう。
ギヤボックスは組み立てるとこうなる。
これを、いつもの100円ショップ「ダイソー」にあるアクリルの枠にねじ止めし、タイヤを取り付け、例のキャスターも取り付ける。
このキャスターの根元に、適当な金具を共締めし、変向角度を制限してやる。
これが、「モーター1個だけで向きも変える工夫」である。ためしに、2.5Vで動かしたがどうも力がなくていけない。そこで、ギア比をうんと落とし、9Vを直接モータにくれてやることにした。まあ、壊れやせんだろ。電流を測ると、200mAくらいなので、Arduinoに直接流さなければ許容範囲である。
さて、機械のほうはこれくらいのぞんざい適当、次に電子回路のほうに取り掛かる。
次のように考え、この通りブレッドボードを作る。
モータ付きの台車に取り付けると、次のとおりである。
スケッチは次のように書く。
// // crawlCar.ino // 27.10.11(日) 0600~ // 佐藤俊夫 // 台車を這いまわらせる // // モータードライバ const int MOTOR1 = 7; const int MOTOR2 = 8; const int MOTORPWM = 6; // 超音波センサ const int TRIG = 9; const int ECHO = 10; // 現在の台車の状態 const unsigned int STOP = 0, FORWARD = 1, BACK = 2; // ストップさせる距離、前進を再開させる距離 const float FOWSTOP = 20.0, FOWCONT = 50.0; // ある程度はバックを持続するようバック継続時間制限(ミリ秒) const unsigned int BACKLIMIT = 2000; // PWMの強さ const unsigned int POWER = 128; void setup(){ pinMode(MOTOR1,OUTPUT); // モータードライバ入力1へ pinMode(MOTOR2,OUTPUT); // モータードライバ入力2へ pinMode(TRIG,OUTPUT); pinMode(ECHO,INPUT); } void loop(){ static unsigned int state = FORWARD; static unsigned long int backstart = 0; float range = 0.0; range = ranging(); if(range >= FOWSTOP && state != BACK){ state = motor(FORWARD); } else if(range < FOWCONT){ if(state == FORWARD){ state = motor(BACK); backstart = millis(); } else{ if(millis() >= (backstart + BACKLIMIT)){ state = motor(FORWARD); } else{ state = motor(BACK); } } } else{ if(millis() >= (backstart + BACKLIMIT)){ state = motor(FORWARD); } } } // // モーター制御 // unsigned int motor(unsigned int command){ switch(command){ case FORWARD: digitalWrite(MOTOR1, LOW); digitalWrite(MOTOR2, HIGH); analogWrite(MOTORPWM, POWER); break; case BACK: digitalWrite(MOTOR1, HIGH); digitalWrite(MOTOR2, LOW); analogWrite(MOTORPWM, POWER); break; case STOP: digitalWrite(MOTOR1, LOW); digitalWrite(MOTOR2, LOW); break; default: digitalWrite(MOTOR1, LOW); digitalWrite(MOTOR2, LOW); break; } return command; } // // 測距 // float ranging(){ float time = 0.0, range = 0.0; digitalWrite(TRIG,LOW); delayMicroseconds(1); digitalWrite(TRIG,HIGH); delayMicroseconds(1); digitalWrite(TRIG,LOW); time = pulseIn(ECHO,HIGH); if (time > 0) { range = (time / 2) * 340 * 100 / 1000000; return(range); }else{ return(9999); } }
これを走り回らせると、次のようになる。
これにカメラを積み込み……
で、動画を撮影するわけだ。
なかなか這いまわっている感じが出て、いいと思う。