fix clang (except logger)

This commit is contained in:
Peter Buchegger 2021-10-14 22:31:56 +01:00
parent 5b1be61032
commit 8e262785b7
7 changed files with 731 additions and 830 deletions

View file

@ -1,22 +1,22 @@
#include <APRS-Decoder.h>
#include <Arduino.h>
#include <LoRa.h>
#include <APRS-Decoder.h>
#include <TinyGPS++.h>
#include <TimeLib.h>
#include <WiFi.h>
#include <OneButton.h>
#include <TimeLib.h>
#include <TinyGPS++.h>
#include <WiFi.h>
#include <logger.h>
#include "configuration.h"
#include "display.h"
#include "pins.h"
#include "power_management.h"
#include "configuration.h"
Configuration Config;
#include "power_management.h"
PowerManagement powerManagement;
OneButton userButton = OneButton(BUTTON_PIN, true, true);
#include "logger.h"
HardwareSerial ss(1);
TinyGPSPlus gps;
@ -35,21 +35,20 @@ String getSmartBeaconState();
String padding(unsigned int number, unsigned int width);
static bool send_update = true;
static void handle_tx_click();
static void handle_tx_click() {
send_update = true;
}
// cppcheck-suppress unusedFunction
void setup()
{
void setup() {
Serial.begin(115200);
#ifdef TTGO_T_Beam_V1_0
Wire.begin(SDA, SCL);
if (!powerManagement.begin(Wire))
{
if (!powerManagement.begin(Wire)) {
logPrintlnI("AXP192 init done!");
}
else
{
} else {
logPrintlnE("AXP192 init failed!");
}
powerManagement.activateLoRa();
@ -68,8 +67,7 @@ void setup()
setup_gps();
setup_lora();
if (Config.ptt.active)
{
if (Config.ptt.active) {
pinMode(Config.ptt.io_pin, OUTPUT);
digitalWrite(Config.ptt.io_pin, Config.ptt.reverse ? HIGH : LOW);
}
@ -78,8 +76,7 @@ void setup()
WiFi.mode(WIFI_OFF);
btStop();
if (Config.beacon.button_tx)
{
if (Config.beacon.button_tx) {
// attach TX action to user button (defined by BUTTON_PIN)
userButton.attachClick(handle_tx_click);
}
@ -91,23 +88,17 @@ void setup()
}
// cppcheck-suppress unusedFunction
void loop()
{
void loop() {
userButton.tick();
if(Config.debug)
{
while(Serial.available() > 0)
{
if (Config.debug) {
while (Serial.available() > 0) {
char c = Serial.read();
// Serial.print(c);
gps.encode(c);
}
}
else
{
while(ss.available() > 0)
{
} else {
while (ss.available() > 0) {
char c = ss.read();
// Serial.print(c);
gps.encode(c);
@ -122,24 +113,18 @@ void loop()
static double previousHeading = 0;
static unsigned int rate_limit_message_text = 0;
if(gps.time.isValid())
{
if (gps.time.isValid()) {
setTime(gps.time.hour(), gps.time.minute(), gps.time.second(), gps.date.day(), gps.date.month(), gps.date.year());
if(gps_loc_update && nextBeaconTimeStamp <= now())
{
if (gps_loc_update && nextBeaconTimeStamp <= now()) {
send_update = true;
if (Config.smart_beacon.active)
{
if (Config.smart_beacon.active) {
currentHeading = gps.course.deg();
// enforce message text on slowest Config.smart_beacon.slow_rate
rate_limit_message_text = 0;
}
else
{
} else {
// enforce message text every n's Config.beacon.timeout frame
if (Config.beacon.timeout * rate_limit_message_text > 30)
{
if (Config.beacon.timeout * rate_limit_message_text > 30) {
rate_limit_message_text = 0;
}
}
@ -166,39 +151,32 @@ void loop()
}
#endif
if(!send_update && gps_loc_update && Config.smart_beacon.active)
{
if (!send_update && gps_loc_update && Config.smart_beacon.active) {
uint32_t lastTx = millis() - lastTxTime;
currentHeading = gps.course.deg();
lastTxdistance = TinyGPSPlus::distanceBetween(gps.location.lat(), gps.location.lng(), lastTxLat, lastTxLng);
if(lastTx >= txInterval)
{
if (lastTx >= txInterval) {
// Trigger Tx Tracker when Tx interval is reach
// Will not Tx if stationary bcos speed < 5 and lastTxDistance < 20
if (lastTxdistance > 20)
{
if (lastTxdistance > 20) {
send_update = true;
}
}
if (!send_update)
{
if (!send_update) {
// Get headings and heading delta
double headingDelta = abs(previousHeading - currentHeading);
if(lastTx > Config.smart_beacon.min_bcn * 1000)
{
if (lastTx > Config.smart_beacon.min_bcn * 1000) {
// Check for heading more than 25 degrees
if(headingDelta > Config.smart_beacon.turn_min && lastTxdistance > Config.smart_beacon.min_tx_dist)
{
if (headingDelta > Config.smart_beacon.turn_min && lastTxdistance > Config.smart_beacon.min_tx_dist) {
send_update = true;
}
}
}
}
if(send_update && gps_loc_update)
{
if (send_update && gps_loc_update) {
send_update = false;
nextBeaconTimeStamp = now() + (Config.smart_beacon.active ? Config.smart_beacon.slow_rate : (Config.beacon.timeout * SECS_PER_MIN));
@ -221,55 +199,48 @@ void loop()
String alt = "";
int alt_int = max(-99999, min(999999, (int)gps.altitude.feet()));
if (alt_int < 0)
{
if (alt_int < 0) {
alt = "/A=-" + padding(alt_int * -1, 5);
}
else
{
} else {
alt = "/A=" + padding(alt_int, 6);
}
String course_and_speed = "";
int speed_int = max(0, min(999, (int)gps.speed.knots()));
if (speed_zero_sent < 3)
{
if (speed_zero_sent < 3) {
String speed = padding(speed_int, 3);
int course_int = max(0, min(360, (int)gps.course.deg()));
/* course in between 1..360 due to aprs spec */
if (course_int == 0)
{
if (course_int == 0) {
course_int = 360;
}
String course = padding(course_int, 3);
course_and_speed = course + "/" + speed;
}
if (speed_int == 0)
{
if (speed_int == 0) {
/* speed is 0.
we send 3 packets with speed zero (so our friends know we stand still).
After that, we save airtime by not sending speed/course 000/000.
Btw, even if speed we really do not move, measured course is changeing (-> no useful / even wrong info)
Btw, even if speed we really do not move, measured course is changeing
(-> no useful / even wrong info)
*/
if (speed_zero_sent < 3)
{
if (speed_zero_sent < 3) {
speed_zero_sent += 1;
}
}
else
{
} else {
speed_zero_sent = 0;
}
String aprsmsg;
aprsmsg = "!" + lat + Config.beacon.overlay + lng + Config.beacon.symbol + course_and_speed + alt;
// message_text every 10's packet (i.e. if we have beacon rate 1min at high speed -> every 10min). May be enforced above (at expirey of smart beacon rate (i.e. every 30min), or every third packet on static rate (i.e. static rate 10 -> every third packet)
if (!(rate_limit_message_text++ % 10))
{
// message_text every 10's packet (i.e. if we have beacon rate 1min at high
// speed -> every 10min). May be enforced above (at expirey of smart beacon
// rate (i.e. every 30min), or every third packet on static rate (i.e.
// static rate 10 -> every third packet)
if (!(rate_limit_message_text++ % 10)) {
aprsmsg += Config.beacon.message;
}
if (BatteryIsConnected)
{
if (BatteryIsConnected) {
aprsmsg += " - _Bat.: " + batteryVoltage + "V - Cur.: " + batteryChargeCurrent + "mA";
}
@ -282,8 +253,7 @@ void loop()
logPrintlnD(data);
show_display("<< TX >>", data);
if (Config.ptt.active)
{
if (Config.ptt.active) {
digitalWrite(Config.ptt.io_pin, Config.ptt.reverse ? LOW : HIGH);
delay(Config.ptt.start_delay);
}
@ -297,8 +267,7 @@ void loop()
LoRa.write((const uint8_t *)data.c_str(), data.length());
LoRa.endPacket();
if (Config.smart_beacon.active)
{
if (Config.smart_beacon.active) {
lastTxLat = gps.location.lat();
lastTxLng = gps.location.lng();
previousHeading = currentHeading;
@ -306,69 +275,58 @@ void loop()
lastTxTime = millis();
}
if (Config.ptt.active)
{
if (Config.ptt.active) {
delay(Config.ptt.end_delay);
digitalWrite(Config.ptt.io_pin, Config.ptt.reverse ? HIGH : LOW);
}
}
if(gps_time_update)
{
show_display(Config.callsign,
createDateString(now()) + " " + createTimeString(now()),
String("Sats: ") + gps.satellites.value() + " HDOP: " + gps.hdop.hdop(),
String("Nxt Bcn: ") + (Config.smart_beacon.active ? "~" : "") + createTimeString(nextBeaconTimeStamp),
BatteryIsConnected ? (String("Bat: ") + batteryVoltage + "V, " + batteryChargeCurrent + "mA" ) : "Powered via USB",
String("Smart Beacon: " + getSmartBeaconState()) );
if (gps_time_update) {
show_display(Config.callsign, createDateString(now()) + " " + createTimeString(now()), String("Sats: ") + gps.satellites.value() + " HDOP: " + gps.hdop.hdop(), String("Nxt Bcn: ") + (Config.smart_beacon.active ? "~" : "") + createTimeString(nextBeaconTimeStamp), BatteryIsConnected ? (String("Bat: ") + batteryVoltage + "V, " + batteryChargeCurrent + "mA") : "Powered via USB", String("Smart Beacon: " + getSmartBeaconState()));
if(Config.smart_beacon.active)
{
if (Config.smart_beacon.active) {
// Change the Tx internal based on the current speed
int curr_speed = (int)gps.speed.kmph();
if(curr_speed < Config.smart_beacon.slow_speed)
{
if (curr_speed < Config.smart_beacon.slow_speed) {
txInterval = Config.smart_beacon.slow_rate * 1000;
}
else if(curr_speed > Config.smart_beacon.fast_speed)
{
} else if (curr_speed > Config.smart_beacon.fast_speed) {
txInterval = Config.smart_beacon.fast_rate * 1000;
}
else
{
} else {
/* Interval inbetween low and high speed
min(slow_rate, ..) because: if slow rate is 300s at slow speed <= 10km/h and fast rate is 60s at fast speed >= 100km/h
everything below current speed 20km/h (100*60/20 = 300) is below slow_rate.
-> In the first check, if curr speed is 5km/h (which is < 10km/h), tx interval is 300s, but if speed is 6km/h, we are landing in this section,
what leads to interval 100*60/6 = 1000s (16.6min) -> this would lead to decrease of beacon rate in between 5 to 20 km/h. what is even below
the slow speed rate.
min(slow_rate, ..) because: if slow rate is 300s at slow speed <=
10km/h and fast rate is 60s at fast speed >= 100km/h everything below
current speed 20km/h (100*60/20 = 300) is below slow_rate.
-> In the first check, if curr speed is 5km/h (which is < 10km/h), tx
interval is 300s, but if speed is 6km/h, we are landing in this
section, what leads to interval 100*60/6 = 1000s (16.6min) -> this
would lead to decrease of beacon rate in between 5 to 20 km/h. what
is even below the slow speed rate.
*/
txInterval = min(Config.smart_beacon.slow_rate, Config.smart_beacon.fast_speed * Config.smart_beacon.fast_rate / curr_speed) * 1000;
}
}
}
if ((Config.debug == false) && (millis() > 5000 && gps.charsProcessed() < 10))
{
logPrintlnE("No GPS frames detected! Try to reset the GPS Chip with this firmware: https://github.com/lora-aprs/TTGO-T-Beam_GPS-reset");
if ((Config.debug == false) && (millis() > 5000 && gps.charsProcessed() < 10)) {
logPrintlnE("No GPS frames detected! Try to reset the GPS Chip with this "
"firmware: https://github.com/lora-aprs/TTGO-T-Beam_GPS-reset");
}
}
void load_config()
{
void load_config() {
ConfigurationManagement confmg("/tracker.json");
Config = confmg.readConfiguration();
if(Config.callsign == "NOCALL-10")
{
logPrintlnE("You have to change your settings in 'data/tracker.json' and upload it via \"Upload File System image\"!");
show_display("ERROR", "You have to change your settings in 'data/tracker.json' and upload it via \"Upload File System image\"!");
while(true)
{}
if (Config.callsign == "NOCALL-10") {
logPrintlnE("You have to change your settings in 'data/tracker.json' and "
"upload it via \"Upload File System image\"!");
show_display("ERROR", "You have to change your settings in 'data/tracker.json' and "
"upload it via \"Upload File System image\"!");
while (true) {
}
}
}
void setup_lora()
{
void setup_lora() {
logPrintlnI("Set SPI pins!");
SPI.begin(LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS);
logPrintlnI("Set LoRa pins!");
@ -380,8 +338,8 @@ void setup_lora()
if (!LoRa.begin(freq)) {
logPrintlnE("Starting LoRa failed!");
show_display("ERROR", "Starting LoRa failed!");
while(true)
{}
while (true) {
}
}
LoRa.setSpreadingFactor(Config.lora.spreadingFactor);
LoRa.setSignalBandwidth(Config.lora.signalBandwidth);
@ -393,15 +351,15 @@ void setup_lora()
show_display("INFO", "LoRa init done!", 2000);
}
void setup_gps()
{
void setup_gps() {
ss.begin(9600, SERIAL_8N1, GPS_TX, GPS_RX);
}
char *s_min_nn(uint32_t min_nnnnn, int high_precision)
{
/* min_nnnnn: RawDegrees billionths is uint32_t by definition and is n'telth degree (-> *= 6 -> nn.mmmmmm minutes)
* high_precision: 0: round at decimal position 2. 1: round at decimal position 4. 2: return decimal position 3-4 as base91 encoded char
char *s_min_nn(uint32_t min_nnnnn, int high_precision) {
/* min_nnnnn: RawDegrees billionths is uint32_t by definition and is n'telth
* degree (-> *= 6 -> nn.mmmmmm minutes) high_precision: 0: round at decimal
* position 2. 1: round at decimal position 4. 2: return decimal position 3-4
* as base91 encoded char
*/
static char buf[6];
@ -423,52 +381,44 @@ char *s_min_nn(uint32_t min_nnnnn, int high_precision)
sprintf(buf, "%02u.%02u", (unsigned int)((min_nnnnn / 100000) % 100), (unsigned int)((min_nnnnn / 1000) % 100));
else
sprintf(buf, "%c", (char)((min_nnnnn % 1000) / 11) + 33);
// Like to verify? type in python for i.e. RawDegrees billions 566688333: i = 566688333; "%c" % (int(((i*.0006+0.5) % 100)/1.1) +33)
// Like to verify? type in python for i.e. RawDegrees billions 566688333: i =
// 566688333; "%c" % (int(((i*.0006+0.5) % 100)/1.1) +33)
return buf;
}
static void handle_tx_click()
{
send_update = true;
}
String create_lat_aprs(RawDegrees lat)
{
String create_lat_aprs(RawDegrees lat) {
char str[20];
char n_s = 'N';
if(lat.negative)
{
if (lat.negative) {
n_s = 'S';
}
// we like sprintf's float up-rounding.
// but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation ;)
// but sprintf % may round to 60.00 -> 5360.00 (53° 60min is a wrong notation
// ;)
sprintf(str, "%02d%s%c", lat.deg, s_min_nn(lat.billionths, 0), n_s);
String lat_str(str);
return lat_str;
}
String create_lat_aprs_dao(RawDegrees lat)
{
String create_lat_aprs_dao(RawDegrees lat) {
// round to 4 digits and cut the last 2
char str[20];
char n_s = 'N';
if(lat.negative)
{
if (lat.negative) {
n_s = 'S';
}
// we need sprintf's float up-rounding. Must be the same principle as in aprs_dao(). We cut off the string to two decimals afterwards.
// but sprintf % may round to 60.0000 -> 5360.0000 (53° 60min is a wrong notation ;)
// we need sprintf's float up-rounding. Must be the same principle as in
// aprs_dao(). We cut off the string to two decimals afterwards. but sprintf %
// may round to 60.0000 -> 5360.0000 (53° 60min is a wrong notation ;)
sprintf(str, "%02d%s%c", lat.deg, s_min_nn(lat.billionths, 1 /* high precision */), n_s);
String lat_str(str);
return lat_str;
}
String create_long_aprs(RawDegrees lng)
{
String create_long_aprs(RawDegrees lng) {
char str[20];
char e_w = 'E';
if(lng.negative)
{
if (lng.negative) {
e_w = 'W';
}
sprintf(str, "%03d%s%c", lng.deg, s_min_nn(lng.billionths, 0), e_w);
@ -476,13 +426,11 @@ String create_long_aprs(RawDegrees lng)
return lng_str;
}
String create_long_aprs_dao(RawDegrees lng)
{
String create_long_aprs_dao(RawDegrees lng) {
// round to 4 digits and cut the last 2
char str[20];
char e_w = 'E';
if(lng.negative)
{
if (lng.negative) {
e_w = 'W';
}
sprintf(str, "%03d%s%c", lng.deg, s_min_nn(lng.billionths, 1 /* high precision */), e_w);
@ -490,11 +438,10 @@ String create_long_aprs_dao(RawDegrees lng)
return lng_str;
}
String create_dao_aprs(RawDegrees lat, RawDegrees lng)
{
String create_dao_aprs(RawDegrees lat, RawDegrees lng) {
// !DAO! extension, use Base91 format for best precision
// /1.1 : scale from 0-99 to 0-90 for base91, int(... + 0.5): round to nearest integer
// https://metacpan.org/dist/Ham-APRS-FAP/source/FAP.pm
// /1.1 : scale from 0-99 to 0-90 for base91, int(... + 0.5): round to nearest
// integer https://metacpan.org/dist/Ham-APRS-FAP/source/FAP.pm
// http://www.aprs.org/aprs12/datum.txt
//
@ -505,35 +452,28 @@ String create_dao_aprs(RawDegrees lat, RawDegrees lng)
return dao_str;
}
String createDateString(time_t t)
{
String createDateString(time_t t) {
return String(padding(day(t), 2) + "." + padding(month(t), 2) + "." + padding(year(t), 4));
}
String createTimeString(time_t t)
{
String createTimeString(time_t t) {
return String(padding(hour(t), 2) + "." + padding(minute(t), 2) + "." + padding(second(t), 2));
}
String getSmartBeaconState()
{
if (Config.smart_beacon.active)
{
String getSmartBeaconState() {
if (Config.smart_beacon.active) {
return "On";
}
return "Off";
}
String padding(unsigned int number, unsigned int width)
{
String padding(unsigned int number, unsigned int width) {
String result;
String num(number);
if(num.length() > width)
{
if (num.length() > width) {
width = num.length();
}
for(unsigned int i = 0; i < width - num.length(); i++)
{
for (unsigned int i = 0; i < width - num.length(); i++) {
result.concat('0');
}
result.concat(num);

View file

@ -1,40 +1,33 @@
#include <SPIFFS.h>
#include <logger.h>
#ifndef CPPCHECK
#include <ArduinoJson.h>
#endif
#include "configuration.h"
#include "logger.h"
ConfigurationManagement::ConfigurationManagement(String FilePath)
: mFilePath(FilePath)
{
if(!SPIFFS.begin(true))
{
ConfigurationManagement::ConfigurationManagement(String FilePath) : mFilePath(FilePath) {
if (!SPIFFS.begin(true)) {
logPrintlnE("Mounting SPIFFS was not possible. Trying to format SPIFFS...");
SPIFFS.format();
if(!SPIFFS.begin())
{
if (!SPIFFS.begin()) {
logPrintlnE("Formating SPIFFS was not okay!");
}
}
}
// cppcheck-suppress unusedFunction
Configuration ConfigurationManagement::readConfiguration()
{
Configuration ConfigurationManagement::readConfiguration() {
File file = SPIFFS.open(mFilePath);
if(!file)
{
if (!file) {
logPrintlnE("Failed to open file for reading...");
return Configuration();
}
DynamicJsonDocument data(2048);
DeserializationError error = deserializeJson(data, file);
if(error)
{
if (error) {
logPrintlnE("Failed to read file, using default configuration.");
}
file.close();
@ -80,11 +73,9 @@ Configuration ConfigurationManagement::readConfiguration()
}
// cppcheck-suppress unusedFunction
void ConfigurationManagement::writeConfiguration(Configuration conf)
{
void ConfigurationManagement::writeConfiguration(Configuration conf) {
File file = SPIFFS.open(mFilePath, "w");
if(!file)
{
if (!file) {
logPrintlnE("Failed to open file for writing...");
return;
}

View file

@ -5,13 +5,12 @@
#include <Arduino.h>
class Configuration
{
class Configuration {
public:
class Beacon
{
class Beacon {
public:
Beacon() : message("LoRa Tracker, Info: github.com/lora-aprs/LoRa_APRS_Tracker"), timeout(1), symbol("["), overlay("/"), button_tx(false) {}
Beacon() : message("LoRa Tracker, Info: github.com/lora-aprs/LoRa_APRS_Tracker"), timeout(1), symbol("["), overlay("/"), button_tx(false) {
}
String message;
int timeout;
@ -20,10 +19,10 @@ public:
bool button_tx;
};
class Smart_Beacon
{
class Smart_Beacon {
public:
Smart_Beacon() : active(false), turn_min(25), slow_rate(300), slow_speed(10), fast_rate(60), fast_speed(100), min_tx_dist(100), min_bcn(5) {}
Smart_Beacon() : active(false), turn_min(25), slow_rate(300), slow_speed(10), fast_rate(60), fast_speed(100), min_tx_dist(100), min_bcn(5) {
}
bool active;
int turn_min;
@ -35,10 +34,10 @@ public:
int min_bcn;
};
class LoRa
{
class LoRa {
public:
LoRa() : frequencyRx(433775000), frequencyTx(433775000), power(20), spreadingFactor(12), signalBandwidth(125000), codingRate4(5) {}
LoRa() : frequencyRx(433775000), frequencyTx(433775000), power(20), spreadingFactor(12), signalBandwidth(125000), codingRate4(5) {
}
long frequencyRx;
long frequencyTx;
@ -48,10 +47,10 @@ public:
int codingRate4;
};
class PTT
{
class PTT {
public:
PTT() : active(false), io_pin(4), start_delay(0), end_delay(0), reverse(false) {}
PTT() : active(false), io_pin(4), start_delay(0), end_delay(0), reverse(false) {
}
bool active;
int io_pin;
@ -71,8 +70,7 @@ public:
PTT ptt;
};
class ConfigurationManagement
{
class ConfigurationManagement {
public:
explicit ConfigurationManagement(String FilePath);

View file

@ -1,28 +1,26 @@
#include <Wire.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <Wire.h>
#include <logger.h>
#include "display.h"
#include "pins.h"
#include "logger.h"
Adafruit_SSD1306 display(128, 64, &Wire, OLED_RST);
// cppcheck-suppress unusedFunction
void setup_display()
{
void setup_display() {
pinMode(OLED_RST, OUTPUT);
digitalWrite(OLED_RST, LOW);
delay(20);
digitalWrite(OLED_RST, HIGH);
Wire.begin(OLED_SDA, OLED_SCL);
if(!display.begin(SSD1306_SWITCHCAPVCC, 0x3c, false, false))
{
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3c, false, false)) {
logPrintlnE("SSD1306 allocation failed");
while(true)
{}
while (true) {
}
}
display.clearDisplay();
@ -36,8 +34,7 @@ void setup_display()
}
// cppcheck-suppress unusedFunction
void show_display(String header, int wait)
{
void show_display(String header, int wait) {
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(2);
@ -50,8 +47,7 @@ void show_display(String header, int wait)
}
// cppcheck-suppress unusedFunction
void show_display(String header, String line1, int wait)
{
void show_display(String header, String line1, int wait) {
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(2);
@ -67,8 +63,7 @@ void show_display(String header, String line1, int wait)
}
// cppcheck-suppress unusedFunction
void show_display(String header, String line1, String line2, int wait)
{
void show_display(String header, String line1, String line2, int wait) {
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(2);
@ -86,8 +81,7 @@ void show_display(String header, String line1, String line2, int wait)
}
// cppcheck-suppress unusedFunction
void show_display(String header, String line1, String line2, String line3, int wait)
{
void show_display(String header, String line1, String line2, String line3, int wait) {
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(2);
@ -107,8 +101,7 @@ void show_display(String header, String line1, String line2, String line3, int w
}
// cppcheck-suppress unusedFunction
void show_display(String header, String line1, String line2, String line3, String line4, int wait)
{
void show_display(String header, String line1, String line2, String line3, String line4, int wait) {
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(2);
@ -130,8 +123,7 @@ void show_display(String header, String line1, String line2, String line3, Strin
}
// cppcheck-suppress unusedFunction
void show_display(String header, String line1, String line2, String line3, String line4, String line5, int wait)
{
void show_display(String header, String line1, String line2, String line3, String line4, String line5, int wait) {
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(2);

View file

@ -2,90 +2,71 @@
#include "power_management.h"
// cppcheck-suppress uninitMemberVar
PowerManagement::PowerManagement()
{
PowerManagement::PowerManagement() {
}
// cppcheck-suppress unusedFunction
bool PowerManagement::begin(TwoWire & port)
{
bool PowerManagement::begin(TwoWire &port) {
bool result = axp.begin(port, AXP192_SLAVE_ADDRESS);
if(!result)
{
if (!result) {
axp.setDCDC1Voltage(3300);
}
return result;
}
// cppcheck-suppress unusedFunction
void PowerManagement::activateLoRa()
{
void PowerManagement::activateLoRa() {
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON);
}
// cppcheck-suppress unusedFunction
void PowerManagement::deactivateLoRa()
{
void PowerManagement::deactivateLoRa() {
axp.setPowerOutPut(AXP192_LDO2, AXP202_OFF);
}
// cppcheck-suppress unusedFunction
void PowerManagement::activateGPS()
{
void PowerManagement::activateGPS() {
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON);
}
// cppcheck-suppress unusedFunction
void PowerManagement::deactivateGPS()
{
void PowerManagement::deactivateGPS() {
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF);
}
// cppcheck-suppress unusedFunction
void PowerManagement::activateOLED()
{
void PowerManagement::activateOLED() {
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
}
// cppcheck-suppress unusedFunction
void PowerManagement::decativateOLED()
{
void PowerManagement::decativateOLED() {
axp.setPowerOutPut(AXP192_DCDC1, AXP202_OFF);
}
// cppcheck-suppress unusedFunction
void PowerManagement::activateMeasurement()
{
axp.adc1Enable(AXP202_BATT_CUR_ADC1 |
AXP202_BATT_VOL_ADC1,
true);
void PowerManagement::activateMeasurement() {
axp.adc1Enable(AXP202_BATT_CUR_ADC1 | AXP202_BATT_VOL_ADC1, true);
}
// cppcheck-suppress unusedFunction
void PowerManagement::deactivateMeasurement()
{
axp.adc1Enable(AXP202_BATT_CUR_ADC1 |
AXP202_BATT_VOL_ADC1,
false);
void PowerManagement::deactivateMeasurement() {
axp.adc1Enable(AXP202_BATT_CUR_ADC1 | AXP202_BATT_VOL_ADC1, false);
}
// cppcheck-suppress unusedFunction
double PowerManagement::getBatteryVoltage()
{
double PowerManagement::getBatteryVoltage() {
return axp.getBattVoltage() / 1000.0;
}
// cppcheck-suppress unusedFunction
double PowerManagement::getBatteryChargeDischargeCurrent()
{
if(axp.isChargeing())
{
double PowerManagement::getBatteryChargeDischargeCurrent() {
if (axp.isChargeing()) {
return axp.getBattChargeCurrent();
}
return -1.0 * axp.getBattDischargeCurrent();
}
bool PowerManagement::isBatteryConnect()
{
bool PowerManagement::isBatteryConnect() {
return axp.isBatteryConnect();
}

View file

@ -4,8 +4,7 @@
#include <Arduino.h>
#include <axp20x.h>
class PowerManagement
{
class PowerManagement {
public:
PowerManagement();
bool begin(TwoWire &port);