look4sat communication, finally!

master
Vinícius W 1 year ago
parent e5ece399e8
commit 95a2a82111

@ -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

@ -21,33 +21,49 @@ void CommunicationsController::initWifi() {
void CommunicationsController::init() {
initOta();
initWifi();
WebMonitor.begin();
}
void CommunicationsController::process() {
ArduinoOTA.handle();
while (WiFi.status() != WL_CONNECTED);
if (!l4s) {
return;
WebMonitor.begin();
l4sServer.begin();
}
if (l4s.connected()) {
byte CommunicationsController::process(float *azimuth, float *altitude) {
ArduinoOTA.handle();
create_connection();
if (l4s) {
while (l4s.connected()) {
handle_client();
} else {
create_connection();
byte resp = parseLook4Sat(azimuth, altitude);
ArduinoOTA.handle();
if (resp == 1) {
return 1;
}
}
}
return 0;
}
void CommunicationsController::handle_client() {
l4s.flush();
received = recv();
WebMonitor.println(received);
}
void CommunicationsController::parseLook4Sat(float* azimuth, float* altitude) {
*azimuth = received.substring(0, 3).toFloat();
*altitude = received.substring(3, 6).toFloat(); //TODO
byte CommunicationsController::parseLook4Sat(float* azimuth, float* altitude) {
String tmp = received.substring(9);
int spaceIndex = tmp.indexOf(' ');
if (spaceIndex != -1) {
*azimuth = tmp.substring(0, spaceIndex).toFloat();
*altitude = tmp.substring(spaceIndex+1).toFloat();
return 1;
}
return 0;
}
void CommunicationsController::create_connection() {

@ -12,9 +12,11 @@
#ifndef COMM_H
#define COMM_H
class CommunicationsController {
private:
String received;
String received = "Ç";
WiFiClient l4s;
WiFiServer l4sServer{L4S_PORT};
@ -26,8 +28,8 @@ class CommunicationsController {
public:
void init();
void process();
void parseLook4Sat(float* azimuth, float* altitude);
byte process(float* azimuth, float* altitude);
byte parseLook4Sat(float* azimuth, float* altitude);
};
#endif

@ -21,7 +21,19 @@ void setup() {
delay(1000);
}
float azimuth = 0.0;
float altitude = 0.0;
void loop() {
comms.process();
byte resp = comms.process(&azimuth, &altitude);
if (resp != 1) {
return;
}
controller.updateHeading();
WebMonitor.println(azimuth);
WebMonitor.println(altitude);
controller.moveToAzAlt(azimuth, altitude);
}

@ -5,6 +5,7 @@ void ServoController::initServos() {
HrzSrv.attach(12, 500, 2500);
delay(50); // Espera 50ms para o motor se mover
VrtSrv.attach(13, 500, 2500);
delay(50);
}
void ServoController::initMag() {
@ -60,7 +61,7 @@ void ServoController::updateHeading() {
headingDegrees /= HEADING_BUFFER_LENGTH;
}
void ServoController::moveToAzAlt() {
void ServoController::moveToAzAlt(float azimuth, float altitude) {
}

@ -21,7 +21,7 @@ class ServoController {
public:
void initServos();
void initMag();
void moveToAzAlt();
void moveToAzAlt(float azimuth, float altitude);
void moveToRADec();
void updateHeading();
};

Loading…
Cancel
Save