You thought about it, do IT !

Smart Solar Tracker – Code

Smart Solar Tracker – Code

The actual running code

Please be indulgent, code provided as is and has been developed for my personal needs.

I know EEPROM use could be better programed, code is not optimized.

Main file :

//Bibliothèques nécessaires au fonctionnement
#include <Wire.h>
#include <LiquidCrystal_I2C.h>
#include <EEPROM.h>
#include <ESP8266WiFi.h>
#include <WiFiUdp.h>
#include <NTPClient.h>
#include <SolarPosition.h>
#include <HMC5883L.h>
#include <ADS1X15.h>
#include <Adafruit_MCP23017.h>
#include <Arduino_JSON.h>
#include <ESP8266HTTPClient.h>
#include <WiFiClient.h>
#include <ESPAsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include <ArduinoOTA.h>
#include <PubSubClient.h>
#include <time.h>
#include "TRACKER_Parameters.h"
#include "TRACKER_IndexPage.h"
#include "TRACKER_ParamPage.h"

//Initialisation WIFI
const char *WIFI_ssid     = SECRET_WIFI_SSID;
const char *WIFI_password = SECRET_WIFI_PASSWORD;

//Definit le serveur de temps NTP
WiFiUDP ntpUDP;
NTPClient timeClient(ntpUDP, TRACKER_NTP_SERVER);

//Variables pour les fonctions de calcul de position du soleil
//Nombre de décimales à afficher
const uint8_t SOLARPOSITION_digits = 3;
//Localisation du Tracker
const float TRACKER_latitude = TRACKER_LOCATION_LATITUDE;
const float TRACKER_longitude = TRACKER_LOCATION_LONGITUDE;
SolarPosition TRACKER_location(TRACKER_latitude, TRACKER_longitude);
int TRACKER_delta_elevation;

//Initialise les variables du capteur gyroscopique MPU6050
const int MPU6050_addr=0x68;
int16_t MPU6050_AcX,MPU6050_AcY,MPU6050_AcZ,MPU6050_Tmp,MPU6050_GyX,MPU6050_GyY,MPU6050_GyZ;
int MPU6050_minVal=265;
int MPU6050_maxVal=402;
double MPU6050_x;
double MPU6050_y;
double MPU6050_z;

//Initialise les variables du multiplexeur analogique I2C ADS1115
ADS1115 ADS1115(0x48);

//Initialise les variables pour le multiplexeur numérique I2C MCP23017
#define MCP23017_button0 0
#define MCP23017_button1 1
#define MCP23017_button2 2
#define MCP23017_button3 3

Adafruit_MCP23017 MCP23017;
int MCP23017_pin_state = 0;

//Initialise les variables pour le gestionnaire de moteur L298N (2 Pins du 23017 à paramétrer en sortie pour chaque moteur)
int MCP23017_L298N_in1 = 8;
int MCP23017_L298N_in2 = 9;
int ESP8266_L298N_ena = D4;
int MCP23017_L298N_in3 = 11;
int MCP23017_L298N_in4 = 12;
int ESP8266_L298N_enb = D3;
int L298N_set_elevation_done = 0;

//Definition de la taille de l'EEPROM
#define EEPROM_SIZE 40

//Adresses utilisées de la mémoire EEPROM
int EEPROM_TRACKER_selected_mode_addr = 0;
int EEPROM_TRACKER_security_override_addr = 1;
int EEPROM_ANEMO_wind_limit_addr = 2;
int EEPROM_ANEMO_record_time_addr = 3;
int EEPROM_TRACKER_wind_limit_time_addr = 4;
int EEPROM_TRACKER_azi_start_move_dur_addr = 6;
int EEPROM_TRACKER_elevation_min_mv_time_addr = 7;
int EEPROM_TRACKER_ele_max_move_dur_addr = 8;
int EEPROM_TRACKER_elevation_mini_addr = 9;
int EEPROM_TRACKER_elevation_maxi_addr = 10;
int EEPROM_TRACKER_vertical_speed_addr = 11;
int EEPROM_TRACKER_horizontal_speed_addr = 12;
int EEPROM_OPENWEATHER_wind_limit_addr = 13;
int EEPROM_TRACKER_azi_max_move_dur_addr = 14;
int EEPROM_TRACKER_static_mode_azimuth_addr = 15;
int EEPROM_TRACKER_static_mode_elevation_addr = 16;
int EEPROM_TRACKER_azimuth_mini_addr = 17;
int EEPROM_TRACKER_azimuth_maxi_addr = 18;
int EEPROM_TRACKER_azimuth_min_mv_time_addr = 19;
int EEPROM_ANEMO_wind_inter_limit_addr = 20;
int EEPROM_TRACKER_wind_inter_angle_addr = 21;
int EEPROM_OPENWEATHER_wind_inter_limit_addr = 22;
int EEPROM_ANEMO_wind_smart_coeff_addr = 23;
int EEPROM_OPENWEATHER_wind_smart_coeff_addr = 24;
int EEPROM_SUNSENSOR_offset_droite_addr = 25;
int EEPROM_SUNSENSOR_offset_gauche_addr = 26;
int EEPROM_SUNSENSOR_offset_haut_addr = 27;
int EEPROM_SUNSENSOR_offset_bas_addr = 28;
int EEPROM_SUNSENSOR_delta_haut_bas_addr = 29;
int EEPROM_SUNSENSOR_delta_droite_gauche_addr = 30;
int EEPROM_TRACKER_anemometer_model_addr = 31;
int EEPROM_TRACKER_secu_vertical_speed_addr = 32;
int EEPROM_ANEMO_analog_coefficient_addr = 33;

//Variables du tracker
int TRACKER_selected_mode;
int TRACKER_anemometer_model;
int TRACKER_vertical_speed;
int TRACKER_secu_vertical_speed = 150;
int TRACKER_horizontal_speed;
int TRACKER_static_mode_azimuth;
int TRACKER_static_mode_elevation;
int TRACKER_azimuth_mini;
int TRACKER_azimuth_maxi;
int TRACKER_azimuth_min_mv_time;
int TRACKER_elevation_mini;
int TRACKER_elevation_maxi;
int TRACKER_elevation_min_mv_time;
int TRACKER_security_override = 0;
double TRACKER_wind_inter_angle = 0;
int TRACKER_wind_limit_time;
double TRACKER_wind_smart_angle = 0;

//Variables de l'interface
String INTERFACE_selected_mode0_style;
String INTERFACE_selected_mode1_style;
String INTERFACE_selected_mode2_style;
String INTERFACE_selected_mode3_style;
String INTERFACE_selected_secu0_style;
String INTERFACE_selected_secu1_style;
String INTERFACE_selected_secu2_style;
String INTERFACE_selected_secu3_style;
int INTERFACE_restart_on_save = 0;
String INTERFACE_tracker_selected_mode = "";
String INTERFACE_selected_anemo0_style;
String INTERFACE_selected_anemo1_style;
String INTERFACE_tracker_selected_anemometer_model = "";

//Initialisation action de mise en securite
int ANEMO_security_position = 1;
int OPENWEATHER_security_position = 1;

//Reglage
int GUI_selected_setting;

//Initialisation de l'écran
LiquidCrystal_I2C lcd(0x27,16,2);

//Initialisation d'OpenWeather
String OPENWEATHER_MapApiKey = OPENWEATHER_MAP_API_KEY;
String OPENWEATHER_city = OPENWEATHER_CITY_NAME;
String OPENWEATHER_countryCode = OPENWEATHER_COUNTRY_CODE;
unsigned long OPENWEATHER_lastTime = 0;
unsigned long OPENWEATHER_timerDelay = 60000;
String OPENWEATHER_jsonBuffer;
double OPENWEATHER_wind_gust = 0;
int OPENWEATHER_wind_direction = 0;
int OPENWEATHER_wind_limit = 0;
int OPENWEATHER_wind_inter_limit = 5;
int OPENWEATHER_success = 0 ;
double OPENWEATHER_wind_smart_coeff = 150;
double OPENWEATHER_wind_smart_angle = 50;

//Initialisation du serveur Web
AsyncWebServer server(80);

//Variables de butée
int TRACKER_is_at_east_limit = 0;
int TRACKER_is_at_west_limit = 0;
int TRACKER_azi_max_move_dur = 60;
int TRACKER_azi_start_move_dur = 50;
int L298N_azimuth_last_move_start_time = 0;
int TRACKER_ele_max_move_dur = 60;
int TRACKER_is_at_up_limit = 0;
int TRACKER_is_at_down_limit = 0;
int L298N_elevation_last_move_start_time = 0;

//Variables de mouvement basé sur le temps
int L298N_azimuth_moved_duration = 0;
int L298N_elevation_moved_duration = 0;

//Variables de gestion de l'anémomètre
int ANEMO_wind_limit = 0;
int ANEMO_wind_inter_limit = 5;
int ANEMO_record_time = 15;
int ANEMO_sensor_pin = D5;
int ANEMO_interrupt_counter;
float ANEMO_wind_speed;
float ANEMO_wind_gust_secupos = 0;
float ANEMO_wind_gust = 0;
int ANEMO_last_wind_gust_start_time = 0;
double ANEMO_wind_smart_coeff = 175;
double ANEMO_wind_smart_angle = 50;
const int ANEMO_analog_pin = A0;
float ANEMO_analog_voltage = 0;
float ANEMO_analog_voltage_correction = 0.082111;
float ANEMO_analog_coefficient = 110;

//Variables nécessaires au MQTT
const char* mqtt_server = MQTT_BROKER_IP;
#define MSG_BUFFER_SIZE  (50)
char msg[MSG_BUFFER_SIZE];
WiFiClient client;
PubSubClient MQTTclient(client);

//Variables calibration des LDR
int SUNSENSOR_offset_droite;
int SUNSENSOR_offset_gauche;
int SUNSENSOR_offset_haut;
int SUNSENSOR_offset_bas;

//Variables range - Delta déséquilibre valeurs sondes qui ne déclenchent pas de mouvement
int SUNSENSOR_delta_haut_bas;
int SUNSENSOR_delta_droite_gauche;
 
//Initialisation du tracker
void setup() {
  Wire.begin();
  
  //Initialisation communication serie
  Serial.begin(115200);

  //Initialisation de l'écran
  lcd.init();

  //Connection au Wi-Fi
  Serial.println("WIFI - Initialisation du WIFI de ESP8266");
  Serial.print("WIFI - Connection à ");
  Serial.println(WIFI_ssid);
  WiFi.hostname("SOLAR_TRACKER");
  WiFi.begin(WIFI_ssid, WIFI_password);
  while (WiFi.status() != WL_CONNECTED) {
    delay(500);
    Serial.print(".");
  }
  Serial.println("WIFI - Connection établie !");  
  Serial.print("WIFI - Adresse IP : ");
  Serial.println(WiFi.localIP());   

  //Initialise le client NTP
  Serial.print("NTP - Synchronisation NTP en temps UTC");
  timeClient.begin();
  //Définit le fuseau horaire (TimeOffset) - Ne pas activer temps UTC nécessaire pour calculs trajectoire
  // GMT +1 = 3600
  timeClient.setTimeOffset(0);

  //Controle du nombre de devices I2C
  LCD_quick_print("Init. I2C Devices",I2C_check_devices(4), 1, 4000, 1);

  //Initialisation capteur gyroscopique
  Serial.println("I2C - Initialisation du capteur gyroscopique I2C GY-521 MPU-6050");
  Wire.beginTransmission(MPU6050_addr);
  Wire.write(0x6B);
  Wire.write(0);
  Wire.endTransmission(true);

  //Initialisation du multiplexeur analogique ADS1115
  Serial.println("I2C - Initialisation de l'expandeur analogique I2C ADS1115");
  ADS1115.begin();
  ADS1115.setGain(0);
  ADS1115.setMode(1);
  ADS1115.setDataRate(4);
  ADS1115.readADC(0);

  //Initialisation du multiplexeur numérique MCP23017
  //Adresse I2C 0x26 définie dans mcp23017.h
  Serial.println("I2C - Initialisation de l'expandeur numérique I2C MCP23017");
  MCP23017.begin();
  Serial.println("I2C - Paramétrage des entrées boutons de l'expandeur numérique I2C MCP23017");
  MCP23017.pinMode(MCP23017_button0,INPUT);
  MCP23017.pullUp(MCP23017_button0,HIGH);
  MCP23017.pinMode(MCP23017_button1,INPUT);
  MCP23017.pullUp(MCP23017_button1,HIGH);
  MCP23017.pinMode(MCP23017_button2,INPUT);
  MCP23017.pullUp(MCP23017_button2,HIGH);
  MCP23017.pinMode(MCP23017_button3,INPUT);
  MCP23017.pullUp(MCP23017_button3,HIGH);
  Serial.println("I2C - Paramétrage des entrées capteur effet hall de l'expandeur numérique I2C MCP23017");

  //Initialise le gestionnaire de moteur L298H
  Serial.println("I2C - Initialisation des sorties de l'expandeur numérique I2C MCP23017 pour le gestionnaire de moteur L298N");
  MCP23017.pinMode(MCP23017_L298N_in1,OUTPUT);
  MCP23017.pinMode(MCP23017_L298N_in2,OUTPUT);
  MCP23017.digitalWrite(MCP23017_L298N_in1,LOW);
  MCP23017.digitalWrite(MCP23017_L298N_in2,LOW);
  MCP23017.pinMode(MCP23017_L298N_in3,OUTPUT);
  MCP23017.pinMode(MCP23017_L298N_in4,OUTPUT);
  MCP23017.digitalWrite(MCP23017_L298N_in3,LOW);
  MCP23017.digitalWrite(MCP23017_L298N_in4,LOW);

  //Initialisation de l'EEPROM
  Serial.println("EEPROM - Initialisation de l'EEPROM");
  EEPROM.begin(EEPROM_SIZE);

  //Verifie que la mémoire a été initialisée et récupère les variables qui y sont stockées
  EEPROM_settings_init_and_read(0);

  //Services Web
  //Envoie la page d'acceuil'
  server.on("/", HTTP_GET, [](AsyncWebServerRequest *request){
     request->send_P(200, "text/html", indexpage, processor);
  });

  //Envoie la page de paramétrage
  server.on("/param.html", HTTP_GET, [](AsyncWebServerRequest *request){
     request->send_P(200, "text/html", parampage, processor);
  });

  // Send a GET request to <ESP_IP>/get?input1=<inputMessage>
  server.on("/get", HTTP_GET, [] (AsyncWebServerRequest *request) {
    
    //Verifie le mot de passe avant tout
    if ((request->hasParam("TRACKER_password")) && (request->getParam("TRACKER_password")->value()==SECRET_SETUP_PASSWORD)) {
   
      //Recherche le mode actuel du tracker
      if (request->hasParam("TRACKER_selected_mode")) {
        if ((request->getParam("TRACKER_selected_mode")->value().toInt()>=0) && (request->getParam("TRACKER_selected_mode")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_selected_mode_addr, request->getParam("TRACKER_selected_mode")->value().toInt());
          TRACKER_selected_mode = EEPROM.read(EEPROM_TRACKER_selected_mode_addr);
        }
      }
      if (request->hasParam("TRACKER_anemometer_model")) {
        if ((request->getParam("TRACKER_anemometer_model")->value().toInt()>=0) && (request->getParam("TRACKER_anemometer_model")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_anemometer_model_addr, request->getParam("TRACKER_anemometer_model")->value().toInt());
          TRACKER_anemometer_model = EEPROM.read(EEPROM_TRACKER_anemometer_model_addr);
        }
      }
      if (request->hasParam("TRACKER_static_mode_azimuth")) {
        if ((request->getParam("TRACKER_static_mode_azimuth")->value().toInt()>=0) && (request->getParam("TRACKER_static_mode_azimuth")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_static_mode_azimuth_addr, request->getParam("TRACKER_static_mode_azimuth")->value().toInt());
          TRACKER_static_mode_azimuth = EEPROM.read(EEPROM_TRACKER_static_mode_azimuth_addr);
        }
      }
      if (request->hasParam("TRACKER_static_mode_elevation")) {
        if ((request->getParam("TRACKER_static_mode_elevation")->value().toInt()>=0) && (request->getParam("TRACKER_static_mode_elevation")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_static_mode_elevation_addr, request->getParam("TRACKER_static_mode_elevation")->value().toInt());
          TRACKER_static_mode_elevation = EEPROM.read(EEPROM_TRACKER_static_mode_elevation_addr);
        }
      }
      if (request->hasParam("TRACKER_azimuth_mini")) {
        if ((request->getParam("TRACKER_azimuth_mini")->value().toInt()>=0) && (request->getParam("TRACKER_azimuth_mini")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_azimuth_mini_addr, request->getParam("TRACKER_azimuth_mini")->value().toInt());
          TRACKER_azimuth_mini = EEPROM.read(EEPROM_TRACKER_azimuth_mini_addr);
        }
      }
      if (request->hasParam("TRACKER_azimuth_maxi")) {
        if ((request->getParam("TRACKER_azimuth_maxi")->value().toInt()>=0) && (request->getParam("TRACKER_azimuth_maxi")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_azimuth_maxi_addr, request->getParam("TRACKER_azimuth_maxi")->value().toInt());
          TRACKER_azimuth_maxi = EEPROM.read(EEPROM_TRACKER_azimuth_maxi_addr);
        }
      }      
      if (request->hasParam("TRACKER_azimuth_min_mv_time")) {
        if ((request->getParam("TRACKER_azimuth_min_mv_time")->value().toInt()>=0) && (request->getParam("TRACKER_azimuth_min_mv_time")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_azimuth_min_mv_time_addr, request->getParam("TRACKER_azimuth_min_mv_time")->value().toInt());
          TRACKER_azimuth_min_mv_time = EEPROM.read(EEPROM_TRACKER_azimuth_min_mv_time_addr);
        }
      }
      if (request->hasParam("TRACKER_elevation_min_mv_time")) {
        if ((request->getParam("TRACKER_elevation_min_mv_time")->value().toInt()>=0) && (request->getParam("TRACKER_elevation_min_mv_time")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_elevation_min_mv_time_addr, request->getParam("TRACKER_elevation_min_mv_time")->value().toInt());
          TRACKER_elevation_min_mv_time = EEPROM.read(EEPROM_TRACKER_elevation_min_mv_time_addr);
        }
      }
      if (request->hasParam("TRACKER_ele_max_move_dur")) {
        if ((request->getParam("TRACKER_ele_max_move_dur")->value().toInt()>=0) && (request->getParam("TRACKER_ele_max_move_dur")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_ele_max_move_dur_addr, request->getParam("TRACKER_ele_max_move_dur")->value().toInt());
         TRACKER_ele_max_move_dur = EEPROM.read(EEPROM_TRACKER_ele_max_move_dur_addr);
        }
      }
      if (request->hasParam("TRACKER_elevation_mini")) {
        if ((request->getParam("TRACKER_elevation_mini")->value().toInt()>=0) && (request->getParam("TRACKER_elevation_mini")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_elevation_mini_addr, request->getParam("TRACKER_elevation_mini")->value().toInt());
          TRACKER_elevation_mini = EEPROM.read(EEPROM_TRACKER_elevation_mini_addr);
        }
      }
      if (request->hasParam("TRACKER_elevation_maxi")) {
        if ((request->getParam("TRACKER_elevation_maxi")->value().toInt()>=0) && (request->getParam("TRACKER_elevation_maxi")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_elevation_maxi_addr, request->getParam("TRACKER_elevation_maxi")->value().toInt());
          TRACKER_elevation_maxi = EEPROM.read(EEPROM_TRACKER_elevation_maxi_addr);
        }
      }
      if (request->hasParam("TRACKER_wind_inter_angle")) {
        if ((request->getParam("TRACKER_wind_inter_angle")->value().toInt()>=0) && (request->getParam("TRACKER_wind_inter_angle")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_wind_inter_angle_addr, request->getParam("TRACKER_wind_inter_angle")->value().toInt());
          TRACKER_wind_inter_angle = EEPROM.read(EEPROM_TRACKER_wind_inter_angle_addr);
        }
      }
      if (request->hasParam("TRACKER_wind_limit_time")) {
        if ((request->getParam("TRACKER_wind_limit_time")->value().toInt()>=0) && (request->getParam("TRACKER_wind_limit_time")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_wind_limit_time_addr, request->getParam("TRACKER_wind_limit_time")->value().toInt());
          TRACKER_wind_limit_time = EEPROM.read(EEPROM_TRACKER_wind_limit_time_addr);
        }
      }
      if (request->hasParam("TRACKER_vertical_speed")) {
        if ((request->getParam("TRACKER_vertical_speed")->value().toInt()>=0) && (request->getParam("TRACKER_vertical_speed")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_vertical_speed_addr, request->getParam("TRACKER_vertical_speed")->value().toInt());
          TRACKER_vertical_speed = EEPROM.read(EEPROM_TRACKER_vertical_speed_addr);
        }
      }
      if (request->hasParam("TRACKER_secu_vertical_speed")) {
        if ((request->getParam("TRACKER_secu_vertical_speed")->value().toInt()>=0) && (request->getParam("TRACKER_secu_vertical_speed")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_secu_vertical_speed_addr, request->getParam("TRACKER_secu_vertical_speed")->value().toInt());
          TRACKER_secu_vertical_speed = EEPROM.read(EEPROM_TRACKER_secu_vertical_speed_addr);
        }
      }
      if (request->hasParam("TRACKER_horizontal_speed")) {
        if ((request->getParam("TRACKER_horizontal_speed")->value().toInt()>=0) && (request->getParam("TRACKER_horizontal_speed")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_horizontal_speed_addr, request->getParam("TRACKER_horizontal_speed")->value().toInt());
          TRACKER_horizontal_speed = EEPROM.read(EEPROM_TRACKER_horizontal_speed_addr);
        }
      }
      if (request->hasParam("OPENWEATHER_wind_limit")) {
        if ((request->getParam("OPENWEATHER_wind_limit")->value().toInt()>=0) && (request->getParam("OPENWEATHER_wind_limit")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_OPENWEATHER_wind_limit_addr, request->getParam("OPENWEATHER_wind_limit")->value().toInt());
          OPENWEATHER_wind_limit = EEPROM.read(EEPROM_OPENWEATHER_wind_limit_addr);
        }
      }
      if (request->hasParam("OPENWEATHER_wind_inter_limit")) {
        if ((request->getParam("OPENWEATHER_wind_inter_limit")->value().toInt()>=0) && (request->getParam("OPENWEATHER_wind_inter_limit")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_OPENWEATHER_wind_inter_limit_addr, request->getParam("OPENWEATHER_wind_inter_limit")->value().toInt());
          OPENWEATHER_wind_inter_limit = EEPROM.read(EEPROM_OPENWEATHER_wind_inter_limit_addr);
        }
      }
      if (request->hasParam("OPENWEATHER_wind_smart_coeff")) {
        if ((request->getParam("OPENWEATHER_wind_smart_coeff")->value().toInt()>=0) && (request->getParam("OPENWEATHER_wind_smart_coeff")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_OPENWEATHER_wind_smart_coeff_addr, request->getParam("OPENWEATHER_wind_smart_coeff")->value().toInt());
          OPENWEATHER_wind_smart_coeff = EEPROM.read(EEPROM_OPENWEATHER_wind_smart_coeff_addr);
        }
      }
      if (request->hasParam("ANEMO_wind_limit")) {
        if ((request->getParam("ANEMO_wind_limit")->value().toInt()>=0) && (request->getParam("ANEMO_wind_limit")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_ANEMO_wind_limit_addr, request->getParam("ANEMO_wind_limit")->value().toInt());
          ANEMO_wind_limit = EEPROM.read(EEPROM_ANEMO_wind_limit_addr);
        }
      }
      if (request->hasParam("ANEMO_wind_inter_limit")) {
        if ((request->getParam("ANEMO_wind_inter_limit")->value().toInt()>=0) && (request->getParam("ANEMO_wind_inter_limit")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_ANEMO_wind_inter_limit_addr, request->getParam("ANEMO_wind_inter_limit")->value().toInt());
          ANEMO_wind_inter_limit = EEPROM.read(EEPROM_ANEMO_wind_inter_limit_addr);
        }
      }
      if (request->hasParam("ANEMO_wind_smart_coeff")) {
        if ((request->getParam("ANEMO_wind_smart_coeff")->value().toInt()>=0) && (request->getParam("ANEMO_wind_smart_coeff")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_ANEMO_wind_smart_coeff_addr, request->getParam("ANEMO_wind_smart_coeff")->value().toInt());
          ANEMO_wind_smart_coeff = EEPROM.read(EEPROM_ANEMO_wind_smart_coeff_addr);
        }
      }
      if (request->hasParam("ANEMO_record_time")) {
        if ((request->getParam("ANEMO_record_time")->value().toInt()>=0) && (request->getParam("ANEMO_record_time")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_ANEMO_record_time_addr, request->getParam("ANEMO_record_time")->value().toInt());
          ANEMO_record_time = EEPROM.read(EEPROM_ANEMO_record_time_addr);
        }
      }
      if (request->hasParam("ANEMO_analog_coefficient")) {
        if ((request->getParam("ANEMO_analog_coefficient")->value().toInt()>=0) && (request->getParam("ANEMO_analog_coefficient")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_ANEMO_analog_coefficient_addr, request->getParam("ANEMO_analog_coefficient")->value().toInt());
          ANEMO_analog_coefficient = EEPROM.read(EEPROM_ANEMO_analog_coefficient_addr);
        }
      }
      if (request->hasParam("TRACKER_azi_max_move_dur")) {
        if ((request->getParam("TRACKER_azi_max_move_dur")->value().toInt()>=0) && (request->getParam("TRACKER_azi_max_move_dur")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_azi_max_move_dur_addr, request->getParam("TRACKER_azi_max_move_dur")->value().toInt());
          TRACKER_azi_max_move_dur = EEPROM.read(EEPROM_TRACKER_azi_max_move_dur_addr);
        }
      }
      if (request->hasParam("TRACKER_azi_start_move_dur")) {
        if ((request->getParam("TRACKER_azi_start_move_dur")->value().toInt()>=0) && (request->getParam("TRACKER_azi_start_move_dur")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_azi_start_move_dur_addr, request->getParam("TRACKER_azi_start_move_dur")->value().toInt());
          TRACKER_azi_start_move_dur = EEPROM.read(EEPROM_TRACKER_azi_start_move_dur_addr);
        }
      }
      if (request->hasParam("TRACKER_security_override")) {
        if ((request->getParam("TRACKER_security_override")->value().toInt()>=0) && (request->getParam("TRACKER_security_override")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_TRACKER_security_override_addr, request->getParam("TRACKER_security_override")->value().toInt());
          TRACKER_security_override = EEPROM.read(EEPROM_TRACKER_security_override_addr);
        }
      }
      if (request->hasParam("SUNSENSOR_offset_droite")) {
        if ((request->getParam("SUNSENSOR_offset_droite")->value().toInt()>=0) && (request->getParam("SUNSENSOR_offset_droite")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_SUNSENSOR_offset_droite_addr, request->getParam("SUNSENSOR_offset_droite")->value().toInt()+128);
          SUNSENSOR_offset_droite = EEPROM.read(EEPROM_SUNSENSOR_offset_droite_addr)-128;
        }
      }
      if (request->hasParam("SUNSENSOR_offset_gauche")) {
        if ((request->getParam("SUNSENSOR_offset_gauche")->value().toInt()>=0) && (request->getParam("SUNSENSOR_offset_gauche")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_SUNSENSOR_offset_gauche_addr, request->getParam("SUNSENSOR_offset_gauche")->value().toInt()+128);
          SUNSENSOR_offset_gauche = EEPROM.read(EEPROM_SUNSENSOR_offset_gauche_addr)-128;
        }
      }
      if (request->hasParam("SUNSENSOR_offset_haut")) {
        if ((request->getParam("SUNSENSOR_offset_haut")->value().toInt()>=0) && (request->getParam("SUNSENSOR_offset_haut")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_SUNSENSOR_offset_haut_addr, request->getParam("SUNSENSOR_offset_haut")->value().toInt()+128);
          SUNSENSOR_offset_haut = EEPROM.read(EEPROM_SUNSENSOR_offset_haut_addr)-128;
        }
      }
      if (request->hasParam("SUNSENSOR_offset_bas")) {
        if ((request->getParam("SUNSENSOR_offset_bas")->value().toInt()>=0) && (request->getParam("SUNSENSOR_offset_bas")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_SUNSENSOR_offset_bas_addr, request->getParam("SUNSENSOR_offset_bas")->value().toInt()+128);
          SUNSENSOR_offset_bas = EEPROM.read(EEPROM_SUNSENSOR_offset_bas_addr)-128;
        }
      }
      if (request->hasParam("SUNSENSOR_delta_haut_bas")) {
        if ((request->getParam("SUNSENSOR_delta_haut_bas")->value().toInt()>=0) && (request->getParam("SUNSENSOR_delta_haut_bas")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_SUNSENSOR_delta_haut_bas_addr, request->getParam("SUNSENSOR_delta_haut_bas")->value().toInt());
          SUNSENSOR_delta_haut_bas = EEPROM.read(EEPROM_SUNSENSOR_delta_haut_bas_addr);
        }
      }
      if (request->hasParam("SUNSENSOR_delta_droite_gauche")) {
        if ((request->getParam("SUNSENSOR_delta_droite_gauche")->value().toInt()>=0) && (request->getParam("SUNSENSOR_delta_droite_gauche")->value().toInt()<=255)) {
          EEPROM_update(EEPROM_SUNSENSOR_delta_droite_gauche_addr, request->getParam("SUNSENSOR_delta_droite_gauche")->value().toInt());
          SUNSENSOR_delta_droite_gauche = EEPROM.read(EEPROM_SUNSENSOR_delta_droite_gauche_addr);
        }
      }
      
      //request->send(200, "text/html", "<style>body {background: linear-gradient(#003,#77b5fe,#003);background-attachment:fixed;font-size:150%;text-align:center;width:100%;max-width:1000px;margin:auto;}</style><body><br><center><font color=green>Reglages sauvegardes avec succes</font></center><br><br><center><a href=\"/\">Retour</a></center></body>");
      request->redirect("/param.html");
      
      //Si on a choisi de redémarrer le tracker après sauvegarde des paramètres
      if ((request->hasParam("INTERFACE_restart_on_save")) && (request->getParam("INTERFACE_restart_on_save")->value()=="1")) {
         delay(5000);
         ESP.restart();
      }
    } else {
      request->send(200, "text/html", "<style>body {background: linear-gradient(#003,#77b5fe,#003);background-attachment:fixed;font-size:150%;text-align:center;width:100%;max-width:1000px;margin:auto;}</style><body><br><br><br><center><font color=red>Acces non autorise !</font><br><br></center></body>"); 
    }
  });
  server.onNotFound(notFound);
  server.begin();

  //Initialisation MAJ Arduino via OTA
  Serial.println("OTA - Initialisation OTA");
  ArduinoOTA.setHostname(TRACKER_HOSTNAME);
  ArduinoOTA.setPassword(SECRET_SETUP_PASSWORD);
  ArduinoOTA.begin();  //Mandatory
  ArduinoOTA.onStart([]() {
    Serial.println("OTA - Démarrage");
  });
  ArduinoOTA.onEnd([]() {
    Serial.println("\nEnd");
  });
  ArduinoOTA.onProgress([](unsigned int progress, unsigned int total) {
    Serial.printf("OTA - Progression: %u%%\r", (progress / (total / 100)));
  });
  ArduinoOTA.onError([](ota_error_t error) {
    Serial.printf("Error[%u]: ", error);
    if (error == OTA_AUTH_ERROR) Serial.println("OTA - Authentification échouée");
    else if (error == OTA_BEGIN_ERROR) Serial.println("OTA - Demarrage échoué");
    else if (error == OTA_CONNECT_ERROR) Serial.println("OTA - Connection échouée");
    else if (error == OTA_RECEIVE_ERROR) Serial.println("OTA - Réception échouée");
    else if (error == OTA_END_ERROR) Serial.println("OTA - Finalisation échouée");
  });
  ArduinoOTA.begin();
  Serial.println("OTA - Prêt");
  Serial.print("OTA - Adresse IP : ");
  Serial.println(WiFi.localIP());

  //Initialisation MQTT
  MQTTclient.setServer(mqtt_server, 1883);

  //Se place a l'est en position securite
  Serial.println("L298N - Mise à plat des panneaux");
  L298N_set_to_horizontal_position();
  L298N_set_to_east_position();
  
  //Debug position GPS traqueur
  Serial.println("TRACKER - Position GPS du tracker : ");
  Serial.print("TRACKER - Latitude : ");
  Serial.println(TRACKER_latitude);
  Serial.print("TRACKER - Longitude : ");
  Serial.println(TRACKER_longitude);
  Serial.println();

}
 
void loop() {
   
  Serial.println("************************************************************");
 
  //delay(500);
 
  //Prise en compte OTA
  ArduinoOTA.handle();
  
  //Si le bouton 1 est appuyé rentre dans la fonction de paramétrage
  if (MCP23017_pin_status(MCP23017_button0) == 1) {
    TRACKER_selected_mode=GUI_mode_menu(TRACKER_selected_mode,5);
  }

  //Si on entre en mode configuration
  if (TRACKER_selected_mode == 4){
    GUI_setup_menu(29);
  }
  
  //Si le mode n'existe pas remet à zéro le tracker
  if (TRACKER_selected_mode > 4){
    EEPROM_settings_init_and_read(1);
  }

  //Actualisation date et heure + position soleil
  NTP_set_system_TimeAndDate();
  SolarPosition::setTimeProvider(now);

  //Verifie le vent
  ANEMO_security_check();
  OPENWEATHER_security_check();

  //Calcule l'angle max en fonction du vent
  TRACKER_wind_smart_calc();

  //Si mise en sécurité forcée
  //if ((TRACKER_selected_mode == 0)&&(TRACKER_is_at_east_limit == 0 )){
  if (TRACKER_selected_mode == 0){
    Serial.println("TRACKER - selected_mode : 0 (SecurPosition activé)");
    L298N_set_to_horizontal_position();
    L298N_set_to_east_position(); 
  }
  
  //Si lever de soleil et meteo ok
  if (((ANEMO_security_position != 1)&&(OPENWEATHER_security_position != 1)&&(TRACKER_location.getSolarPosition().elevation>0))||(TRACKER_security_override == 1)) {

    if (TRACKER_selected_mode == 1){
      Serial.println("TRACKER - selected_mode : 1 (SolarPosition activé)");      
      SOLARPOSITION_analyze();
    }
    
    if (TRACKER_selected_mode == 2){
      Serial.println("TRACKER - selected_mode : 2 (SunSensor activé)");
      SUNSENSOR_analyze();
    }

    if (TRACKER_selected_mode == 3){
      Serial.println("TRACKER - selected_mode : 3 (StaticPosition activé)");
      STATICMODE_set();
    }

  //Sinon mise en sécurité du tracker (Plat si nuit ou vent + Est si nuit)
  } else {

    //Met a plat si le tracker n'y est pas
    Serial.println("L298N - Mise à plat des panneaux");
    if (TRACKER_is_at_up_limit==0) {
      L298N_set_to_horizontal_position(); 
    }
    
    //Place à l'est si on n'y est pas déja la nuit uniquement
    if ((TRACKER_is_at_east_limit == 0 )&&(TRACKER_location.getSolarPosition().elevation<0)){
      L298N_set_to_east_position();   
    } else {
      Serial.println("SECURITY - Position de securite atteinte");
      LCD_quick_print("POSITION DE","SECURITE",1,0,0);
    }
  
  }

  //Envoi données MQTT
  MQTT_Publish();
}

//Affiche une chaine sur une ligne du LCD et l'autre sur la deuxième
void LCD_quick_print(String string1, String string2, int blacklight_enable, int display_time, int clear_at_end) {

  //Active le retroeclairage si souhaité
  if (blacklight_enable == 1) {
    lcd.backlight();
  } else {
    lcd.noBacklight();
  }

  //Affiche les informations de chaque ligne
  lcd.clear();
  lcd.setCursor(0,0);
  lcd.print(string1);
  lcd.setCursor(0,1);
  lcd.print(string2);
  
  //Attend le temps souhaité
  delay(display_time);

  //Efface si souhaité
  if (clear_at_end == 1 ) {
    lcd.clear();
  }

}

//Verifie qu'il y a bien number i2c devices de detectées au démarrage du tracker
String I2C_check_devices(int i2c_devices_number) {

  String errorCode = "";
  
  Serial.println("\nI2C - Checking I2C Devices");
  byte error, address;
  int nDevices;
  Serial.println("I2C - Scanning...");
  nDevices = 0;
  for(address = 1; address < 127; address++ ) {
    Wire.beginTransmission(address);
    error = Wire.endTransmission();
    if (error == 0) {
      Serial.print("I2C - Device found at address 0x");
      if (address<16) {
        Serial.print("0");
      }
      Serial.println(address,HEX);
      nDevices++;
    }
    else if (error==4) {
      Serial.print("I2C - Unknow error at address 0x");
      if (address<16) {
        Serial.print("0");
      }
      Serial.println(address,HEX);
    }    
  }
  if (nDevices == 0) {
    Serial.println("I2C - No I2C devices found\n");
    errorCode = "No device";
  }
  if (nDevices == i2c_devices_number) {
    Serial.println("I2C - All devices online\n");
    errorCode = "OK";
  }
  if (nDevices < i2c_devices_number) {
    Serial.println("I2C - Device(s) missing\n");
    errorCode = "Device missing";
  }

  return (errorCode);

}

//Renvoie l'état binaire d'une pin du MCP23017
int MCP23017_pin_status(int pin){

  int pin_binary_status;
  
  MCP23017_pin_state = MCP23017.digitalRead(pin);
  Serial.print("MCP23017 - Etat pin ");
  Serial.print(pin);
  Serial.print(" : ");

  if (MCP23017_pin_state == LOW) {
    pin_binary_status=1;
  } else {
    pin_binary_status=0;
  }

  Serial.print(pin_binary_status);
  Serial.println(""); 

  return (pin_binary_status);

}

//Selection du mode de fonctionnement sans le sauvegarder ou entree en mode parametrage
int GUI_mode_menu(int TRACKER_selected_mode, int max_modes) {

  lcd.clear();
  lcd.setCursor(0,0);
  lcd.print("Select Mode :");
  
  while (MCP23017_pin_status(MCP23017_button1)!=1) {
    
    if (MCP23017_pin_status(MCP23017_button2) == 1) {
      TRACKER_selected_mode = TRACKER_selected_mode+1;
      LCD_blank_line(1);
    }
    if (MCP23017_pin_status(MCP23017_button3) == 1) {
      TRACKER_selected_mode = TRACKER_selected_mode-1;
      LCD_blank_line(1);
    }

    if (TRACKER_selected_mode> max_modes) {
      TRACKER_selected_mode = 0;
    }

    if (TRACKER_selected_mode< 0) {
      TRACKER_selected_mode = max_modes;
    }

    Serial.print("TRACKER - TRACKER_selected_mode : ");
    Serial.print(TRACKER_selected_mode);
    Serial.println("");

    lcd.setCursor(0,1);
    
    if (TRACKER_selected_mode == 0) {  
      lcd.print("SecurPosition");
    }
    if (TRACKER_selected_mode == 1) {  
      lcd.print("SolarPosition");
    }
    if (TRACKER_selected_mode == 2) {  
      lcd.print("SunSensor");
    }
    if (TRACKER_selected_mode == 3) {  
      lcd.print("Static");
    }
    if (TRACKER_selected_mode == 4) {  
      lcd.print("Configuration");
    }
    if (TRACKER_selected_mode == 5) {  
      lcd.print("Reset");
    }

    delay(1000);

  }

  lcd.clear();

  //Si on n'est pas en mode configuration on enregistre
  if (TRACKER_selected_mode < 4) {
    lcd.print("Mode saved");
    
    EEPROM_update(EEPROM_TRACKER_selected_mode_addr, TRACKER_selected_mode);

    Serial.print("TRACKER - Set Default Mode : ");
    Serial.print(TRACKER_selected_mode);
    Serial.println("");
  }
  
  //Si on est sur RESET on réinitialise les réglages en mémoire
  if (TRACKER_selected_mode == 5) { 
    EEPROM_settings_init_and_read(1);
    lcd.print("Reset Done");
  }

  delay(2000);
  lcd.clear();

  return (TRACKER_selected_mode);

}

//Menu de configuration des paramètres du tracker
void GUI_setup_menu(int max_settings) {

  lcd.clear();
  
  int value = 0;
  int pushed = 0;
  int longpushed = 0;
  int delta = 1;

  while (MCP23017_pin_status(MCP23017_button1)!=1) {
    
    //Si on n'a pas appuyé sur le bouton pour sauvegarder le réglage
    if (MCP23017_pin_status(MCP23017_button0) == 1) {
      GUI_selected_setting = GUI_selected_setting+1;
      lcd.clear();
    }

    if (GUI_selected_setting> max_settings) {
      GUI_selected_setting = 0;
    }

    Serial.print("GUI - GUI_selected_setting : ");
    Serial.print(GUI_selected_setting);
    Serial.println("");
    
    //si on n'a pas appuyé de bouton pour augmenter ou diminuer une valeur
    if ((MCP23017_pin_status(MCP23017_button2)==0)&&(MCP23017_pin_status(MCP23017_button3)==0)) {
    
      longpushed=0;

      if (GUI_selected_setting == 0) {
        if (pushed == 1 ) {
            TRACKER_ele_max_move_dur = value;        
        }  
        LCD_quick_print("TR El Max Mov Dura",String(TRACKER_ele_max_move_dur), 1, 0, 0);
        value = TRACKER_ele_max_move_dur;
      }
      if (GUI_selected_setting == 1) {
        if (pushed == 1 ) {
            TRACKER_elevation_mini = value;        
        }  
        LCD_quick_print("TR Elevati Mini",String(TRACKER_elevation_mini), 1, 0, 0);
        value = TRACKER_elevation_mini;
      }
      if (GUI_selected_setting == 2) {
        if (pushed == 1 ) {
            TRACKER_elevation_maxi = value;        
        }  
        LCD_quick_print("TR Elevati Maxi",String(TRACKER_elevation_maxi), 1, 0, 0);
        value = TRACKER_elevation_maxi;
      }
      if (GUI_selected_setting == 3) {
        if (pushed == 1 ) {
            TRACKER_elevation_min_mv_time = value;        
        }  
        LCD_quick_print("TR Ele MinMov Dur",String(TRACKER_elevation_min_mv_time), 1, 0, 0);
        value = TRACKER_elevation_min_mv_time;
      }
      if (GUI_selected_setting == 4) {
        if (pushed == 1 ) {
            TRACKER_wind_inter_angle = value;        
        }  
        LCD_quick_print("TR Wind Int Angl",String(TRACKER_wind_inter_angle), 1, 0, 0);
        value = TRACKER_wind_inter_angle;
      }
      if (GUI_selected_setting == 5) {
        if (pushed == 1 ) {
            TRACKER_wind_limit_time = value;        
        }  
        LCD_quick_print("TR Wind Lim Time",String(TRACKER_wind_limit_time), 1, 0, 0);
        value = TRACKER_wind_limit_time;
      }
      if (GUI_selected_setting == 6) {
        if (pushed == 1 ) {
            TRACKER_vertical_speed = value;        
        }  
        LCD_quick_print("TR Vertical Speed",String(TRACKER_vertical_speed), 1, 0, 0);
        value = TRACKER_vertical_speed;
      }
      if (GUI_selected_setting == 7) {
        if (pushed == 1 ) {
            TRACKER_horizontal_speed = value;        
        }  
        LCD_quick_print("TR Horizon Speed",String(TRACKER_horizontal_speed), 1, 0, 0);
        value = TRACKER_horizontal_speed;
      }
      if (GUI_selected_setting == 8) {
        if (pushed == 1 ) {
            OPENWEATHER_wind_limit = value;        
        }  
        LCD_quick_print("OW Wind Limit",String(OPENWEATHER_wind_limit), 1, 0, 0);
        value = OPENWEATHER_wind_limit;
      }
      if (GUI_selected_setting == 9) {
        if (pushed == 1 ) {
            OPENWEATHER_wind_inter_limit = value;        
        }  
        LCD_quick_print("OW Wind IntLimit",String(OPENWEATHER_wind_inter_limit), 1, 0, 0);
        value = OPENWEATHER_wind_inter_limit;
      }
      if (GUI_selected_setting == 10) {
        if (pushed == 1 ) {
            OPENWEATHER_wind_smart_coeff = value;        
        }  
        LCD_quick_print("OW Wind SmarCoef",String(OPENWEATHER_wind_smart_coeff), 1, 0, 0);
        value = OPENWEATHER_wind_smart_coeff;
      }
      if (GUI_selected_setting == 11) {
        if (pushed == 1 ) {
            ANEMO_wind_limit = value;        
        }  
        LCD_quick_print("AM Wind Limit",String(ANEMO_wind_limit), 1, 0, 0);
        value = ANEMO_wind_limit;
      }
      
      if (GUI_selected_setting == 12) {
        if (pushed == 1 ) {
            ANEMO_wind_inter_limit = value;        
        }  
        LCD_quick_print("AM Wind IntLimit",String(ANEMO_wind_inter_limit), 1, 0, 0);
        value = ANEMO_wind_inter_limit;
      }
      if (GUI_selected_setting == 13) {
        if (pushed == 1 ) {
            ANEMO_wind_smart_coeff = value;        
        }  
        LCD_quick_print("AM Wind SmarCoef",String(ANEMO_wind_smart_coeff), 1, 0, 0);
        value = ANEMO_wind_smart_coeff;
      }
      if (GUI_selected_setting == 14) {
        if (pushed == 1 ) {
            ANEMO_record_time = value;        
        }  
        LCD_quick_print("AM Reco Time",String(ANEMO_record_time), 1, 0, 0);
        value = ANEMO_record_time;
      }
      if (GUI_selected_setting == 15) {
        if (pushed == 1 ) {
            TRACKER_azi_max_move_dur = value;        
        }  
        LCD_quick_print("TR Az Max Mov Dura",String(TRACKER_azi_max_move_dur), 1, 0, 0);
        value = TRACKER_azi_max_move_dur;
      }
      if (GUI_selected_setting == 16) {
        if (pushed == 1 ) {
            TRACKER_azi_start_move_dur = value;        
        }  
        LCD_quick_print("TR Az Str Mov Dura",String(TRACKER_azi_start_move_dur), 1, 0, 0);
        value = TRACKER_azi_start_move_dur;
      }
      if (GUI_selected_setting == 17) {
        if (pushed == 1 ) {
            TRACKER_static_mode_azimuth = value;        
        }  
        LCD_quick_print("TR Sta Mod Azimut",String(TRACKER_static_mode_azimuth), 1, 0, 0);
        value = TRACKER_static_mode_azimuth;
      }
      if (GUI_selected_setting == 18) {
        if (pushed == 1 ) {
            TRACKER_static_mode_elevation = value;        
        }  
        LCD_quick_print("TR Sta Mod Elevat",String(TRACKER_static_mode_elevation), 1, 0, 0);
        value = TRACKER_static_mode_elevation;
      }
      if (GUI_selected_setting == 19) {
        if (pushed == 1 ) {
            TRACKER_azimuth_mini = value;        
        }  
        LCD_quick_print("TR Azimut Mini",String(TRACKER_azimuth_mini), 1, 0, 0);
        value = TRACKER_azimuth_mini;
      }
      if (GUI_selected_setting == 20) {
        if (pushed == 1 ) {
            TRACKER_azimuth_maxi = value;        
        }  
        LCD_quick_print("TR Azimut Maxi",String(TRACKER_azimuth_maxi), 1, 0, 0);
        value = TRACKER_azimuth_maxi;
      }
      if (GUI_selected_setting == 21) {
        if (pushed == 1 ) {
            TRACKER_azimuth_min_mv_time = value;        
        }  
        LCD_quick_print("TR Azi MinMov Dur",String(TRACKER_azimuth_min_mv_time), 1, 0, 0);
        value = TRACKER_azimuth_min_mv_time;
      }
      if (GUI_selected_setting == 22) {
        if (pushed == 1 ) {
            TRACKER_security_override = value;        
        }  
        LCD_quick_print("TR Secur Override",String(TRACKER_security_override), 1, 0, 0);
        value = TRACKER_security_override;
      }
      if (GUI_selected_setting == 23) {  
        if (pushed == 1 ) {
            SUNSENSOR_delta_haut_bas = value;        
        }
        LCD_quick_print("SSensor V Delta",String(SUNSENSOR_delta_haut_bas), 1, 0, 0);
        value = SUNSENSOR_delta_haut_bas;
      }
      if (GUI_selected_setting == 24) {
        if (pushed == 1 ) {
            SUNSENSOR_delta_droite_gauche = value;        
        }  
        LCD_quick_print("SSensor H Delta",String(SUNSENSOR_delta_droite_gauche), 1, 0, 0);
        value = SUNSENSOR_delta_droite_gauche;
      }
      if (GUI_selected_setting == 25) {  
        if (pushed == 1 ) {
            SUNSENSOR_offset_haut = value;        
        }
        LCD_quick_print("SSensor H Offset",String(SUNSENSOR_offset_haut), 1, 0, 0);
        value = SUNSENSOR_offset_haut;
      }
      if (GUI_selected_setting == 26) {
        if (pushed == 1 ) {
            SUNSENSOR_offset_bas = value;        
        }
        LCD_quick_print("SSensor D Offset",String(SUNSENSOR_offset_bas), 1, 0, 0);
        value = SUNSENSOR_offset_bas;  
      }
      if (GUI_selected_setting == 27) {
        if (pushed == 1 ) {
            SUNSENSOR_offset_droite = value;        
        }
        LCD_quick_print("SSensor R Offset",String(SUNSENSOR_offset_droite), 1, 0, 0);
        value = SUNSENSOR_offset_droite;  
      }
      if (GUI_selected_setting == 28) {
        if (pushed == 1 ) {
            SUNSENSOR_offset_gauche = value;        
        }  
        LCD_quick_print("SSensor L Offset",String(SUNSENSOR_offset_gauche), 1, 0, 0);
        value = SUNSENSOR_offset_gauche;
      }       
      if (GUI_selected_setting == 29) {
        LCD_quick_print("Exit","Configuration", 1, 0, 0);
        //Change le mode du tracker en le remettant sur le mode sélectionné par défaut
        TRACKER_selected_mode = EEPROM.read(EEPROM_TRACKER_selected_mode_addr);
      }

      //Remet pushed à 0
      if (pushed == 1 ) {
            pushed = 0;        
      }

    } else {

        //detecte un appui long pour incrémenter ou baisser plus rapidement
        longpushed = longpushed + 1;
        if (longpushed >5) {
          delta = 5;
        } 
        if (longpushed >8) {
          delta = 10;
        }
        if (longpushed <5) {
          delta = 1;
        }

        //Modifie la valeur de + ou - delta
        if (MCP23017_pin_status(MCP23017_button2) == 1) {
          value = value+delta;
        }

        if (MCP23017_pin_status(MCP23017_button3) == 1) {
          value = value-delta;
        }

        //Evite que la valeur ne soit pas pertinente en fonction du reglage choisi
        if ((GUI_selected_setting != 22)&&( GUI_selected_setting != 25)&&( GUI_selected_setting != 26)&&( GUI_selected_setting != 27)&&( GUI_selected_setting != 28)) {
          if (value<0) {
            value = 0;
          }
          if (value>255) {
            value = 255;
          }
        }
        if ( GUI_selected_setting == 22) {
          if (value<0) {
            value = 0;
          }
          if (value>3) {
            value = 3;
          }
        }
       if (GUI_selected_setting == 25 || GUI_selected_setting == 26 || GUI_selected_setting == 27 || GUI_selected_setting == 28) {
          if (value<-128) {
            value = -128;
          }
          if (value>128) {
            value = 128;
          }
        }

        //Met la variable pushed à 1 pour modifier la valeur affichée
        pushed = 1;

        //Efface la ligne contenant l'ancienne valeur
        LCD_blank_line(1);

        //Affiche la nouvelle valeur
        lcd.setCursor(0,1);
        lcd.print(value);

        Serial.print("GUI - Value : ");
        Serial.print(value);
        Serial.println(""); 

    }
    
    delay(1000);

  } 
   
  //Si on a appuyé sur le bouton pour sauvegarder
  if (GUI_selected_setting == 0) {
    EEPROM_update(EEPROM_TRACKER_ele_max_move_dur_addr, value);
  }
  if (GUI_selected_setting == 1) {
    EEPROM_update(EEPROM_TRACKER_elevation_mini_addr, value);
  }
  if (GUI_selected_setting == 2) {
    EEPROM_update(EEPROM_TRACKER_elevation_maxi_addr, value);
  }
  if (GUI_selected_setting == 3) {
    EEPROM_update(EEPROM_TRACKER_elevation_min_mv_time_addr, value);
  }
  if (GUI_selected_setting == 4) {
    EEPROM_update(EEPROM_TRACKER_wind_inter_angle_addr, value);
  }
  if (GUI_selected_setting == 5) {
    EEPROM_update(EEPROM_TRACKER_wind_limit_time_addr, value);
  }
  if (GUI_selected_setting == 6) {
    EEPROM_update(EEPROM_TRACKER_vertical_speed_addr, value);
  }
  if (GUI_selected_setting == 7) {
    EEPROM_update(EEPROM_TRACKER_horizontal_speed_addr, value);
  }
  if (GUI_selected_setting == 8) {
    EEPROM_update(EEPROM_OPENWEATHER_wind_limit_addr, value);
  }
  if (GUI_selected_setting == 9) {
    EEPROM_update(EEPROM_OPENWEATHER_wind_inter_limit_addr, value);
  }
  if (GUI_selected_setting == 10) {
    EEPROM_update(EEPROM_OPENWEATHER_wind_smart_coeff_addr, value);
  }  
  if (GUI_selected_setting == 11) {
    EEPROM_update(EEPROM_ANEMO_wind_limit_addr, value);
  }
  if (GUI_selected_setting == 12) {
    EEPROM_update(EEPROM_ANEMO_wind_inter_limit_addr, value);
  }
  if (GUI_selected_setting == 13) {
    EEPROM_update(EEPROM_ANEMO_wind_smart_coeff_addr, value);
  }
  if (GUI_selected_setting == 14) {
    EEPROM_update(EEPROM_ANEMO_record_time_addr, value);
  }
  if (GUI_selected_setting == 15) {
    EEPROM_update(EEPROM_TRACKER_azi_max_move_dur_addr, value);
  }
  if (GUI_selected_setting == 16) {
    EEPROM_update(EEPROM_TRACKER_azi_start_move_dur_addr, value);
  }
  if (GUI_selected_setting == 17) {
    EEPROM_update(EEPROM_TRACKER_static_mode_azimuth_addr, value);
  }
  if (GUI_selected_setting == 18) {
    EEPROM_update(EEPROM_TRACKER_static_mode_elevation_addr, value);
  }
  if (GUI_selected_setting == 19) {
    EEPROM_update(EEPROM_TRACKER_azimuth_mini_addr, value);
  }
  if (GUI_selected_setting == 20) {
    EEPROM_update(EEPROM_TRACKER_azimuth_maxi_addr, value);
  }
  if (GUI_selected_setting == 21) {
    EEPROM_update(EEPROM_TRACKER_azimuth_min_mv_time_addr, value);
  }
  if (GUI_selected_setting == 22) {
    EEPROM_update(EEPROM_TRACKER_security_override_addr, value);
  }
   if (GUI_selected_setting == 23) {  
    EEPROM_update(EEPROM_SUNSENSOR_delta_haut_bas_addr, value);
  }
  if (GUI_selected_setting == 24) {
    EEPROM_update(EEPROM_SUNSENSOR_delta_droite_gauche_addr, value);
  }
  if (GUI_selected_setting == 25) {  
    EEPROM_update(EEPROM_SUNSENSOR_offset_haut_addr, value+128);
  }
  if (GUI_selected_setting == 26) {  
    EEPROM_update(EEPROM_SUNSENSOR_offset_bas_addr, value+128);
  }
  if (GUI_selected_setting == 27) {  
    EEPROM_update(EEPROM_SUNSENSOR_offset_droite_addr, value+128);
  }
  if (GUI_selected_setting == 28) {  
    EEPROM_update(EEPROM_SUNSENSOR_offset_gauche_addr, value+128);
  }
  
  if (GUI_selected_setting != 29) {
    lcd.clear();
    lcd.print("Setting saved");
  }
  
  delay(2000);
  lcd.clear();

}

//Efface la ligne souhaitée
void LCD_blank_line(int line)
{
  lcd.setCursor(0,line);
  lcd.print("                ");
}


//Initialise les variables dans l'eeprom si ce n'est pas fait et définit les variables qui y sont stockées
void EEPROM_settings_init_and_read(int reset){
  
  //Verifie le contenu de la mémoire, l'initialise si besoin
  EEPROM_check(EEPROM_TRACKER_selected_mode_addr,0);
  EEPROM_check(EEPROM_TRACKER_anemometer_model_addr,0);
  EEPROM_check(EEPROM_TRACKER_ele_max_move_dur_addr,60);
  EEPROM_check(EEPROM_TRACKER_elevation_mini_addr,0);
  EEPROM_check(EEPROM_TRACKER_elevation_maxi_addr,52);
  EEPROM_check(EEPROM_TRACKER_elevation_min_mv_time_addr,1);
  EEPROM_check(EEPROM_TRACKER_wind_inter_angle_addr,30);
  EEPROM_check(EEPROM_TRACKER_wind_limit_time_addr,15);
  EEPROM_check(EEPROM_TRACKER_vertical_speed_addr,100);
  EEPROM_check(EEPROM_TRACKER_secu_vertical_speed_addr,100);
  EEPROM_check(EEPROM_TRACKER_horizontal_speed_addr,100);
  EEPROM_check(EEPROM_OPENWEATHER_wind_limit_addr,8);
  EEPROM_check(EEPROM_OPENWEATHER_wind_inter_limit_addr,20);
  EEPROM_check(EEPROM_OPENWEATHER_wind_smart_coeff_addr,150);
  EEPROM_check(EEPROM_ANEMO_wind_limit_addr,8);
  EEPROM_check(EEPROM_ANEMO_wind_inter_limit_addr,20);
  EEPROM_check(EEPROM_ANEMO_wind_smart_coeff_addr,175);
  EEPROM_check(EEPROM_ANEMO_record_time_addr,15);
  EEPROM_check(EEPROM_ANEMO_analog_coefficient_addr,0);
  EEPROM_check(EEPROM_TRACKER_azi_max_move_dur_addr,60);
  EEPROM_check(EEPROM_TRACKER_azi_start_move_dur_addr,50);
  EEPROM_check(EEPROM_TRACKER_static_mode_azimuth_addr,90);
  EEPROM_check(EEPROM_TRACKER_static_mode_elevation_addr,30);
  EEPROM_check(EEPROM_TRACKER_azimuth_mini_addr,90);
  EEPROM_check(EEPROM_TRACKER_azimuth_maxi_addr,190);
  EEPROM_check(EEPROM_TRACKER_azimuth_min_mv_time_addr,1);
  EEPROM_check(EEPROM_TRACKER_security_override_addr,0);
  EEPROM_check(EEPROM_SUNSENSOR_offset_droite_addr,128);
  EEPROM_check(EEPROM_SUNSENSOR_offset_gauche_addr,128);
  EEPROM_check(EEPROM_SUNSENSOR_offset_haut_addr,128);
  EEPROM_check(EEPROM_SUNSENSOR_offset_bas_addr,128);
  EEPROM_check(EEPROM_SUNSENSOR_delta_haut_bas_addr,0);
  EEPROM_check(EEPROM_SUNSENSOR_delta_droite_gauche_addr,0);
     
  if (reset == 1) {
    EEPROM_update(EEPROM_TRACKER_selected_mode_addr,0);
    EEPROM_update(EEPROM_TRACKER_anemometer_model_addr,0);
    EEPROM_update(EEPROM_TRACKER_ele_max_move_dur_addr,60);
    EEPROM_update(EEPROM_TRACKER_elevation_mini_addr,0);
    EEPROM_update(EEPROM_TRACKER_elevation_maxi_addr,52);
    EEPROM_update(EEPROM_TRACKER_elevation_min_mv_time_addr,1);
    EEPROM_update(EEPROM_TRACKER_wind_inter_angle_addr,30);
    EEPROM_update(EEPROM_TRACKER_wind_limit_time_addr,15);
    EEPROM_update(EEPROM_TRACKER_vertical_speed_addr,100);
    EEPROM_update(EEPROM_TRACKER_secu_vertical_speed_addr,100);
    EEPROM_update(EEPROM_TRACKER_horizontal_speed_addr,100);
    EEPROM_update(EEPROM_ANEMO_wind_limit_addr,8);
    EEPROM_update(EEPROM_ANEMO_wind_inter_limit_addr,20);
    EEPROM_update(EEPROM_ANEMO_wind_smart_coeff_addr,175);
    EEPROM_update(EEPROM_ANEMO_record_time_addr,15);
    EEPROM_update(EEPROM_ANEMO_analog_coefficient_addr,50);
    EEPROM_update(EEPROM_OPENWEATHER_wind_limit_addr,8);
    EEPROM_update(EEPROM_OPENWEATHER_wind_inter_limit_addr,20);
    EEPROM_update(EEPROM_OPENWEATHER_wind_smart_coeff_addr,150);
    EEPROM_update(EEPROM_TRACKER_azi_max_move_dur_addr,60);
    EEPROM_update(EEPROM_TRACKER_azi_start_move_dur_addr,50);
    EEPROM_update(EEPROM_TRACKER_static_mode_azimuth_addr,90);
    EEPROM_update(EEPROM_TRACKER_static_mode_elevation_addr,30);
    EEPROM_update(EEPROM_TRACKER_azimuth_mini_addr,90);
    EEPROM_update(EEPROM_TRACKER_azimuth_maxi_addr,190);
    EEPROM_update(EEPROM_TRACKER_azimuth_min_mv_time_addr,1);
    EEPROM_update(EEPROM_TRACKER_security_override_addr,0);
    EEPROM_update(EEPROM_SUNSENSOR_offset_droite_addr,128);
    EEPROM_update(EEPROM_SUNSENSOR_offset_gauche_addr,128);
    EEPROM_update(EEPROM_SUNSENSOR_offset_haut_addr,128);
    EEPROM_update(EEPROM_SUNSENSOR_offset_bas_addr,128);
    EEPROM_update(EEPROM_SUNSENSOR_delta_haut_bas_addr,50);
    EEPROM_update(EEPROM_SUNSENSOR_delta_droite_gauche_addr,50);
  }

  //recupère le contenu des variables globales de réglages depuis l'EEPROM
  TRACKER_selected_mode = EEPROM.read(EEPROM_TRACKER_selected_mode_addr);
  TRACKER_anemometer_model = EEPROM.read(EEPROM_TRACKER_anemometer_model_addr);
  TRACKER_ele_max_move_dur = EEPROM.read(EEPROM_TRACKER_ele_max_move_dur_addr);
  TRACKER_elevation_mini = EEPROM.read(EEPROM_TRACKER_elevation_mini_addr);
  TRACKER_elevation_maxi = EEPROM.read(EEPROM_TRACKER_elevation_maxi_addr);
  TRACKER_elevation_min_mv_time = EEPROM.read(EEPROM_TRACKER_elevation_min_mv_time_addr);
  TRACKER_wind_inter_angle = EEPROM.read(EEPROM_TRACKER_wind_inter_angle_addr);
  TRACKER_wind_limit_time = EEPROM.read(EEPROM_TRACKER_wind_limit_time_addr);
  TRACKER_vertical_speed = EEPROM.read(EEPROM_TRACKER_vertical_speed_addr);
  TRACKER_secu_vertical_speed = EEPROM.read(EEPROM_TRACKER_secu_vertical_speed_addr);
  TRACKER_horizontal_speed = EEPROM.read(EEPROM_TRACKER_horizontal_speed_addr);
  ANEMO_wind_limit = EEPROM.read(EEPROM_ANEMO_wind_limit_addr);
  ANEMO_wind_inter_limit = EEPROM.read(EEPROM_ANEMO_wind_inter_limit_addr);
  ANEMO_wind_smart_coeff = EEPROM.read(EEPROM_ANEMO_wind_smart_coeff_addr);
  ANEMO_record_time = EEPROM.read(EEPROM_ANEMO_record_time_addr);
  ANEMO_analog_coefficient = EEPROM.read(EEPROM_ANEMO_analog_coefficient_addr);
  OPENWEATHER_wind_limit = EEPROM.read(EEPROM_OPENWEATHER_wind_limit_addr);
  OPENWEATHER_wind_inter_limit = EEPROM.read(EEPROM_OPENWEATHER_wind_inter_limit_addr);
  OPENWEATHER_wind_smart_coeff = EEPROM.read(EEPROM_OPENWEATHER_wind_smart_coeff_addr);
  TRACKER_azi_max_move_dur = EEPROM.read(EEPROM_TRACKER_azi_max_move_dur_addr);
  TRACKER_azi_start_move_dur = EEPROM.read(EEPROM_TRACKER_azi_start_move_dur_addr);
  TRACKER_static_mode_azimuth = EEPROM.read(EEPROM_TRACKER_static_mode_azimuth_addr);
  TRACKER_static_mode_elevation = EEPROM.read(EEPROM_TRACKER_static_mode_elevation_addr);
  TRACKER_azimuth_mini = EEPROM.read(EEPROM_TRACKER_azimuth_mini_addr);
  TRACKER_azimuth_maxi = EEPROM.read(EEPROM_TRACKER_azimuth_maxi_addr);
  TRACKER_azimuth_min_mv_time = EEPROM.read(EEPROM_TRACKER_azimuth_min_mv_time_addr);
  TRACKER_security_override = EEPROM.read(EEPROM_TRACKER_security_override_addr);
  SUNSENSOR_offset_droite = EEPROM.read(EEPROM_SUNSENSOR_offset_droite_addr)-128;
  SUNSENSOR_offset_gauche = EEPROM.read(EEPROM_SUNSENSOR_offset_gauche_addr)-128;
  SUNSENSOR_offset_haut = EEPROM.read(EEPROM_SUNSENSOR_offset_haut_addr)-128;
  SUNSENSOR_offset_bas = EEPROM.read(EEPROM_SUNSENSOR_offset_bas_addr)-128;
  SUNSENSOR_delta_haut_bas = EEPROM.read(EEPROM_SUNSENSOR_delta_haut_bas_addr);
  SUNSENSOR_delta_droite_gauche = EEPROM.read(EEPROM_SUNSENSOR_delta_droite_gauche_addr);

  //Envoie dans l'EEPROM
  EEPROM.commit();
  EEPROM.end();
  EEPROM.begin(EEPROM_SIZE);

  //Debug
  Serial.println("EEPROM - Recupération des réglages depuis l'EEPROM");
  Serial.print("EEPROM - Mode selectionné : ");
  Serial.println(TRACKER_selected_mode);
  Serial.print("EEPROM - TRACKER_anemometer_model : ");
  Serial.println(TRACKER_anemometer_model);
  Serial.print("EEPROM - TRACKER_ele_max_move_dur : ");
  Serial.println(TRACKER_ele_max_move_dur);
  Serial.print("EEPROM - TRACKER_elevation_mini : ");
  Serial.println(TRACKER_elevation_mini);
  Serial.print("EEPROM - TRACKER_elevation_maxi : ");
  Serial.println(TRACKER_elevation_maxi);
  Serial.print("EEPROM - TRACKER_elevation_min_mv_time : ");
  Serial.println(TRACKER_elevation_min_mv_time);
  Serial.print("EEPROM - TRACKER_wind_inter_angle : ");
  Serial.println(TRACKER_wind_inter_angle);
  Serial.print("EEPROM - TRACKER_wind_limit_time : ");
  Serial.println(TRACKER_wind_limit_time);
  Serial.print("EEPROM - TRACKER_vertical_speed : ");
  Serial.println(TRACKER_vertical_speed);
  Serial.print("EEPROM - TRACKER_secu_vertical_speed : ");
  Serial.println(TRACKER_secu_vertical_speed);
  Serial.print("EEPROM - TRACKER_horizontal_speed : ");
  Serial.println(TRACKER_horizontal_speed);
  Serial.print("EEPROM - OPENWEATHER_wind_limit : ");
  Serial.println(OPENWEATHER_wind_limit);
  Serial.print("EEPROM - OPENWEATHER_wind_inter_limit : ");
  Serial.println(OPENWEATHER_wind_inter_limit);
  Serial.print("EEPROM - OPENWEATHER_wind_smart_coeff : ");
  Serial.println(OPENWEATHER_wind_smart_coeff);
  Serial.print("EEPROM - ANEMO_wind_limit : ");
  Serial.println(ANEMO_wind_limit);
  Serial.print("EEPROM - ANEMO_wind_inter_limit : ");
  Serial.println(ANEMO_wind_inter_limit);
  Serial.print("EEPROM - ANEMO_wind_smart_coeff : ");
  Serial.println(ANEMO_wind_smart_coeff);
  Serial.print("EEPROM - ANEMO_record_time: ");
  Serial.println(ANEMO_record_time);
  Serial.print("EEPROM - ANEMO_analog_coefficient: ");
  Serial.println(ANEMO_analog_coefficient);
  Serial.print("EEPROM - TRACKER_azi_max_move_dur: ");
  Serial.println(TRACKER_azi_max_move_dur);
  Serial.print("EEPROM - TRACKER_azi_start_move_dur: ");
  Serial.println(TRACKER_azi_start_move_dur);
  Serial.print("EEPROM - TRACKER_static_mode_azimuth: ");
  Serial.println(TRACKER_static_mode_azimuth);
  Serial.print("EEPROM - TRACKER_static_mode_elevation: ");
  Serial.println(TRACKER_static_mode_elevation);
  Serial.print("EEPROM - TRACKER_azimuth_mini: ");
  Serial.println(TRACKER_azimuth_mini);
  Serial.print("EEPROM - TRACKER_azimuth_maxi: ");
  Serial.println(TRACKER_azimuth_maxi);
  Serial.print("EEPROM - TRACKER_azimuth_min_mv_time: ");
  Serial.println(TRACKER_azimuth_min_mv_time);
  Serial.print("EEPROM - TRACKER_security_override: ");
  Serial.println(TRACKER_security_override);
  Serial.print("EEPROM - SUNSENSOR_offset_droite : ");
  Serial.println(SUNSENSOR_offset_droite);
  Serial.print("EEPROM - SUNSENSOR_offset_gauche : ");
  Serial.println(SUNSENSOR_offset_gauche);
  Serial.print("EEPROM - SUNSENSOR_offset_haut : ");
  Serial.println(SUNSENSOR_offset_haut);
  Serial.print("EEPROM - SUNSENSOR_offset_bas : ");
  Serial.println(SUNSENSOR_offset_bas);
  Serial.print("EEPROM - SUNSENSOR_delta_haut_bas : ");
  Serial.println(SUNSENSOR_delta_haut_bas);
  Serial.print("EEPROM - SUNSENSOR_delta_droite_gauche : ");
  Serial.println(SUNSENSOR_delta_droite_gauche);

}

//Fonction qui verifie l'existence d'un enregistrement dans la mémoire et l'initialise si cela n'a jamais été fait
void EEPROM_check(int eeprom_addr,int default_value) {

  int check;
  
  //Verifie le contenu de la mémoire concernant le mode de fonctionnement du tracker
  check = EEPROM.read(eeprom_addr);

  //Si rien dans la mémoire on enregistre la valeur par défaut
  if (isnan(check)){
    Serial.print("EEPROM - Enregistrement de la valeur par défaut "); 
    Serial.print(default_value);
    Serial.print(" à l'adresse ");
    Serial.print(eeprom_addr);
    Serial.println("");
    EEPROM_update(eeprom_addr,default_value);
  }

}

//Fonction qui met à jour une valeur de la mémoire si besoin
void EEPROM_update(int eeprom_addr,int new_value) {

  //Si la valeur a changé
  if(new_value!=EEPROM.read(eeprom_addr)){  
    
    Serial.print("EEPROM - Enregistrement de la valeur "); 
    Serial.print(new_value);
    Serial.print(" à l'adresse ");
    Serial.print(eeprom_addr);
    Serial.println("");

    EEPROM.write(eeprom_addr,new_value);
    EEPROM.commit();
    EEPROM.end();
    EEPROM.begin(EEPROM_SIZE);

  //Sinon
  } else {

    Serial.print("EEPROM - Valeur déjà égale à "); 
    Serial.print(new_value);
    Serial.print(" à l'adresse ");
    Serial.print(eeprom_addr);
    Serial.println("");

  }

}

//Mise à l'heure du système via NTP
void NTP_set_system_TimeAndDate() {

  //Met a jour la date et l'heure avec le serveur NTP
  Serial.println("NTP - Vérification de la date et de l'heure : ");
  timeClient.update();
  unsigned long epochTime = timeClient.getEpochTime();
  Serial.print("NTP - Epoch : ");
  Serial.println(epochTime);
     
  //Met en forme
  char buff[32];
  sprintf(buff, "%02d.%02d.%02d %02d:%02d:%02d", day(epochTime), month(epochTime), year(epochTime), hour(epochTime), minute(epochTime), second(epochTime));
  Serial.print("NTP - Datetime : ");
  Serial.println(buff);
  
  //Affiche l'heure actuelle de l'ESP
  Serial.print("ESP - Epoch Systeme : ");
  Serial.println(now());
  
  //Met l'ESP à l'heure si il y a lieu
  if (now()-epochTime > 120 || now()-epochTime < -120 && epochTime>1660032686) {
    Serial.println("ESP - Correction de l'heure système via la source NTP");
    setTime(hour(epochTime), minute(epochTime), second(epochTime), day(epochTime), month(epochTime), year(epochTime));
  }
  
}

//Fonction pour récupérer l'angle vertical du tracker
double MPU6050_get_elevation() {

  Wire.beginTransmission(MPU6050_addr);
  Wire.write(0x3B);
  Wire.endTransmission(false);
  Wire.requestFrom(MPU6050_addr,14,true);
  MPU6050_AcX=Wire.read()<<8|Wire.read();
  MPU6050_AcY=Wire.read()<<8|Wire.read();
  MPU6050_AcZ=Wire.read()<<8|Wire.read();
  int MPU6050_xAng = map(MPU6050_AcX,MPU6050_minVal,MPU6050_maxVal,-90,90);
  int MPU6050_yAng = map(MPU6050_AcY,MPU6050_minVal,MPU6050_maxVal,-90,90);
  int MPU6050_zAng = map(MPU6050_AcZ,MPU6050_minVal,MPU6050_maxVal,-90,90);

  MPU6050_x= RAD_TO_DEG * (atan2(-MPU6050_yAng, -MPU6050_zAng)+PI);
  MPU6050_y= RAD_TO_DEG * (atan2(-MPU6050_xAng, -MPU6050_zAng)+PI);
  MPU6050_z= RAD_TO_DEG * (atan2(-MPU6050_yAng, -MPU6050_xAng)+PI);

  //Debug Serie
  //Serial.print("GY-521 MPU-6050 - AngleX : ");
  //Serial.println(MPU6050_x);
  //Serial.print("GY-521 MPU-6050 - AngleZ : ");
  //Serial.println(MPU6050_z);

  //Calcule l'angle des panneaux
  if (MPU6050_y <= 270) {
    MPU6050_y = MPU6050_y + 360;
  }
  MPU6050_y = MPU6050_y - 270;

  //Si en dehors de la plage de mesure on considère 0
  if ((MPU6050_y >= 90) && (MPU6050_y <= 360)) {
    MPU6050_y = 0;  
  }
  Serial.print("GY-521 MPU-6050 - Angle Tracker : ");
  Serial.println(MPU6050_y);
 
  //Renvoie la valeur de l'angle qui nous intéresse selon le placement du capteur
  return(round(MPU6050_y));

}

//Fonction pour corriger l'angle vertical du tracker en lisant l'angle du capteur
void MPU6050_correct_elevation(double required_elevation) {
  
  //Pause avant lecture
  delay(5);

  //Elevation réelle du traqueur - Moyenne 10 lectures 
  float MPU6050_AverageAngle = 0;
  int MPU6050_NBMeasurements = 3;
  for(int i = 0; i < MPU6050_NBMeasurements; ++i)
  {
    MPU6050_AverageAngle += MPU6050_get_elevation();
    delay(1);
  }
  MPU6050_AverageAngle /= MPU6050_NBMeasurements;
  Serial.print("MPU6050 - Elevation réelle du tracker : ");
  Serial.println(MPU6050_AverageAngle);

  //Corrige l'angle
  //Temps de mouvement estime pour être à l'elevation voulue à partir de l élévation réelle
  int required_elevation_required_move_duration = (required_elevation-TRACKER_elevation_mini) * ((TRACKER_ele_max_move_dur*1000)/(TRACKER_elevation_maxi-TRACKER_elevation_mini));
  int MPU6050_elevation_done_move_duration = (MPU6050_AverageAngle-TRACKER_elevation_mini) * ((TRACKER_ele_max_move_dur*1000)/(TRACKER_elevation_maxi-TRACKER_elevation_mini));
  Serial.print("L298N - Temps de mouvement estimé pour être à l'elevation demandée : ");
  Serial.println(required_elevation_required_move_duration);
  Serial.print("MPU6050 - Temps de mouvement déja effectué réellement d'après le capteur d'inclinaison : ");
  Serial.println(MPU6050_elevation_done_move_duration);
  int L298N_elevation_next_move_duration = required_elevation_required_move_duration-MPU6050_elevation_done_move_duration;
  Serial.print("L298N - Temps de mouvement à effectuer pour être à la bonne elevation : ");
  Serial.println(L298N_elevation_next_move_duration);
  float MPU6050_DiffAngle = abs(required_elevation-MPU6050_AverageAngle);
  Serial.print("MPU6050 - Différence d'angle : ");
  Serial.println(MPU6050_DiffAngle);
  
  //Corrige si il y a deux degrés ou plus d'écart
  if (MPU6050_DiffAngle>=2) {

    //Si on est dans la plage de deplacement, regarde quel temps de deplacement on devrait avoir pour être a la bonne elevation
    if ((abs(L298N_elevation_next_move_duration)>=TRACKER_elevation_min_mv_time*1000)){
      Serial.println("L298N - Positionnement du panneau");
    
      //Si L298N_elevation_moved_duration > required_elevation_required_move_duration on doit retourner vers le haut (si pas en butée)
      if ((L298N_elevation_next_move_duration<0)&&(TRACKER_is_at_up_limit == 0)) {
        Serial.println("Moving UP");
        L298N_elevation_up(TRACKER_vertical_speed);
      }
      //Bouge vers le bas pendant le temps calculé si pas en limite
      if ((L298N_elevation_next_move_duration>0)&&(TRACKER_is_at_down_limit == 0)) {
        Serial.println("Moving WEST");
        L298N_elevation_down(TRACKER_vertical_speed);
      }
      //Si en limite on ne bouge pas
      if (((L298N_elevation_next_move_duration>0)&&(TRACKER_is_at_down_limit == 1))||((L298N_elevation_next_move_duration<0)&&(TRACKER_is_at_up_limit == 1))) {
        Serial.println("L298N - Position inacccessible, déja en limite");
        L298N_elevation_next_move_duration = 0;
      }
    
      //Si on bouge
      if (L298N_elevation_next_move_duration != 0) {
        //Lance le mouvement pour la durée voulue
        delay(abs(L298N_elevation_next_move_duration));   
        //Stoppe le mouvement
        L298N_stop_elevation_move();
      }

    } else {
      Serial.println("MPU6050 - Position correcte");
    }
  }

}

//Affichage des informations de localisation du soleil pour DEBUG
void DEBUG_print_SolarPosition(SolarPosition_t pos, int numDigits)
{
  Serial.print(F("SOLARPOSITION - Elevation : "));
  Serial.print(pos.elevation, numDigits);
  Serial.print(F(" deg\t"));

  Serial.print(F(" Azimuth : "));
  Serial.print(pos.azimuth, numDigits);
  Serial.println(F(" deg"));
}

//Fonction de debug de la position soleil / tracker sur le LCD
void SOLARPOSITION_debug_lcd(double sun_azimut, double tracker_azimut, double sun_elevation, double tracker_elevation) {
    
    lcd.clear();
    lcd.setCursor(0, 0);
    lcd.print("Sun_Azimut=");
    lcd.setCursor(11, 0);
    lcd.print(sun_azimut);
    lcd.setCursor(0, 1);
    lcd.print("Tra_Azimut=");
    lcd.setCursor(11, 1);
    lcd.print(tracker_azimut);
    delay(1000);
    lcd.clear();
    lcd.setCursor(0, 0);
    lcd.print("Req_Elevat=");
    double TRACKER_required_elevation = 90-sun_elevation;
    lcd.setCursor(11, 0);
    lcd.print(TRACKER_required_elevation);
    lcd.setCursor(0, 1);
    lcd.print("Tra_Elevat=");
    lcd.setCursor(11, 1);
    lcd.print(tracker_elevation);
    delay(1000);
}

//Estime l'azimuth actuel du panneau
double L298N_get_azimuth() {

    //Calcule l'azimuth actuel en fonction du temps de déplacement
    float TRACKER_estimated_azimuth =  TRACKER_azimuth_mini + ((L298N_azimuth_moved_duration*(TRACKER_azimuth_maxi-TRACKER_azimuth_mini))/(TRACKER_azi_max_move_dur*1000));
    return (TRACKER_estimated_azimuth); 

}

//Fonction pour mettre le panneau à un azimuth précis
double L298N_set_azimuth(float required_azimuth) {

  //Affiche l'azimut du tracker
  float TRACKER_azimuth =  L298N_get_azimuth();
  Serial.print("L298N - Azimuth estimé du tracker : ");
  Serial.println(TRACKER_azimuth);

  //Temps de mouvement estime pour être à l'azimuth voulu
  int required_azimuth_required_move_duration = (required_azimuth-TRACKER_azimuth_mini) * ((TRACKER_azi_max_move_dur*1000)/(TRACKER_azimuth_maxi-TRACKER_azimuth_mini));
  Serial.print("L298N - Temps de mouvement estimé pour être à l'azimuth demandé : ");
  Serial.println(required_azimuth_required_move_duration);
  Serial.print("L298N - Temps de mouvement déja effectué : ");
  Serial.println(L298N_azimuth_moved_duration);
  int L298N_azimuth_next_move_duration = required_azimuth_required_move_duration-L298N_azimuth_moved_duration;
  Serial.print("L298N - Temps de mouvement à effectuer pour être au bon azimuth : ");
  Serial.println(L298N_azimuth_next_move_duration);
  Serial.print("L298N - Temps de mouvement à effectuer pour être au bon azimuth avec temps de demarrage actionneur : ");
  int L298N_azimuth_next_complete_move_duration = L298N_azimuth_next_move_duration + (TRACKER_azi_start_move_dur*10);
  Serial.println(L298N_azimuth_next_complete_move_duration);

  //Si on est dans la plage de deplacement, regarde quel temps de deplacement on devrait avoir pour être au bon azimuth
  if ((abs(L298N_azimuth_next_move_duration)>=TRACKER_azimuth_min_mv_time*1000)){
    Serial.println("L298N - Positionnement du panneau");
    
    //Si L298N_azimuth_moved_duration > required_azimuth_required_move_duration on doit retourner vers l'EST (si pas en butée)
    if ((L298N_azimuth_next_move_duration<0)&&(TRACKER_is_at_east_limit == 0)) {
      Serial.println("Moving EAST");
      L298N_move_east();
    }
    //Bouge à l'ouest pendant le temps calculé si pas en limite
    if ((L298N_azimuth_next_move_duration>0)&&(TRACKER_is_at_west_limit == 0)) {
      Serial.println("Moving WEST");
      L298N_move_west();
    }
    //Si en limite on ne bouge pas
    if (((L298N_azimuth_next_move_duration>0)&&(TRACKER_is_at_west_limit == 1))||((L298N_azimuth_next_move_duration<0)&&(TRACKER_is_at_east_limit == 1))) {
      Serial.println("L298N - Position inacccessible, déja en limite");
      L298N_azimuth_next_move_duration = 0;
    }
    
    //Si on bouge
    if (L298N_azimuth_next_move_duration != 0) {
      //Lance le mouvement pour la durée voulue
      delay(abs(L298N_azimuth_next_complete_move_duration));   
      //Stoppe le mouvement
      L298N_stop_azimuth_move();
      //Met a jour la durée de deplacement
      L298N_azimuth_moved_duration=L298N_azimuth_moved_duration+L298N_azimuth_next_move_duration;
    }

    //La corrige si elle est supérieure à l'amplitude possible
    if (L298N_azimuth_moved_duration>=TRACKER_azi_max_move_dur*1000) {
      Serial.println("L298N - Butée Ouest");
      TRACKER_is_at_west_limit = 1;
      L298N_azimuth_moved_duration = TRACKER_azi_max_move_dur*1000;
    }
    if (L298N_azimuth_moved_duration<0){
      Serial.println("L298N - Butée Est");
      TRACKER_is_at_east_limit = 1;
      L298N_azimuth_moved_duration = 0;
    }
  } else {
    Serial.println("L298N - Position correcte");
  }

  //Renvoie l'azimuth estimé
  return(TRACKER_azimuth);

}

//Estime l'azimuth actuel du panneau
double L298N_get_elevation() {

    //Calcule l'azimuth actuel en fonction du temps de déplacement
    float TRACKER_estimated_elevation =  TRACKER_elevation_mini + ((L298N_elevation_moved_duration*(TRACKER_elevation_maxi-TRACKER_elevation_mini))/(TRACKER_ele_max_move_dur*1000));
    return (TRACKER_estimated_elevation); 

}

//Fonction pour mettre le panneau à un angle précis
double L298N_set_elevation(double required_elevation) {

  //Affiche l'elevation du tracker
  float TRACKER_elevation =  L298N_get_elevation();
  Serial.print("L298N - Elevation estimée du tracker : ");
  Serial.println(TRACKER_elevation);

  //Temps de mouvement estime pour être à l'elevation voulue
  int required_elevation_required_move_duration = (required_elevation-TRACKER_elevation_mini) * ((TRACKER_ele_max_move_dur*1000)/(TRACKER_elevation_maxi-TRACKER_elevation_mini));
  Serial.print("L298N - Temps de mouvement estimé pour être à l'elevation demandée : ");
  Serial.println(required_elevation_required_move_duration);
  Serial.print("L298N - Temps de mouvement déja effectué : ");
  Serial.println(L298N_elevation_moved_duration);
  int L298N_elevation_next_move_duration = required_elevation_required_move_duration-L298N_elevation_moved_duration;
  Serial.print("L298N - Temps de mouvement à effectuer pour être à la bonne elevation : ");
  Serial.println(L298N_elevation_next_move_duration);

  //Si on est dans la plage de deplacement, regarde quel temps de deplacement on devrait avoir pour être a la bonne elevation
  if ((abs(L298N_elevation_next_move_duration)>=TRACKER_elevation_min_mv_time*1000)){
    
    Serial.println("L298N - Positionnement du panneau");
    
    //Si on ne met pas à plat
    if (required_elevation != 0) {
      
      //Si L298N_elevation_moved_duration > required_elevation_required_move_duration on doit retourner vers le haut (si pas en butée)
      if ((L298N_elevation_next_move_duration<0)&&(TRACKER_is_at_up_limit == 0)) {
        Serial.println("Moving UP");
        L298N_elevation_up(TRACKER_vertical_speed);
      }
      //Bouge vers le bas pendant le temps calculé si pas en limite
      if ((L298N_elevation_next_move_duration>0)&&(TRACKER_is_at_down_limit == 0)) {
        Serial.println("Moving DOWN");
        L298N_elevation_down(TRACKER_vertical_speed);
      }
      //Si en limite on ne bouge pas
      if (((L298N_elevation_next_move_duration>0)&&(TRACKER_is_at_down_limit == 1))||((L298N_elevation_next_move_duration<0)&&(TRACKER_is_at_up_limit == 1))) {
        Serial.println("L298N - Position inacccessible, déja en limite");
        L298N_elevation_next_move_duration = 0;
      }
    
      //Si on bouge
      if (L298N_elevation_next_move_duration != 0) {
        //Lance le mouvement pour la durée voulue
        delay(abs(L298N_elevation_next_move_duration));   
        //Stoppe le mouvement
        L298N_stop_elevation_move();
        //Met a jour la durée de deplacement
        L298N_elevation_moved_duration=L298N_elevation_moved_duration+L298N_elevation_next_move_duration;
      }

      //La corrige si elle est supérieure à l'amplitude possible
      if (L298N_elevation_moved_duration>=TRACKER_ele_max_move_dur*1000) {
        Serial.println("L298N - Butée Bas");
        TRACKER_is_at_down_limit = 1;
        L298N_elevation_moved_duration = TRACKER_ele_max_move_dur*1000;
      }
      if (L298N_elevation_moved_duration<0){
        Serial.println("L298N - Butée Haut");
        TRACKER_is_at_up_limit = 1;
        L298N_elevation_moved_duration = 0;
      }
      
    //Sinon mise à plat rapide
    } else {

      //Mise à plat
      L298N_set_to_horizontal_position();

    }
      
  } else {
    Serial.println("L298N - Position correcte");
  }

  //Renvoie l'elevation estimée
  return(TRACKER_elevation); 
  
}

//Fonction de placement du panneau en position statique
void STATICMODE_set(){
  
  Serial.println(F("STATICMODE - Placement en position statique"));
  LCD_quick_print("POSITION","STATIQUE",1,0,0);
  
  //Verifie si on doit se mettre en position intermediaire en raison du vent si l'angle requis est superieur à l'angle intermediaire de securite
  if (((ANEMO_security_position==2)||(OPENWEATHER_security_position==2))&&(TRACKER_security_override != 1)&&(90-TRACKER_static_mode_elevation>TRACKER_wind_smart_angle)) {
    Serial.print("SOLARPOSITION - Position de securite intermediaire requise ");
    L298N_set_elevation(TRACKER_wind_smart_angle);
    //Corrige l'angle si besoin
    MPU6050_correct_elevation(TRACKER_wind_smart_angle);
  } else {
    //Placement Elevation Demandee
    L298N_set_elevation(90-TRACKER_static_mode_elevation);
    //Corrige l'angle si besoin
    MPU6050_correct_elevation(90-TRACKER_static_mode_elevation);
  }

  //Placement Azimuth
  L298N_set_azimuth(TRACKER_static_mode_azimuth);
  
}

//Fonction de gestion de l'orientation en fonction de la position du soleil
void SOLARPOSITION_analyze() {
 
  //Met à l'heure le système
  NTP_set_system_TimeAndDate();

  //Affiche la position du soleil actuelle pour la localisation spécifiée
  Serial.println(F("SOLARPOSITION - Position du soleil pour l'Epoch Systeme :\t"));
  SolarPosition::setTimeProvider(now);
  DEBUG_print_SolarPosition(TRACKER_location.getSolarPosition(), SOLARPOSITION_digits);
  double SOLARPOSITION_elevation = TRACKER_location.getSolarPosition().elevation;
  double SOLARPOSITION_azimuth = TRACKER_location.getSolarPosition().azimuth;

  //Affiche les informations du capteur gyroscopique
  double TRACKER_elevation = MPU6050_get_elevation();
  Serial.print("GY-521 MPU-6050 - Elevation du tracker : ");
  Serial.println(TRACKER_elevation);
  
  //Calcule l'angle du tracker en fonction de celui du soleil (180 - (angle soleil+90))
  double SOLARPOSITION_tracker_elevation = 180 - (SOLARPOSITION_elevation+90);
  Serial.print("SOLARPOSITION - Elevation requise du tracker : ");
  Serial.println(SOLARPOSITION_tracker_elevation);
      
  //Verifie si on doit se mettre en position intermediaire en raison du vent si l'angle requis est superieur a la position intermediaire
  if (((ANEMO_security_position==2)||(OPENWEATHER_security_position==2))&&(TRACKER_security_override != 1)&&(round(SOLARPOSITION_tracker_elevation)>TRACKER_wind_smart_angle)){ 
    SOLARPOSITION_tracker_elevation=TRACKER_wind_smart_angle;
    Serial.print("SOLARPOSITION - Position de securite intermediaire requise ");
  }
  
  //Se met à la bonne elevation
  L298N_set_elevation(round(SOLARPOSITION_tracker_elevation));
    
  //Affiche l'azimuth du soleil
  Serial.print("SOLARPOSITION - Azimuth du soleil : ");
  Serial.println( SOLARPOSITION_azimuth);
  
  //Met le tracker au bon azimuth
  double TRACKER_azimuth = L298N_set_azimuth(SOLARPOSITION_azimuth);

  //Corrige l'angle si besoin
  MPU6050_correct_elevation(round(SOLARPOSITION_tracker_elevation));
  
  //Debug LCD
  SOLARPOSITION_debug_lcd(SOLARPOSITION_azimuth, TRACKER_azimuth, SOLARPOSITION_elevation, MPU6050_get_elevation());
  
}

//Fonction qui realise une requete HTTP GET
String OPENWEATHER_httpGETRequest(const char* serverName) {
  WiFiClient client;
  HTTPClient http;
    
  // Your IP address with path or Domain name with URL path 
  http.begin(client, serverName);
  
  // Send HTTP POST request
  int httpResponseCode = http.GET();
  
  String payload = "{}"; 
  
  if (httpResponseCode>0) {
    Serial.print("OPENWEATHER - HTTP Response code : ");
    Serial.println(httpResponseCode);
    payload = http.getString();
  }
  else {
    Serial.print("Error code: ");
    Serial.println(httpResponseCode);
  }
  // Free resources
  http.end();

  return payload;
}

//Fonction qui verifie les données météorologiques sur OpenWeather
void OPENWEATHER_security_check() {
  
  Serial.println("OPENWEATHER - Verification meteo");
  
  //Verifie la meteo avant tout sur OpenWeather pour déterminer si position de securite ou non
  if ((millis() - OPENWEATHER_lastTime) > OPENWEATHER_timerDelay) {
    String OPENWEATHER_serverPath = "http://api.openweathermap.org/data/2.5/weather?q=" + OPENWEATHER_city + "," + OPENWEATHER_countryCode + "&APPID=" + OPENWEATHER_MapApiKey;

    OPENWEATHER_jsonBuffer = OPENWEATHER_httpGETRequest(OPENWEATHER_serverPath.c_str());
    Serial.println(OPENWEATHER_jsonBuffer);
    JSONVar OPENWEATHER_myObject = JSON.parse(OPENWEATHER_jsonBuffer);
  
    // JSON.typeof(jsonVar) can be used to get the type of the var
    if (JSON.typeof(OPENWEATHER_myObject) == "undefined") {
      Serial.println("OPENWEATHER - Parsing input failed!");
      OPENWEATHER_success = 0;
      //return;
    } else {
      float OPENWEATHER_wind_speed = 3.6*JSON.stringify(OPENWEATHER_myObject["wind"]["speed"]).toFloat();
      OPENWEATHER_wind_gust =  3.6*JSON.stringify(OPENWEATHER_myObject["wind"]["gust"]).toFloat();
      OPENWEATHER_wind_direction =  JSON.stringify(OPENWEATHER_myObject["wind"]["deg"]).toInt();

      Serial.print("OPENWEATHER - Vitesse du vent (km/h) : ");
      Serial.println(OPENWEATHER_wind_speed);
      Serial.print("OPENWEATHER - Vitesse des rafales de vent (km/h) : ");
      Serial.println(OPENWEATHER_wind_gust);
      Serial.print("OPENWEATHER - Direction du vent : ");
      Serial.println(OPENWEATHER_wind_direction);
      
      OPENWEATHER_lastTime = millis();

      OPENWEATHER_success = 1;

      lcd.clear();
      lcd.setCursor(0, 0);
      lcd.print("RAFA VENT = ");  
      lcd.setCursor(12, 0);
      lcd.print(OPENWEATHER_wind_gust);
      lcd.setCursor(0,1);
      lcd.print("DIR VENT = ");  
      lcd.setCursor(12, 1);
      lcd.print(OPENWEATHER_wind_direction);
      //Attend le temps souhaité
      delay(1000);
      lcd.clear();
    }
   
  }

  //Si les conditions sont bonnes pas de position de sécurité
  if ((OPENWEATHER_wind_gust < OPENWEATHER_wind_limit)&&(OPENWEATHER_success == 1)) {
    Serial.println("OPENWEATHER - Conditions favorables");
    OPENWEATHER_security_position = 0;
  }

  //Si les conditions ne sont pas bonnes du tout position de sécurité maxi
  if ((OPENWEATHER_wind_gust >= OPENWEATHER_wind_limit)&&(OPENWEATHER_success == 1)) {
    Serial.println("OPENWEATHER - Trop de vent, mise en position de sécurité");
    OPENWEATHER_security_position = 1;
  }

  //Si les conditions ne sont pas bonnes mais compatibles position intermediaire
  if ((OPENWEATHER_wind_gust >= OPENWEATHER_wind_inter_limit)&&(OPENWEATHER_wind_gust < OPENWEATHER_wind_limit)&&(OPENWEATHER_success == 1)) {
    Serial.println("OPENWEATHER - Trop de vent, mise en position de sécurité intermédiaire");
    OPENWEATHER_security_position = 2;
  }

  //Si on a bypassé la meteo OW, pas de position de securite
  if (TRACKER_security_override == 2) {
    Serial.println("OPENWEATHER - Bypass du capteur via TRACKER_security_override à 2");
    OPENWEATHER_security_position = 0;
  }

  //Debug
  if (OPENWEATHER_security_position >= 1) {
    Serial.println("OPENWEATHER -  Trop de vent, mise en position de sécurité");
    //Debug
    LCD_quick_print("POSITION DE","SECURITE",1,0,0); 
  }

}

//Pointe vers l'est
void L298N_move_east(){

  analogWrite(ESP8266_L298N_ena, TRACKER_horizontal_speed);
  
  //Enregistre le moment du depart du mouvement pour déterminer si on est en butée ou pas
  L298N_azimuth_last_move_start_time = millis();
  
  LCD_quick_print("ORIENTE VERS","L'EST",1,0,0);
  Serial.println("L298N - Diminue l'azimuth - Direction EST");

  //Indique que le traqueur n'est plus en butée ouest
  TRACKER_is_at_west_limit = 0;

  MCP23017.digitalWrite(MCP23017_L298N_in1,HIGH);
  MCP23017.digitalWrite(MCP23017_L298N_in2,LOW); 
  
}

//Pointe vers l'ouest
void L298N_move_west(){

  analogWrite(ESP8266_L298N_ena, TRACKER_horizontal_speed);
  
  //Enregistre le moment du depart du mouvement pour déterminer si on est en butée ou pas
  L298N_azimuth_last_move_start_time = millis();
  
  LCD_quick_print("ORIENTE VERS","L'OUEST",1,0,0);
  Serial.println("L298N - Diminue l'azimuth - Direction OUEST");

  //Indique que le traqueur n'est plus en butée est
  TRACKER_is_at_east_limit = 0;

  MCP23017.digitalWrite(MCP23017_L298N_in1,LOW);
  MCP23017.digitalWrite(MCP23017_L298N_in2,HIGH);
  
}

//Pointe vers le haut
void L298N_elevation_up(int vertical_speed){
 
  analogWrite(ESP8266_L298N_enb, vertical_speed);
 
  LCD_quick_print("POINTE VERS","LE HAUT",1,0,0);
  Serial.println("L298N - Diminue l'angle");

  //Indique que le traqueur n'est plus en butée bas
  TRACKER_is_at_down_limit = 0;

  //Enregistre le moment du depart du mouvement pour déterminer si on est en butée ou pas
  L298N_elevation_last_move_start_time = millis();

  MCP23017.digitalWrite(MCP23017_L298N_in3,HIGH);
  MCP23017.digitalWrite(MCP23017_L298N_in4,LOW);
  
}

//Pointe vers le bas
void L298N_elevation_down(int vertical_speed){
  
  analogWrite(ESP8266_L298N_enb, vertical_speed);
  
  LCD_quick_print("POINTE VERS","LE BAS",1,0,0);
  Serial.println("L298N - Augmente l'angle");

  //Indique que le traqueur n'est plus en butée haut
  TRACKER_is_at_up_limit = 0;

  //Enregistre le moment du depart du mouvement pour déterminer si on est en butée ou pas
  L298N_elevation_last_move_start_time = millis();
    
  MCP23017.digitalWrite(MCP23017_L298N_in3,LOW);
  MCP23017.digitalWrite(MCP23017_L298N_in4,HIGH);
  
}

//Arrete le mouvement horizontal
void L298N_stop_azimuth_move(){

  //Stoppe le mouvement
  MCP23017.digitalWrite(MCP23017_L298N_in1,LOW);
  MCP23017.digitalWrite(MCP23017_L298N_in2,LOW);
  digitalWrite(ESP8266_L298N_ena,LOW);
  
}

//Arrete le mouvement vertical
void L298N_stop_elevation_move(){

  //Stoppe le mouvement
  MCP23017.digitalWrite(MCP23017_L298N_in3,LOW);
  MCP23017.digitalWrite(MCP23017_L298N_in4,LOW);
  digitalWrite(ESP8266_L298N_enb,LOW);
  
}

//Regarde le temps de déplacement
int L298N_azimuth_virtual_limit_switch(){
  
  //Si on a depassé le temps de déplacement maxi, on est en butée
  if (millis()-L298N_azimuth_last_move_start_time>TRACKER_azi_max_move_dur*1000) {
    return(1);
  } else {
    return(0);
  }

}

//Retourne à l'EST la nuit pour etre pret pour le matin suivant
void L298N_set_to_east_position(){
  
  //Delace les panneaux
  Serial.println("L298N - Placement en butée EST");
  L298N_move_east();
  //x1100 pour etre sur d'être en butée
  delay(TRACKER_azi_max_move_dur*1100);

  //Indique que le traqueur est en butée est
  TRACKER_is_at_east_limit = 1;

  //Temps de deplacement depuis l'est repart à 0
  L298N_azimuth_moved_duration = 0;

  //Stoppe le mouvement
  L298N_stop_azimuth_move();
    
}

//Se met en position horizontale en vitesse rapide
void L298N_set_to_horizontal_position(){
  
  //Deplace les panneaux
  Serial.println("L298N - Placement en butée UP");
  L298N_elevation_up(TRACKER_secu_vertical_speed);
  //x1100 pour etre sur d'être en butée
  delay(TRACKER_ele_max_move_dur*1100);
 
  //Temps de deplacement depuis UP repart à 0
  L298N_elevation_moved_duration = 0;

  //Stoppe le mouvement
  L298N_stop_elevation_move();

  //Corrige si erreur
  MPU6050_correct_elevation(0);

  //Indique que le traqueur est en butée up
  TRACKER_is_at_up_limit = 1;
    
}

//Requete non trouvée
void notFound(AsyncWebServerRequest *request) {
  request->send(404, "text/plain", "Not found");
}

//Conversion des variables html en valeurs
String processor(const String& var) {
  
  int PROCESSOR_actual_angle=MPU6050_get_elevation();
  int PROCESSOR_actual_azimuth=L298N_get_azimuth();
  
  //Serial.println(var);
  if (var == "TRACKER_selected_mode"){
    return String(TRACKER_selected_mode); 
  }
  if (var == "TRACKER_anemometer_model"){
    return String(TRACKER_anemometer_model); 
  }
  if (var == "TRACKER_static_mode_azimuth"){
    return String(TRACKER_static_mode_azimuth); 
  }
  if (var == "TRACKER_static_mode_elevation"){
    return String(TRACKER_static_mode_elevation); 
  }
  if (var == "TRACKER_azi_max_move_dur"){
    return String(TRACKER_azi_max_move_dur); 
  }
  if (var == "TRACKER_azi_start_move_dur"){
    return String(TRACKER_azi_start_move_dur); 
  }
  if (var == "TRACKER_azimuth_mini"){
    return String(TRACKER_azimuth_mini); 
  }
  if (var == "TRACKER_azimuth_maxi"){
    return String(TRACKER_azimuth_maxi); 
  }
  if (var == "TRACKER_azimuth_min_mv_time"){
    return String(TRACKER_azimuth_min_mv_time); 
  }
  if (var == "TRACKER_ele_max_move_dur"){
    return String(TRACKER_ele_max_move_dur); 
  }
  if (var == "TRACKER_elevation_mini"){
    return String(TRACKER_elevation_mini); 
  }
  if (var == "TRACKER_elevation_maxi"){
    return String(TRACKER_elevation_maxi); 
  }
  if (var == "TRACKER_elevation_min_mv_time"){
    return String(TRACKER_elevation_min_mv_time); 
  }
  if (var == "TRACKER_vertical_speed"){
    return String(TRACKER_vertical_speed); 
  }
  if (var == "TRACKER_secu_vertical_speed"){
    return String(TRACKER_secu_vertical_speed); 
  }
  if (var == "TRACKER_horizontal_speed"){
    return String(TRACKER_horizontal_speed); 
  }
  if (var == "TRACKER_wind_inter_angle"){
    return String(TRACKER_wind_inter_angle); 
  }
  if (var == "TRACKER_wind_limit_time"){
    return String(TRACKER_wind_limit_time); 
  }
  if (var == "OPENWEATHER_wind_limit"){
    return String(OPENWEATHER_wind_limit); 
  }
  if (var == "OPENWEATHER_wind_inter_limit"){
    return String(OPENWEATHER_wind_inter_limit); 
  }
  if (var == "OPENWEATHER_wind_smart_coeff"){
    return String(OPENWEATHER_wind_smart_coeff); 
  }
  if (var == "ANEMO_wind_limit"){
    return String(ANEMO_wind_limit); 
  }
  if (var == "ANEMO_wind_inter_limit"){
    return String(ANEMO_wind_inter_limit); 
  }
  if (var == "ANEMO_wind_smart_coeff"){
    return String(ANEMO_wind_smart_coeff); 
  }
  if (var == "ANEMO_wind_speed"){
    return String(ANEMO_wind_speed); 
  }
  if (var == "TRACKER_actual_azimuth"){
    return String(PROCESSOR_actual_azimuth); 
  }
  if (var == "TRACKER_actual_elevation"){
    return String(90-PROCESSOR_actual_angle); 
  }
  if (var == "TRACKER_actual_angle"){
    return String(PROCESSOR_actual_angle); 
  }
  if (var == "OPENWEATHER_wind_gust"){
    return String(OPENWEATHER_wind_gust); 
  }
  if (var == "ANEMO_wind_gust"){
    return String(ANEMO_wind_gust); 
  }
  if (var == "NTP_time"){
    return String(now()); 
  }
  if (var == "L298N_azimuth_moved_duration"){
    return String(L298N_azimuth_moved_duration); 
  }
  if (var == "TRACKER_is_at_west_limit"){
    return String(TRACKER_is_at_west_limit); 
  }
  if (var == "TRACKER_is_at_east_limit"){
    return String(TRACKER_is_at_east_limit); 
  }
  if (var == "L298N_elevation_moved_duration"){
    return String(L298N_elevation_moved_duration); 
  }
  if (var == "TRACKER_is_at_up_limit"){
    return String(TRACKER_is_at_up_limit); 
  }
  if (var == "TRACKER_is_at_down_limit"){
    return String(TRACKER_is_at_down_limit); 
  }
  if (var == "SUN_azimuth"){
    return String(TRACKER_location.getSolarPosition().azimuth); 
  }
  if (var == "SUN_angle"){
    return String(90-TRACKER_location.getSolarPosition().elevation); 
  }
  if (var == "SUN_elevation"){
    return String(TRACKER_location.getSolarPosition().elevation); 
  }
  if (var == "TRACKER_security_override"){
    return String(TRACKER_security_override); 
  }
  if (var == "ANEMO_record_time"){
    return String(ANEMO_record_time); 
  }
  if (var == "ANEMO_analog_coefficient"){
    return String(ANEMO_analog_coefficient); 
  }
  if (var == "ANEMO_wind_gust_secupos"){
    return String(ANEMO_wind_gust_secupos); 
  }
  if (var == "TRACKER_wind_smart_angle"){
    return String(TRACKER_wind_smart_angle); 
  }
  if (var == "SUNSENSOR_offset_droite"){
    return String(SUNSENSOR_offset_droite); 
  }
  if (var == "SUNSENSOR_offset_gauche"){
    return String(SUNSENSOR_offset_gauche); 
  }
  if (var == "SUNSENSOR_offset_haut"){
    return String(SUNSENSOR_offset_haut); 
  }
  if (var == "SUNSENSOR_offset_bas"){
    return String(SUNSENSOR_offset_bas); 
  }
  if (var == "SUNSENSOR_delta_haut_bas"){
    return String(SUNSENSOR_delta_haut_bas); 
  }
  if (var == "SUNSENSOR_delta_droite_gauche"){
    return String(SUNSENSOR_delta_droite_gauche); 
  }

  if (var == "TRACKER_VERSION"){
    return String(TRACKER_VERSION);
  }

  if (var == "ANEMO_interrupt_counter"){
    return String(ANEMO_interrupt_counter);
  }

  if (var == "ANEMO_analog_voltage"){
    return String(ANEMO_analog_voltage,6);
  }
  
  if (var == "INTERFACE_restart_on_save"){
    return String(INTERFACE_restart_on_save);
  }

  if (var == "INTERFACE_tracker_selected_mode") {
    INTERFACE_tracker_selected_mode="";
    if (TRACKER_selected_mode == 0) {INTERFACE_tracker_selected_mode="Mode Securite";}
    if (TRACKER_selected_mode == 1) {INTERFACE_tracker_selected_mode="Mode SolarPosition";}
    if (TRACKER_selected_mode == 2) {INTERFACE_tracker_selected_mode="Mode SunSensor";}
    if (TRACKER_selected_mode == 3) {INTERFACE_tracker_selected_mode="Mode Statique";}
    if ( TRACKER_location.getSolarPosition().elevation < 0) {INTERFACE_tracker_selected_mode+=" - Nuit";}
    return String(INTERFACE_tracker_selected_mode);
  }

  if (var == "INTERFACE_smangle_status_style"){
    int delta = abs (TRACKER_wind_smart_angle-PROCESSOR_actual_angle);
    if (delta>=-2) {
      return String("lightgreen");   
    } else {
      return String("red");   
    }
  }
  
  if (var == "INTERFACE_tracker_selected_anemometer_model") {
    INTERFACE_tracker_selected_anemometer_model="";
    if (TRACKER_anemometer_model == 0) {INTERFACE_tracker_selected_anemometer_model="0 - Numerique - Compteur";}
    if (TRACKER_anemometer_model == 1) {INTERFACE_tracker_selected_anemometer_model="1 - Analogique - Voltage";}
    return String(INTERFACE_tracker_selected_anemometer_model);
  }

  //Génère l'azimuth requis et l'élévation requise en fonction du mode
  int INTERFACE_required_elevation = 0;
  int INTERFACE_required_azimuth = 0;
  if (TRACKER_selected_mode == 1 || TRACKER_selected_mode == 2){
      INTERFACE_required_elevation = TRACKER_location.getSolarPosition().elevation;
      INTERFACE_required_azimuth = TRACKER_location.getSolarPosition().azimuth;  
  }
  if (TRACKER_selected_mode == 3) {
      INTERFACE_required_elevation = TRACKER_static_mode_elevation;
      INTERFACE_required_azimuth = TRACKER_static_mode_azimuth;
  }
  if (TRACKER_location.getSolarPosition().elevation < 0 || TRACKER_selected_mode == 0) {
      INTERFACE_required_elevation = 90; 
      INTERFACE_required_azimuth = TRACKER_azimuth_mini;     
  }
  
  if (var == "INTERFACE_required_elevation") {
     return String (INTERFACE_required_elevation);
  }

  if (var == "INTERFACE_required_azimuth") {
     return String (INTERFACE_required_azimuth);
  }

  if (var == "INTERFACE_elevation_status_style"){
      return String(INTERFACE_table_line_color(90-PROCESSOR_actual_angle,INTERFACE_required_elevation));  
  }
  
  if (var == "INTERFACE_azimuth_status_style"){
      return String(INTERFACE_table_line_color(PROCESSOR_actual_azimuth,INTERFACE_required_azimuth));
  }

  //Gestion de la selection du mode dans le menu de parametrage
  INTERFACE_selected_mode0_style="";
  INTERFACE_selected_mode1_style="";
  INTERFACE_selected_mode2_style="";
  INTERFACE_selected_mode3_style="";
  if (TRACKER_selected_mode == 0) {
    INTERFACE_selected_mode0_style=" selected=yes";
  }
  if (TRACKER_selected_mode == 1) {
    INTERFACE_selected_mode1_style=" selected=yes";
  }
  if (TRACKER_selected_mode == 2) {
    INTERFACE_selected_mode2_style=" selected=yes";
  }
  if (TRACKER_selected_mode == 3) {
    INTERFACE_selected_mode3_style=" selected=yes";
  }
  if (var == "INTERFACE_selected_mode0_style") {
    return String(INTERFACE_selected_mode0_style);
  }
  if (var == "INTERFACE_selected_mode1_style") {
    return String(INTERFACE_selected_mode1_style);
  }
  if (var == "INTERFACE_selected_mode2_style") {
    return String(INTERFACE_selected_mode2_style);
  }
  if (var == "INTERFACE_selected_mode3_style") {
    return String(INTERFACE_selected_mode3_style);
  }

  //Gestion de la selection du mode de securite dans le menu de parametrage
  INTERFACE_selected_secu0_style="";
  INTERFACE_selected_secu1_style="";
  INTERFACE_selected_secu2_style="";
  INTERFACE_selected_secu3_style="";
  if (TRACKER_security_override == 0) {
    INTERFACE_selected_secu0_style=" selected=yes";
  }
  if (TRACKER_security_override == 1) {
    INTERFACE_selected_secu1_style=" selected=yes";
  }
  if (TRACKER_security_override == 2) {
    INTERFACE_selected_secu2_style=" selected=yes";
  }
  if (TRACKER_security_override == 3) {
    INTERFACE_selected_secu3_style=" selected=yes";
  }
  if (var == "INTERFACE_selected_secu0_style") {
    return String(INTERFACE_selected_secu0_style);
  }
  if (var == "INTERFACE_selected_secu1_style") {
    return String(INTERFACE_selected_secu1_style);
  }
  if (var == "INTERFACE_selected_secu2_style") {
    return String(INTERFACE_selected_secu2_style);
  }
  if (var == "INTERFACE_selected_secu3_style") {
    return String(INTERFACE_selected_secu3_style);
  }

  
  //Gestion de la selection du mode de securite dans le menu de parametrage
  INTERFACE_selected_anemo0_style="";
  INTERFACE_selected_anemo1_style="";
  if (TRACKER_anemometer_model == 0) {
    INTERFACE_selected_anemo0_style=" selected=yes";
  }
  if (TRACKER_anemometer_model == 1) {
    INTERFACE_selected_anemo1_style=" selected=yes";
  }
  if (var == "INTERFACE_selected_anemo0_style") {
    return String(INTERFACE_selected_anemo0_style);
  }
  if (var == "INTERFACE_selected_anemo1_style") {
    return String(INTERFACE_selected_anemo1_style);
  }
 
}


//Fonction de comptage des impulsions de l'anemometre (ICACHE_RAM_ATTR pour eviter le crash du pulsecount avec wifi) 
void IRAM_ATTR ANEMO_count_up() {
  ANEMO_interrupt_counter++;
}

//Mesure la vitesse du vent
void ANEMO_get_wind(){

  Serial.println("ANEMO - Prise de mesure");
      
  //Si anemometre numerique - compte les impulsions
  if (TRACKER_anemometer_model == 0) {
    
    //Compte les impulsions et calcule la vitesse
    ANEMO_interrupt_counter = 0;
    attachInterrupt(digitalPinToInterrupt(ANEMO_sensor_pin), ANEMO_count_up, RISING);
    delay(1000 * ANEMO_record_time);
    detachInterrupt(digitalPinToInterrupt(ANEMO_sensor_pin));
    ANEMO_wind_speed = (((float)ANEMO_interrupt_counter * 2.4)/ (float)ANEMO_record_time);
    Serial.print("ANEMO - Compteur : ");
    Serial.println(ANEMO_interrupt_counter);
    Serial.print(ANEMO_wind_speed/3.6);
    Serial.println(" m/s");
  
  }

  //Si analogique mesure la tension
  if (TRACKER_anemometer_model == 1) {

    //Lit la tension sur le port analog de l'anemometre
    float ANEMO_analog_value = analogRead(ANEMO_analog_pin);
    //Convertit en tension entre 0 et 4V (proportionnel au pont 0 à 3.3v)
    ANEMO_analog_voltage = ANEMO_analog_value * (4.0 / 1023.0) - ANEMO_analog_voltage_correction;
    ANEMO_wind_speed = (float)ANEMO_analog_voltage * (float)ANEMO_analog_coefficient;
    if (ANEMO_wind_speed < 0 ) { ANEMO_wind_speed = 0;} 
    Serial.print("ANEMO - Tension : ");
    Serial.println(ANEMO_analog_voltage);    
    
  }

  //Debug
  Serial.print("ANEMO - Vitesse du vent : ");
  Serial.print(ANEMO_wind_speed);
  Serial.print(" km/h - ");

  //Gestion des rafales
  //Si nouvelle rafale on met à jour la valeur et le moment ou celle ci est apparue
  if (ANEMO_wind_speed >=  ANEMO_wind_gust) {
    ANEMO_last_wind_gust_start_time = millis();
    ANEMO_wind_gust = ANEMO_wind_speed;  
  //Sinon si on a depassé le temps maxi entre deux rafales, on efface la rafale et on met le vent le plus rapide enregistré pendant que le tracker etait en securité
  } else if (millis()-ANEMO_last_wind_gust_start_time>(TRACKER_wind_limit_time*60000)){
    ANEMO_wind_gust = ANEMO_wind_gust_secupos;
    ANEMO_wind_gust_secupos = 0;
    ANEMO_last_wind_gust_start_time = millis();
  //Enregistre la plus grosse rafale pendant que le tracker est en securite
  } else if (millis()-ANEMO_last_wind_gust_start_time<(TRACKER_wind_limit_time*60000)){
    if (ANEMO_wind_speed > ANEMO_wind_gust_secupos) {
      ANEMO_wind_gust_secupos = ANEMO_wind_speed;
    }
  }
  //Debug
  Serial.print("ANEMO - Rafales : ");
  Serial.print(ANEMO_wind_gust);
  Serial.print(" km/h - ");
  Serial.print(ANEMO_wind_gust/3.6);
  Serial.println(" m/s");

  //Affichage LCD
  lcd.clear();
  lcd.setCursor(0, 0);
  lcd.print("VENT ANEMO = ");  
  lcd.setCursor(12, 0);
  lcd.print(ANEMO_wind_speed);
  lcd.setCursor(0,1);
  lcd.print("RAF VENT = ");  
  lcd.setCursor(12, 1);
  lcd.print(ANEMO_wind_gust);
  //Attend le temps souhaité
  delay(1000);
  lcd.clear();

}

//Fonction qui met le tracker en securite en fonction des mesures de l'anemometre
void ANEMO_security_check() {

  //Mesure le vent
  ANEMO_get_wind();

  //Reinitialise la variable de securite
  ANEMO_security_position = 0; 
  
  //Renvoie 1 si il y a trop de vent et qu'on n'a pas bypassé le capteur
  if ((ANEMO_wind_gust>=ANEMO_wind_limit)&&(TRACKER_security_override != 3)) {
    Serial.println("ANEMO - Trop de vent, mise en position de sécurité");
    ANEMO_security_position = 1;
  } 

  //Renvoie 2 si il y a trop de vent et qu'on n'a dépassé la limite de position de securite complète et qu'on n'a pas bypassé le capteur
  if ((ANEMO_wind_gust>=ANEMO_wind_inter_limit)&&(ANEMO_wind_gust<ANEMO_wind_limit)&&(TRACKER_security_override !=3)) {
    Serial.println("ANEMO - Trop de vent, mise en position de sécurité intermédiaire");
    ANEMO_security_position = 2;
  }
  
  //Debug
  if (TRACKER_security_override == 3){
    Serial.println("ANEMO - Bypass du capteur via TRACKER_security_override à 3");
  }
  if (ANEMO_security_position == 0){
      Serial.println("ANEMO - Conditions favorables");
  }

  Serial.println("ANEMO - Fin de verification");
  
}

void TRACKER_wind_smart_calc() {

  //Calcule l'angle requis maxi en fonction du vent et des coefficients si on depasse la limite intermediaire et qu'on n'a pas désactivé le capteur
  //ANGLE = ANGLE MAXI POSITION INTERMEDIAIRE - (VENT*(COEFF/100))
  if ((ANEMO_wind_gust > ANEMO_wind_inter_limit)&&(TRACKER_security_override != 3)&&(TRACKER_security_override != 1)) {
    ANEMO_wind_smart_angle = TRACKER_wind_inter_angle - (ANEMO_wind_gust * (ANEMO_wind_smart_coeff/100));
  } else {
    ANEMO_wind_smart_angle = TRACKER_elevation_maxi;
  }
  if ((OPENWEATHER_wind_gust > OPENWEATHER_wind_inter_limit)&&(TRACKER_security_override != 2)&&(TRACKER_security_override != 1)) {
    OPENWEATHER_wind_smart_angle = TRACKER_wind_inter_angle - (OPENWEATHER_wind_gust * (OPENWEATHER_wind_smart_coeff/100));
  } else {
    OPENWEATHER_wind_smart_angle = TRACKER_elevation_maxi;
  }
  
  //Prend l'angle le plus petit par securite
  if (OPENWEATHER_wind_smart_angle > ANEMO_wind_smart_angle){
    TRACKER_wind_smart_angle = ANEMO_wind_smart_angle;
  } else {
    TRACKER_wind_smart_angle = OPENWEATHER_wind_smart_angle;
  }

  //Si angle maxi inférieur à 0, le met à 0
  if (TRACKER_wind_smart_angle < 0) {
    TRACKER_wind_smart_angle = 0;
  }

  //Debug
  if (TRACKER_security_override == 3){
    Serial.println("ANEMO - Bypass du capteur via TRACKER_security_override à 3");
  }
  if (TRACKER_security_override == 2){
    Serial.println("OW - Bypass du capteur via TRACKER_security_override à 2");
  }
  if (TRACKER_security_override == 1){
    Serial.println("TRACKER - Bypass de tous les capteurs de vent via TRACKER_security_override à 1");
  }
  Serial.print("ANEMO - ANEMO_wind_smart_angle : ");
  Serial.print(ANEMO_wind_smart_angle);
  Serial.println("OPENWEATHER - OPENWEATHER_wind_smart_angle : ");
  Serial.print(OPENWEATHER_wind_smart_angle);
  Serial.println("TRACKER - TRACKER_wind_smart_angle : ");
  Serial.print(TRACKER_wind_smart_angle);

}

//Fonction qui publie les données sur le broker MQTT
void MQTT_Publish(){
  
  //Debug
  Serial.print("MQTT - Publication des valeurs");

  //Reconnecte si plus connecté
  if (!MQTTclient.connected()) {
    Serial.print("MQTT - Tentative de connexion...");
    MQTTclient.connect(TRACKER_HOSTNAME,MQTT_USERNAME, MQTT_PASSWORD);
  }
  
  //Tente de se connecter
  if (MQTTclient.connected()) {
    Serial.println("MQTT - Connecté");
    //Si connecté publie les topic
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Actual_Angle", String(MPU6050_get_elevation()).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Required_Angle", String(180-(TRACKER_location.getSolarPosition().elevation+90)).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Sun_Elevation", String(TRACKER_location.getSolarPosition().elevation).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Anemo_Wind_Gust", String(ANEMO_wind_gust).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Anemo_Wind_Speed", String(ANEMO_wind_speed).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_OW_Wind_Gust", String(OPENWEATHER_wind_gust).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Angle_Smart_Limit", String(TRACKER_wind_smart_angle).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Azimuth", String(L298N_get_azimuth()).c_str(),true);
    MQTTclient.publish("SOLAR_TRACKER/TRACKER_Required_Azimuth", String(TRACKER_location.getSolarPosition().azimuth).c_str(),true);
  } else {
    Serial.print("MQTT - Echec, rc=");
    Serial.print(MQTTclient.state());
  }

}

//Fonction qui analyse les données du capteur de soleil et gère les mouvements en conséquence
void SUNSENSOR_analyze() {
  // Mesure les tensions par rapport à la masse pour chaque LDR
  int16_t SUNSENSOR_LDR0 = ADS1115.readADC(0);           
  int16_t SUNSENSOR_LDR1 = ADS1115.readADC(1);
  int16_t SUNSENSOR_LDR2 = ADS1115.readADC(2);
  int16_t SUNSENSOR_LDR3 = ADS1115.readADC(3);
  String move_direction;
  int value;
  int oppositvalue;

  //Si on doit orienter vers la gauche
  if (((SUNSENSOR_LDR0 + SUNSENSOR_offset_gauche)-(SUNSENSOR_LDR3 + SUNSENSOR_offset_droite)) > SUNSENSOR_delta_droite_gauche) {
    Serial.println("SUNSENSOR - Aller à gauche !");
    move_direction = "GAUCHE | droite";
    value = SUNSENSOR_LDR0 + SUNSENSOR_offset_gauche;
    oppositvalue = SUNSENSOR_LDR3 + SUNSENSOR_offset_droite;
    //turnLEFT();
  }

  //Si on doit orienter vers la droite
  if (((SUNSENSOR_LDR3 + SUNSENSOR_offset_droite)-(SUNSENSOR_LDR0 + SUNSENSOR_offset_gauche)) > SUNSENSOR_delta_droite_gauche) {
    Serial.println("SUNSENSOR - Aller à droite !");
    move_direction = "DROITE | gauche";
    value = SUNSENSOR_LDR3 + SUNSENSOR_offset_droite;
    oppositvalue = SUNSENSOR_LDR0 + SUNSENSOR_offset_gauche;
    //turnRIGHT();
  }

  //Si on ne fait rien en horizontal
  if ((((SUNSENSOR_LDR3 + SUNSENSOR_offset_droite)-(SUNSENSOR_LDR0 + SUNSENSOR_offset_gauche)) < SUNSENSOR_delta_droite_gauche) && (((SUNSENSOR_LDR0 + SUNSENSOR_offset_gauche)-(SUNSENSOR_LDR3 + SUNSENSOR_offset_droite)) < SUNSENSOR_delta_droite_gauche)) {
    Serial.println("SUNSENSOR - Equilibre Droite - Gauche atteint !");
    move_direction = "DROITE = GAUCHE";
    value = SUNSENSOR_LDR3 + SUNSENSOR_offset_droite;
    oppositvalue = SUNSENSOR_LDR0 + SUNSENSOR_offset_gauche;
  }
  
  //Debug mouvement horizontal
  SUNSENSOR_debug_lcd_direction (value, oppositvalue, move_direction);

  //Si on doit orienter vers le bas
  if (((SUNSENSOR_LDR2 + SUNSENSOR_offset_bas)-(SUNSENSOR_LDR1 + SUNSENSOR_offset_haut)) > SUNSENSOR_delta_haut_bas) {
    Serial.println("SUNSENSOR - Aller en bas !");
    move_direction = "BAS    | haut";
    value = SUNSENSOR_LDR2 + SUNSENSOR_offset_bas;
    oppositvalue = SUNSENSOR_LDR1 + SUNSENSOR_offset_haut;
  }
 
  //Si on doit orienter vers le haut
  if (((SUNSENSOR_LDR1 + SUNSENSOR_offset_haut)-(SUNSENSOR_LDR2 + SUNSENSOR_offset_bas)) > SUNSENSOR_delta_haut_bas) {
    Serial.println("SUNSENSOR - Aller en haut !");
    move_direction = "HAUT   | bas";
    value = SUNSENSOR_LDR1 + SUNSENSOR_offset_haut;
    oppositvalue = SUNSENSOR_LDR2 +  SUNSENSOR_offset_bas;
  }

  //Si on ne fait rien en vertical
  if ((((SUNSENSOR_LDR2 + SUNSENSOR_offset_bas)-(SUNSENSOR_LDR1 + SUNSENSOR_offset_haut)) < SUNSENSOR_delta_haut_bas) && (((SUNSENSOR_LDR1 + SUNSENSOR_offset_haut)-(SUNSENSOR_LDR2 + SUNSENSOR_offset_bas)) < SUNSENSOR_delta_haut_bas)) {
    Serial.println("SUNSENSOR - Equilibre Bas - Haut atteint !");
    move_direction = "BAS    = HAUT";
    value = SUNSENSOR_LDR2 + SUNSENSOR_offset_bas;
    oppositvalue = SUNSENSOR_LDR1 + SUNSENSOR_offset_haut;   
  }

  //Debug mouvement vertical
  SUNSENSOR_debug_lcd_direction (value, oppositvalue, move_direction);
  Serial.println();

}

//Fonction de debug qui affiche les différentes valeurs LDR et la direction à prendre
void SUNSENSOR_debug_lcd_direction(int value, int oppositvalue, String move_direction){

   lcd.setCursor(0, 0);
   String printed_move_direction = String(move_direction);
   lcd.print(printed_move_direction);
   lcd.setCursor(0, 1);
   lcd.print(value);
   lcd.setCursor(7, 1);
   lcd.print("|");
   lcd.setCursor(9, 1);
   lcd.print(oppositvalue);

   delay(1000);
   //Efface l'écran pour afficher un nouveau message
   lcd.clear(); 
   
}

//Fonction qui renvoie une couleur de ligne pour l'interface en fonction de la comparaison de deux valeurs
String INTERFACE_table_line_color(int value1, int value2){

  int delta=abs(value1-value2);
  if (delta<2){
      return String("lightgreen");
    }
    if ((delta>=2)&&(delta<=5)){
      return String("yellow");
    }
    if (delta>5){
      return String("red");
    }    

}

Please note that sunsensor mode is not fully implemented.

TRACKER_IndexPage.h :

#ifndef INDEXPAGE_H
#define INDEXPAGE_H

const char* indexpage = R"=====(
<!DOCTYPE HTML><html><head>
  <style>
  body {background: linear-gradient(#003,#77b5fe,#003);background-attachment:fixed;font-size:150%;text-align:center;width:100%;max-width:1000px;margin:auto;}
  a:link {color:#aaf;text-decoration: none;}
  a:visited {color:#ccf;text-decoration: none;}
  .tableau { background-color:white;display:inline-block;margin:auto;padding:4px;}
  table {border:10px inset azure;}
  td { text-align: left;padding:4px;}
  th { text-align: center;padding:4px;}
  h2{text-align:center;color:white;}
  .aqua { background-color:aqua;}
  .blue { background-color:#ddf;}
  .yellow { background-color:#ff8;}
  .red { background-color:#f88;}
  .lightgreen { background-color:lightgreen;}
  .titlebis { color:white;}
  .pied{display:flex;justify-content:space-between;font-size:14px;color:white;}
  .onglets{margin-top:4px;font-size:130%;}
  .boutonselec,.bouton {margin-left:20px;border:outset 4px grey;background-color:#333;border-radius:6px;padding-left:20px;padding-right:20px;display:inline-block;}
  .boutonselec{border:inset 8px azure;}
  </style>
  <title>SOLAR TRACKER V$TRACKER_VERSION$</title>
  <meta name="viewport" content="width=device-width, initial-scale=1">
  </head><body>
  <div class='onglets'><div class='boutonselec'><a href='/'>Accueil</a></div><div class='bouton'><a href='/param.html'>Param&egrave;tres</a></div></div>
  <h2>Traqueur Solaire</h2>
  <center><div class='titlebis'>$INTERFACE_tracker_selected_mode$</div>
  <div><div class='tableau'><table>
  <tr class='blue'><th></th><th>Requis</th><th>Actuel</th></tr>
  <tr class='$INTERFACE_azimuth_status_style$'><td>Azimuth</td><td>$INTERFACE_required_azimuth$&#176;</td><td>$TRACKER_actual_azimuth$&#176;</td></tr>
  <tr class='$INTERFACE_elevation_status_style$'><td>Elevation</td><td>$INTERFACE_required_elevation$&#176;</td><td>$TRACKER_actual_elevation$&#176;</td></tr>
  <tr class='$INTERFACE_smangle_status_style$'><td>Smart angle securite</td><td>$TRACKER_wind_smart_angle$&#176;</td><td>$TRACKER_actual_angle$&#176;</td></tr>
  </table></div></div>
  <br>
  <div class='titlebis'>Donn&eacute;es brutes</div>
  <div><div class='tableau'><table>
  <tr><td>Time:</td><td>$NTP_time$</td></tr>
  <tr><td>Azimuth soleil:</td><td>$SUN_azimuth$</td></tr>
  <tr><td>Elevation soleil:</td><td>$SUN_elevation$</td></tr>
  <tr><td>Azimuth traqueur:</td><td>$TRACKER_actual_azimuth$</td></tr>
  <tr><td>Elevation traqueur:</td><td>$TRACKER_actual_elevation$</td></tr>
  <tr><td>Temps deplacement Azimuth:</td><td>$L298N_azimuth_moved_duration$</td></tr>
  <tr><td>Butee OUEST:</td><td>$TRACKER_is_at_west_limit$</td></tr>
  <tr><td>Butee EST:</td><td>$TRACKER_is_at_east_limit$</td></tr>
  <tr><td>Temps deplacement Elevation:</td><td>$L298N_elevation_moved_duration$</td></tr>
  <tr><td>Butee HAUT:</td><td>$TRACKER_is_at_up_limit$</td></tr>
  <tr><td>Butee BAS:</td><td>$TRACKER_is_at_down_limit$</td></tr>
  <tr><td>Rafales OpenWeather:</td><td>$OPENWEATHER_wind_gust$</td></tr>
  <tr><td>Vent anemometre:</td><td>$ANEMO_wind_speed$</td></tr>
  <tr><td>Rafales anemometre:</td><td>$ANEMO_wind_gust$</td></tr>
  <tr><td>Tours anemometre:</td><td>$ANEMO_interrupt_counter$</td></tr>
  <tr><td>Voltage anemometre:</td><td>$ANEMO_analog_voltage$</td></tr>
  <tr><td>Rafales anemometre position securite:</td><td>$ANEMO_wind_gust_secupos$</td></tr>
  <tr><td>Smart angle securite:</td><td>$TRACKER_wind_smart_angle$</td></tr>
  </table></div></div></center>
  <br><br>
  <div class='pied'><div>Version : $TRACKER_VERSION$</div><div><a href='https://' >&#169;AlkaYoda</a></div></div>
<br></body></html>
)=====";

#endif

TRACKER_ParamPage.h :

#ifndef PRAMPAGE_H
#define PRAMPAGE_H

const char* parampage = R"=====(
<!DOCTYPE HTML><html><head>
  <style>
  body {background: linear-gradient(#003,#77b5fe,#003);background-attachment:fixed;font-size:150%;text-align:center;width:100%;max-width:1000px;margin:auto;}
  a:link {color:#aaf;text-decoration: none;}
  a:visited {color:#ccf;text-decoration: none;}
  .tableau { background-color:white;display:inline-block;margin:auto;padding:4px;}
  table {border:10px inset azure;}
  td { text-align: left;padding:4px;}
  th { text-align: center;padding:4px;}
  h2{text-align:center;color:white;}
  .aqua { background-color:aqua;}
  .blue { background-color:#ddf;}
  .yellow { background-color:#ff8;}
  .red { background-color:#f88;}
  .lightgreen { background-color:lightgreen;}
  .titlebis { color:white;}
  .pied{display:flex;justify-content:space-between;font-size:14px;color:white;}
  .onglets{margin-top:4px;font-size:130%;}
  .boutonselec,.bouton {margin-left:20px;border:outset 4px grey;background-color:#333;border-radius:6px;padding-left:20px;padding-right:20px;display:inline-block;}
  .boutonselec{border:inset 8px azure;}
  </style>
  <title>SOLAR TRACKER V$TRACKER_VERSION$</title>
  <meta name="viewport" content="width=device-width, initial-scale=1">
  </head><body>
  <div class='onglets'><div class='bouton'><a href='/'>Accueil</a></div><div class='boutonselec'><a href='/param.html'>Param&egrave;tres</a></div></div>
  <center><h2>Traqueur Solaire</h2>
  <div class='titlebis'>Param&egrave;tres</div>
  <div><div class='tableau'><table>
  <form action="/get">
    <tr><td>TR Selected Mode: </td><td><select name="TRACKER_selected_mode">
    <option value="0"$INTERFACE_selected_mode0_style$>0 - S&eacute;curit&eacute;</option>
    <option value="1"$INTERFACE_selected_mode1_style$>1 - Automatique SolarPosition</option>
    <option value="2"$INTERFACE_selected_mode2_style$>2 - Automatique SunSensor</option>
    <option value="3"$INTERFACE_selected_mode3_style$>3 - Statique</option>
    </select></td></tr>
    <tr><td>TR Security Mode : </td><td><select name="TRACKER_security_override">
    <option value="0"$INTERFACE_selected_secu0_style$>0 - OpenWeather + An&eacute;mom&egrave;tre</option>
    <option value="1"$INTERFACE_selected_secu1_style$>1 - Aucune s&eacute;curit&eacute;</option>
    <option value="2"$INTERFACE_selected_secu2_style$>2 - An&eacute;mom&egrave;tre seul</option>
    <option value="3"$INTERFACE_selected_secu3_style$>3 - OpenWeather seul</option>
    </select></td></tr>
    <tr><td>TR Anemometer Model : </td><td><select name="TRACKER_anemometer_model">
    <option value="0"$INTERFACE_selected_anemo0_style$>0 - Numerique - Compteur</option>
    <option value="1"$INTERFACE_selected_anemo1_style$>1 - Analogique - Voltage</option>
    </select></td></tr>      
    <tr><td>TR Static Mode Azimuth: </td><td><input type="text" name="TRACKER_static_mode_azimuth" value="$TRACKER_static_mode_azimuth$" ></td></tr>
    <tr><td>TR Static Mode Elevation: </td><td><input type="text" name="TRACKER_static_mode_elevation" value="$TRACKER_static_mode_elevation$" ></td></tr>
    <tr><td>TR Azimuth Start Move Duration (cs): </td><td><input type="text" name="TRACKER_azi_start_move_dur" value="$TRACKER_azi_start_move_dur$"></td></tr>
    <tr><td>TR Azimuth Max Move Duration: </td><td><input type="text" name="TRACKER_azi_max_move_dur" value="$TRACKER_azi_max_move_dur$"></td></tr>
    <tr><td>TR Azimuth Mini: </td><td><input type="text" name="TRACKER_azimuth_mini" value="$TRACKER_azimuth_mini$"></td></tr>
    <tr><td>TR Azimuth Maxi: </td><td><input type="text" name="TRACKER_azimuth_maxi" value="$TRACKER_azimuth_maxi$"></td></tr>
    <tr><td>TR Azimuth Minimal Move Duration: </td><td><input type="text" name="TRACKER_azimuth_min_mv_time" value="$TRACKER_azimuth_min_mv_time$"></td></tr>
    <tr><td>TR Elevation Max Move Duration: </td><td><input type="text" name="TRACKER_ele_max_move_dur" value="$TRACKER_ele_max_move_dur$"></td></tr>
    <tr><td>TR Elevation Mini (Angle): </td><td><input type="text" name="TRACKER_elevation_mini" value="$TRACKER_elevation_mini$"></td></tr>
    <tr><td>TR Elevation Maxi (Angle): </td><td><input type="text" name="TRACKER_elevation_maxi" value="$TRACKER_elevation_maxi$"></td></tr>
    <tr><td>TR Elevation Minimal Move Duration: </td><td><input type="text" name="TRACKER_elevation_min_mv_time" value="$TRACKER_elevation_min_mv_time$"></td></tr>
    <tr><td>TR Vertical Speed: </td><td><input type="text" name="TRACKER_vertical_speed" value="$TRACKER_vertical_speed$"></td></tr>
    <tr><td>TR Secu Vertical Speed: </td><td><input type="text" name="TRACKER_secu_vertical_speed" value="$TRACKER_secu_vertical_speed$"></td></tr>
    <tr><td>TR Horizont Speed: </td><td><input type="text" name="TRACKER_horizontal_speed" value="$TRACKER_horizontal_speed$"></td></tr>
    <tr><td>TR Wind Intermediate Angle: </td><td><input type="text" name="TRACKER_wind_inter_angle" value="$TRACKER_wind_inter_angle$"></td></tr>
    <tr><td>TR Wind Limit Time: </td><td><input type="text" name="TRACKER_wind_limit_time" value="$TRACKER_wind_limit_time$"></td></tr>
    <tr><td>OW Wind Limit: </td><td><input type="text" name="OPENWEATHER_wind_limit" value="$OPENWEATHER_wind_limit$"></td></tr>
    <tr><td>OW Wind Intermediate Limit: </td><td><input type="text" name="OPENWEATHER_wind_inter_limit" value="$OPENWEATHER_wind_inter_limit$"></td></tr>
    <tr><td>OW Wind Smart Coeff: </td><td><input type="text" name="OPENWEATHER_wind_smart_coeff" value="$OPENWEATHER_wind_smart_coeff$"></td></tr>
    <tr><td>AM Wind Limit: </td><td><input type="text" name="ANEMO_wind_limit" value="$ANEMO_wind_limit$"></td></tr>
    <tr><td>AM Wind Intermediate Limit: </td><td><input type="text" name="ANEMO_wind_inter_limit" value="$ANEMO_wind_inter_limit$"></td></tr>
    <tr><td>AM Wind Smart Coeff: </td><td><input type="text" name="ANEMO_wind_smart_coeff" value="$ANEMO_wind_smart_coeff$"></td></tr>
    <tr><td>AM Digital Record Time: </td><td><input type="text" name="ANEMO_record_time" value="$ANEMO_record_time$"></td></tr>
    <tr><td>AM Analog Voltage Coeff: </td><td><input type="text" name="ANEMO_analog_coefficient" value="$ANEMO_analog_coefficient$"></td></tr>
    <tr><td>SS Offset Droite: </td><td><input type="text" name="SUNSENSOR_offset_droite" value="$SUNSENSOR_offset_droite$"></td></tr>
    <tr><td>SS Offset Gauche: </td><td><input type="text" name="SUNSENSOR_offset_gauche" value="$SUNSENSOR_offset_gauche$"></td></tr>
    <tr><td>SS Offset Haut: </td><td><input type="text" name="SUNSENSOR_offset_haut" value="$SUNSENSOR_offset_haut$"></td></tr>
    <tr><td>SS Offset Bas: </td><td><input type="text" name="SUNSENSOR_offset_bas" value="$SUNSENSOR_offset_bas$"></td></tr>
    <tr><td>SS Delta Haut Bas: </td><td><input type="text" name="SUNSENSOR_delta_haut_bas" value="$SUNSENSOR_delta_haut_bas$"></td></tr>
    <tr><td>SS Delta Droite Gauche: </td><td><input type="text" name="SUNSENSOR_delta_droite_gauche" value="$SUNSENSOR_delta_droite_gauche$"></td></tr>
    <tr><td><input type="checkbox" name="INTERFACE_restart_on_save" value="1">Redemarrer apres sauvegarde</td></tr>
    <tr><td></td><td><input type="password" name="TRACKER_password" value=""></td></tr><tr><td></td><td><input type="submit" value="Sauvegarder"></td></tr>
  </form></table></div></div></center>
  <br><br>
  
  
  
  <div class='pied'><div>Version : $TRACKER_VERSION$</div><div><a href='https://' >&#169;AlkaYoda</a></div></div>
<br></body></html>
)=====";

#endif

TRACKER_Parameters.h

#define TRACKER_HOSTNAME "SOLAR_TRACKER"
#define TRACKER_VERSION "4.2"
#define SECRET_WIFI_SSID "YOUR SSID"
#define SECRET_WIFI_PASSWORD "YOUR WIFI PASSWORD"
#define SECRET_SETUP_PASSWORD "YOUR SECRET PASSWORD FOR CONFIG"
#define TRACKER_LOCATION_LATITUDE YOUR_LATITUDE
#define TRACKER_LOCATION_LONGITUDE YOUR_LONGITUDE
#define TRACKER_NTP_SERVER "pool.ntp.org"
#define MQTT_BROKER_IP "YOUR_MQTT_BROKER_IP"
#define MQTT_USERNAME "YOUR_MQTT_USERNAME"
#define MQTT_PASSWORD "YOUR_MQTT_PASSWORD"
#define OPENWEATHER_MAP_API_KEY "YOUR_OPENWEATHER_API_KEY"
#define OPENWEATHER_CITY_NAME "YOUR_OPENWEATHER_CITY_NAME"
#define OPENWEATHER_COUNTRY_CODE "YOUR_OPENWEATHER_COUNTRY_CODE"

Compiled with Arduino IDE 1.8

Last settings not available using buttons, prefer web interface for set up.

WARNING : for security reasons you musn’t expose you solar tracker directly to the internet ! Use a vpn if you want to access to your device remotely.

do-it.dev Avatar
if you liked it, please contribute !

Leave a Reply

Your email address will not be published. Required fields are marked *

Aurélien Bordinat

I am a french computer engineer, adept of DIY, home automation and new technologies. When i’m not busy trail running, i spend some time prototyping.