Stuff™️

master
Vinícius W 1 year ago
parent 3dc5d73cf0
commit 246f9e7c42

@ -1,21 +1,18 @@
#include "comm.h" #include "comm.h"
#include <ArduinoOTA.h>
#include <WiFiSettings.h>
void CommunicationsController::initota() {
void setup_ota() {
ArduinoOTA.setHostname(WIFI_SSID); ArduinoOTA.setHostname(WIFI_SSID);
ArduinoOTA.setPassword(WIFI_PASSWORD); ArduinoOTA.setPassword(WIFI_PASSWORD);
ArduinoOTA.begin(); ArduinoOTA.begin();
} }
void setup_wifi() { void CommunicationsController::init_wifi() {
WiFiSettings.hostname = WIFI_SSID; WiFiSettings.hostname = WIFI_SSID;
WiFiSettings.password = WIFI_PASSWORD; WiFiSettings.password = WIFI_PASSWORD;
WiFiSettings.onPortal = []() { WiFiSettings.onPortal = []() {
setup_ota(); ota();
}; };
WiFiSettings.onPortalWaitLoop = []() { WiFiSettings.onPortalWaitLoop = []() {
ArduinoOTA.handle(); ArduinoOTA.handle();
@ -24,13 +21,50 @@ void setup_wifi() {
WiFiSettings.connect(); WiFiSettings.connect();
} }
void setup_comm() { void CommunicationsController::init() {
setup_wifi(); ota();
setup_ota(); wifi();
WebMonitor.begin(); WebMonitor.begin();
} }
void comms_loop() { void CommunicationsController::process() {
ArduinoOTA.handle(); ArduinoOTA.handle();
if (!l4s) {
return;
}
if (l4s.connected()) {
handle_client();
} else {
create_connection();
}
}
void CommunicationsController::handle_client() {
l4s.flush();
recv = recv();
Serial.println(recv);
}
void CommunicationsController::parseLook4Sat(float* azimuth, float* altitude) {
azimuth = recv.substring();
altitude = recv.substring(); //TODO
}
void CommunicationsController::create_connection() {
l4s = l4sServer.accept();
} }
String CommunicationsController::recv() {
String rec = "";
while (l4s.available()) {
rec += (char)(l4s.read());
}
if (rec.length() == 0) {
rec = "Ç";
}
return rec;
}

@ -1,10 +1,33 @@
#include <ArduinoOTA.h>
#include <WebMonitor.h> #include <WebMonitor.h>
#include <ESP8266WiFi.h>
#include <WiFiSettings.h>
#define L4S_PORT 4533
#define WIFI_SSID "VynTracker" #define WIFI_SSID "VynTracker"
#define WIFI_PASSWORD "senha1234" #define WIFI_PASSWORD "senha1234"
void setup_ota();
void setup_wifi();
void setup_comm();
void comms_loop(); #ifndef COMM_H
#define COMM_H
class CommunicationsController {
private:
String recv;
WifiClient l4s;
WifiServer l4sServer(L4S_PORT);
void recv();
void init_ota();
void init_wifi();
void handle_client();
void create_connection();
public:
void init();
void process();
void parseLook4Sat(float* azimuth, float* altitude);
}
#endif

@ -5,12 +5,14 @@
#include <LittleFS.h> #include <LittleFS.h>
ServoController controller; ServoController controller;
CommunicationsController comms;
void setup() { void setup() {
LittleFS.begin();
comms.init();
controller.initServos(); controller.initServos();
controller.initMag(); controller.initMag();
LittleFS.begin();
setup_comm();
pinMode(15, OUTPUT); pinMode(15, OUTPUT);
pinMode(12, OUTPUT); pinMode(12, OUTPUT);
@ -20,14 +22,6 @@ void setup() {
} }
void loop() { void loop() {
comms_loop(); comms.process();
controller.updateHeading(); controller.updateHeading();
digitalWrite(15, 1);
WebMonitor.printf("ON!");
delay(1000);
digitalWrite(15, 0);
WebMonitor.printf("OFF!");
delay(1000);
} }

@ -1,5 +1,4 @@
#include "servo.h" #include "servo.h"
#include <WebMonitor>
void ServoController::initServos() { void ServoController::initServos() {
@ -34,7 +33,7 @@ void ServoController::initMag() {
WebMonitor.print("Sample: "); WebMonitor.print("Sample: ");
WebMonitor.println(mag.getSamples()); WebMonitor.println(mag.getSamples());
mag.setDeclination(DECLINATION); mag.setDeclinationAngle(DECLINATION);
WebMonitor.print("Declinação: "); WebMonitor.print("Declinação: ");
WebMonitor.println(DECLINATION); WebMonitor.println(DECLINATION);
} else { } else {
@ -45,7 +44,20 @@ void ServoController::initMag() {
} }
void ServoController::updateHeading() { 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 = 0;
for (byte i = 0; i < HEADING_BUFFER_LENGTH; i++) {
headingDegrees += headingBuffer[i];
}
headingDegrees /= HEADING_BUFFER_LENGTH;
} }
void ServoController::moveToAzAlt() { void ServoController::moveToAzAlt() {

@ -1,14 +1,18 @@
#include <Servo> #include <Servo.h>
#include <DFRobot_QMC5883> #include <WebMonitor.h>
#include <DFRobot_QMC5883.h>
#define DECLINATION -0.353429173528852 #define DECLINATION -0.353429173528852
#define HEADING_BUFFER_LENGTH 16
#ifndef SERVO_H #ifndef SERVO_H
#define SERVO_H #define SERVO_H
class ServoController { class ServoController {
private: private:
float headingDegress; int headingDegrees;
byte bufferPos = 0;
float headingBuffer[HEADING_BUFFER_LENGTH];
Servo HrzSrv; Servo HrzSrv;
Servo VrtSrv; Servo VrtSrv;

Loading…
Cancel
Save