<meter id="pryje"><nav id="pryje"><delect id="pryje"></delect></nav></meter>
          <label id="pryje"></label>

          新聞中心

          EEPW首頁 > 嵌入式系統 > 設計應用 > Arduino通過太陽能操作機器人割草機動力

          Arduino通過太陽能操作機器人割草機動力

          作者:時間:2023-08-31來源:電子產品世界收藏

          這個機器人會修剪你花園里的草,呆在指定的區域內,避開所有障礙,完全自主工作,用電池板自動充電。

          本文引用地址:http://www.ex-cimer.com/article/202308/450104.htm

          MowerFea2

          在這篇文章中,我們介紹了一種機器人割草機,它由供電,能夠僅利用來自太陽的清潔能源進行操作;這與商業項目有很大的不同,商業項目需要一個連接到電網的充電站。在設計驅動的割草機時,至關重要的是,大部分能量來自太陽,當然,如果太陽能足以為機器人完全供電,最終結果就會得到:然而,鑒于現有太陽能電池板的低效率,這一目標將很難實現。在我們的項目中,機器人的整個表面都是太陽能電池板,同時也是一個蓋子:只有側面是自由的,無論如何,它們在供應能源方面都不會發揮決定性作用。顯然,這種選擇對項目的其余部分構成了嚴重的限制,因為通過這種方式,我們已經定義了可用的最大功率。

          我們必須考慮到,太陽能并不總是可用的,因為許多花園區域經常處于陰涼處,或者無論如何都沒有被太陽直接照射,所以我們必須考慮相當大的電力損失。只有當機器人有一個蓄能器,能夠在缺乏陽光的情況下提供能量時,才能彌補這些損失。在這種情況下,電池起到緩沖作用,在電量充足時積累能量,相反,在機器人處于陰影下時提供能量。從這個角度來看,鉛電池是最合適的電池,但沒有什么能阻止我們使用在重量和容量方面表現更好的電池,比如鋰電池。在陽光充足的情況下,太陽能電池板能夠用約0.6A的電流為內部電池充電,總功率約為8W,遠低于最高效的電動割草機所使用的功率,功率為220Vac。這讓我們已經明白,像我們在這些頁面中描述的產品不能完全取代手動割草機,因為當草太高時,應該不時使用最后一款。相反,機器人割草機可以用于連續穩定地修剪草坪。

          MowerConnection

          這種解決方案還提供了另一個優勢,因為連續割草可以確保草始終年輕柔軟,而且當它被切成很小的碎片時,它會在短時間內自行分解,從而為草坪施肥。你不應該指望被割下的草會被收集起來:相反,它會沉積在剛剛割下的草葉中。

          對于這種用途,所需的電力更少,并且可以使用電池供電系統輕松管理。游戲中的弱動力說服我們選擇一個牽引力和功率降低的切割發動機。也許,它們可能不完全符合我們讀者的需求,他們可能會根據預算和個人需求選擇他們喜歡的引擎和結構。為了確定草坪上的切割區域,地下布線系統被證明是簡單、準確和可靠的。它也是定義機器人工作區域的最佳系統。

          一切都是基于一根簡單電線的使用,電線鋪設在地上或其下,并連接到一個控制單元,用大約10V和34KHz頻率的交流電信號為電線本身供電。在機器人底盤的下部安裝了兩個小卷軸,一個在右側,另一個在左側,這兩個卷軸都是指由并聯的電容器形成的電路。由并聯電感和電容器形成的電路被稱為并聯諧振電路,并且被計算為使得當磁場以34KHz的頻率變化時,由外部磁場感應的其端部的張力處于最大值。

          Mowerinside3

          現在讓我們來更詳細地描述這個項目所采用的電氣部分。最重要的創新是采用了作為控制板,使你能夠獲得一個更用戶友好、更易于破解的項目,即使是經驗不足的人。為了實現最大的使用靈活性,我們認為要實現特定的屏蔽,而不是實現特定的電子板。

          這種選擇也決定了一個缺點,即當板處于待機模式時,電流的吸收,這種情況可能發生在夜間,機器人仍然沒有電源。在這種情況下,內部電池將不得不面對板和屏蔽的長時間供電。

          關于發動機的管理,就牽引力而言,我們計算了商用護罩的使用情況,這是唯一一種可用于修改控制銷分配的商用護罩;為此,請使用表1正確分配引腳。發動機護罩可管理兩臺發動機,每臺發動機的總最大吸收功率為2A,確保有足夠的動力用于牽引。顯然,沒有什么可以禁止我們使用其他類型的驅動器來驅動發動機,從而增加功率;唯一重要的是,駕駛員為每臺發動機提供兩個可用的控制信號,一個用于定義方向,另一個用于控制速度所需的PWM信號。

          1143_Schema

          該屏蔽是使用具有特定功能的最新組件設計的,因此需要使用高度集成的SMD組件,從而將所有東西都安裝到與 UNO兼容的屏蔽中。用于讀取地下線路的部分基于包含六個CD4069型NOT門的集成電路。使用這種集成電路,我們只需放大并平方并聯諧振電路頭部的弱信號。即使在這個項目中,我們也計算了激活或停用太陽能電池板的可能性;為此,我們依靠集成電路ASSR1611,這是一種由光隔離器控制的固態開關。如果使用的緩沖電池是鉛電池,則無需拆下面板,因為這種電池可以很好地支持過充電,但如果您使用更現代的鋰電池,則必須在達到極限電壓后暫停充電,否則您可能會導致電池損壞,或在最壞的情況下發生爆炸。

          兩個名為ACS712的集成電路可以測量太陽能電池板提供的電流和切割引擎吸收的電流:5A范圍的版本對我們來說似乎綽綽有余。

          這些集成電路使用霍爾效應技術來提供(作為輸出)與電源電路上的循環電流成比例的張力,從而與輸出級保持電流分離。測量太陽能電池板電流的可能性將是檢測最適合給電池充電的區域的基礎。運行時,實際上會存儲面板提供的電流水平,當割草機必須找到充電區時,在電池電量接近低的情況下,會再次使用數據。機器人不知道真實的大氣情況(晴天或陰天),也不知道是否有陰影區域,甚至不知道它是否在變暗:它只會在上一次工作中檢測到的最大發光強度方面尋找一個足夠亮的區域。測量切割引擎吸收的電流將是了解切割過程中的作用力的基礎,也是計算在異常情況下何時停止切割的基礎。

          為了完成關于屏蔽的討論,我們必須注意二極管D1,它是在電池電量不足的情況下避免電池在光伏面板上的張力所必需的;以及使I2C總線可用所需的兩個連接器。

          1143_TopSilk

          MowerShieldTop

          還設計了三個通用按鈕,它們通過電阻網絡連接到模擬輸入A0;事實上,所有的數字引腳都已被占用。一個入口由一個簧片傳感器使用,該傳感器放置在非??拷髽休S輪的位置,并由一個小磁鐵操作,該磁鐵在每次旋轉時插入同一個輪中。有了這個傳感器,就可以確定機器人是否有規律地移動,或者一個或多個輪子是否被鎖住或徒勞地移動。

          Img6

          我們增加了兩個數字輸入,您可以將前面的障礙物識別機械開關連接到它們;除此之外,經驗證的超聲波傳感器連接到I2C總線并檢測前方物體。

          超聲波傳感器雖然性能非常好,但可能會被表面特別小的物體(如金屬網)或一些非常不規則的表面(如灌木)所欺騙。

          至于草坪修剪,我們依賴于航空建模領域使用的無刷電機,該電機與通過組合兩個刀片獲得的刀片相連。

          Mowerinside

          我們談論的是一臺200W的發動機,但它的使用率不超過20%。發動機控制分配給模型構建中使用的ESC(電子速度控制),并使用簡單的PWM信號進行操作,易于使用Arduino進行管理,因為它已經在系統庫中具有相關功能。

          MowerPin

          為了測量電池頭部的張力,我們將使用電機護罩中已有的分壓器。然而,需要修改軌道,將分配器輸出的張力從引腳A5帶到引腳A3,以便引腳A4和A5可用于I2C總線。兩條數字線路D0和D1用于與PC通信,但一旦對Arduino進行了編程,它們就可以用于與GPS或藍牙等其他外圍設備通信。

          Tab. 1 Mower Shield pin connect

          Pin Arduino

             nameDescription
          A0Button_pinPush button
          A1ICut_pinMotor cut current
          A2IPanel_pinSolar panel current
          A3VBat_pinBattery voltage (from motorshield_FE)
          A4SDA_pinI2C BUS
          A5SCL_pinI2C BUS
          D0RXD_pinGPS or bluetooth
          D1TXD_pinGPS or bluetooth
          D2Encoder_pinEncoder pivoting wheel
          D3PWMA_pinPWM motor A motorshield_FE
          D4DIRA_pinDirection motor A motorshield_FE
          D5BWFR_pinBuried Wire Fence Right
          D6BWFL_pinBuried Wire Fence Left
          D7Panel_pinON/OFF pannel
          D8ESC_pinESC cut motor signal
          D9SWOL_pinObstacle switch Right
          D10SWOR_pinObstacle switch Left
          D11PWMB_pinPWM motor B motorshield_FE
          D12DIRB_pinDirection motor B motorshield_FE
          D13LCD_pinSerial LCD

          硬件現在已經相當完整,防護罩做得非常好,盡管還可以添加一些更多的功能,比如雨水傳感器,或者更好的是,草濕度傳感器,這將使機器人能夠停下來等待更好的切割條件。作為一種安全措施,我們在旋轉輪上安裝了一個編碼器,作為一種支撐,甚至可以在牽引輪上添加一個編碼器甚至可以添加一個傳感器來測量吸收的電流。

          電氣部分還計算了用于調試功能且絕對不需要的綠色背景黑色文本串行顯示器的使用情況。

          使用一個簡單的Arduino板應該可以讓許多用戶嘗試實現電動割草機,當然也不會缺少社區的貢獻,以及進一步改進的建議。

          Mowerinside2

          關于屏蔽的電氣連接,請參考下表:

          表2–屏蔽連接器的鏈接

          connector function

          J1 Ignition switch

          J2 Battery Power

          J3 Photovoltaic panel

          J4 Electronic speed control (ESC) for the cutting engine

          J5 Obstacle detection Switch left

          J6 Obstacle detection Switch right

          J7 Cotrol signal for the speed control of the cutting engine

          J8 LCD Display

          J9 Reed contact for the rear pivoting wheel

          J10 1mH Reel for underground wiring detection left

          J11 1mH Reel for underground wiring detection right

          J12 Ultrasonic Sensor SRF-02 right

          J13 Ultrasonic Sensor SRF-02 left

          J14 Buttons

          我們將在下面列出本項目中使用的所有硬件組件:

          N°2微電機齒輪箱RH-158-12-200

          N°2輪轂

          2號超聲波傳感器SRF02。

          N°1鉛蓄電池2,1Ah NP21-12

          N°1太陽能電池板STP10M 10W 0,59A

          用于診斷的N°1 LCD串行顯示器1446-LCDSER16X2NV

          用于航空建模BMA20-22L的N°1無刷電機

          ESC-18A無刷電機的N°1速度控制

          1個用于報警系統的磁性傳感器(用作編碼器)

          能量平衡使我們能夠了解有用的能量循環以及一天可以做多少工作:

          切割發動機吸收的電流,約1.4A

          電子設備吸收的電流0,07A

          發動機吸收的電流0,4A

          光伏板吸收的電流,約0.6A

          根據測量數據(使用所述設置),我們可以推斷運行機器所需的電流是光伏板提供的電流的三倍,也就是說,一個小時的工作需要三個小時的充電,有用的使用百分比為30%??紤]到在夏天,在最佳條件下,大約有九個晴天,我們可能一天有大約三個小時的時間進行修剪,這通常足以維持500平方米的花園秩序。

          MowerMounting

          BOM

          R1: 10 Mohm (0805)
          R2: 100 kohm (0805)
          R3: 10 Mohm (0805)
          R4: 100 kohm (0805)
          R5: 390 ohm (0805)
          R6: 4,7 kohm (0805)
          R7: 2,2 kohm (0805)
          R8: 6,8 kohm (0805)

          C1: 100 μF 25 VL (D)
          C2: 100 nF (0805)
          C3: 470 nF (0805)
          C4: 470 nF (0805)
          C5: 100 nF (0805)
          C6: 100 nF (0805)
          C7: 22 nF (0805)
          C8: 1 nF (0805)
          C9: 1 nF (0805)
          C10: 22 nF (0805)
          C11: 1 nF (0805)
          C12: 1 nF (0805)

          U1: ACS712ELCTR-05B-T
          U2: ACS712ELCTR-05B-T
          U3: CD4069UBM
          U4: ASSR-1611-301E

          F1: RUEF300

          D1: GF1M


          固件

          /*
            SolarMower V1.0
            SolarMower use mowershield_FE
            2014 Mirco Segatello
            For hardware see www.elettronicain.it
            
            Press PEN during power-on for ESC test  
            Press PUP during power-on for test motor
            Press PDW during power-on for test sensor
           */
          
          #include <EEPROM.h>
          #include <SoftwareSerial.h>
          #include <Servo.h> 
          #include "Wire.h"
          #include "SRF02.h"
          #include "Configuration.h"
          
          Servo ESC;
          
          //variables
          float VBat;               // Battery voltage [V]
          int VBatPC;               // Battery voltage percentage
          float VBatScale=0.054;    // Battery scale for Volt converter
          float IPanel;             // Panel current [A]
          float IPanelOffset;       // Panel current offset
          float IPanelScale=0.185;  // Panel current scale V/A
          float ICut;               // Motor cut current [A]
          float ICutOffset;         // Motor cut current offset
          float ICutScale=0.185;    // Motor cut current scale V/A
          int i;
          int cutPower=0;           // Cut Power from 0%=ESC_MIN_SIGNAL to 100%=ESC_MAX_SIGNAL
          int cutPower_uSec=ESC_MIN_SIGNAL;      // Cut Power from ESC_MIN_SIGNAL to ESC_MAX_SIGNAL
          int oldSpeed=0;           // Speed of mower (0-255)
          float IPanelMax=0;           // IPanel max current
          unsigned long BWFL_count;
          unsigned long BWFR_count;
          unsigned long previousMillis = 0;
          unsigned long currentMillis; 
          volatile int mowerStatus=0; // 0=oncharge (press pen for run)
                                      // 1=run
                                      // 2=stuck
                                      // 3=search
                                      // 4=batlow
                                      // 5=charge and restart when full
                                      // 6=cuterror
          volatile unsigned long wheelTime=0;
          
          // LCD does not send data back to the Arduino, only define the txPin
          SoftwareSerial LCD = SoftwareSerial(0, LCD_pin);
          int LCD_Page = 0;         // Page to display
          
          SRF02 US_SX(US_SX_address, SRF02_CENTIMETERS);
          SRF02 US_DX(US_DX_address, SRF02_CENTIMETERS);
          
          
          
          
          void setup() 
          {
            Serial.begin(9600);
            Wire.begin();
            pinMode(Encoder_Pin, INPUT_PULLUP);
            pinMode(PWMA_pin, OUTPUT);
            pinMode(DIRA_pin, OUTPUT);  
            pinMode(BWFR_pin, INPUT);
            pinMode(BWFL_pin, INPUT);    
            pinMode(Panel_pin, OUTPUT);  
            pinMode(ESC_pin, OUTPUT);  
            pinMode(SWOR_pin, INPUT_PULLUP);
            pinMode(SWOL_pin, INPUT_PULLUP);       
            pinMode(PWMB_pin, OUTPUT);
            pinMode(DIRB_pin, OUTPUT);   
            pinMode(LCD_pin, OUTPUT);  
          
            digitalWrite(DIRA_pin, LOW); 
            digitalWrite(DIRB_pin, LOW);   
            analogWrite(PWMA_pin, 0);
            analogWrite(PWMB_pin, 0);  
            digitalWrite(Panel_pin, LOW);   
          
           
            // For SerialMonitor diagnostic 
            Serial.println("Solar Mower V1.0n"); 
            Serial.println("Init ESC..."); 
            ESC.attach(ESC_pin);
            cutOFF(); 
            
            Serial.println("Init SerLCD...");       
            serLCDInit();   
            clearLCD();
            lcdPosition(0,0);
            LCD.print("Solar Mower v1.0");
            lcdPosition(1,0);
            LCD.print("Init...");      
            
          
            Serial.println("Init Sensor");  
            sensorInit();  
            Serial.print("IPanelOffset= ");
            Serial.println(IPanelOffset);
            Serial.print("ICutOffset= ");
            Serial.println(ICutOffset);  
            Serial.println(); 
          
          
            // TEST MOTOR
            if (Button(Button_pin)==PUP) 
            {
              while(1)
              {
                clearLCD();
                lcdPosition(0,0);
                LCD.print("Test motor");
                lcdPosition(1,0);  
                LCD.print("PEN begin test  ");  
                Serial.println("Press PEN for begin motor test"); 
                while (Button(Button_pin)!=3) { }
                testMotor();
              }   
            }   
            
            //TEST SENSOR
            if (Button(Button_pin)==PDW) 
            { 
                clearLCD();
                lcdPosition(0,0);
                LCD.print("Test sensor");    
                Serial.println("Test sensor");
                delay(1000);
              while(1)
              {
                sensorReading();
                
                clearLCD();
                lcdPosition(0,0);
                LCD.print("VB=");
                LCD.print(VBat);
                
                lcdPosition(0,9); 
                if ((US_DX.read()>0) && (US_DX.read()<USdistance))   {
                      LCD.print("UsDX ");
                      Serial.println("UsDX");
                }      
                if ((US_SX.read()>0) && (US_SX.read()<USdistance)) {
                      LCD.print("UsSX ");   
                      Serial.println("UsSX");            
                }      
                if ( (BWFL_count>3000) && (BWFL_count<4000) ) {
                      LCD.print("BWFL");
                      Serial.println("BWFL");
                }      
                if ( (BWFR_count>2000) && (BWFR_count<4000) ) {
                      LCD.print("BWFR");    
                      Serial.println("BWFR");            
                }      
                if (digitalRead(Encoder_Pin)==0) {
                      LCD.print("Encoder");
                      Serial.println("Encoder");            
                }      
                if (digitalRead(SWOR_pin)==0) {
                      LCD.print("SWOR");
                      Serial.println("SWOR");            
                }      
                if (digitalRead(SWOL_pin)==0) {
                      LCD.print("SWOL");       
                      Serial.println("SWOL");            
                }      
                if (Button(Button_pin)==1) {
                      LCD.print("PUP");
                      Serial.println("PUP");            
                }      
                if (Button(Button_pin)==2) {
                      LCD.print("PDW");  
                      Serial.println("PDW");            
                }            
                if (Button(Button_pin)==3) {
                      LCD.print("PEN");
                      Serial.println("PEN");            
                }      
                
                lcdPosition(1,0);
                LCD.print("IC=");
                LCD.print(ICut);  
                Serial.print("IC=");     
                Serial.println(ICut);       
                lcdPosition(1,9);
                LCD.print("IP=");
                LCD.print(IPanel);  
                Serial.print("IP=");     
                Serial.println(IPanel);        
          
                delay(250);  
              }
            }    
            
            //TEST ESC
            if (Button(Button_pin)==PEN)   
            {
              Serial.println("Test ESC...");   
              clearLCD();
              lcdPosition(0,0);
              LCD.print("Test ESC");
              while(1)
              {
                  sensorReading();
                  cutPower = map(cutPower_uSec, ESC_MIN_SIGNAL, ESC_MAX_SIGNAL, 0, 100);
                  lcdPosition(0,9);
                  LCD.print("IC=");
                  LCD.print(ICut);          
                  lcdPosition(1,0);  
                  LCD.print("cutPower="); 
                  LCD.print(cutPower);
                  LCD.print("%  ");
                  Serial.print("cutPower=");
                  Serial.print(cutPower);
                  Serial.print("%   usec=");
                  Serial.println(cutPower_uSec);
                  
                  if (Button(Button_pin)==2) 
                     if (cutPower_uSec<ESC_MAX_SIGNAL) cutPower_uSec += 20;
                  if (Button(Button_pin)==1) 
                     if (cutPower_uSec>ESC_MIN_SIGNAL) cutPower_uSec -= 20;      
                     
                  ESC.writeMicroseconds(cutPower_uSec);
                  delay(200);   
              } 
            } 
            attachInterrupt(0, rotate, FALLING);
          }
          
          
          void loop() 
          {
            //main program
            digitalWrite(Panel_pin, HIGH);  
          
            main: 
            //wait for PEN press
            while(Button(Button_pin)!=3) 
            { 
              currentMillis = millis();
              if(currentMillis - previousMillis > timeClock) 
              {    
                  sensorReading(); 
                  LCDdebug();
              }  
            }  
            
            Serial.println("GO!");      
            mowerStatus=1;
            IPanelMax=0;
            LCDdebug();  
            cutON();
            setMowerSpeed(255);
          
          
            //main loop    
            while(1)
            { 
              
              //ferma tutto
              if (Button(Button_pin)==PUP || Button(Button_pin)==PDW)
              {
                cutOFF();  
                setMowerSpeed(0);
                mowerStatus=0;
                goto main; 
              }
          
              //if not an interrupt wheels occurs within 10 seconds, the robot is blocked
              if (millis()>wheelTime+10000)
              {
                cutOFF();  
                setMowerSpeed(0);
                mowerStatus=2;
                goto main;       
              }
              
              // gestione sensori ostacolo
              if (digitalRead(SWOL_pin)==LOW) obstacleAvoidSX();   
              if (digitalRead(SWOR_pin)==LOW) obstacleAvoidDX();       
                 
              
              // reads the sensors every timeClock
              currentMillis = millis();
              if(currentMillis - previousMillis > timeClock) 
              {
                previousMillis = currentMillis; 
          
                sensorReading(); 
                  
                if ((US_DX.read()>0) && (US_DX.read()<USdistance)) 
                {
                      obstacleAvoidSX();  
                      resetEncoder();
                }      
                if ((US_SX.read()>0) && (US_SX.read()<USdistance)) 
                {
                      obstacleAvoidDX();      
                      resetEncoder();
                }      
                if ((BWFL_count>3000) && (BWFL_count<4000))
                {
                      obstacleAvoidSX();  
                      resetEncoder();
                }      
                if ((BWFR_count>2000) && (BWFR_count<4000)) 
                {       
                      obstacleAvoidDX();     
                      resetEncoder();
                }      
                
                
                //**********************************************************************
                if (IPanel>IPanelMax) IPanelMax=IPanel; //memory to max current on panel
                
                //battery lower then 10% then searching the point to charge
                if (VBatPC<10) 
                {                
                  mowerStatus=3;
                  cutOFF();  //stop cut
                }  
                
                //continues to advance until it finds a light source at least 80% of the previous maximum.
                if (mowerStatus==3)
                {     
                  if  (IPanel>IPanelMax*0.8) 
                  {
                    setMowerSpeed(0);
                    mowerStatus=5; //charge with restart
                  }    
                }
                //**********************************************************************
                
                if (mowerStatus==5)
                {
                  resetEncoder();
                  // full charge then restart
                  if (VBatPC>=100)
                  {
                      mowerStatus=1;
                      IPanelMax=0;
                      cutON();
                      setMowerSpeed(255);         
                  }    
                }  
                  
                if (VBat > VBat_Level_Max)
                {
                   //lead battery never stop charge 
                   //disable charge only for lipo battery
                   //digitalWrite(Panel_pin, LOW); 
                } 
                
                //battery is completely discharged      
                if (VBat < VBat_Level_Min) 
                {
                  cutOFF();  
                  setMowerSpeed(0);
                  digitalWrite(Panel_pin, HIGH); 
                  mowerStatus=4;
                  goto main;       
                } 
                
                // ICut too high 
                if (ICut > ICut_Max) 
                {
                  cutOFF();  
                  setMowerSpeed(0);
                  digitalWrite(Panel_pin, HIGH); 
                  mowerStatus=6;
                  goto main;       
                }       
                
                serialDebug();      
                LCDdebug();    
                }
            }  
          }
          
          void rotate()
          {
            wheelTime=millis();   
          }
          
          void resetEncoder()  //reset value for block wheels
          {
            wheelTime=millis();   
          }
          
          void obstacleAvoidSX()
          {
                // obstacle avoid
                setMowerSpeed(-PWMSpeed);
                delay(timeReverse);
                setMowerRotate(-PWMSpeed); //gira a sinistra
                delay(timeRotate);
                setMowerSpeed(PWMSpeed);
          }
          
          void obstacleAvoidDX()
          {
                // obstacle avoid     
                setMowerSpeed(-PWMSpeed);
                delay(timeReverse);
                setMowerRotate(PWMSpeed);
                delay(timeRotate);
                setMowerSpeed(PWMSpeed);   
          }
          
          
          void setMowerRotate(int newSpeed)
          { 
            //rotate mower (first set speed at zero) 
            constrain(newSpeed, -255, 255);
              for (i=oldSpeed; i>=0; i--)
              {
                 analogWrite(PWMA_pin, i);
                 analogWrite(PWMB_pin, i);
                 delay(accelerateTime);
              }      
              oldSpeed=0;
              
            if (newSpeed<0) 
            {  
              digitalWrite(DIRA_pin, HIGH); 
              digitalWrite(DIRB_pin, LOW);   
              newSpeed=-newSpeed;    
            }
            else
            {
              digitalWrite(DIRA_pin, LOW); 
              digitalWrite(DIRB_pin, HIGH);    
            }  
            
            for (i=0; i<=newSpeed; i++)
            {
                 analogWrite(PWMA_pin, i);
                 analogWrite(PWMB_pin, i);
                 delay(accelerateTime);
            }  
            oldSpeed=newSpeed;
          }
          
          
          void setMowerSpeed(int newSpeed)
          {
            //set new speed for mower (first set speed at zero) 
            constrain(newSpeed, -255, 255);
              for (i=oldSpeed; i>=0; i--)
              {
                 analogWrite(PWMA_pin, i);
                 analogWrite(PWMB_pin, i);
                 delay(accelerateTime);
              }    
              oldSpeed=0; 
            
            if (newSpeed<0)
            {  
              digitalWrite(DIRA_pin, HIGH); 
              digitalWrite(DIRB_pin, HIGH);    
              newSpeed=-newSpeed;
            }
            else
            {
              digitalWrite(DIRA_pin, LOW); 
              digitalWrite(DIRB_pin, LOW);    
            }
            
            if (newSpeed > oldSpeed)
            {
              for (i=oldSpeed; i<=newSpeed; i++)
              {
                 analogWrite(PWMA_pin, i);
                 analogWrite(PWMB_pin, i);
                 delay(accelerateTime);
              }   
            }
            else
            {
              for (i=oldSpeed; i>=newSpeed; i--)
              {
                 analogWrite(PWMA_pin, i);
                 analogWrite(PWMB_pin, i);
                 delay(accelerateTime);
              }        
            } 
            oldSpeed=newSpeed; 
          }
          
           
          void cutON()
          {
            //cutter ON
            for (cutPower_uSec=ESC_MIN_SIGNAL; cutPower_uSec<=ESC_MAX_SIGNAL; cutPower_uSec += 10)
            {
              ESC.writeMicroseconds(cutPower_uSec);
              delay(50); 
            }
            wheelTime=millis(); 
          }
          
          void cutOFF()
          {
            //cutter OFF
            ESC.writeMicroseconds(ESC_MIN_SIGNAL);      
          }

          草圖被分為不同的文件,每個文件都有特定的用途,可以對功能進行排序,使閱讀更容易;我們將在下面看到構成草圖的文件。

          文件configuration.h包含用于設置Arduino的工作參數和所有引腳分配的所有定義指令。在所有參數中,最重要的是:

          ESC_MAX_SIGNAL 2000:它定義了與ESC最大功率相關的信號的持續時間(以微秒為單位),與切割發動機的控制有關。

          #定義ESC_MIN_SIGNAL 1000:它定義與ESC停止有關的信號的持續時間(以微秒為單位),與切割發動機的控制有關。

          #define VBat_Level_Min 9.0:它定義電池的最小電壓:在此值下,除太陽能電池板充電外,所有割草機功能都將停用。

          #定義VBat_Level_Max:它定義電池的最大電壓:超過該值,太陽能電池板的充電將中斷。最小值和最大值也用于確定蓄電池充電水平。

          #define ICut_Min:它定義切割引擎吸收的最小電流:低于該值時會產生警報。

          #define ICut_Max:它定義切割引擎吸收的最大電流:超過該值,前進速度會降低。

          #define accelerateTime:它定義了分配給運動的發動機的加速持續時間;總加速時間等于accelerateTime*255[msec]。

          #定義Usdistance:檢測到障礙物并且機器人改變方向的距離(以厘米為單位)。

          #定義時間反向:檢測到障礙物后,機器人反向運動的持續時間(以毫秒為單位)。

          #define timeRotate:檢測到障礙物后,在修改行進方向的操作過程中,機器人旋轉的持續時間(以毫秒為單位)。

          SerLCD.ino文件包含LCD顯示器的初始化和控制功能。debug.ino文件包含機器人運行過程中測量值在LCD顯示器上的初始化和可視化功能,還包含用于將測量數據發送到PC的功能。

          sensor.ino文件包含讀取傳感器時使用的功能;為了便于比較,所有測量值都以安培和伏特為單位進行轉換。特別有趣的是FreqCounter(int引腳,無符號長gateTime)功能,它允許測量來自用于檢測地下線路的輸入的脈沖數量。

          從用于檢測地下布線的電路獲得的方波信號僅在正確檢測到布線的情況下才呈現特定頻率。

          參數gateTime顯示信號檢測的持續時間,也表示函數計數所需的時間,其默認值為100msec。文件TestMotor.ino包含牽引發動機測試過程中使用的功能。

          對于割草機的每一項功能,都會在LCD顯示屏上進行確認,并向PC發送等效消息:LCD顯示屏為數據管理提供了更大的便利,無需PC連接。

          主程序包含在文件SolarMower.ino中:它監督所有操作,并按正確順序調用所有功能。

          一旦電氣部分完成,就需要正確驗證功能和接線:為此,預先設置了三個特定的公用設施。我們要記住,割草的刀片非常危險,因此我們建議在結束所有測試之前移除刀片。

          當點火時,或按下Arduino的重置按鈕時,或當重新啟動串行監視器時(如果連接到Arduino),固件將開始其細化;作為第一次操作,它將驗證是否按下了其中一個按鈕,在這種情況下,它將啟動特定的設置程序,如下所示:

          按下PUP按鈕,進入傳感器測試;

          按下PDW按鈕,進入發動機測試;

          按下PEN按鈕,進入ESC測試。

          ESC測試程序允許校準最大值和最小值;這不是一個編程順序,相反,它需要參考正在使用的ESC的特定手冊。

          1斷開切割刀片和ESC電源連接器。

          2為割草機和ESC測試條目供電。

          3使用PUP 100%=2000usec按鈕將cutPower設置為最大值

          4為ESC供電,等待最大點的配置(您將聽到特定的聲學信號)。

          5使用PDW按鈕將cutPower設置為最小值(您將聽到特定的聲學信號)。

          6現在將完成校準。電子穩定控制系統將自動設置最小值在10-30%范圍內,最大值在70-100%范圍內的限值。通過操作PUP和PDW按鈕,可以修改cutPower的值,并驗證電機是否正確運行。

          要驗證運動發動機,啟動發動機測試程序:它將通過逐漸加速和減速依次啟動兩個電機。然后,您必須驗證旋轉方式是否與Arduino串行監視器或LDC顯示器上顯示的信息一致:如果旋轉方式不同,則足以反轉發動機的導線。您還必須驗證DX引擎是否與正確的引擎匹配,反之亦然。

          Img2

          在啟動傳感器測試程序之前,我們必須討論超聲波傳感器:由于它們都連接到同一個I2C總線,因此需要用不同的地址對其中一個進行編程。傳感器屬于SRF02類型,在銷售時分配了值地址HEX0x70。因此,如果連接到同一個總線,剛剛購買的兩個傳感器將發生沖突。我們將保留左側傳感器的默認地址0x70,并修改右側傳感器的地址。

          要做到這一點,請將屏蔽單獨連接到右側傳感器,并打開SRF02_address.ino樣本,該樣本包含在SRF02庫中,與本文的文件一起提供,然后將其加載到Arduino上;地址將被自動修改。您可以使用庫中包含的示例程序來驗證地址的更改是否正確。

          通過啟動傳感器測試程序,您將有機會驗證所有輸入外圍設備是否正確運行;在LCS顯示器(如果可用)和串行監視器(如果連接到Arduino)上,都可以看到從當前傳感器獲取的數據、數字條目的值以及檢測到的障礙物的存在與否。

          一旦確定一切正常,您可以進行第一次現場測試:按下主屏幕上的PEN按鈕即可啟動割草機,同時按下PUP和PDW兩個按鈕之一即可立即停止。

          無論如何,在提起或操作割草機之前,我們建議通過總開關將其關閉:只有這樣,您才能保證任何機制都不會開始工作。

          在不輸入整個固件的詳細信息的情況下,現在讓我們看看在第一個versoin中實現的基本行;其思想是實現有限狀態自動機,其操作狀態存儲在割草機狀態變量中。

          當狀態變量取值為0時,顯示屏上將顯示CHARGE(充電)字樣:這是點火后不久的初始狀態,機器人仍在充電,等待按下PEN引導按鈕。

          當狀態變量的值為1時,顯示屏上將顯示RUN(運行)字樣:這是主要狀態,機器人正在割草,同時驗證是否存在障礙物。在這種情況下,將啟動一個簡單的程序,該程序將修改行駛方向。

          當狀態變量的值為2時,顯示器上將顯示單詞STUCK:在這種狀態下,機器人被卡住了。由于后輪停止轉動并且沒有向板發出任何信號,因此檢測到了這種情況。

          當狀態變量取值3時,顯示屏上將顯示單詞SEARCH:在這種狀態下,電池電量接近低,切割發動機停止,機器人尋找發光的地方為自己充電。

          當狀態變量的值為4時,顯示屏上將顯示單詞BATLOW:在這種狀態下,電池電量不足,無法找到令人滿意的充電位置。甚至牽引電機也被停止,機器人仍處于充電模式。

          當狀態變量取值5時,顯示屏上將顯示CHARGE RS字樣:在這種狀態下,機器人處于充電位置,一旦電池完全充電,機器人將準備再次啟動。

          當狀態變量的值為6時,顯示器上將顯示單詞CUTERROR:在這種狀態下,機器人靜止不動,因為它檢測到切割發動機電流吸收異常。

          為地下線路供電的電路

          MowerGround

          如前所述,地下布線需要形成一個閉環,并由頻率為34Khz的交流信號供電。要做到這一點,需要一個非常簡單的不穩定電路。它是用一個NE555集成電路和幾個更多的組件創建的;該電路與以前的版本相同,并計算到具有9伏次級的變壓器的連接,該變壓器又以220Vac連接到電網。

          0826_Schema

          然而,根據該項目背后的理念,建議使用小型太陽能電池板和緩沖電池,從電網中獨立供電。太陽能電池板將是電路的主要電源,而12V電池(與C1電容器并聯)將是在陽光照射不足的情況下的主要電源。橋式整流器的存在將防止電池張力在低陽光暴露期間進入太陽能電池板。為了正確平衡系統,需要確保在夜間電池能夠為電路供電而不會電量過低,而太陽能電池板必須能夠為電路充電,同時在白天為電池充電。

          0826_Silk

          0826_03_montaggio

          該系統與花園中的太陽能燈沒有什么不同,它們不需要連接到家庭網絡的電線。地下布線將形成一個封閉的環,以標記割草機工作區域的界限。由于車載傳感器,該區域內的任何其他障礙物都將得以避免。

          唯一要進行的校準涉及發送到地下線路的信號的頻率調節:將電纜靠近BWF傳感器的卷軸并旋轉微調器就足夠了,直到獲得盡可能好的讀數(為此,使用傳感器測試程序)。

          BOM

          R1: 3,3 kohm

          R2: 12 kohm

          R3: 100 ohm

          R4: 4,7 kohm MV

          C1: 1.000 μF 35 VL

          C2, C4: 100 nF

          C3: 1,2 nF 63 VL

          C5: 1 μF 63 VL

          PT1: W06M

          U1: NE555

          機械設計

          Mechanical




          評論


          相關推薦

          技術專區

          關閉
          看屁屁www成人影院,亚洲人妻成人图片,亚洲精品成人午夜在线,日韩在线 欧美成人 (function(){ var bp = document.createElement('script'); var curProtocol = window.location.protocol.split(':')[0]; if (curProtocol === 'https') { bp.src = 'https://zz.bdstatic.com/linksubmit/push.js'; } else { bp.src = 'http://push.zhanzhang.baidu.com/push.js'; } var s = document.getElementsByTagName("script")[0]; s.parentNode.insertBefore(bp, s); })();