TryBot 原以Arduino UNO為主控板,善用Arduino的數位及類比I/O,可達許多功能。此文改用D1 mini接上TryBot作為主控板,D1 mini的腳位不如Arduino UNO多,但在適當設計下,仍可操控TryBot上面與自走車所有相關之功能,且可兼具藍牙及WiFi無線控制。
接線
電源:原TryBot的Arduino UNO插槽上Vin接至5V,以提供TryBot上5V接腳的5V電源。
- D0: 接Arduino pin A0,作為IR0的輸入,但僅有數位輸入,僅能判斷黑(1)白(0)
- D1: 接Arduino pin A4,作為IR4的輸入,但僅有數位輸入,僅能判斷黑(1)白(0)
- D2: 接Arduino pin 12,超音波發射Trig
- D3: 接Arduino pin 13,超音波接收Echo,內建pull-up
- D4: 接Arduino pin 4,右馬達轉向,高電位前進、低電位後退,內建pull-up
- D5: 接Arduino pin 5,右馬達速度,理論上0~1023
- D6: 接Arduino pin 6,左馬達速度,理論上0~1023
- D7: 接Arduino pin 7,左馬達轉向,高電位前進、低電位後退
- D8: 接Arduino pin 8,蜂鳴器,低準位致能,內建pull-down
- A0: 接Arduino pin A2,作為IR2的輸入,類比輸入0~1023,代表白至黑的灰階
- TX: 接Arduino pin 1 TX,此為硬體序列埠,燒錄程式時需拔除藍牙模組
- RX: 接Arduino pin 0 RX,此為硬體序列埠,燒錄程式時需拔除藍牙模組
- 5V: 接TryBot上5V
- GND: 接TryBot上GND

圖 D1 mini 腳位圖
圖 設定程式
圖 超音波測距模組,此函數有回傳值,代表待測物距離,單位為公分
圖 馬達驅動模組D1 mini的PWM輸出可達1023,為維持與Arduino的相容性,馬達轉速輸入仍為0~255,但在此模組內乘4倍
表 Setup module,分為變數宣告及setup()兩部分
- int left;
- int right;
- int UltraSonic_trig;
- int IR_A2;
- String IR_text;
- int UltraSonic_echo;
- int Left_direction;
- int Left_speed;
- int High_Level_Duration;
- int Right_speed;
- int Right_direction;
- int Buzzer;
- int distance = 0;
- String Receive_text;
- void setup() {
- Serial.begin(9600);
- pinMode(A0, INPUT);
- pinMode(D0, INPUT);
- pinMode(D1, INPUT);
- UltraSonic_trig = D3;
- UltraSonic_echo = D2;
- Left_direction = D7;
- Left_speed = D6;
- Right_speed = D5;
- Right_direction = D4;
- Buzzer = D8;
- IR_A2 = 0;
- Receive_text = u8"";
- IR_text = u8"";
- }
表 Sonic_Distance function,此函數有回傳值,代表待測物距離,單位為公分
- float Sonic_Distance() {
- pinMode(UltraSonic_trig, OUTPUT);
- digitalWrite(UltraSonic_trig, HIGH);
- delayMicroseconds(10);
- pinMode(UltraSonic_trig, OUTPUT);
- digitalWrite(UltraSonic_trig, LOW);
- pinMode(UltraSonic_echo, INPUT);
- High_Level_Duration = pulseIn(UltraSonic_echo, HIGH, 10000);
- if (High_Level_Duration == 0) {
- pinMode(UltraSonic_echo, OUTPUT);
- digitalWrite(UltraSonic_echo, LOW);
- }
- return (float)(High_Level_Duration / 58.2);
- }
表 IR detect function,偵測結果以IR_text變數的三個結果表示,B為黑色、W為白色
- void IR_detect() {
- IR_text = u8"";
- if (digitalRead(D0)) {
- IR_text += String(u8"B");
- } else {
- IR_text += String(u8"W");
- }
- if (analogRead(A0) > 511) {
- IR_text += String(u8"B");
- } else {
- IR_text += String(u8"W");
- }
- if (digitalRead(D1)) {
- IR_text += String(u8"B");
- } else {
- IR_text += String(u8"W");
- }
- }
表 motor control function,D1 mini的PWM輸出可達1023,為維持與Arduino的相容性,馬達轉速輸入仍為0~255,但在此模組內乘4倍
- void motor(int left, int right) {
- if (left >= 0) {
- pinMode(Left_direction, OUTPUT);
- digitalWrite(Left_direction, HIGH);
- } else {
- pinMode(Left_direction, OUTPUT);
- digitalWrite(Left_direction, LOW);
- }
- analogWrite(Left_speed, (4 * abs(left)));
- if (right >= 0) {
- pinMode(Right_direction, OUTPUT);
- digitalWrite(Right_direction, HIGH);
- } else {
- pinMode(Right_direction, OUTPUT);
- digitalWrite(Right_direction, LOW);
- }
- analogWrite(Right_speed, (4 * abs(right)));
- }
沒有留言:
張貼留言