这个机器人会修剪你花园里的草,呆在指定的区域内,避开所有障碍,完全自主工作,用电池板自动充电。
本文引用地址:在这篇文章中,我们介绍了一种机器人割草机,它由供电,能够仅利用来自太阳的清洁能源进行操作;这与商业项目有很大的不同,商业项目需要一个连接到电网的充电站。在设计驱动的割草机时,至关重要的是,大部分能量来自太阳,当然,如果太阳能足以为机器人完全供电,最终结果就会得到:然而,鉴于现有太阳能电池板的低效率,这一目标将很难实现。在我们的项目中,机器人的整个表面都是太阳能电池板,同时也是一个盖子:只有侧面是自由的,无论如何,它们在供应能源方面都不会发挥决定性作用。显然,这种选择对项目的其余部分构成了严重的限制,因为通过这种方式,我们已经定义了可用的最大功率。
我们必须考虑到,太阳能并不总是可用的,因为许多花园区域经常处于阴凉处,或者无论如何都没有被太阳直接照射,所以我们必须考虑相当大的电力损失。只有当机器人有一个蓄能器,能够在缺乏阳光的情况下提供能量时,才能弥补这些损失。在这种情况下,电池起到缓冲作用,在电量充足时积累能量,相反,在机器人处于阴影下时提供能量。从这个角度来看,铅电池是最合适的电池,但没有什么能阻止我们使用在重量和容量方面表现更好的电池,比如锂电池。在阳光充足的情况下,太阳能电池板能够用约0.6A的电流为内部电池充电,总功率约为8W,远低于最高效的电动割草机所使用的功率,功率为220Vac。这让我们已经明白,像我们在这些页面中描述的产品不能完全取代手动割草机,因为当草太高时,应该不时使用最后一款。相反,机器人割草机可以用于连续稳定地修剪草坪。
这种解决方案还提供了另一个优势,因为连续割草可以确保草始终年轻柔软,而且当它被切成很小的碎片时,它会在短时间内自行分解,从而为草坪施肥。你不应该指望被割下的草会被收集起来:相反,它会沉积在刚刚割下的草叶中。
对于这种用途,所需的电力更少,并且可以使用电池供电系统轻松管理。游戏中的弱动力说服我们选择一个牵引力和功率降低的切割发动机。也许,它们可能不完全符合我们读者的需求,他们可能会根据预算和个人需求选择他们喜欢的引擎和结构。为了确定草坪上的切割区域,地下布线系统被证明是简单、准确和可靠的。它也是定义机器人工作区域的最佳系统。
一切都是基于一根简单电线的使用,电线铺设在地上或其下,并连接到一个控制单元,用大约10V和34KHz频率的交流电信号为电线本身供电。在机器人底盘的下部安装了两个小卷轴,一个在右侧,另一个在左侧,这两个卷轴都是指由并联的电容器形成的电路。由并联电感和电容器形成的电路被称为并联谐振电路,并且被计算为使得当磁场以34KHz的频率变化时,由外部磁场感应的其端部的张力处于最大值。
现在让我们来更详细地描述这个项目所采用的电气部分。最重要的创新是采用了作为控制板,使你能够获得一个更用户友好、更易于破解的项目,即使是经验不足的人。为了实现最大的使用灵活性,我们认为要实现特定的屏蔽,而不是实现特定的电子板。
这种选择也决定了一个缺点,即当板处于待机模式时,电流的吸收,这种情况可能发生在夜间,机器人仍然没有电源。在这种情况下,内部电池将不得不面对板和屏蔽的长时间供电。
关于发动机的管理,就牵引力而言,我们计算了商用护罩的使用情况,这是唯一一种可用于修改控制销分配的商用护罩;为此,请使用表1正确分配引脚。发动机护罩可管理两台发动机,每台发动机的总最大吸收功率为2A,确保有足够的动力用于牵引。显然,没有什么可以禁止我们使用其他类型的驱动器来驱动发动机,从而增加功率;唯一重要的是,驾驶员为每台发动机提供两个可用的控制信号,一个用于定义方向,另一个用于控制速度所需的PWM信号。
该屏蔽是使用具有特定功能的最新组件设计的,因此需要使用高度集成的SMD组件,从而将所有东西都安装到与 UNO兼容的屏蔽中。用于读取地下线路的部分基于包含六个CD4069型NOT门的集成电路。使用这种集成电路,我们只需放大并平方并联谐振电路头部的弱信号。即使在这个项目中,我们也计算了激活或停用太阳能电池板的可能性;为此,我们依靠集成电路ASSR1611,这是一种由光隔离器控制的固态开关。如果使用的缓冲电池是铅电池,则无需拆下面板,因为这种电池可以很好地支持过充电,但如果您使用更现代的锂电池,则必须在达到极限电压后暂停充电,否则您可能会导致电池损坏,或在最坏的情况下发生爆炸。
两个名为ACS712的集成电路可以测量太阳能电池板提供的电流和切割引擎吸收的电流:5A范围的版本对我们来说似乎绰绰有余。
这些集成电路使用霍尔效应技术来提供(作为输出)与电源电路上的循环电流成比例的张力,从而与输出级保持电流分离。测量太阳能电池板电流的可能性将是检测最适合给电池充电的区域的基础。运行时,实际上会存储面板提供的电流水平,当割草机必须找到充电区时,在电池电量接近低的情况下,会再次使用数据。机器人不知道真实的大气情况(晴天或阴天),也不知道是否有阴影区域,甚至不知道它是否在变暗:它只会在上一次工作中检测到的最大发光强度方面寻找一个足够亮的区域。测量切割引擎吸收的电流将是了解切割过程中的作用力的基础,也是计算在异常情况下何时停止切割的基础。
为了完成关于屏蔽的讨论,我们必须注意二极管D1,它是在电池电量不足的情况下避免电池在光伏面板上的张力所必需的;以及使I2C总线可用所需的两个连接器。
还设计了三个通用按钮,它们通过电阻网络连接到模拟输入A0;事实上,所有的数字引脚都已被占用。一个入口由一个簧片传感器使用,该传感器放置在非常靠近后枢轴轮的位置,并由一个小磁铁操作,该磁铁在每次旋转时插入同一个轮中。有了这个传感器,就可以确定机器人是否有规律地移动,或者一个或多个轮子是否被锁住或徒劳地移动。
我们增加了两个数字输入,您可以将前面的障碍物识别机械开关连接到它们;除此之外,经验证的超声波传感器连接到I2C总线并检测前方物体。
超声波传感器虽然性能非常好,但可能会被表面特别小的物体(如金属网)或一些非常不规则的表面(如灌木)所欺骗。
至于草坪修剪,我们依赖于航空建模领域使用的无刷电机,该电机与通过组合两个刀片获得的刀片相连。
我们谈论的是一台200W的发动机,但它的使用率不超过20%。发动机控制分配给模型构建中使用的ESC(电子速度控制),并使用简单的PWM信号进行操作,易于使用Arduino进行管理,因为它已经在系统库中具有相关功能。
为了测量电池头部的张力,我们将使用电机护罩中已有的分压器。然而,需要修改轨道,将分配器输出的张力从引脚A5带到引脚A3,以便引脚A4和A5可用于I2C总线。两条数字线路D0和D1用于与PC通信,但一旦对Arduino进行了编程,它们就可以用于与GPS或蓝牙等其他外围设备通信。
Tab. 1 Mower Shield pin connect
Pin Arduino |
name | Description |
A0 | Button_pin | Push button |
A1 | ICut_pin | Motor cut current |
A2 | IPanel_pin | Solar panel current |
A3 | VBat_pin | Battery voltage (from motorshield_FE) |
A4 | SDA_pin | I2C BUS |
A5 | SCL_pin | I2C BUS |
D0 | RXD_pin | GPS or bluetooth |
D1 | TXD_pin | GPS or bluetooth |
D2 | Encoder_pin | Encoder pivoting wheel |
D3 | PWMA_pin | PWM motor A motorshield_FE |
D4 | DIRA_pin | Direction motor A motorshield_FE |
D5 | BWFR_pin | Buried Wire Fence Right |
D6 | BWFL_pin | Buried Wire Fence Left |
D7 | Panel_pin | ON/OFF pannel |
D8 | ESC_pin | ESC cut motor signal |
D9 | SWOL_pin | Obstacle switch Right |
D10 | SWOR_pin | Obstacle switch Left |
D11 | PWMB_pin | PWM motor B motorshield_FE |
D12 | DIRB_pin | Direction motor B motorshield_FE |
D13 | LCD_pin | Serial LCD |
硬件现在已经相当完整,防护罩做得非常好,尽管还可以添加一些更多的功能,比如雨水传感器,或者更好的是,草湿度传感器,这将使机器人能够停下来等待更好的切割条件。作为一种安全措施,我们在旋转轮上安装了一个编码器,作为一种支撑,甚至可以在牵引轮上添加一个编码器甚至可以添加一个传感器来测量吸收的电流。
电气部分还计算了用于调试功能且绝对不需要的绿色背景黑色文本串行显示器的使用情况。
使用一个简单的Arduino板应该可以让许多用户尝试实现电动割草机,当然也不会缺少社区的贡献,以及进一步改进的建议。
关于屏蔽的电气连接,请参考下表:
表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平方米的花园秩序。
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引擎是否与正确的引擎匹配,反之亦然。
在启动传感器测试程序之前,我们必须讨论超声波传感器:由于它们都连接到同一个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:在这种状态下,机器人静止不动,因为它检测到切割发动机电流吸收异常。
为地下线路供电的电路
如前所述,地下布线需要形成一个闭环,并由频率为34Khz的交流信号供电。要做到这一点,需要一个非常简单的不稳定电路。它是用一个NE555集成电路和几个更多的组件创建的;该电路与以前的版本相同,并计算到具有9伏次级的变压器的连接,该变压器又以220Vac连接到电网。
然而,根据该项目背后的理念,建议使用小型太阳能电池板和缓冲电池,从电网中独立供电。太阳能电池板将是电路的主要电源,而12V电池(与C1电容器并联)将是在阳光照射不足的情况下的主要电源。桥式整流器的存在将防止电池张力在低阳光暴露期间进入太阳能电池板。为了正确平衡系统,需要确保在夜间电池能够为电路供电而不会电量过低,而太阳能电池板必须能够为电路充电,同时在白天为电池充电。
该系统与花园中的太阳能灯没有什么不同,它们不需要连接到家庭网络的电线。地下布线将形成一个封闭的环,以标记割草机工作区域的界限。由于车载传感器,该区域内的任何其他障碍物都将得以避免。
唯一要进行的校准涉及发送到地下线路的信号的频率调节:将电缆靠近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
机械设计