From 0d951f3174f938c08aa5f3af6f16447c4220dcf5 Mon Sep 17 00:00:00 2001
From: Vynwg <me@vynwg.com>
Date: Sun, 26 Nov 2023 20:12:21 -0300
Subject: [PATCH] Remove heading filter

---
 platformio.ini |  2 +-
 src/comm.cpp   |  3 ++-
 src/main.cpp   |  4 +---
 src/servo.cpp  | 18 +++++++-----------
 src/servo.h    |  3 ---
 5 files changed, 11 insertions(+), 19 deletions(-)

diff --git a/platformio.ini b/platformio.ini
index 6ef56c1..30b2219 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -17,4 +17,4 @@ lib_deps =
 	dfrobot/DFRobot_QMC5883@^1.0.0
 	juerd/ESP-WiFiSettings@^3.8.0
 	https://github.com/sivar2311/WebMonitor
-upload_flags = --auth=senha1234
+;upload_flags = --auth=senha1234
diff --git a/src/comm.cpp b/src/comm.cpp
index 1597c8b..a0963e7 100644
--- a/src/comm.cpp
+++ b/src/comm.cpp
@@ -34,9 +34,10 @@ byte CommunicationsController::process(float *azimuth, float *altitude) {
 
     if (l4s) {
         while (l4s.connected()) {
+            ArduinoOTA.handle();
+            
             handle_client();
             byte resp = parseLook4Sat(azimuth, altitude);
-            ArduinoOTA.handle();
 
             if (resp == 1) {
                 return 1;
diff --git a/src/main.cpp b/src/main.cpp
index ca91fe9..93dd7d6 100644
--- a/src/main.cpp
+++ b/src/main.cpp
@@ -6,7 +6,6 @@
 
 ServoController controller;
 CommunicationsController comms;
-
 void setup() {
     LittleFS.begin();
     comms.init();
@@ -32,8 +31,7 @@ void loop() {
     }
 
     controller.updateHeading();
-
+    controller.moveToAzAlt(azimuth, altitude);
     WebMonitor.println(azimuth);
     WebMonitor.println(altitude);
-    controller.moveToAzAlt(azimuth, altitude);
 }
diff --git a/src/servo.cpp b/src/servo.cpp
index 0582d04..9b59340 100644
--- a/src/servo.cpp
+++ b/src/servo.cpp
@@ -6,6 +6,11 @@ void ServoController::initServos() {
     delay(50); // Espera 50ms para o motor se mover
     VrtSrv.attach(13,  500, 2500);
     delay(50);
+
+    HrzSrv.write(0);
+    delay(50);
+    VrtSrv.write(0);
+    delay(50);
 }
 
 void ServoController::initMag() {
@@ -47,18 +52,9 @@ void ServoController::initMag() {
 void ServoController::updateHeading() {
     mag.getHeadingDegrees();
     sVector_t raw = mag.readRaw();
-    float tmp = raw.HeadingDegress;
-    
-    headingBuffer[bufferPos++] = tmp;
-    if (bufferPos > HEADING_BUFFER_LENGTH) {
-        bufferPos = 0;
-    }
+    headingDegrees = raw.HeadingDegress;
 
-    headingDegrees = 0;
-    for (byte i = 0; i < HEADING_BUFFER_LENGTH; i++) {
-        headingDegrees += headingBuffer[i];
-    }
-    headingDegrees /= HEADING_BUFFER_LENGTH;
+    WebMonitor.println(headingDegrees);
 }
 
 void ServoController::moveToAzAlt(float azimuth, float altitude) {
diff --git a/src/servo.h b/src/servo.h
index 07474bd..da603c3 100644
--- a/src/servo.h
+++ b/src/servo.h
@@ -3,7 +3,6 @@
 #include <DFRobot_QMC5883.h>
 
 #define DECLINATION -0.353429173528852
-#define HEADING_BUFFER_LENGTH 16
 
 #ifndef SERVO_H
 #define SERVO_H
@@ -11,8 +10,6 @@
 class ServoController {
     private:
         int headingDegrees;
-        byte bufferPos = 0;
-        float headingBuffer[HEADING_BUFFER_LENGTH];
 
         Servo HrzSrv;
         Servo VrtSrv;