##概要
Arduinoを利用した自動運転車です。
超音波センサと赤外線センサを併用し、障害物を回避して進みます。
※起動時に気温測定し、音速の設定に反映しました。(2019/7/27追記)
※Bluetoothでシリアル通信できるよう、モーターシールドを改造しました。(2019/7/27追記)
##ロジック
①起動時に気温を測定(気温によって音速が変わるため)
②赤外線センサで前面距離をチェック
③超音波センサで右45度の距離をチェック
④超音波センサで前面距離をチェック
⑤赤外線センサで前面距離をチェック
⑥超音波センサで左45度の距離をチェック
⑦赤外線センサで前面距離をチェック
⑧超音波センサで前面距離をチェック
.....
左右の壁との距離が19cm未満のときは反対方向に旋回し、
前面距離が13cm未満の場合は一旦バックし、左右90度の距離を測定して距離が遠い方に旋回します。
(赤外線の場合はボリュームで調整した距離で反応。概ね壁から3cmくらいで調整。)
##必要なもの
- Arduino Uno(互換機)
- タミヤ 楽しい工作シリーズ No.97 ツインモーターギヤーボックス (70097)
- タミヤ 楽しい工作シリーズ No.100 トラック&ホイールセット (70100)
- タミヤ 楽しい工作シリーズ No.157 ユニバーサルプレート 2枚セット (70157)
- Rasbee オリジナル L293D モーター ドライブ シールド
- EasyWordMall HC-SR04 超音波距離センサーモジュール
- LM393 IR赤外線障害物回避センサモジュール
- DS18B20 シングルバスデジタル 温度センサ モジュール
- HC-06 Bluetooth モジュール
- マイクロサーボ SG92R
- 0.1μfコンデンサ
- 電池ケース(単3*4)
- 006Pスナップ
- ピンソケット(A0〜A5ピンを使用するために、シールドにハンダ付けします。)
##ソースコード
L293D_tank_auto_avoid.ino
#include <DallasTemperature.h>
#include <OneWire.h>
#include <AFMotor.h>
#include <Servo.h>
Servo servo1; //任意のサーボモータークラスを用意。
AF_DCMotor right_motor(4);
AF_DCMotor left_motor(1);
const int trig = 15; // 出力ピン
const int echo = 14; // 入力ピン
const int ir = 18; // 入力ピン
const int servopwm = 9; // Servolib only 9 or 10
const int DS18B20_PIN = 19;
OneWire oneWire(DS18B20_PIN);
DallasTemperature sensors(&oneWire);
float temp;
void setup() {
Serial.begin(9600);
pinMode(trig,OUTPUT);
pinMode(echo,INPUT);
servo1.attach(servopwm);
sensors.begin();
// turn on motor
right_motor.setSpeed(200);
left_motor.setSpeed(200);
right_motor.run(RELEASE);
left_motor.run(RELEASE);
sensors.requestTemperatures();
temp = sensors.getTempCByIndex(0);
Serial.print("Temperature: ");
Serial.print(sensors.getTempCByIndex(0));
//Serial.print((char)223);
Serial.println("C");
delay(100);
}
void loop() {
ircheck();
right_check();
ircheck();
forward_check();
ircheck();
left_check();
ircheck();
forward_check();
moter_forward(127,125,130);
}
float measure(){
// 超音波の出力終了
digitalWrite(trig,LOW);
delayMicroseconds(1);
// 超音波を出力
digitalWrite(trig,HIGH);
delayMicroseconds(11);
// 超音波を出力終了
digitalWrite(trig,LOW);
// 出力した超音波が返って来る時間を計測
int t = pulseIn(echo,HIGH);
// 計測した時間と音速から反射物までの距離を計算
float sonic = 331.5 + 0.6*temp;
float distance = (float)t * ((sonic*0.0001)/2);
//float distance = t*0.017;
// 計算結果をシリアル通信で出力
Serial.print(distance);
Serial.println(" cm");
//delay(500);
if (distance < 0){
distance = 20;
}
return distance;
}
void ircheck(){
int irresult;
irresult = analogRead(ir) ; // IRセンサーから読込む
Serial.print("irresult:");
Serial.println(irresult) ; // シリアルモニターに表示させる
if (irresult < 100){
avoid();
}
}
void moter_forward(int L_duty, int R_duty, int keeptime){
Serial.println("Forward");
right_motor.setSpeed(R_duty);
left_motor.setSpeed(L_duty);
right_motor.run(FORWARD);
left_motor.run(FORWARD);
delay(keeptime);
}
void moter_back(int L_duty, int R_duty, int keeptime){
Serial.println("Backward");
right_motor.setSpeed(R_duty);
left_motor.setSpeed(L_duty);
right_motor.run(BACKWARD);
left_motor.run(BACKWARD);
delay(keeptime);
}
void moter_left(int L_duty, int R_duty, int keeptime){
Serial.println("Left");
right_motor.setSpeed(R_duty);
left_motor.setSpeed(L_duty);
right_motor.run(FORWARD);
left_motor.run(BACKWARD);
delay(keeptime);
}
void moter_right(int L_duty, int R_duty, int keeptime){
Serial.println("Right");
right_motor.setSpeed(R_duty);
left_motor.setSpeed(L_duty);
right_motor.run(BACKWARD);
left_motor.run(FORWARD);
delay(keeptime);
}
void moter_stop(int keeptime){
Serial.println("Stop");
right_motor.run(RELEASE);
left_motor.run(RELEASE);
delay(keeptime);
}
void right_check(){
servo1.write(45); //right
delay(300);
Serial.print("Right:");
float r_cm = measure();
if(r_cm < 19){
moter_stop(10);
moter_left(150,150,15);
}
}
void forward_check(){
servo1.write(83); //forward
delay(300);
Serial.print("Forward:");
float distance = measure();
if (distance < 13){
avoid();
}
}
void left_check(){
servo1.write(134); //left
delay(300);
Serial.print("Left:");
float l_cm = measure();
if(l_cm < 19){
moter_stop(10);
moter_right(150,150,15);
}
}
void avoid(){
Serial.println("Avoid");
moter_stop(80);
moter_back(150,150,600);
moter_stop(80);
servo1.write(0); //right
delay(500);
Serial.print("Right:");
float r_cm = measure();
servo1.write(173); //left
delay(500);
Serial.print("Left:");
float l_cm = measure(); //forward
servo1.write(83); //forward
delay(300);
if(r_cm > l_cm) {
moter_right(160,160,300);
}
else{
moter_left(160,160,300);
}
}
https://github.com/type89/arduino_auto_tank
##工夫したところ
- 壁への角度が浅い場合にうまく検知できないので、45度の角度で首振りするようにしました。
- 正面衝突を防ぐため、前進する速度は最低限にしました。
- 赤外線センサの併用は 「あること・ないこと日記」 に記載の記事を参考にさせていただきました。超音波センサーで検知できないことも多いため、効果は大きいです。
- バック、旋回を出力を強めにして、絨毯の上でも鋭く曲がれるようにしました。曲がりすぎないように時間は短時間に調整しています。
- L293Dモータシールドの規定のサーボのコネクタを利用すると、サーボモータの駆動にArduinoの電源(006P)を使用してしまいます。006Pの電力消費を抑えるため、DCモータ用の電源(単3*4)から取得するよう接続しました。(マイナスの配線を電池のマイナスとArduinoのGNDに分岐させることが必要。)
- 温度センサを追加し、気温に基づいて音速を測定するよう修正しました。(2019/7/22追記)
- Bluetoothでシリアル通信できるよう、モーターシールドを改造しました。RXピン・TXピンは使用していないので、シールドの該当ピンに直接ケーブルをハンダ付けしました。(2019/7/27追記)
##作者のサイト