采用Arduino Nano控制模塊制作的超聲波測距平衡小車
1、項(xiàng)目概述 因?yàn)榈谝淮沃谱髯云胶庑≤,心里沒底,也就沒有投入過多的資金,一切按照最小配置進(jìn)行,所以選擇“TT馬達(dá)”,俗稱“香蕉電機(jī)”的小車底盤。在等快遞送貨期間,才看到各種說用“香蕉電機(jī)”做自平衡小車的問題,最大的問題就是電機(jī)啟動對傳感器和單片機(jī)的干擾問題,還有就是平衡的穩(wěn)定性不好等問題。在我以Arduino + MPU6050 + L298N為核心做完后,閑得沒事干,就想做一款成本低,易上手,最小配置和最基本功能的自平衡小車,其目的就是給那些沒有什么經(jīng)驗(yàn)的剛?cè)胄械男率謧兲峁┮粋(gè)入門的解決方案。所以這個(gè)項(xiàng)目的目標(biāo)有以下幾點(diǎn): a、成本低; b、目標(biāo)功能明確,就是實(shí)現(xiàn)小車的自平衡; c、系統(tǒng)穩(wěn)定可靠; d、調(diào)試、操作方便簡單。
2、項(xiàng)目方案 基于上述目標(biāo),本方案采用超聲波測距模塊作為小車平衡狀態(tài)的檢測,免去了對加速度、陀螺儀傳感器的理解和復(fù)雜處理算法。小車的平衡控制仍然采用網(wǎng)絡(luò)上流行的Arduino開源硬件,再加上電機(jī)驅(qū)動模塊 L298N,電機(jī)仍然采用TT馬達(dá)(香蕉電機(jī))。 該方案為了降低成本,采用電位器調(diào)整設(shè)定小車的平衡參數(shù),不使用藍(lán)牙無線模塊或有線串口在線調(diào)整參數(shù)。 用超聲波測距的方式實(shí)現(xiàn)的自平衡小車,網(wǎng)絡(luò)上有人提出這種方案無法在坡度變化的斜坡上保持平衡,這種說法經(jīng)過我的實(shí)踐,是有解決方案的,這個(gè)問題我將在后面進(jìn)行闡述。 平衡控制的算法還是采用平衡車中經(jīng)典的PD算法。
3、硬件設(shè)計(jì) 硬件設(shè)計(jì)比較簡單,以Arduino Nano為核心控制模塊,采用HC-SR04超聲波測距模塊,L298N電機(jī)驅(qū)動模塊,供電采用7.4V/2200mAh鋰電池。圖中三個(gè)10K電位器分別用于平衡點(diǎn)設(shè)置、PD算法中Kp和Kd系數(shù)設(shè)置的調(diào)整。 電路原理圖如下所示: 圖中J1為HC-SR04超聲波測距模塊,J2、J3為L298N模塊,Arduino Nano為核心控制模塊,MG1、MG2分別為左右電機(jī)。 程序源代碼見附件 6、調(diào)試流程 超聲平衡小車裝配完畢后如下圖所示。
串口調(diào)試助手程序見附件 a、準(zhǔn)備工作 將Kp與Kd調(diào)為0,調(diào)整方法是,旋轉(zhuǎn)電位器后,按下Arduino模塊上的復(fù)位鍵調(diào)整方可有效。調(diào)整后用串口調(diào)試助手(sscom42.exe)發(fā)送“F”命令,讀取超聲自平衡小車參數(shù)的設(shè)定值。在使用串口調(diào)試助手前,首先選擇串口調(diào)試助手對應(yīng)的串口號,設(shè)置好波特率,方可發(fā)送上述命令讀取超聲自平衡小車參數(shù)的設(shè)定值,操作界面如下圖所示。 第一個(gè)數(shù)據(jù)為平衡點(diǎn)設(shè)定值,第二個(gè)數(shù)據(jù)為Kp,第三個(gè)數(shù)據(jù)為Kd。b、超聲波測距測試 發(fā)送相應(yīng)“L”命令,讀取超聲波的測距值,注意,這里不是實(shí)際的mm或cm值,而是對應(yīng)距離來回的傳播時(shí)間值,是單片機(jī)內(nèi)部計(jì)時(shí)的輸出值。 操作界面如下圖所示。 第一個(gè)數(shù)為超聲波測距模塊的直接輸出值,第二個(gè)數(shù)為一階濾波后的值。改變超聲波測距模塊與被測界面的距離,這兩個(gè)值會發(fā)生相應(yīng)的改變,距離近,測得的值變小,距離遠(yuǎn)測得的值就增大。 c、尋找物理平衡點(diǎn) 在Kp、Kd為0時(shí),用手尋找自平衡小車的物理平衡點(diǎn),同時(shí)用“L”命令(500ms定時(shí)發(fā)送)讀取超聲波測量的返回值,確定平衡點(diǎn)的返回值,并記錄下來。 d、平衡點(diǎn)PB的設(shè)定 調(diào)整PB電位器,并在Arduino復(fù)位后,用“F”命令讀取超聲自平衡小車參數(shù)的設(shè)定值,使得第一個(gè)返回的數(shù)據(jù)與上述確定的物理平衡點(diǎn)相一致。 e、判斷電機(jī)運(yùn)轉(zhuǎn)方向是否正確 在完成上述調(diào)整后,逐漸增大Kp(請記住,每次調(diào)整后,都必須復(fù)位Arduino模塊,調(diào)整才能生效),看到電機(jī)能夠動作時(shí),停止調(diào)整Kp。這時(shí)將超聲波模塊一端稍稍下壓(也就是使超聲波探頭與地面距離縮短),觀察兩個(gè)電機(jī)的轉(zhuǎn)動方向,往前(超聲波測距模塊一端為前)轉(zhuǎn)測試正確的,往后轉(zhuǎn)則說明相應(yīng)的電機(jī)兩根線接反了,將接反的線調(diào)換過來即可。
f、Kp參數(shù)整定 在電機(jī)接線正確后,再逐漸增大Kp,使得小車能夠來回有點(diǎn)擺動即可進(jìn)入調(diào)整Kd參數(shù)階段。 g、Kd參數(shù)整定 在調(diào)整完Kp后,逐漸增大Kd,使得擺動消失,如果繼續(xù)增大Kd,小車會出現(xiàn)明顯的抖動,此時(shí)將Kd往回調(diào)整,使得抖動消失即可。 h、平衡點(diǎn)PB的進(jìn)一步調(diào)整 在上述參數(shù)調(diào)整完畢后,小車一般就能保持平衡了,如果出現(xiàn)小車往一邊跑的現(xiàn)象,可通過調(diào)整PB電位器加以修正。如果小車往前跑(超聲波模塊一端為前),調(diào)整PB使得平衡點(diǎn)設(shè)定值增大;如果小車往后跑,調(diào)整PB使得平衡點(diǎn)設(shè)定值減小,直到小車能夠長時(shí)間穩(wěn)定為止。 7、照片 8、總結(jié)與展望 超聲自平衡小車的基本版已經(jīng)完成,在制作過程中與我之前用MPU6050制作的小平衡車相比有以下幾點(diǎn)體會: a、在用TT馬達(dá)的情況下,如果系統(tǒng)使用同一組電池供電,電機(jī)一啟動Arduino與MPU6050立即死機(jī),或者M(jìn)PU6050的數(shù)據(jù)受干擾極為嚴(yán)重,不可使用。解決辦法是用另一組電池單獨(dú)給L298N供電,并且L298N要選擇帶光耦隔離的。但同樣的使用TT馬達(dá)的情況下,用超聲波測距方案,系統(tǒng)僅用一組電池即可,而且L298N也無需光耦隔離,系統(tǒng)很穩(wěn)定。 b、超聲波傳感器的選擇要選擇最小測量周期短的模塊,第一次我使用的是US-015 超聲波測距模塊,US-015是目前市場上分辨率最高,重復(fù)測量一致性最好的超聲波測距模塊,US-015的分辨率高于1mm,可達(dá)0.5mm,測距精度高,重復(fù)測量一致性好,測距穩(wěn)定可靠。但他的最小測量周期大于10ms,而且對輸出數(shù)據(jù)經(jīng)常有跳動(這是由于它的靈敏度很高,在近距離時(shí)超聲波在模塊與地面之間的來回反射的二次信號都能被檢測到),為此在地面墊上一個(gè)地毯吸收了部分能量的超聲波,才能穩(wěn)定工作。在第二版中更換了HC-SR04超聲波模塊,這個(gè)模塊的測距精度雖然只有3mm,但它的最小測量周期僅略大于3ms。但這種模塊市場上有兩種,一種沒有晶體,一種是帶晶體的,帶晶體的很不穩(wěn)定,建議大家不要選擇。 c、小車的平衡穩(wěn)定性與多種因素有關(guān),建議在結(jié)構(gòu)上,重心越低越好。 d、另外,我還做了一個(gè)對比測試,數(shù)據(jù)見下表: 誤差絕對值是指小車在一段時(shí)間內(nèi),實(shí)測距離與設(shè)定平衡點(diǎn)距離誤差絕對值的平均值;濾波是指程序中對超聲波測量的距離濾波或不濾波直接使用;循環(huán)周期是程序中的延時(shí)時(shí)間,超聲波測量需要大約704us,一個(gè)周期大約為3.84ms,程序處理時(shí)間大約為136us,實(shí)測波形圖如下。 超聲測距波形圖: 3ms延時(shí)的一個(gè)周期波形圖: 通過以上對比分析,當(dāng)一個(gè)循環(huán)周期大于20ms時(shí),小車很難長時(shí)間保持平衡了,另外重心的升高,平衡的穩(wěn)定性明顯變差。 e、下一步選擇具有測速功能的小車底盤,實(shí)現(xiàn)上下坡、下臺階等復(fù)雜動作,不為別的,只是證明超聲自平衡小車這個(gè)方案是沒有嚴(yán)重的缺陷的。因?yàn)樽云胶庑≤嚤旧砭陀泻芏嗑窒扌,譬如他能下臺階就不能上臺階吧,也不能在極不平坦的路上行走等等。 f、最后,我想說明一下,自平衡小車雖然簡單,但也是一個(gè)麻雀雖小五臟俱全的項(xiàng)目,譬如小車的結(jié)構(gòu)設(shè)計(jì)、電機(jī)的響應(yīng)、扭矩的大小、小車的輪胎的選擇、PID的調(diào)參等等都會影響到小車的平衡穩(wěn)定性。我們在網(wǎng)上看到的資料大都是說傳感器、程序和調(diào)參,在結(jié)構(gòu)設(shè)計(jì)、電機(jī)的選擇(明確的參數(shù)數(shù)據(jù)對比)等方面都很欠缺或不完整,沒有充分的說服力。很多新人就想學(xué)校的實(shí)驗(yàn)課程一樣,僅僅照別人的做法做了一遍,沒有太大的收獲,特別是碰到問題不知道如何深入分析。大家在DIY的過程中都做出點(diǎn)自己的東西,無論成功與失敗,哪怕做一些經(jīng)驗(yàn)和教訓(xùn)的總結(jié)也是對大家的貢獻(xiàn)。希望大家在DIY這個(gè)樂園里無拘無束的、自由自在的、快快樂樂的玩耍。! 9、后記 在完成上述工作之后,又進(jìn)行了一些不成系統(tǒng)的零散實(shí)驗(yàn)性的工作。第一項(xiàng)工作是在上述平臺上增加了一個(gè)具有AB相編碼輸出的測速單元,將小車的速度控制作為最終目標(biāo),以調(diào)整平衡設(shè)定距離來控制小車的速度為手段,這樣就可實(shí)現(xiàn)超聲自平衡小車在變化的坡度上保持動態(tài)穩(wěn)定平衡。 小車平衡算法一般有兩種:一種是平衡(角度或距離)PID + 速度PID;另一種是,速度PIDà平衡PID。這第二種就是用速度PID的輸出去改變平衡PID的目標(biāo)值。要實(shí)現(xiàn)超聲自平衡小車在變化的坡度上保持動態(tài)穩(wěn)定平衡,就必須采用這第二種控制算法。 另外,網(wǎng)絡(luò)上有些人利用控制電機(jī)的PWM輸出值,代替測速單元,近似的給出小車的速度。對于此問題我也簡單的測試和分析過,現(xiàn)簡要談?wù)勎覍@一問題的看法:這種方式在一定的條件下是可以近似替代的,前提是在水平的地面上,地面不能有影響小車運(yùn)動的各種障礙物,第三個(gè)是小車的響應(yīng)不能太滯后。如果這三條不能滿足,此方案不可取。 這項(xiàng)工作的驗(yàn)證比較簡單,就是在有測速單元的小車上,同時(shí)增加PWM輸出模擬測速,將兩個(gè)測速的結(jié)果輸出,對輸出的數(shù)據(jù)畫出曲線,就可直觀的看出兩者的差距。 另一項(xiàng)工作是,在原有的平臺上增加了一個(gè)升壓模塊,將L298N的Vin由以前的7.4V提高到12V,小車的穩(wěn)定性有一定的改觀,關(guān)于這一點(diǎn)一是通過觀察就可感覺到平衡的穩(wěn)定性有所提高,另外通過數(shù)據(jù)分析也可明顯的得出結(jié)論。在兩種電壓(注意,此時(shí)的Kp、Kd、PB等參數(shù)都要做相應(yīng)的調(diào)整,使得每種電壓下都是最佳狀態(tài))下,將PID的輸出值(這個(gè)值是在輸出限制在255以內(nèi)之前的值),觀察超過255的頻數(shù)就可得出結(jié)論,如果超過255,在輸出之前被限制了,就說明這次調(diào)整是不到位的。 第三項(xiàng)工作是增加了一個(gè)四通道遙控開關(guān),實(shí)現(xiàn)了小車的前進(jìn)、后退、左轉(zhuǎn)、右轉(zhuǎn)功能,這項(xiàng)工作中就利用PWM的輸出近似得出小車的速度。這個(gè)遙控開關(guān)也很便宜,雖然只有A、B、C、D四個(gè)按鍵,但可以輕易的做到八個(gè)有效狀態(tài)的控制。這八個(gè)狀態(tài)分別為:A、B、C、D、AB、CD、AC、BD。 
Arduino Nano源程序如下:
- //利用超聲波測距傳感器實(shí)現(xiàn)小車平衡
- char val='z'; //調(diào)節(jié)與控制命令字
- double Kp=0.01, Kd=0.02; //PID系數(shù)
- unsigned int PB_ad=0, KP_ad=0, KD_ad=0, i; //平衡點(diǎn)調(diào)整,PID各調(diào)整設(shè)定系數(shù)
- unsigned int Len_Echo = 0; //回波時(shí)間
- int E_0 = 0, E_1 = 0, PWM_Out; //誤差,PWM輸出
- double Len_filter = 0, Len_0 = 100; //測距濾波,機(jī)械平衡距離
- unsigned int TrigPin = 4; //HC-SR04觸發(fā)信號
- unsigned int EchoPin = 5; //HC-SR04回波檢測
- unsigned int M_IN1 = 6; // L298-IN1
- unsigned int M_IN2 = 7; // L298-IN2
- unsigned int M_IN3 = 8; // L298-IN3
- unsigned int M_IN4 = 9; // L298-IN4
- unsigned int M_ENA = 10; // L298-ENA
- unsigned int M_ENB = 11; // L298-ENB
- //初始化
- void setup() {
- Serial.begin(115200);
- pinMode(M_ENA, OUTPUT); //電機(jī)控制
- pinMode(M_IN1, OUTPUT);
- pinMode(M_IN2, OUTPUT);
- pinMode(M_ENB, OUTPUT);
- pinMode(M_IN3, OUTPUT);
- pinMode(M_IN4, OUTPUT);
- pinMode(EchoPin, INPUT); //超聲波測距
- pinMode(TrigPin, OUTPUT);
- digitalWrite(TrigPin, LOW);
- for(i=0; i<64; i++) {
- PB_ad += analogRead(A0); //讀取平衡點(diǎn)電位器設(shè)定值
- KP_ad += analogRead(A1); //讀取PID-P電位器設(shè)定值
- KD_ad += analogRead(A2); //讀取PID-D電位器設(shè)定值
- }
- Kp *= KP_ad/64; //Kp = 3.23;
- Kd *= KD_ad/64; //Kd = 8.14;
- Len_0 += PB_ad/640; //Len_0 = 189;
- i = 0;
- }
- //主循環(huán)程序
- void loop() {
- if (Serial.available() > 0) {
- val = Serial.read();
- if(val == 'F') {
- Serial.print(Len_0); Serial.print("\t"); Serial.print(Kp); Serial.print("\t"); Serial.println(Kd);//查看設(shè)置參數(shù)
- }
- if(val == 'L') {
- Serial.print(Len_Echo); Serial.print("\t"); Serial.println(Len_filter); //查看傳感器實(shí)測值,濾波值
- }
- }
- digitalWrite(TrigPin, HIGH); //發(fā)送超聲波測量觸發(fā)脈沖
- delayMicroseconds(10);
- digitalWrite(TrigPin, LOW);
- Len_Echo = pulseIn(EchoPin, HIGH); //回波時(shí)間測量
- if((Len_Echo < 300) && (Len_Echo > 70)) {
- Len_filter *= 0.7; //一階互補(bǔ)濾波
- Len_filter += 0.3*Len_Echo;
- i ++;
- if(i > 50){
- E_0 = Len_0 - Len_filter;
- PWM_Out = Kp * E_0 + Kd * (E_0 - E_1);
- E_1 = E_0;
- i = 100;
- SetMotorVoltage(PWM_Out);
- }
- }else {
- SetMotorVoltage(0); //超出平衡范圍,停止PWM輸出
- }
- delay(5); //延時(shí)5毫秒,保證超聲測距可靠工作
- }
- //電機(jī)輸出
- void SetMotorVoltage(int MotorVol) {
- if(MotorVol >=0) {
- digitalWrite(M_IN1, LOW);
- digitalWrite(M_IN2, HIGH);
- digitalWrite(M_IN3, LOW);
- digitalWrite(M_IN4, HIGH);
- }else {
- digitalWrite(M_IN1, HIGH);
- digitalWrite(M_IN2, LOW);
- digitalWrite(M_IN3, HIGH);
- digitalWrite(M_IN4, LOW);
- MotorVol = -MotorVol;
- }
- if(MotorVol > 255) MotorVol = 255; //防止PWM值超過255
- analogWrite(M_ENA, MotorVol);
- analogWrite(M_ENB, MotorVol);
- }
復(fù)制代碼
所有資料51hei提供下載:
超聲自平衡小車程序.zip
(1.51 KB, 下載次數(shù): 97)
2018-10-13 15:53 上傳
點(diǎn)擊文件名下載附件
下載積分: 黑幣 -5
采用Arduino Nano控制模塊制作的超聲波測距平衡小車設(shè)計(jì)報(bào)告.doc
(1.55 MB, 下載次數(shù): 33)
2018-10-13 15:53 上傳
點(diǎn)擊文件名下載附件
下載積分: 黑幣 -5
串口調(diào)試助手程序.zip
(338.41 KB, 下載次數(shù): 94)
2018-10-13 15:53 上傳
點(diǎn)擊文件名下載附件
下載積分: 黑幣 -5
器件采購清單.doc
(650 KB, 下載次數(shù): 29)
2018-10-13 15:53 上傳
點(diǎn)擊文件名下載附件
下載積分: 黑幣 -5
|