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