Project aiming to make a self-controlled solar reflector
Dependencies: Accelerometer LCD Inverter Algorithm MotorDriver Anemometer GUI ArduinoJson Misc Definitions Pushbutton WebSocketClient temp_fan
main.cpp@25:b04abb0930ef, 2021-03-25 (annotated)
- Committer:
- khaiminhvn
- Date:
- Thu Mar 25 01:17:46 2021 +0000
- Revision:
- 25:b04abb0930ef
- Parent:
- 24:ea7abc25a697
- Child:
- 26:b30a61a55b2f
Fixed Reconnection
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
khaiminhvn | 0:74d6e93ec977 | 1 | /* |
khaiminhvn | 0:74d6e93ec977 | 2 | For settings of system behaviour, see Defs_sett.h |
khaiminhvn | 0:74d6e93ec977 | 3 | For pin assignment list, see PinAssignment.h |
khaiminhvn | 0:74d6e93ec977 | 4 | */ |
khaiminhvn | 0:74d6e93ec977 | 5 | |
khaiminhvn | 0:74d6e93ec977 | 6 | //INCLUDES |
khaiminhvn | 0:74d6e93ec977 | 7 | #include "mbed.h" |
khaiminhvn | 6:0b7a6e51cdf8 | 8 | #include "stdio.h" |
khaiminhvn | 2:944511c6c55f | 9 | #include "string" // std::string, std::to_string |
khaiminhvn | 0:74d6e93ec977 | 10 | #include "Accelerometer.h" |
khaiminhvn | 0:74d6e93ec977 | 11 | #include "Anemometer.h" |
khaiminhvn | 0:74d6e93ec977 | 12 | #include "Algorithm.h" |
khaiminhvn | 0:74d6e93ec977 | 13 | #include "MotorDriver.h" |
khaiminhvn | 0:74d6e93ec977 | 14 | #include "Defs_Sett.h" |
khaiminhvn | 0:74d6e93ec977 | 15 | #include "Pushbutton.h" |
khaiminhvn | 7:2b6438e586e6 | 16 | #include "PinAssignment.h" |
khaiminhvn | 2:944511c6c55f | 17 | #include "LCD.h" |
khaiminhvn | 9:6e950b9a9a81 | 18 | #include "Misc.h" |
khaiminhvn | 16:326404a7a8b8 | 19 | #include "temp_fans.h" |
khaiminhvn | 6:0b7a6e51cdf8 | 20 | #include <string> |
jump_man | 17:238ccf7e3676 | 21 | #include "EthernetInterface.h" |
jump_man | 17:238ccf7e3676 | 22 | #include "Inverter.h" |
jump_man | 17:238ccf7e3676 | 23 | #include "GUI.h" |
khaiminhvn | 0:74d6e93ec977 | 24 | |
khaiminhvn | 0:74d6e93ec977 | 25 | #define timer_read_s(x) chrono::duration_cast<chrono::seconds>((x).elapsed_time()).count() |
khaiminhvn | 11:2ade1ad7bad6 | 26 | #define timer_read_ms(x) chrono::duration_cast<chrono::milliseconds>((x).elapsed_time()).count() |
khaiminhvn | 0:74d6e93ec977 | 27 | |
khaiminhvn | 0:74d6e93ec977 | 28 | //Initialize Global Variables |
khaiminhvn | 7:2b6438e586e6 | 29 | I2C i2c(PIN_SDA,PIN_SCL); |
khaiminhvn | 0:74d6e93ec977 | 30 | Anemometer ane; // |
khaiminhvn | 11:2ade1ad7bad6 | 31 | MotorDriver motor; |
khaiminhvn | 10:566529fff615 | 32 | LowPowerTimer t,t_mode, t_disp; |
khaiminhvn | 7:2b6438e586e6 | 33 | int mode = OP_CALIBRATION; |
jump_man | 17:238ccf7e3676 | 34 | EthernetInterface eth; |
khaiminhvn | 0:74d6e93ec977 | 35 | |
khaiminhvn | 0:74d6e93ec977 | 36 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 0:74d6e93ec977 | 37 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 0:74d6e93ec977 | 38 | int main() |
khaiminhvn | 0:74d6e93ec977 | 39 | { |
khaiminhvn | 7:2b6438e586e6 | 40 | i2c.frequency(I2C_FREQ); |
khaiminhvn | 10:566529fff615 | 41 | Accelerometer acc(&i2c); //Accelerometer |
khaiminhvn | 7:2b6438e586e6 | 42 | LCD lcd(&i2c); |
khaiminhvn | 16:326404a7a8b8 | 43 | temp_fans fan; |
khaiminhvn | 7:2b6438e586e6 | 44 | |
khaiminhvn | 0:74d6e93ec977 | 45 | float ang_P,ang_R; |
khaiminhvn | 0:74d6e93ec977 | 46 | float ref_R1,ref_R2; |
khaiminhvn | 0:74d6e93ec977 | 47 | int t_elapsed; |
khaiminhvn | 0:74d6e93ec977 | 48 | int wthres = WIND_THRES_INIT; |
khaiminhvn | 6:0b7a6e51cdf8 | 49 | |
khaiminhvn | 8:a1481d5f0572 | 50 | //FLAGS |
khaiminhvn | 8:a1481d5f0572 | 51 | int flag_time = 1; //Normal mode time |
khaiminhvn | 8:a1481d5f0572 | 52 | int flag_idle = 0; //Idling time |
khaiminhvn | 8:a1481d5f0572 | 53 | int flag_disp = 1; //Anti-flickering |
khaiminhvn | 9:6e950b9a9a81 | 54 | int flag_bres = 0; //Flag for checking button released |
khaiminhvn | 14:3989d03a8b98 | 55 | int flag_flas = 1; //Flag for flashing symbol |
khaiminhvn | 24:ea7abc25a697 | 56 | int flag_cali = 0; //Flag for calibration |
jump_man | 17:238ccf7e3676 | 57 | bool flag_eth; //Flag for ethernet connection |
jump_man | 17:238ccf7e3676 | 58 | bool flag_aTrack; //Flag for active tracking (0 - offline, 1 - online) |
jump_man | 17:238ccf7e3676 | 59 | bool flag_powerOn; |
khaiminhvn | 20:0a6609515810 | 60 | float sun_angle; |
khaiminhvn | 8:a1481d5f0572 | 61 | |
khaiminhvn | 8:a1481d5f0572 | 62 | //PUSH BUTTONS |
khaiminhvn | 8:a1481d5f0572 | 63 | Pushbutton bt_inc(PIN_BTINC); |
khaiminhvn | 8:a1481d5f0572 | 64 | Pushbutton bt_dec(PIN_BTDEC); |
khaiminhvn | 20:0a6609515810 | 65 | Pushbutton bt_fn(PIN_BTFN,&mode,&flag_disp,PIN_BTINC); |
khaiminhvn | 8:a1481d5f0572 | 66 | |
khaiminhvn | 11:2ade1ad7bad6 | 67 | string topL = "INITIALIZING"; |
khaiminhvn | 11:2ade1ad7bad6 | 68 | string botL = ""; |
khaiminhvn | 11:2ade1ad7bad6 | 69 | lcd.LCD_display(topL, botL); |
khaiminhvn | 0:74d6e93ec977 | 70 | |
jump_man | 17:238ccf7e3676 | 71 | eth.connect(); |
jump_man | 17:238ccf7e3676 | 72 | GUI gui("ws://int-sol-ref.herokuapp.com/", ð, &flag_eth); |
jump_man | 17:238ccf7e3676 | 73 | Inverter inverter("int-sol-ref.herokuapp.com", 80, ð); |
khaiminhvn | 20:0a6609515810 | 74 | bt_fn.setConnected(flag_eth); |
khaiminhvn | 20:0a6609515810 | 75 | |
khaiminhvn | 0:74d6e93ec977 | 76 | t.start(); //Start timer |
khaiminhvn | 10:566529fff615 | 77 | t_disp.start(); |
khaiminhvn | 20:0a6609515810 | 78 | if (flag_eth){gui.getSunAngle();} |
khaiminhvn | 22:6c8535dab84a | 79 | if (flag_eth){ |
khaiminhvn | 22:6c8535dab84a | 80 | topL = "ETHERNET"; |
khaiminhvn | 22:6c8535dab84a | 81 | botL = "CONNECTED"; |
khaiminhvn | 22:6c8535dab84a | 82 | lcd.LCD_display(topL, botL); |
khaiminhvn | 22:6c8535dab84a | 83 | } |
khaiminhvn | 22:6c8535dab84a | 84 | else{ |
khaiminhvn | 22:6c8535dab84a | 85 | topL = "ETHERNET"; |
khaiminhvn | 22:6c8535dab84a | 86 | botL = "NOT CONNECTED"; |
khaiminhvn | 22:6c8535dab84a | 87 | lcd.LCD_display(topL, botL); |
khaiminhvn | 22:6c8535dab84a | 88 | } |
khaiminhvn | 11:2ade1ad7bad6 | 89 | wait_us(1000000); |
khaiminhvn | 0:74d6e93ec977 | 90 | |
khaiminhvn | 11:2ade1ad7bad6 | 91 | topL = "PUT SENSORS IN"; |
khaiminhvn | 11:2ade1ad7bad6 | 92 | botL = "CALIBRATION SLOT"; |
khaiminhvn | 6:0b7a6e51cdf8 | 93 | lcd.LCD_display(topL, botL); |
khaiminhvn | 6:0b7a6e51cdf8 | 94 | |
khaiminhvn | 0:74d6e93ec977 | 95 | while(1) |
khaiminhvn | 0:74d6e93ec977 | 96 | { |
khaiminhvn | 0:74d6e93ec977 | 97 | switch(mode) |
khaiminhvn | 0:74d6e93ec977 | 98 | { |
khaiminhvn | 7:2b6438e586e6 | 99 | case OP_PLACEMENT:{ |
khaiminhvn | 24:ea7abc25a697 | 100 | if(flag_cali == 0){ |
khaiminhvn | 24:ea7abc25a697 | 101 | topL = "CALIBRATING"; |
khaiminhvn | 24:ea7abc25a697 | 102 | botL = ""; |
khaiminhvn | 24:ea7abc25a697 | 103 | lcd.LCD_display(topL,botL); |
khaiminhvn | 24:ea7abc25a697 | 104 | acc.calibrate(); |
khaiminhvn | 24:ea7abc25a697 | 105 | topL = "PUT SENSOR ON"; |
khaiminhvn | 24:ea7abc25a697 | 106 | botL = "PANEL&REFLECTORS"; |
khaiminhvn | 24:ea7abc25a697 | 107 | lcd.LCD_display(topL,botL); |
khaiminhvn | 24:ea7abc25a697 | 108 | flag_cali = 1; |
khaiminhvn | 24:ea7abc25a697 | 109 | } |
khaiminhvn | 7:2b6438e586e6 | 110 | break; |
khaiminhvn | 8:a1481d5f0572 | 111 | } |
khaiminhvn | 0:74d6e93ec977 | 112 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 14:3989d03a8b98 | 113 | case OP_CONFIRM:{ |
khaiminhvn | 14:3989d03a8b98 | 114 | while(mode == OP_CONFIRM){ |
khaiminhvn | 14:3989d03a8b98 | 115 | topL = "R1 || P || R2"; |
khaiminhvn | 16:326404a7a8b8 | 116 | botL = Misc::itos(acc.getAngle(S_R1),3) + |
khaiminhvn | 16:326404a7a8b8 | 117 | "||" + Misc::itos(acc.getAngle(S_PANEL),3) + |
khaiminhvn | 16:326404a7a8b8 | 118 | "||" + Misc::itos(acc.getAngle(S_R2),3); |
khaiminhvn | 14:3989d03a8b98 | 119 | lcd.LCD_display(topL,botL); |
khaiminhvn | 14:3989d03a8b98 | 120 | flag_disp = 0; |
khaiminhvn | 14:3989d03a8b98 | 121 | wait_us(LCD_RRATE); |
khaiminhvn | 14:3989d03a8b98 | 122 | } |
khaiminhvn | 14:3989d03a8b98 | 123 | } |
khaiminhvn | 14:3989d03a8b98 | 124 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 7:2b6438e586e6 | 125 | case OP_NORMAL:{ |
khaiminhvn | 20:0a6609515810 | 126 | if (flag_eth){gui.getSunAngle();} |
khaiminhvn | 20:0a6609515810 | 127 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
khaiminhvn | 16:326404a7a8b8 | 128 | fan.checkTemp(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 16:326404a7a8b8 | 129 | ane.checkWind(&mode);if(mode != OP_NORMAL){break;} |
jump_man | 17:238ccf7e3676 | 130 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 12:14bac44e33b9 | 131 | topL = "NORMAL:IDLING"; |
khaiminhvn | 24:ea7abc25a697 | 132 | topL = (flag_aTrack) ? topL : "*" + topL; |
khaiminhvn | 14:3989d03a8b98 | 133 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 25:b04abb0930ef | 134 | botL = Misc::itos(ane.getWind(&flag_disp)) + "kph*" + Misc::itos(fan.getTemp()) + "C*" |
khaiminhvn | 25:b04abb0930ef | 135 | + ((flag_eth)?Misc::itos(inverter.getPower()):"---") + "W"; |
khaiminhvn | 10:566529fff615 | 136 | t_disp.reset(); |
khaiminhvn | 10:566529fff615 | 137 | t_disp.start(); |
khaiminhvn | 10:566529fff615 | 138 | } |
khaiminhvn | 8:a1481d5f0572 | 139 | if(flag_disp){ |
khaiminhvn | 8:a1481d5f0572 | 140 | lcd.LCD_display(topL,botL); |
khaiminhvn | 8:a1481d5f0572 | 141 | flag_disp = 0; |
khaiminhvn | 8:a1481d5f0572 | 142 | } |
khaiminhvn | 0:74d6e93ec977 | 143 | |
khaiminhvn | 12:14bac44e33b9 | 144 | if(flag_time) //If delay interval has passed |
khaiminhvn | 12:14bac44e33b9 | 145 | { |
khaiminhvn | 12:14bac44e33b9 | 146 | ane.checkWind(&mode); |
khaiminhvn | 12:14bac44e33b9 | 147 | //Get Angle of Panel |
khaiminhvn | 20:0a6609515810 | 148 | if(flag_aTrack) |
khaiminhvn | 20:0a6609515810 | 149 | ang_P = acc.getAngle(S_PANEL); |
khaiminhvn | 20:0a6609515810 | 150 | else{ |
khaiminhvn | 20:0a6609515810 | 151 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
khaiminhvn | 20:0a6609515810 | 152 | ang_P = sun_angle; |
khaiminhvn | 20:0a6609515810 | 153 | } |
khaiminhvn | 12:14bac44e33b9 | 154 | |
khaiminhvn | 12:14bac44e33b9 | 155 | //Calculate the Angle of Both Reflector |
khaiminhvn | 12:14bac44e33b9 | 156 | ref_R1 = Algorithm::calcAngle(1,ang_P); |
khaiminhvn | 12:14bac44e33b9 | 157 | ref_R2 = Algorithm::calcAngle(2,ang_P); |
khaiminhvn | 12:14bac44e33b9 | 158 | |
khaiminhvn | 14:3989d03a8b98 | 159 | //Moving Reflector 1 |
khaiminhvn | 12:14bac44e33b9 | 160 | ang_R = acc.getAngle(S_R1); |
khaiminhvn | 15:2b3b5d8bf692 | 161 | while(ang_R <= ref_R1 && !acc.checkAngle(ref_R1,ang_R) && mode == OP_NORMAL) |
khaiminhvn | 12:14bac44e33b9 | 162 | { |
khaiminhvn | 20:0a6609515810 | 163 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
jump_man | 17:238ccf7e3676 | 164 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 165 | fan.checkTemp(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 16:326404a7a8b8 | 166 | ane.checkWind(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 14:3989d03a8b98 | 167 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 168 | topL = (flag_flas)? "NORMAL:R1 <=>" : "NORMAL:R1 <-=->"; |
khaiminhvn | 24:ea7abc25a697 | 169 | topL = (flag_aTrack) ? topL : "*" + topL; |
khaiminhvn | 14:3989d03a8b98 | 170 | flag_flas = !flag_flas; |
khaiminhvn | 25:b04abb0930ef | 171 | botL = Misc::itos(ane.getWind(&flag_disp)) + "kph*" + Misc::itos(fan.getTemp()) + "C*" |
khaiminhvn | 25:b04abb0930ef | 172 | + ((flag_eth)?Misc::itos(inverter.getPower()):"---") + "W"; |
khaiminhvn | 14:3989d03a8b98 | 173 | t_disp.reset(); |
khaiminhvn | 14:3989d03a8b98 | 174 | t_disp.start(); |
khaiminhvn | 14:3989d03a8b98 | 175 | } |
khaiminhvn | 14:3989d03a8b98 | 176 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 177 | motor.moveForward(M1); |
khaiminhvn | 12:14bac44e33b9 | 178 | ang_R = acc.getAngle(S_R1); |
khaiminhvn | 12:14bac44e33b9 | 179 | } |
khaiminhvn | 15:2b3b5d8bf692 | 180 | while(ang_R >= ref_R1 && !acc.checkAngle(ref_R1,ang_R) && mode == OP_NORMAL) |
khaiminhvn | 12:14bac44e33b9 | 181 | { |
khaiminhvn | 20:0a6609515810 | 182 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
jump_man | 17:238ccf7e3676 | 183 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 184 | fan.checkTemp(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 16:326404a7a8b8 | 185 | ane.checkWind(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 14:3989d03a8b98 | 186 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 187 | topL = (flag_flas)? "NORMAL:R1 > = < " : "NORMAL:R1 ->=<-"; |
khaiminhvn | 24:ea7abc25a697 | 188 | topL = (flag_aTrack) ? topL : "*" + topL; |
khaiminhvn | 14:3989d03a8b98 | 189 | flag_flas = !flag_flas; |
khaiminhvn | 25:b04abb0930ef | 190 | botL = Misc::itos(ane.getWind(&flag_disp)) + "kph*" + Misc::itos(fan.getTemp()) + "C*" |
khaiminhvn | 25:b04abb0930ef | 191 | + ((flag_eth)?Misc::itos(inverter.getPower()):"---") + "W"; |
khaiminhvn | 14:3989d03a8b98 | 192 | t_disp.reset(); |
khaiminhvn | 14:3989d03a8b98 | 193 | t_disp.start(); |
khaiminhvn | 14:3989d03a8b98 | 194 | } |
khaiminhvn | 14:3989d03a8b98 | 195 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 196 | motor.moveBackward(M1); |
khaiminhvn | 12:14bac44e33b9 | 197 | ang_R = acc.getAngle(S_R1); |
khaiminhvn | 12:14bac44e33b9 | 198 | } |
khaiminhvn | 12:14bac44e33b9 | 199 | motor.stop(); |
khaiminhvn | 12:14bac44e33b9 | 200 | |
khaiminhvn | 12:14bac44e33b9 | 201 | //Moving Reflector 2 |
khaiminhvn | 12:14bac44e33b9 | 202 | ang_R = acc.getAngle(S_R2); |
khaiminhvn | 15:2b3b5d8bf692 | 203 | while(ang_R <= ref_R2 && !acc.checkAngle(ref_R2,ang_R) && mode == OP_NORMAL) |
khaiminhvn | 12:14bac44e33b9 | 204 | { |
khaiminhvn | 20:0a6609515810 | 205 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
jump_man | 17:238ccf7e3676 | 206 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 207 | fan.checkTemp(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 16:326404a7a8b8 | 208 | ane.checkWind(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 14:3989d03a8b98 | 209 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 210 | topL = (flag_flas)? "NORMAL:R2 <=>" : "NORMAL:R2 <-=->"; |
khaiminhvn | 24:ea7abc25a697 | 211 | topL = (flag_aTrack) ? topL : "*" + topL; |
khaiminhvn | 14:3989d03a8b98 | 212 | flag_flas = !flag_flas; |
khaiminhvn | 25:b04abb0930ef | 213 | botL = Misc::itos(ane.getWind(&flag_disp)) + "kph*" + Misc::itos(fan.getTemp()) + "C*" |
khaiminhvn | 25:b04abb0930ef | 214 | + ((flag_eth)?Misc::itos(inverter.getPower()):"---") + "W"; |
khaiminhvn | 14:3989d03a8b98 | 215 | t_disp.reset(); |
khaiminhvn | 14:3989d03a8b98 | 216 | t_disp.start(); |
khaiminhvn | 14:3989d03a8b98 | 217 | } |
khaiminhvn | 14:3989d03a8b98 | 218 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 219 | motor.moveForward(M2); |
khaiminhvn | 12:14bac44e33b9 | 220 | ang_R = acc.getAngle(S_R2); |
khaiminhvn | 12:14bac44e33b9 | 221 | } |
khaiminhvn | 15:2b3b5d8bf692 | 222 | while(ang_R >= ref_R2 && !acc.checkAngle(ref_R2,ang_R) && mode == OP_NORMAL) |
khaiminhvn | 12:14bac44e33b9 | 223 | { |
khaiminhvn | 20:0a6609515810 | 224 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
jump_man | 17:238ccf7e3676 | 225 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 226 | fan.checkTemp(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 16:326404a7a8b8 | 227 | ane.checkWind(&mode);if(mode != OP_NORMAL){break;} |
khaiminhvn | 14:3989d03a8b98 | 228 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 229 | topL = (flag_flas)? "NORMAL:R2 > = < " : "NORMAL:R2 ->=<-"; |
khaiminhvn | 24:ea7abc25a697 | 230 | topL = (flag_aTrack) ? topL : "*" + topL; |
khaiminhvn | 14:3989d03a8b98 | 231 | flag_flas = !flag_flas; |
khaiminhvn | 25:b04abb0930ef | 232 | botL = Misc::itos(ane.getWind(&flag_disp)) + "kph*" + Misc::itos(fan.getTemp()) + "C*" |
khaiminhvn | 25:b04abb0930ef | 233 | + ((flag_eth)?Misc::itos(inverter.getPower()):"---") + "W"; |
khaiminhvn | 14:3989d03a8b98 | 234 | t_disp.reset(); |
khaiminhvn | 14:3989d03a8b98 | 235 | t_disp.start(); |
khaiminhvn | 14:3989d03a8b98 | 236 | } |
khaiminhvn | 14:3989d03a8b98 | 237 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 238 | motor.moveBackward(M2); |
khaiminhvn | 12:14bac44e33b9 | 239 | ang_R = acc.getAngle(S_R2); |
khaiminhvn | 12:14bac44e33b9 | 240 | } |
khaiminhvn | 12:14bac44e33b9 | 241 | motor.stop(); |
khaiminhvn | 12:14bac44e33b9 | 242 | flag_time = 0; //Reset timer flag |
khaiminhvn | 12:14bac44e33b9 | 243 | flag_disp = 1; //Reset display flag |
khaiminhvn | 12:14bac44e33b9 | 244 | t.reset(); //Reset timer |
khaiminhvn | 12:14bac44e33b9 | 245 | } |
khaiminhvn | 12:14bac44e33b9 | 246 | t_elapsed = (int)timer_read_s(t); |
khaiminhvn | 12:14bac44e33b9 | 247 | flag_time = (t_elapsed >= TIME_NORMAL) ? 1 : 0; //Enable flag if delay interval has passed |
khaiminhvn | 9:6e950b9a9a81 | 248 | flag_idle = 0; |
khaiminhvn | 7:2b6438e586e6 | 249 | break; |
khaiminhvn | 8:a1481d5f0572 | 250 | } |
khaiminhvn | 7:2b6438e586e6 | 251 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 7:2b6438e586e6 | 252 | case OP_WIND:{ |
khaiminhvn | 20:0a6609515810 | 253 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
jump_man | 17:238ccf7e3676 | 254 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 255 | fan.checkTemp(&mode);if(mode != OP_WIND){break;} |
khaiminhvn | 16:326404a7a8b8 | 256 | ane.checkWind(&mode);if(mode != OP_WIND){break;} |
khaiminhvn | 14:3989d03a8b98 | 257 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 258 | topL = (flag_flas)? "WIND SAFETY *!*" : "WIND SAFETY"; |
khaiminhvn | 15:2b3b5d8bf692 | 259 | flag_flas = !flag_flas; |
khaiminhvn | 25:b04abb0930ef | 260 | botL = Misc::itos(ane.getWind(&flag_disp)) + "kph*" + Misc::itos(fan.getTemp()) + "C*" |
khaiminhvn | 25:b04abb0930ef | 261 | + ((flag_eth)?Misc::itos(inverter.getPower()):"---") + "W"; |
khaiminhvn | 10:566529fff615 | 262 | t_disp.reset(); |
khaiminhvn | 10:566529fff615 | 263 | t_disp.start(); |
khaiminhvn | 10:566529fff615 | 264 | } |
khaiminhvn | 8:a1481d5f0572 | 265 | if(flag_disp){ |
khaiminhvn | 8:a1481d5f0572 | 266 | lcd.LCD_display(topL,botL); |
khaiminhvn | 8:a1481d5f0572 | 267 | flag_disp = 0; |
khaiminhvn | 8:a1481d5f0572 | 268 | } |
khaiminhvn | 0:74d6e93ec977 | 269 | |
khaiminhvn | 11:2ade1ad7bad6 | 270 | //Move all motor backward |
khaiminhvn | 11:2ade1ad7bad6 | 271 | motor.moveBackward(M_ALL); |
khaiminhvn | 11:2ade1ad7bad6 | 272 | flag_time = 1; //Set the system in motion once windspeed has subsided |
khaiminhvn | 11:2ade1ad7bad6 | 273 | break; |
khaiminhvn | 11:2ade1ad7bad6 | 274 | |
khaiminhvn | 9:6e950b9a9a81 | 275 | flag_idle = 0; |
khaiminhvn | 7:2b6438e586e6 | 276 | break; |
khaiminhvn | 8:a1481d5f0572 | 277 | } |
khaiminhvn | 0:74d6e93ec977 | 278 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 7:2b6438e586e6 | 279 | case OP_MANUAL1:{ |
jump_man | 17:238ccf7e3676 | 280 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 281 | fan.checkTemp(&mode);if(mode != OP_MANUAL1){break;} |
khaiminhvn | 15:2b3b5d8bf692 | 282 | topL = "MANUAL:M1"; |
jump_man | 17:238ccf7e3676 | 283 | botL = Misc::itos(ane.getWind(&flag_disp)) + "kph*" + Misc::itos(fan.getTemp()) + "C*" |
jump_man | 17:238ccf7e3676 | 284 | + ((flag_eth)?Misc::itos(inverter.getPower()):"---") + "W"; |
khaiminhvn | 8:a1481d5f0572 | 285 | if(flag_disp){ |
khaiminhvn | 8:a1481d5f0572 | 286 | lcd.LCD_display(topL,botL); |
khaiminhvn | 8:a1481d5f0572 | 287 | flag_disp = 0; |
khaiminhvn | 8:a1481d5f0572 | 288 | } |
khaiminhvn | 0:74d6e93ec977 | 289 | |
khaiminhvn | 12:14bac44e33b9 | 290 | //TIMEOUT |
khaiminhvn | 12:14bac44e33b9 | 291 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 12:14bac44e33b9 | 292 | if(!flag_idle) //Check if button is not pressed |
khaiminhvn | 12:14bac44e33b9 | 293 | { |
khaiminhvn | 12:14bac44e33b9 | 294 | t_mode.reset(); |
khaiminhvn | 12:14bac44e33b9 | 295 | t_mode.start(); |
khaiminhvn | 12:14bac44e33b9 | 296 | flag_idle = 1; //Indicate idling |
khaiminhvn | 12:14bac44e33b9 | 297 | } |
khaiminhvn | 12:14bac44e33b9 | 298 | else if(timer_read_s(t_mode) > TIME_MANUAL_TIMEOUT) |
khaiminhvn | 12:14bac44e33b9 | 299 | { |
khaiminhvn | 12:14bac44e33b9 | 300 | mode = OP_NORMAL; |
khaiminhvn | 12:14bac44e33b9 | 301 | flag_disp = 1; |
khaiminhvn | 12:14bac44e33b9 | 302 | break; |
khaiminhvn | 12:14bac44e33b9 | 303 | } |
khaiminhvn | 12:14bac44e33b9 | 304 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 12:14bac44e33b9 | 305 | |
khaiminhvn | 12:14bac44e33b9 | 306 | while(bt_inc.read()) //Extend |
khaiminhvn | 12:14bac44e33b9 | 307 | { |
jump_man | 17:238ccf7e3676 | 308 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 15:2b3b5d8bf692 | 309 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 310 | topL = (flag_flas)? "MANUAL:M1 <=> " : "MANUAL:M1 <-=->"; |
khaiminhvn | 15:2b3b5d8bf692 | 311 | flag_flas = !flag_flas; |
khaiminhvn | 15:2b3b5d8bf692 | 312 | t_disp.reset(); |
khaiminhvn | 15:2b3b5d8bf692 | 313 | t_disp.start(); |
khaiminhvn | 12:14bac44e33b9 | 314 | botL = "EXTENDING"; |
khaiminhvn | 12:14bac44e33b9 | 315 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 316 | } |
khaiminhvn | 15:2b3b5d8bf692 | 317 | |
khaiminhvn | 12:14bac44e33b9 | 318 | flag_idle = 0; |
khaiminhvn | 12:14bac44e33b9 | 319 | motor.moveForward(M1); |
khaiminhvn | 12:14bac44e33b9 | 320 | } |
khaiminhvn | 12:14bac44e33b9 | 321 | while(bt_dec.read()) //Retract |
khaiminhvn | 12:14bac44e33b9 | 322 | { |
jump_man | 17:238ccf7e3676 | 323 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 15:2b3b5d8bf692 | 324 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 325 | topL = (flag_flas)? "MANUAL:M1 > = <" : "MANUAL:M1 ->=<-"; |
khaiminhvn | 15:2b3b5d8bf692 | 326 | flag_flas = !flag_flas; |
khaiminhvn | 15:2b3b5d8bf692 | 327 | t_disp.reset(); |
khaiminhvn | 15:2b3b5d8bf692 | 328 | t_disp.start(); |
khaiminhvn | 12:14bac44e33b9 | 329 | botL = "RETRACTING"; |
khaiminhvn | 12:14bac44e33b9 | 330 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 331 | } |
khaiminhvn | 12:14bac44e33b9 | 332 | flag_idle = 0; |
khaiminhvn | 12:14bac44e33b9 | 333 | motor.moveBackward(M1); |
khaiminhvn | 12:14bac44e33b9 | 334 | } |
khaiminhvn | 12:14bac44e33b9 | 335 | if(!bt_inc.read() && !bt_dec.read() && !flag_disp) |
khaiminhvn | 12:14bac44e33b9 | 336 | { |
khaiminhvn | 12:14bac44e33b9 | 337 | flag_disp = 1; |
khaiminhvn | 12:14bac44e33b9 | 338 | motor.stop(); |
khaiminhvn | 12:14bac44e33b9 | 339 | } |
khaiminhvn | 15:2b3b5d8bf692 | 340 | flag_time = 1; |
khaiminhvn | 7:2b6438e586e6 | 341 | break; |
khaiminhvn | 8:a1481d5f0572 | 342 | } |
khaiminhvn | 7:2b6438e586e6 | 343 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 7:2b6438e586e6 | 344 | case OP_MANUAL2:{ |
jump_man | 17:238ccf7e3676 | 345 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 346 | fan.checkTemp(&mode);if(mode != OP_MANUAL2){break;} |
khaiminhvn | 15:2b3b5d8bf692 | 347 | topL = "MANUAL:M2"; |
khaiminhvn | 16:326404a7a8b8 | 348 | botL = Misc::itos(ane.getWind(&flag_disp),3) + "kph | " + Misc::itos(fan.getTemp()) + "C"; |
khaiminhvn | 8:a1481d5f0572 | 349 | if(flag_disp){ |
khaiminhvn | 8:a1481d5f0572 | 350 | lcd.LCD_display(topL,botL); |
khaiminhvn | 8:a1481d5f0572 | 351 | flag_disp = 0; |
khaiminhvn | 8:a1481d5f0572 | 352 | } |
khaiminhvn | 12:14bac44e33b9 | 353 | |
khaiminhvn | 12:14bac44e33b9 | 354 | //TIMEOUT |
khaiminhvn | 12:14bac44e33b9 | 355 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 12:14bac44e33b9 | 356 | if(!flag_idle) //Check if button is not pressed |
khaiminhvn | 12:14bac44e33b9 | 357 | { |
khaiminhvn | 12:14bac44e33b9 | 358 | t_mode.reset(); |
khaiminhvn | 12:14bac44e33b9 | 359 | t_mode.start(); |
khaiminhvn | 12:14bac44e33b9 | 360 | flag_idle = 1; //Indicate idling |
khaiminhvn | 12:14bac44e33b9 | 361 | } |
khaiminhvn | 12:14bac44e33b9 | 362 | else if(timer_read_s(t_mode) > TIME_MANUAL_TIMEOUT) |
khaiminhvn | 12:14bac44e33b9 | 363 | { |
khaiminhvn | 12:14bac44e33b9 | 364 | mode = OP_NORMAL; |
khaiminhvn | 12:14bac44e33b9 | 365 | flag_disp = 1; |
khaiminhvn | 12:14bac44e33b9 | 366 | break; |
khaiminhvn | 12:14bac44e33b9 | 367 | } |
khaiminhvn | 12:14bac44e33b9 | 368 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 12:14bac44e33b9 | 369 | |
khaiminhvn | 12:14bac44e33b9 | 370 | while(bt_inc.read()) //Extend |
khaiminhvn | 12:14bac44e33b9 | 371 | { |
jump_man | 17:238ccf7e3676 | 372 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 15:2b3b5d8bf692 | 373 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 374 | topL = (flag_flas)? "MANUAL:M2 <=> " : "MANUAL:M2 <-=->"; |
khaiminhvn | 15:2b3b5d8bf692 | 375 | flag_flas = !flag_flas; |
khaiminhvn | 15:2b3b5d8bf692 | 376 | t_disp.reset(); |
khaiminhvn | 15:2b3b5d8bf692 | 377 | t_disp.start(); |
khaiminhvn | 12:14bac44e33b9 | 378 | botL = "EXTENDING"; |
khaiminhvn | 12:14bac44e33b9 | 379 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 380 | } |
khaiminhvn | 15:2b3b5d8bf692 | 381 | |
khaiminhvn | 12:14bac44e33b9 | 382 | flag_idle = 0; |
khaiminhvn | 16:326404a7a8b8 | 383 | motor.moveForward(M2); |
khaiminhvn | 12:14bac44e33b9 | 384 | } |
khaiminhvn | 12:14bac44e33b9 | 385 | while(bt_dec.read()) //Retract |
khaiminhvn | 12:14bac44e33b9 | 386 | { |
jump_man | 17:238ccf7e3676 | 387 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 15:2b3b5d8bf692 | 388 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 389 | topL = (flag_flas)? "MANUAL:M2 > = <" : "MANUAL:M2 ->=<-"; |
khaiminhvn | 15:2b3b5d8bf692 | 390 | flag_flas = !flag_flas; |
khaiminhvn | 15:2b3b5d8bf692 | 391 | t_disp.reset(); |
khaiminhvn | 15:2b3b5d8bf692 | 392 | t_disp.start(); |
khaiminhvn | 12:14bac44e33b9 | 393 | botL = "RETRACTING"; |
khaiminhvn | 12:14bac44e33b9 | 394 | lcd.LCD_display(topL,botL); |
khaiminhvn | 12:14bac44e33b9 | 395 | } |
khaiminhvn | 12:14bac44e33b9 | 396 | flag_idle = 0; |
khaiminhvn | 16:326404a7a8b8 | 397 | motor.moveBackward(M2); |
khaiminhvn | 12:14bac44e33b9 | 398 | } |
khaiminhvn | 12:14bac44e33b9 | 399 | if(!bt_inc.read() && !bt_dec.read() && !flag_disp) |
khaiminhvn | 12:14bac44e33b9 | 400 | { |
khaiminhvn | 12:14bac44e33b9 | 401 | flag_disp = 1; |
khaiminhvn | 12:14bac44e33b9 | 402 | motor.stop(); |
khaiminhvn | 12:14bac44e33b9 | 403 | } |
khaiminhvn | 15:2b3b5d8bf692 | 404 | flag_time = 1; |
khaiminhvn | 15:2b3b5d8bf692 | 405 | break; |
khaiminhvn | 15:2b3b5d8bf692 | 406 | } |
khaiminhvn | 15:2b3b5d8bf692 | 407 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 15:2b3b5d8bf692 | 408 | case OP_MANUAL_ALL:{ |
jump_man | 17:238ccf7e3676 | 409 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 410 | fan.checkTemp(&mode);if(mode != OP_MANUAL_ALL){break;} |
khaiminhvn | 15:2b3b5d8bf692 | 411 | topL = "MANUAL:ALL"; |
khaiminhvn | 16:326404a7a8b8 | 412 | botL = Misc::itos(ane.getWind(&flag_disp),3) + "kph | " + Misc::itos(fan.getTemp()) + "C"; |
khaiminhvn | 15:2b3b5d8bf692 | 413 | if(flag_disp){ |
khaiminhvn | 15:2b3b5d8bf692 | 414 | lcd.LCD_display(topL,botL); |
khaiminhvn | 15:2b3b5d8bf692 | 415 | flag_disp = 0; |
khaiminhvn | 15:2b3b5d8bf692 | 416 | } |
khaiminhvn | 15:2b3b5d8bf692 | 417 | |
khaiminhvn | 15:2b3b5d8bf692 | 418 | //TIMEOUT |
khaiminhvn | 15:2b3b5d8bf692 | 419 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 15:2b3b5d8bf692 | 420 | if(!flag_idle) //Check if button is not pressed |
khaiminhvn | 15:2b3b5d8bf692 | 421 | { |
khaiminhvn | 15:2b3b5d8bf692 | 422 | t_mode.reset(); |
khaiminhvn | 15:2b3b5d8bf692 | 423 | t_mode.start(); |
khaiminhvn | 15:2b3b5d8bf692 | 424 | flag_idle = 1; //Indicate idling |
khaiminhvn | 15:2b3b5d8bf692 | 425 | } |
khaiminhvn | 15:2b3b5d8bf692 | 426 | else if(timer_read_s(t_mode) > TIME_MANUAL_TIMEOUT) |
khaiminhvn | 15:2b3b5d8bf692 | 427 | { |
khaiminhvn | 15:2b3b5d8bf692 | 428 | mode = OP_NORMAL; |
khaiminhvn | 15:2b3b5d8bf692 | 429 | flag_disp = 1; |
khaiminhvn | 15:2b3b5d8bf692 | 430 | break; |
khaiminhvn | 15:2b3b5d8bf692 | 431 | } |
khaiminhvn | 15:2b3b5d8bf692 | 432 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 15:2b3b5d8bf692 | 433 | |
khaiminhvn | 15:2b3b5d8bf692 | 434 | while(bt_inc.read()) //Extend |
khaiminhvn | 15:2b3b5d8bf692 | 435 | { |
jump_man | 17:238ccf7e3676 | 436 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 15:2b3b5d8bf692 | 437 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 438 | topL = (flag_flas)? "MANUAL:ALL <=> " : "MANUAL:ALL <-=->"; |
khaiminhvn | 15:2b3b5d8bf692 | 439 | flag_flas = !flag_flas; |
khaiminhvn | 15:2b3b5d8bf692 | 440 | t_disp.reset(); |
khaiminhvn | 15:2b3b5d8bf692 | 441 | t_disp.start(); |
khaiminhvn | 15:2b3b5d8bf692 | 442 | botL = "EXTENDING"; |
khaiminhvn | 15:2b3b5d8bf692 | 443 | lcd.LCD_display(topL,botL); |
khaiminhvn | 15:2b3b5d8bf692 | 444 | } |
khaiminhvn | 15:2b3b5d8bf692 | 445 | |
khaiminhvn | 15:2b3b5d8bf692 | 446 | flag_idle = 0; |
khaiminhvn | 16:326404a7a8b8 | 447 | motor.moveForward(M_ALL); |
khaiminhvn | 15:2b3b5d8bf692 | 448 | } |
khaiminhvn | 15:2b3b5d8bf692 | 449 | while(bt_dec.read()) //Retract |
khaiminhvn | 15:2b3b5d8bf692 | 450 | { |
jump_man | 17:238ccf7e3676 | 451 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 15:2b3b5d8bf692 | 452 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 15:2b3b5d8bf692 | 453 | topL = (flag_flas)? "MANUAL:ALL > = <" : "MANUAL:ALL ->=<-"; |
khaiminhvn | 15:2b3b5d8bf692 | 454 | flag_flas = !flag_flas; |
khaiminhvn | 15:2b3b5d8bf692 | 455 | t_disp.reset(); |
khaiminhvn | 15:2b3b5d8bf692 | 456 | t_disp.start(); |
khaiminhvn | 15:2b3b5d8bf692 | 457 | botL = "RETRACTING"; |
khaiminhvn | 15:2b3b5d8bf692 | 458 | lcd.LCD_display(topL,botL); |
khaiminhvn | 15:2b3b5d8bf692 | 459 | } |
khaiminhvn | 15:2b3b5d8bf692 | 460 | flag_idle = 0; |
khaiminhvn | 16:326404a7a8b8 | 461 | motor.moveBackward(M_ALL); |
khaiminhvn | 15:2b3b5d8bf692 | 462 | } |
khaiminhvn | 15:2b3b5d8bf692 | 463 | if(!bt_inc.read() && !bt_dec.read() && !flag_disp) |
khaiminhvn | 15:2b3b5d8bf692 | 464 | { |
khaiminhvn | 15:2b3b5d8bf692 | 465 | flag_disp = 1; |
khaiminhvn | 15:2b3b5d8bf692 | 466 | motor.stop(); |
khaiminhvn | 15:2b3b5d8bf692 | 467 | } |
khaiminhvn | 15:2b3b5d8bf692 | 468 | flag_time = 1; |
khaiminhvn | 0:74d6e93ec977 | 469 | break; |
khaiminhvn | 8:a1481d5f0572 | 470 | } |
khaiminhvn | 7:2b6438e586e6 | 471 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 7:2b6438e586e6 | 472 | case OP_WSETTING:{ |
jump_man | 17:238ccf7e3676 | 473 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 474 | fan.checkTemp(&mode);if(mode != OP_WSETTING){break;} |
khaiminhvn | 7:2b6438e586e6 | 475 | topL = "Threshold:"; |
khaiminhvn | 9:6e950b9a9a81 | 476 | botL = Misc::itos(wthres) + " kph"; |
khaiminhvn | 8:a1481d5f0572 | 477 | if(flag_disp){ |
khaiminhvn | 8:a1481d5f0572 | 478 | lcd.LCD_display(topL,botL); |
khaiminhvn | 8:a1481d5f0572 | 479 | flag_disp = 0; |
khaiminhvn | 8:a1481d5f0572 | 480 | } |
khaiminhvn | 0:74d6e93ec977 | 481 | |
khaiminhvn | 9:6e950b9a9a81 | 482 | //TIMEOUT |
khaiminhvn | 9:6e950b9a9a81 | 483 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 9:6e950b9a9a81 | 484 | if(!flag_idle) //Check if button is not pressed |
khaiminhvn | 9:6e950b9a9a81 | 485 | { |
khaiminhvn | 9:6e950b9a9a81 | 486 | t_mode.reset(); |
khaiminhvn | 9:6e950b9a9a81 | 487 | t_mode.start(); |
khaiminhvn | 9:6e950b9a9a81 | 488 | flag_idle = 1; //Indicate idling |
khaiminhvn | 9:6e950b9a9a81 | 489 | } |
khaiminhvn | 9:6e950b9a9a81 | 490 | else if(timer_read_s(t_mode) > TIME_WSETTING_TIMEOUT) |
khaiminhvn | 9:6e950b9a9a81 | 491 | { |
khaiminhvn | 9:6e950b9a9a81 | 492 | mode = OP_NORMAL; |
khaiminhvn | 9:6e950b9a9a81 | 493 | flag_disp = 1; |
khaiminhvn | 9:6e950b9a9a81 | 494 | break; |
khaiminhvn | 9:6e950b9a9a81 | 495 | } |
khaiminhvn | 9:6e950b9a9a81 | 496 | //////////////////////////////////////////////////////////////////// |
khaiminhvn | 9:6e950b9a9a81 | 497 | |
khaiminhvn | 9:6e950b9a9a81 | 498 | if(!(flag_bres == 1 && bt_inc.read()) && !(flag_bres == -1 && bt_dec.read())){ |
khaiminhvn | 9:6e950b9a9a81 | 499 | if(bt_inc.read() && wthres < WIND_THRES_MAX) |
khaiminhvn | 9:6e950b9a9a81 | 500 | { |
khaiminhvn | 24:ea7abc25a697 | 501 | wthres += WIND_INC; |
khaiminhvn | 24:ea7abc25a697 | 502 | ane.setThres(wthres); |
jump_man | 17:238ccf7e3676 | 503 | if(flag_eth){gui.survivalSpeed(wthres);} |
khaiminhvn | 9:6e950b9a9a81 | 504 | botL = Misc::itos(wthres) + " kph"; |
khaiminhvn | 9:6e950b9a9a81 | 505 | lcd.LCD_display(topL,botL); |
khaiminhvn | 9:6e950b9a9a81 | 506 | flag_idle = 0; |
khaiminhvn | 9:6e950b9a9a81 | 507 | flag_bres = 1; |
khaiminhvn | 9:6e950b9a9a81 | 508 | } |
khaiminhvn | 9:6e950b9a9a81 | 509 | else if(bt_dec.read() && wthres > WIND_THRES_MIN) |
khaiminhvn | 9:6e950b9a9a81 | 510 | { |
khaiminhvn | 24:ea7abc25a697 | 511 | wthres -= WIND_INC; |
khaiminhvn | 24:ea7abc25a697 | 512 | ane.setThres(wthres); |
jump_man | 17:238ccf7e3676 | 513 | if(flag_eth){gui.survivalSpeed(wthres);} |
khaiminhvn | 9:6e950b9a9a81 | 514 | botL = Misc::itos(wthres) + " kph"; |
khaiminhvn | 9:6e950b9a9a81 | 515 | lcd.LCD_display(topL,botL); |
khaiminhvn | 9:6e950b9a9a81 | 516 | flag_idle = 0; |
khaiminhvn | 9:6e950b9a9a81 | 517 | flag_bres = -1; |
khaiminhvn | 9:6e950b9a9a81 | 518 | } |
khaiminhvn | 9:6e950b9a9a81 | 519 | else{ |
khaiminhvn | 9:6e950b9a9a81 | 520 | flag_bres = 0; |
khaiminhvn | 9:6e950b9a9a81 | 521 | } |
khaiminhvn | 9:6e950b9a9a81 | 522 | } |
khaiminhvn | 9:6e950b9a9a81 | 523 | |
khaiminhvn | 9:6e950b9a9a81 | 524 | flag_time = 1; //Set the system in motion once done adjusting |
khaiminhvn | 7:2b6438e586e6 | 525 | break; |
khaiminhvn | 8:a1481d5f0572 | 526 | } |
khaiminhvn | 16:326404a7a8b8 | 527 | //////////////////////////////////////////////////////////////////////// |
khaiminhvn | 16:326404a7a8b8 | 528 | case OP_OVERHEAT:{ |
jump_man | 17:238ccf7e3676 | 529 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 530 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 16:326404a7a8b8 | 531 | topL = (flag_flas)? "*!* OVERHEAT *!*": " OVERHEAT "; |
khaiminhvn | 16:326404a7a8b8 | 532 | botL = (flag_flas)? " KEEP DISTANCE " : (" " + Misc::itos(fan.getTemp(),3) + "C"); |
khaiminhvn | 16:326404a7a8b8 | 533 | flag_flas = !flag_flas; |
khaiminhvn | 16:326404a7a8b8 | 534 | t_disp.reset(); |
khaiminhvn | 16:326404a7a8b8 | 535 | t_disp.start(); |
khaiminhvn | 16:326404a7a8b8 | 536 | lcd.LCD_display(topL,botL); |
khaiminhvn | 16:326404a7a8b8 | 537 | } |
khaiminhvn | 16:326404a7a8b8 | 538 | motor.moveBackward(M_ALL); |
khaiminhvn | 16:326404a7a8b8 | 539 | fan.checkTemp(&mode); |
khaiminhvn | 16:326404a7a8b8 | 540 | flag_disp = 1; |
khaiminhvn | 16:326404a7a8b8 | 541 | flag_time = 1; |
khaiminhvn | 16:326404a7a8b8 | 542 | break; |
khaiminhvn | 16:326404a7a8b8 | 543 | } |
khaiminhvn | 16:326404a7a8b8 | 544 | //////////////////////////////////////////////////////////////////////// |
khaiminhvn | 16:326404a7a8b8 | 545 | case OP_OVERHEAT_MAN:{ |
jump_man | 17:238ccf7e3676 | 546 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 16:326404a7a8b8 | 547 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
khaiminhvn | 16:326404a7a8b8 | 548 | topL = (flag_flas)? "*!* OVERHEAT *!*": " OVERHEAT "; |
khaiminhvn | 16:326404a7a8b8 | 549 | botL = (flag_flas)? " PRESS FN " : (" " + Misc::itos(fan.getTemp(),3) + "C"); |
khaiminhvn | 16:326404a7a8b8 | 550 | flag_flas = !flag_flas; |
khaiminhvn | 16:326404a7a8b8 | 551 | t_disp.reset(); |
khaiminhvn | 16:326404a7a8b8 | 552 | t_disp.start(); |
khaiminhvn | 16:326404a7a8b8 | 553 | lcd.LCD_display(topL,botL); |
khaiminhvn | 16:326404a7a8b8 | 554 | } |
khaiminhvn | 16:326404a7a8b8 | 555 | motor.stop(); |
khaiminhvn | 16:326404a7a8b8 | 556 | flag_disp = 1; |
khaiminhvn | 16:326404a7a8b8 | 557 | break; |
khaiminhvn | 16:326404a7a8b8 | 558 | } |
jump_man | 17:238ccf7e3676 | 559 | //////////////////////////////////////////////////////////////////////// |
jump_man | 17:238ccf7e3676 | 560 | case OP_POWER_OFF:{ |
khaiminhvn | 20:0a6609515810 | 561 | if (flag_eth){gui.receives(&wthres, &flag_aTrack, &flag_powerOn,&sun_angle);} |
jump_man | 17:238ccf7e3676 | 562 | if(mode != OP_POWER_OFF){break;} |
jump_man | 17:238ccf7e3676 | 563 | if (flag_eth){gui.windSpeed(ane.getWind());} |
jump_man | 17:238ccf7e3676 | 564 | fan.checkTemp(&mode);if(mode != OP_WIND){break;} |
jump_man | 17:238ccf7e3676 | 565 | if(timer_read_ms(t_disp) >= LCD_RRATE){ |
jump_man | 17:238ccf7e3676 | 566 | topL = "SLEEP MODE"; |
jump_man | 17:238ccf7e3676 | 567 | flag_flas = !flag_flas; |
jump_man | 17:238ccf7e3676 | 568 | botL = Misc::itos(ane.getWind(&flag_disp),3) + "kph | " + Misc::itos(fan.getTemp()) + "C"; |
jump_man | 17:238ccf7e3676 | 569 | t_disp.reset(); |
jump_man | 17:238ccf7e3676 | 570 | t_disp.start(); |
jump_man | 17:238ccf7e3676 | 571 | } |
jump_man | 17:238ccf7e3676 | 572 | if(flag_disp){ |
jump_man | 17:238ccf7e3676 | 573 | lcd.LCD_display(topL,botL); |
jump_man | 17:238ccf7e3676 | 574 | flag_disp = 0; |
jump_man | 17:238ccf7e3676 | 575 | } |
jump_man | 17:238ccf7e3676 | 576 | |
jump_man | 17:238ccf7e3676 | 577 | //Move all motor backward |
jump_man | 17:238ccf7e3676 | 578 | motor.moveBackward(M_ALL); |
jump_man | 17:238ccf7e3676 | 579 | flag_time = 1; //Set the system in motion once windspeed has subsided |
jump_man | 17:238ccf7e3676 | 580 | break; |
jump_man | 17:238ccf7e3676 | 581 | |
jump_man | 17:238ccf7e3676 | 582 | flag_idle = 0; |
jump_man | 17:238ccf7e3676 | 583 | break; |
jump_man | 17:238ccf7e3676 | 584 | } |
khaiminhvn | 20:0a6609515810 | 585 | //////////////////////////////////////////////////////////////////////// |
khaiminhvn | 20:0a6609515810 | 586 | case OP_ATRACK:{ |
khaiminhvn | 20:0a6609515810 | 587 | flag_aTrack = !flag_aTrack; |
khaiminhvn | 22:6c8535dab84a | 588 | gui.activeTracking(flag_aTrack); |
khaiminhvn | 20:0a6609515810 | 589 | if (flag_eth){gui.windSpeed(ane.getWind());} |
khaiminhvn | 21:e9978d9823fe | 590 | fan.checkTemp(&mode);if(mode != OP_ATRACK){break;} |
khaiminhvn | 20:0a6609515810 | 591 | topL = "TRACKING MODE:"; |
khaiminhvn | 20:0a6609515810 | 592 | botL = (flag_aTrack) ? "ACTIVE (ACC)" : "AUTO (ONLINE)"; |
khaiminhvn | 20:0a6609515810 | 593 | lcd.LCD_display(topL,botL); |
khaiminhvn | 20:0a6609515810 | 594 | flag_disp = 0; |
khaiminhvn | 20:0a6609515810 | 595 | wait_us(TIME_ATRACK_TIMEOUT); |
khaiminhvn | 20:0a6609515810 | 596 | |
khaiminhvn | 20:0a6609515810 | 597 | mode = OP_NORMAL; |
khaiminhvn | 20:0a6609515810 | 598 | flag_time = 1; //Set the system in motion once done adjusting |
khaiminhvn | 20:0a6609515810 | 599 | break; |
khaiminhvn | 20:0a6609515810 | 600 | } |
khaiminhvn | 20:0a6609515810 | 601 | //////////////////////////////////////////////////////////////////////// |
khaiminhvn | 23:5dff9aed3727 | 602 | case OP_RECONNECT:{ |
khaiminhvn | 23:5dff9aed3727 | 603 | topL = "CONNECTING"; |
khaiminhvn | 23:5dff9aed3727 | 604 | botL = ""; |
khaiminhvn | 23:5dff9aed3727 | 605 | lcd.LCD_display(topL,botL); |
khaiminhvn | 23:5dff9aed3727 | 606 | eth.connect(); |
khaiminhvn | 25:b04abb0930ef | 607 | gui.refreshConnection(URL,&flag_eth); |
khaiminhvn | 23:5dff9aed3727 | 608 | inverter.connect(URL, PORT); |
khaiminhvn | 23:5dff9aed3727 | 609 | bt_fn.setConnected(flag_eth); |
khaiminhvn | 23:5dff9aed3727 | 610 | wait_us(1000000); |
khaiminhvn | 23:5dff9aed3727 | 611 | |
khaiminhvn | 23:5dff9aed3727 | 612 | if (flag_eth){gui.getSunAngle();} |
khaiminhvn | 23:5dff9aed3727 | 613 | if (flag_eth){ |
khaiminhvn | 23:5dff9aed3727 | 614 | topL = "ETHERNET"; |
khaiminhvn | 23:5dff9aed3727 | 615 | botL = "CONNECTED"; |
khaiminhvn | 23:5dff9aed3727 | 616 | lcd.LCD_display(topL, botL); |
khaiminhvn | 23:5dff9aed3727 | 617 | } |
khaiminhvn | 23:5dff9aed3727 | 618 | else{ |
khaiminhvn | 23:5dff9aed3727 | 619 | topL = "ETHERNET"; |
khaiminhvn | 23:5dff9aed3727 | 620 | botL = "NOT CONNECTED"; |
khaiminhvn | 23:5dff9aed3727 | 621 | lcd.LCD_display(topL, botL); |
khaiminhvn | 23:5dff9aed3727 | 622 | } |
khaiminhvn | 23:5dff9aed3727 | 623 | wait_us(TIME_RECONNECT_TIMEOUT); |
khaiminhvn | 23:5dff9aed3727 | 624 | |
khaiminhvn | 23:5dff9aed3727 | 625 | mode = OP_NORMAL; |
khaiminhvn | 23:5dff9aed3727 | 626 | flag_time = 1; //Set the system in motion once done adjusting |
khaiminhvn | 23:5dff9aed3727 | 627 | break; |
khaiminhvn | 23:5dff9aed3727 | 628 | } |
khaiminhvn | 23:5dff9aed3727 | 629 | //////////////////////////////////////////////////////////////////////// |
khaiminhvn | 0:74d6e93ec977 | 630 | } |
jump_man | 17:238ccf7e3676 | 631 | |
jump_man | 17:238ccf7e3676 | 632 | if (flag_eth){ |
jump_man | 17:238ccf7e3676 | 633 | gui.state(mode); |
jump_man | 17:238ccf7e3676 | 634 | } |
jump_man | 17:238ccf7e3676 | 635 | |
khaiminhvn | 7:2b6438e586e6 | 636 | wait_us(LOOP_DELAY); |
jump_man | 17:238ccf7e3676 | 637 | flag_disp = 1; |
khaiminhvn | 0:74d6e93ec977 | 638 | } |
khaiminhvn | 0:74d6e93ec977 | 639 | |
khaiminhvn | 0:74d6e93ec977 | 640 | } |
khaiminhvn | 0:74d6e93ec977 | 641 | //////////////////////////////////////////////////////////////////////////////// |
khaiminhvn | 7:2b6438e586e6 | 642 | //////////////////////////////////////////////////////////////////////////////// |