# Cyber Tank ### 程式設計與電路設計 [Cyber_Tank Github 程式連結](https://github.com/WengBingHong/Cyber_Tank.git) ## 使用材料清單 - [ ] Arduino Pro Mini - [ ] 藍芽模組 HC-05 - [ ] 直流馬達驅動模組 L298N - [ ] 步進馬達 28BYJ-48 Stepper Motor with ULN2003 Driver - [ ] 減速馬達 TAMIYA 70168 DOUBLE GEARBOX - [ ] 洞洞板 - [ ] 單芯線(22AWG) - [ ] 杜邦線 - [ ] 蜂鳴器 - [ ] 電阻 1KΩ - [ ] 鋰電池18650 兩顆 - [ ] 端子條形連接器 XH2.5 connector ## 電路圖 ![](https://i.imgur.com/oSDDaRf.jpg) ![](https://i.imgur.com/4HagDvq.jpg) ## 使用APP [Joystick 連結](https://play.google.com/store/apps/details?id=uncia.robotics.joystick&hl=zh_TW&gl=US) ![](https://i.imgur.com/3T7nwOG.png) ## 程式說明 ### Include Library * 計算三角函數 #include <math.h> * 控制步進馬達 #include <Unistep2.h> * 控制藍芽模組 #include <SoftwareSerial.h> ``` #include <math.h> #include <Unistep2.h> #include <SoftwareSerial.h> ``` ### 定義腳位 #### 蜂鳴器、L298N、步進馬達腳位定義 ``` #define buzzer 5 #define L298N_IN1 6 #define L298N_IN2 7 #define L298N_IN3 8 #define L298N_IN4 9 #define L298N_ENA A2 #define L298N_ENB A3 #define step_IN1 10 #define step_IN2 11 #define step_IN3 12 #define step_IN4 13 ``` #### Setup ``` SoftwareSerial btSerial(2, 3); // RX, TX Unistep2 stepper(step_IN1, step_IN2, step_IN3, step_IN4, 4096, 900); // IN1, IN2, IN3, IN4, total step, delay of every step(in micros) ``` ### Value class 設定 共有六個數值angle、strength、button、radian、left_rate、right_rate。 用來接收Android joystick app的藍芽buffer的字串。 | int | float | int | float | float | float | |:---------:|:--------:|:----------:|:---------------------:|:---------:|:----------:| | 角度 | 力量 | 按鈕 | 弳度 | 左輪(方向與速度) | 右輪(方向與速度) | | angle | strength | button | radian | left_rate | right_rate | | 0度~360度 | 0~100 | 1、2、3、4 | = 角度 x (π/180) | -1~+1 | -1~+1 | >Value.parting() 用來解構收到的字串AAASSSBB EX: 18008503 >> 180度 085力量 03號按鈕 >Value.show() 將解構後的數值印出 ``` class Value { public: int angle; //0~359 float strength; //0~100 int button; //1~4 float radian; //Radians = Degrees x (π/180) float left_rate; //-1~+1 float right_rate; //-1~+1 //constructor for setup Value() { Serial.println("Class Value setup..."); } //seperate string cipher to each value void parting(String str) { // angle = (str.substring(0, 3).toInt() + 450) % 360; //rotate 90 degree counterclockwise angle = str.substring(0, 3).toInt(); strength = str.substring(3, 6).toFloat() / 100; button = str.substring(6, 8).toInt(); radian = angle * M_PI / 180; left_rate = strength * (sin(radian) + cos(radian) / 2) / 1.119; //Max value of y=sin(x)+cos(x)/2 is 1.118034 right_rate = strength * (sin(radian) - cos(radian) / 2) / 1.119; //In order to make rate in range -1~+1 } //print all value void show() { Serial.print("angle: "); Serial.print(angle); Serial.print('\t'); Serial.print("strength: "); Serial.print(strength); Serial.print('\t'); Serial.print("button: "); Serial.print(button); Serial.print('\t'); Serial.print("radians: "); Serial.print(radian); Serial.print('\t'); Serial.print("left_rate: "); Serial.print(left_rate); Serial.print('\t'); Serial.print("right_rate: "); Serial.print(right_rate); Serial.println(""); // Serial.flush(); //Waits for the transmission of outgoing serial data to complete } }; Value val; ``` ### 宣告函式 分別用於接收藍芽、控制減速馬達、控制轉盤(步進馬達)、控制蜂鳴器。 ``` bool BT_cmd(); //bluetooth command void Go_Wheel(); //control 2 dc motor void turn_table(); void shoot_sound(); //buzzer shoot sound ``` ### Arduino 初始化 設定各個腳位的輸入、輸出。 >Serial.setTimeout(100) 這一條至關重要,可以防止嚴重的延遲。 ``` void setup() { pinMode(buzzer, OUTPUT); pinMode(L298N_IN1, OUTPUT); // Initialize the L298N Input pins as an output pinMode(L298N_IN2, OUTPUT); pinMode(L298N_IN3, OUTPUT); pinMode(L298N_IN4, OUTPUT); pinMode(L298N_ENA, OUTPUT); pinMode(L298N_ENB, OUTPUT); digitalWrite(L298N_IN1, LOW); // Set the L298N Input pins to LOW digitalWrite(L298N_IN2, LOW); digitalWrite(L298N_IN3, LOW); digitalWrite(L298N_IN4, LOW); analogWrite(L298N_ENA, 0); analogWrite(L298N_ENB, 0); Serial.begin(9600); btSerial.begin(9600); Serial.setTimeout(100); //reduce the delay of bluetooth while (!Serial) { ; // wait for serial port to connect } Serial.println("L298N Module setup..."); } ``` ### Void loop 主程式 用 function 與 class 簡化成。 若收到藍芽訊息就控制減速馬達、轉盤、射擊音效。 ``` void loop() { stepper.run();// We need to call run() frequently during loop() if (BT_cmd()) { Go_Wheel(); turn_table(); shoot_sound(); } } ``` ### bool BT_cmd() 收到藍芽回傳true,並且解構字串利印出來。 沒收到回傳false。 ``` bool BT_cmd() { if (btSerial.available() > 0) { String str = btSerial.readStringUntil('#'); // Serial.print("str = "); // Serial.println(str); if (str.length() == 7) { val.parting(str); val.show(); return true; } } return false; } ``` ### void Go_Wheel() 將本來-1~+1的數值改為0-255,並將0-255的數值map成127到255(讓馬達電壓不會過低),低於143的數值視為0,用PWM控制L298N的左右輪電壓(與速率正相關),再控制左右輪正逆轉。 ``` void Go_Wheel() { float r_rate = abs(val.right_rate) * 255; float l_rate = abs(val.left_rate) * 255; r_rate = map(r_rate, 0, 255, 127, 255); //motor won't go if rate is too low l_rate = map(l_rate, 0, 255, 127, 255); r_rate = r_rate > 143 ? r_rate : 0; //rate below 143 set 0 l_rate = l_rate > 143 ? l_rate : 0; //press middle and motor set 0 motor stop Serial.print("r_rate_map = "); Serial.print(r_rate); Serial.print("\t"); Serial.print("l_rate_map = "); Serial.print(l_rate); Serial.println(""); analogWrite(L298N_ENA, r_rate); analogWrite(L298N_ENB, l_rate); if (val.right_rate >= 0) { // Serial.println("r > 0 "); digitalWrite(L298N_IN1, HIGH); digitalWrite(L298N_IN2, LOW); } else { // Serial.println("r < 0 "); digitalWrite(L298N_IN1, LOW); digitalWrite(L298N_IN2, HIGH); } if (val.left_rate >= 0) { // Serial.println("l > 0 "); digitalWrite(L298N_IN3, HIGH); digitalWrite(L298N_IN4, LOW); } else { // Serial.println("l < 0 "); digitalWrite(L298N_IN3, LOW); digitalWrite(L298N_IN4, HIGH); } } ``` ### void turn_table() 步進馬達一圈為4096格,按鈕2往左轉1/16圈、按鈕4往右轉1/16圈。 ``` void turn_table() { if (val.button == 2 && stepper.stepsToGo() == 0) { //turn table turn left stepper.move(4096 / 16); } if (val.button == 4 && stepper.stepsToGo() == 0) { //turn table turn right stepper.move(-4096 / 16); } } ``` ### void shoot_sound() 控制蜂鳴器,發出像科幻片的射擊聲音。 ``` void shoot_sound() { if (val.button == 3 ) { Serial.println("3 3 3"); for (int i = 0; i < 600; i++) { digitalWrite(buzzer, HIGH); delayMicroseconds(i); digitalWrite(buzzer, LOW); delayMicroseconds(i * 2); } } } ```