Tbeam test initial commit

This commit is contained in:
richonguzman 2024-07-25 13:35:49 -04:00
parent 5b3550300e
commit 7e26e97a12
10 changed files with 71 additions and 58 deletions

View File

@ -52,6 +52,7 @@ build_flags =
-DHAS_SX1278
-DHAS_AXP2101
-DHAS_BT_CLASSIC
-DHAS_GPS_CTRL
lib_deps =
${common.lib_deps}
lewisxhe/XPowersLib @ 0.2.4
@ -68,6 +69,7 @@ build_flags =
-DHAS_SX1276
-DHAS_AXP2101
-DHAS_BT_CLASSIC
-DHAS_GPS_CTRL
lib_deps =
${common.lib_deps}
lewisxhe/XPowersLib @ 0.2.4
@ -85,6 +87,7 @@ build_flags =
-DHAS_SX1262
-DHAS_AXP2101
-DHAS_BT_CLASSIC
-DHAS_GPS_CTRL
lib_deps =
${common.lib_deps}
lewisxhe/XPowersLib @ 0.2.4
@ -102,6 +105,7 @@ build_flags =
-DHAS_SX1278
-DHAS_AXP192
-DHAS_BT_CLASSIC
-DHAS_GPS_CTRL
lib_deps =
${common.lib_deps}
lewisxhe/XPowersLib @ 0.2.4
@ -118,6 +122,7 @@ build_flags =
-DHAS_SX1276
-DHAS_AXP192
-DHAS_BT_CLASSIC
-DHAS_GPS_CTRL
lib_deps =
${common.lib_deps}
lewisxhe/XPowersLib @ 0.2.4
@ -135,6 +140,7 @@ build_flags =
-DHAS_SX1268
-DHAS_AXP192
-DHAS_BT_CLASSIC
-DHAS_GPS_CTRL
lib_deps =
${common.lib_deps}
lewisxhe/XPowersLib @ 0.2.4

View File

@ -95,7 +95,6 @@ APRSPacket lastReceivedPacket;
logging::Logger logger;
//#define DEBUG
bool gpsSleepActive = true; // currentBeacon->gpsEcoMode // true!
extern bool gpsIsActive;
void setup() {

View File

@ -29,6 +29,7 @@ void Configuration::readFile(fs::FS &fs, const char *fileName) {
bcn.callsign = BeaconsArray[i]["callsign"].as<String>();
bcn.callsign.toUpperCase();
bcn.gpsEcoMode = BeaconsArray[i]["gpsEcoMode"].as<bool>();
bcn.symbol = BeaconsArray[i]["symbol"].as<String>();
bcn.overlay = BeaconsArray[i]["overlay"].as<String>();
bcn.micE = BeaconsArray[i]["micE"].as<String>();

View File

@ -8,6 +8,7 @@
class Beacon {
public:
String callsign;
bool gpsEcoMode;
String symbol;
String overlay;
String micE;

View File

@ -327,7 +327,7 @@ void startupScreen(uint8_t index, const String& version) {
case 1: workingFreq += "PL]"; break;
case 2: workingFreq += "UK]"; break;
}
show_display(" LoRa APRS", " (TRACKER)", workingFreq, "", "", " CA2RXU / " + version, 4000);
show_display(" LoRa APRS", " (TRACKER)", workingFreq, "", "", " CA2RXU " + version, 4000);
#ifdef HAS_TFT
cleanTFT();
#endif

View File

@ -76,7 +76,7 @@ namespace GPS_Utils {
sendUpdate = true;
sendStandingUpdate = false;
} else {
if (currentBeacon->gpsEcoMode) {
//
Serial.print("minTxDistance not achieved : ");
Serial.println(lastTxDistance);
@ -86,6 +86,7 @@ namespace GPS_Utils {
}
}
}
}
void calculateHeadingDelta(int speed) {
uint8_t TurnMinAngle;

View File

@ -6,8 +6,9 @@
#include "winlink_utils.h"
#include "station_utils.h"
#include "configuration.h"
#include "power_utils.h"
#include "boards_pinout.h"
#include "power_utils.h"
#include "sleep_utils.h"
#include "msg_utils.h"
#include "display.h"
@ -50,6 +51,7 @@ extern String winlinkBody;
extern String winlinkAlias;
extern String winlinkAliasComplete;
extern bool winlinkCommentState;
extern bool gpsIsActive;
extern std::vector<String> outputMessagesBuffer;
@ -160,6 +162,7 @@ namespace KEYBOARD_Utils {
if (menuDisplay == 0) {
if (displayState) {
sendUpdate = true;
if (!gpsIsActive) SLEEP_Utils::gpsWakeUp();
} else {
display_toggle(true);
displayTime = millis();

View File

@ -1,8 +1,9 @@
#include "configuration.h"
#include "sleep_utils.h"
#include "power_utils.h"
extern bool gpsSleepActive; // currentBeacon->gpsEcoMode // true!
extern Beacon *currentBeacon;
extern uint32_t lastGPSTime;
extern bool gpsIsActive;
@ -10,24 +11,26 @@ extern bool gpsIsActive;
namespace SLEEP_Utils {
void gpsSleep() {
if (gpsSleepActive && gpsIsActive) {
#ifdef HAS_GPS_CTRL
if (currentBeacon->gpsEcoMode && gpsIsActive) {
POWER_Utils::deactivateGPS();
lastGPSTime = millis();
//
Serial.println("GPS SLEEPING");
//
}
#endif
}
void gpsWakeUp() {
if (gpsSleepActive && !gpsIsActive) {
#ifdef HAS_GPS_CTRL
if (currentBeacon->gpsEcoMode && !gpsIsActive) {
POWER_Utils::activateGPS();
//
Serial.println("GPS WAKEUP");
//
}
#endif
}
}

View File

@ -37,7 +37,6 @@ extern uint8_t winlinkStatus;
extern bool winlinkCommentState;
extern int wxModuleType;
extern bool gpsSleepActive; // currentBeacon->gpsEcoMode // true!
extern bool gpsIsActive;
bool sendStandingUpdate = false;
@ -284,7 +283,7 @@ namespace STATION_Utils {
#ifdef HAS_TFT
cleanTFT();
#endif
if (gpsSleepActive) { // currentBeacon->gpsEcoMode // true!
if (currentBeacon->gpsEcoMode) { // currentBeacon->gpsEcoMode // true!
SLEEP_Utils::gpsSleep();
}
}