17,803 total views, 3 views today
前回は、障害物を避けて走るクローラー車を作ったが、今回は、障害物を避けて走る4WD車を作った。
本当は、4WD車で4輪を個別にステアリング操作して全方向移動を実現したかったのだが、そのためには8つ(DCモータ×4とサーボモータ×4)のPWM制御を行う必要がある。
しかし、Arduino UnoにはPWM制御可能なピンが6つしかないので、Arduino Uno互換機では4WD車で4輪個別にステアリング操作はできないということになる。
なんとかならないものかと、いろいろと調べてみたところ、2つのArduinoをi2cで接続するという方法をみつけた。
早速その方法を試してみたところ、一応通信はできたのだが、どうにも意図したとおりの動作はできなかった。
なので今回は、仕方なく前輪と後輪のみステアリング操作をすることにしたわけである。
前輪・後輪の両方をステアリング操作することで、斜め方向への移動はできたので、なかなか面白かった。
目次
動作
- 前輪と後輪を同じ角度にステアリング操作することで、斜めに移動する
- 超音波センサ(前方)で障害物を検知すると、ランダムで左右どちらかに曲がりながらバックし、バック後にも障害物を検知すると、より急角度に曲がりながらさらにバックする
- 赤外線近接センサ(左右)で障害物を検知すると、曲がりながらバックし、バック後にも障害物を検知すると、より急角度に曲がりながらさらにバックする
- 赤外線近接センサでの障害物検知時、直前に検知した赤外線近接センサ(例:右)と反対方向の赤外線近接センサ(例:左)で障害物を検知するとカウントを1つプラスし、それ以外(例:右または前方)だとカウントを0にする。カウントが5を超えると、通常と異なったバックの仕方をする(要は、無限ループ(左右交互に障害物を検知)から抜け出せるようにした)
使用品一覧
品名 | 用途 |
---|---|
Arduino Uno(互換機) | クローラー車の動作制御 |
超音波距離センサ(HC-SR04) | 前方の障害物検知 |
赤外線近接センサ(LM393)×2 | 左右の障害物検知 |
サーボモータ大(HS-422)×2 | 車体のステアリング用 |
サーボモータ小(SG90) | 音波距離センサの検知方向制御 |
タミヤ 6速ギヤーボックス×4 | タイヤ駆動用 |
モーターシールド(L293D) | モータの動作制御 |
ジャンパーワイヤ(オス-メス) | 配線用 |
ジャンパーワイヤ(メス-メス) | 配線用 |
タミヤ 楽しい工作シリーズ 透明 ユニバーサルプレート | 車体 |
タミヤ 楽しい工作シリーズ 透明 ユニバーサルプレートセット 2枚セット | 車体 |
タミヤ ナロータイヤセット×2 | タイヤ |
小型モバイルバッテリー | 電源(Arduino Uno互換機用) |
電池ボックス(単3×4本、スイッチ付) | 電源(モータ用) |
組み立て
車体に関してはユニバーサルプレートを組み合わせるだけなので、その部分の解説は省略し、サーボモータとユニバーサルプレートの接続についてのみ画像を用いて解説する。
サーボモータの固定
サーボモータ(大)とサーボモータ(小)はどちらも、上手い具合にアングル材(ユニバーサルプレート付属)へ取り付けることができた。
サーボモータ(大)の固定
固定用のネジとナットは、ユニバーサルプレート付属のものを使用。
サーボモータ(小)の固定
固定用のネジは、サーボモータ付属のものを使用。
サーボモータをアングル材に固定したら、あとはアングル材とユニバーサルプレートとを接続すれば良い。
サーボモータ(大)のホーンの固定
サーボモータ(大)に付属しているホーンは、ユニバーサールプレート付属のネジとナットで、上手い具合にユニバーサルプレートへ固定することができた。
完成
パーツを全て組み合わせると下記画像のようになる。
なお、ここではユニバーサルプレートを使用せず(ユニバーサルプレート付属の長めのアングル材は使用)、ユニバーサルプレートセットを3セット(5枚)使用して組み立てたが、ユニバーサルプレートセット1セットとユニバーサルプレート1枚で済ませたほうが安価である。
スケッチ(プログラム)
モーターシールド(L293D)を使用した場合と、他のモータードライバ(TA7291Pなど)を使用した場合のスケッチを紹介しておく。
障害物を避けて走るスケッチ
#include <AFMotor.h> #include <Servo.h> Servo myservo_f; Servo myservo_r; Servo myservo_s; AF_DCMotor motor_1(1, MOTOR12_64KHZ); AF_DCMotor motor_2(2, MOTOR12_64KHZ); AF_DCMotor motor_3(3, MOTOR34_64KHZ); AF_DCMotor motor_4(4, MOTOR34_64KHZ); const int trig = 15; const int echo = 16; const int right_sensor = 14; const int left_sensor = 19; int r_sensor_value; int l_sensor_value; int servo_angle = 90; long randNumber; int cnt = 0; int pre_detection = 0; int interval; double distance; int position_of_myservo[] ={71, 56, 71, 94, 109, 124, 109, 94}; int len = sizeof(position_of_myservo) / sizeof(position_of_myservo[0]); void setup() { pinMode(right_sensor, INPUT); pinMode(left_sensor, INPUT); pinMode(trig, OUTPUT); pinMode(echo, INPUT); myservo_f.attach(9); myservo_r.attach(10); myservo_s.attach(17); myservo_f.write(servo_angle); myservo_r.write(servo_angle); myservo_s.write(94); Serial.begin(9600); delay(3000) ; } void loop() { for (int i = 0; i < len; i++){ myservo_s.write(position_of_myservo[i]); distance_from_object(); r_sensor_value = digitalRead(right_sensor); l_sensor_value = digitalRead(left_sensor); if (cnt > 5) { //無限ループ回避用 for (int i = 0; i < 3; i++) { servo_angle = 75 - (i * 15); curve(servo_angle); delay(120); backward(100); delay(500); } servo_angle = 120; curve(servo_angle); delay(120); backward(100); delay(800); cnt = 0; servo_angle = 90; curve(servo_angle); delay(120); } if (distance > 5 && distance < 18) { randNumber = random(3); if (randNumber == 1) { if (servo_angle < 150 && servo_angle >= 90) { servo_angle += 30; curve(servo_angle); delay(120); backward(100); delay(1500); } else if (servo_angle >= 150){ servo_angle = 90; curve(servo_angle); delay(150); backward(100); delay(1500); } } else { if (servo_angle > 30 && servo_angle <= 90) { servo_angle -= 30; curve(servo_angle); delay(120); backward(100); delay(1500); } else if (servo_angle <= 30) { servo_angle = 91; curve(servo_angle); delay(150); backward(100); delay(1500); } } } else if (l_sensor_value ==0) { if (pre_detection == 2) { cnt += 1; } else { cnt = 0; } pre_detection = 1; if (servo_angle > 30 && servo_angle <= 90) { servo_angle -= 30; curve(servo_angle); delay(120); backward(100); delay(1500); } else if (servo_angle <= 30) { servo_angle = 150; curve(servo_angle); delay(150); backward(100); delay(1500); } } else if (r_sensor_value ==0) { if (pre_detection == 1) { cnt += 1; } else { cnt = 0; } pre_detection = 2; if (servo_angle >= 90 && servo_angle < 150) { servo_angle += 30; curve(servo_angle); delay(120); backward(100); delay(1500); } else if (servo_angle >= 150) { servo_angle = 30; curve(servo_angle); delay(150); backward(100); delay(1500); } } else { servo_angle = 90; curve(servo_angle); delay(120); forward(150); } } } void forward(int enable) { motor_1.setSpeed(enable); motor_2.setSpeed(enable); motor_3.setSpeed(enable); motor_4.setSpeed(enable); motor_1.run(BACKWARD); motor_2.run(BACKWARD); motor_3.run(BACKWARD); motor_4.run(BACKWARD); } void backward(int enable) { motor_1.setSpeed(enable); motor_2.setSpeed(enable); motor_3.setSpeed(enable); motor_4.setSpeed(enable); motor_1.run(FORWARD); motor_2.run(FORWARD); motor_3.run(FORWARD); motor_4.run(FORWARD); } void curve(int angle) { myservo_f.write(180 - angle); myservo_r.write(angle); } void diagonal_movement(int angle) { myservo_f.write(angle); myservo_r.write(angle); } void motor_stop() { motor_1.run(RELEASE); motor_2.run(RELEASE); motor_3.run(RELEASE); motor_4.run(RELEASE); delay(100); } void distance_from_object() { Serial.read(); digitalWrite(trig, HIGH ); delayMicroseconds(10); digitalWrite(trig, LOW ); interval = pulseIn( echo, HIGH ); distance = interval * 0.017; delay(80); }
斜め方向に移動するデモのスケッチ
#include <AFMotor.h> #include <Servo.h> Servo myservo_f; Servo myservo_r; Servo myservo_s; AF_DCMotor motor_1(1, MOTOR12_64KHZ); AF_DCMotor motor_2(2, MOTOR12_64KHZ); AF_DCMotor motor_3(3, MOTOR34_64KHZ); AF_DCMotor motor_4(4, MOTOR34_64KHZ); int servo_angle = 90; void setup() { pinMode(front_sensor, INPUT); pinMode(right_sensor, INPUT); pinMode(left_sensor, INPUT); myservo_f.attach(9); myservo_r.attach(10); myservo_s.attach(17); myservo_f.write(servo_angle); myservo_r.write(servo_angle); myservo_s.write(servo_angle); Serial.begin(9600); delay(5000) ; } void loop() { diagonal_movement(45); delay(1000); forward(150); delay(2000); motor_stop(); backward(150); delay(2000); motor_stop(); diagonal_movement(135); delay(1000); forward(150); delay(2000); motor_stop(); backward(150); delay(2000); motor_stop(); } void forward(int enable) { motor_1.setSpeed(enable); motor_2.setSpeed(enable); motor_3.setSpeed(enable); motor_4.setSpeed(enable); motor_1.run(BACKWARD); motor_2.run(BACKWARD); motor_3.run(BACKWARD); motor_4.run(BACKWARD); } void backward(int enable) { motor_1.setSpeed(enable); motor_2.setSpeed(enable); motor_3.setSpeed(enable); motor_4.setSpeed(enable); motor_1.run(FORWARD); motor_2.run(FORWARD); motor_3.run(FORWARD); motor_4.run(FORWARD); } void diagonal_movement(int angle) { myservo_f.write(angle); myservo_r.write(angle); } void motor_stop() { motor_1.run(RELEASE); motor_2.run(RELEASE); motor_3.run(RELEASE); motor_4.run(RELEASE); delay(1000); }
まとめ
- 斜めに移動できる4WD車を作った
- 次は、4輪を個別にステアリング操作することで全方向に移動できる4WD車を作る
- その後は、ジャイロセンサを使って倒立振子を作るのに挑戦する