2022年1月12日 星期三

D1 mini TryBot - WiFi、藍牙、超音波避障、紅外線循跡自走車

TryBot 原以Arduino UNO為主控板,善用Arduino的數位及類比I/O,可達許多功能。此文改用D1 mini接上TryBot作為主控板,D1 mini的腳位不如Arduino UNO多,但在適當設計下,仍可操控TryBot上面與自走車所有相關之功能,且可兼具藍牙及WiFi無線控制。


接線
電源:原TryBot的Arduino UNO插槽上Vin接至5V,以提供TryBot上5V接腳的5V電源。

  1. D0: 接Arduino pin A0,作為IR0的輸入,但僅有數位輸入,僅能判斷黑(1)白(0)
  2. D1: 接Arduino pin A4,作為IR4的輸入,但僅有數位輸入,僅能判斷黑(1)白(0)
  3. D2: 接Arduino pin 12,超音波發射Trig
  4. D3: 接Arduino pin 13,超音波接收Echo,內建pull-up
  5. D4: 接Arduino pin 4,右馬達轉向,高電位前進、低電位後退,內建pull-up
  6. D5: 接Arduino pin 5,右馬達速度,理論上0~1023
  7. D6: 接Arduino pin 6,左馬達速度,理論上0~1023
  8. D7: 接Arduino pin 7,左馬達轉向,高電位前進、低電位後退
  9. D8: 接Arduino pin 8,蜂鳴器,低準位致能,內建pull-down
  10. A0: 接Arduino pin A2,作為IR2的輸入,類比輸入0~1023,代表白至黑的灰階
  11. TX: 接Arduino pin 1 TX,此為硬體序列埠,燒錄程式時需拔除藍牙模組
  12. RX: 接Arduino pin 0 RX,此為硬體序列埠,燒錄程式時需拔除藍牙模組
  13. 5V: 接TryBot上5V
  14. GND: 接TryBot上GND
圖 D1 mini 腳位圖

圖 接線圖

以下分別為FlagBlock圖控程式以及Arduino 程式碼的Setup及函式。
圖 設定程式

圖 超音波測距模組,此函數有回傳值,代表待測物距離,單位為公分

圖 IR紅外線循跡模組,偵測結果以IR_text變數的三個結果表示,B為黑色、W為白色

圖 馬達驅動模組D1 mini的PWM輸出可達1023,為維持與Arduino的相容性,馬達轉速輸入仍為0~255,但在此模組內乘4倍


表 Setup module,分為變數宣告及setup()兩部分
  1. int left;
  2. int right;
  3. int UltraSonic_trig;
  4. int IR_A2;
  5. String IR_text;
  6. int UltraSonic_echo;
  7. int Left_direction;
  8. int Left_speed;
  9. int High_Level_Duration;
  10. int Right_speed;
  11. int Right_direction;
  12. int Buzzer;
  13. int distance = 0;
  14. String Receive_text;
  1. void setup() {
  2.   Serial.begin(9600);
  3.   pinMode(A0, INPUT);
  4.   pinMode(D0, INPUT);
  5.   pinMode(D1, INPUT);

  6.   UltraSonic_trig = D3;
  7.   UltraSonic_echo = D2;
  8.   Left_direction = D7;
  9.   Left_speed = D6;
  10.   Right_speed = D5;
  11.   Right_direction = D4;
  12.   Buzzer = D8;
  13.   IR_A2 = 0;
  14.   Receive_text = u8"";
  15.   IR_text = u8"";
  16. }

表 Sonic_Distance function,此函數有回傳值,代表待測物距離,單位為公分
  1. float Sonic_Distance() {
  2.   pinMode(UltraSonic_trig, OUTPUT);
  3.   digitalWrite(UltraSonic_trig, HIGH);
  4.   delayMicroseconds(10);
  5.   pinMode(UltraSonic_trig, OUTPUT);
  6.   digitalWrite(UltraSonic_trig, LOW);
  7.   pinMode(UltraSonic_echo, INPUT);
  8.   High_Level_Duration = pulseIn(UltraSonic_echo, HIGH, 10000);
  9.   if (High_Level_Duration == 0) {
  10.     pinMode(UltraSonic_echo, OUTPUT);
  11.     digitalWrite(UltraSonic_echo, LOW);
  12.   }
  13.   return (float)(High_Level_Duration / 58.2);
  14. }

表 IR detect function,偵測結果以IR_text變數的三個結果表示,B為黑色、W為白色
  1. void IR_detect() {
  2.   IR_text = u8"";
  3.   if (digitalRead(D0)) {
  4.     IR_text += String(u8"B");
  5.   } else {
  6.     IR_text += String(u8"W");
  7.   }
  8.   if (analogRead(A0) > 511) {
  9.     IR_text += String(u8"B");
  10.   } else {
  11.     IR_text += String(u8"W");
  12.   }
  13.   if (digitalRead(D1)) {
  14.     IR_text += String(u8"B");
  15.   } else {
  16.     IR_text += String(u8"W");
  17.   }
  18. }

表 motor control function,D1 mini的PWM輸出可達1023,為維持與Arduino的相容性,馬達轉速輸入仍為0~255,但在此模組內乘4倍
  1. void motor(int left, int right) {
  2.   if (left >= 0) {
  3.     pinMode(Left_direction, OUTPUT);
  4.     digitalWrite(Left_direction, HIGH);
  5.   } else {
  6.     pinMode(Left_direction, OUTPUT);
  7.     digitalWrite(Left_direction, LOW);
  8.   }
  9.   analogWrite(Left_speed, (4 * abs(left)));
  10.   if (right >= 0) {
  11.     pinMode(Right_direction, OUTPUT);
  12.     digitalWrite(Right_direction, HIGH);
  13.   } else {
  14.     pinMode(Right_direction, OUTPUT);
  15.     digitalWrite(Right_direction, LOW);
  16.   }
  17.   analogWrite(Right_speed, (4 * abs(right)));
  18. }















沒有留言:

張貼留言