1
0
mirror of https://github.com/thooge/esp32-nmea2000-obp60.git synced 2026-03-28 18:06:37 +01:00

29 Commits

Author SHA1 Message Date
86cd1ed97c Add missing functions to LedSpiTask 2026-03-08 15:22:26 +01:00
e33f908187 Page system rework and improvements 2026-02-25 20:03:54 +01:00
Norbert Walter
065a9807d2 Merge pull request #229 from thooge/formatter
Added format "formatXdr:A:rd" to formatter (see #159)
2026-02-25 10:21:45 +01:00
Norbert Walter
98c318f055 Merge pull request #228 from thooge/patching
System page with N2K device list by improved patching feature and patch
2026-02-25 10:21:02 +01:00
97fcebdcb7 Added format "formatXdr:A:rd" to formatter (see #159) 2026-02-23 18:56:20 +01:00
a6fd3ef599 System page with N2K device list by improved patching feature and patch 2026-02-23 15:34:10 +01:00
norbert-walter
66e71acac3 Fix for GwWifi 2026-02-20 09:52:41 +01:00
norbert-walter
b85504bf50 Merge branch 'autopilot2' 2026-02-20 09:43:17 +01:00
norbert-walter
3043be8e1d Code cleaning 2026-02-15 19:17:52 +01:00
norbert-walter
02b2c888ee Fix for GwWifi 2026-02-15 19:16:24 +01:00
Norbert Walter
00b06f458b GwWifi race condition safe, PageNavigation check the Wifi connection befor using 2026-02-15 16:11:19 +00:00
Norbert Walter
43b0a780d5 Merge pull request #227 from thooge/master
Add feature to optionally apply patches to gateway code
2026-02-15 15:53:26 +01:00
0363ba4379 Add feature to optionally apply patches to gateway code 2026-02-15 13:13:19 +01:00
Norbert Walter
4b6e2abe33 Merge pull request #226 from Scorgan01/master
Small improvements to charts + pages OneValue + TwoValues
2026-02-15 12:21:32 +01:00
Norbert Walter
0401d82b62 Merge pull request #225 from thooge/master
Make code compile for OBP60 v2.0 again
2026-02-15 12:20:41 +01:00
Scorgan01
2fecbee492 Merge branch 'norbert-walter:master' into master 2026-02-11 22:19:11 +01:00
Ulrich Meine
fc5daaba37 - change control of key settings on PageOneValue + PageTwoValues
- added taskYIELD() to chart loop to be nice to other tasks
- fix typo in config_obp40.json
- fine tune chart labels
- disable debug messages
2026-02-09 22:31:07 +01:00
Norbert Walter
04dc09e44a Fix directory path for tool installation 2026-02-09 15:25:27 +01:00
norbert-walter
6c7997e369 Fix iRTC time for N2K bus 2026-02-08 22:00:22 +01:00
1d2ba2f71d Make code compile for OBP60 v2.0 again 2026-02-08 18:02:50 +01:00
norbert-walter
7f747e9b35 Add data connections for PageAutopilot 2026-02-08 14:49:40 +01:00
Norbert Walter
71512e7262 Actualize PageAutopilot 2026-02-08 13:18:39 +00:00
norbert-walter
4468c0555b Implement rudder bargraf in PageAutopilot 2026-02-08 14:09:10 +01:00
Norbert Walter
99404991a3 Add rudder bargraf 2026-02-08 12:40:20 +00:00
Norbert Walter
ee5077e0a5 Add PageAutopilot 2026-02-07 16:59:17 +00:00
norbert-walter
bbecf5e55f Code ceaning 2026-02-07 17:36:14 +01:00
norbert-walter
ded1b2b22e Typo 2026-02-07 17:10:59 +01:00
norbert-walter
a0a88fa2c9 Modify reagatta timer funktion 2026-02-07 17:05:41 +01:00
Norbert Walter
e9bf54e99f Add sync button for Timer 2026-02-07 14:34:54 +00:00
31 changed files with 1021 additions and 2457 deletions

View File

@@ -2,6 +2,9 @@
#define _GWWIFI_H #define _GWWIFI_H
#include <WiFi.h> #include <WiFi.h>
#include <GWConfig.h> #include <GWConfig.h>
#include <freertos/FreeRTOS.h>
#include <freertos/semphr.h>
class GwWifi{ class GwWifi{
private: private:
const GwConfigHandler *config; const GwConfigHandler *config;
@@ -16,13 +19,19 @@ class GwWifi{
bool apActive=false; bool apActive=false;
bool fixedApPass=true; bool fixedApPass=true;
bool clientIsConnected=false; bool clientIsConnected=false;
SemaphoreHandle_t wifiMutex=nullptr;
static const TickType_t WIFI_MUTEX_TIMEOUT=pdMS_TO_TICKS(1000);
bool acquireMutex();
void releaseMutex();
public: public:
const char *AP_password = "esp32nmea2k"; const char *AP_password = "esp32nmea2k";
GwWifi(const GwConfigHandler *config,GwLog *log, bool fixedApPass=true); GwWifi(const GwConfigHandler *config,GwLog *log, bool fixedApPass=true);
~GwWifi();
void setup(); void setup();
void loop(); void loop();
bool clientConnected(); bool clientConnected();
bool connectClient(); bool connectClient(); // Blocking version
bool connectClientAsync(); // Non-blocking version for other tasks
String apIP(); String apIP();
bool isApActive(){return apActive;} bool isApActive(){return apActive;}
bool isClientActive(){return wifiClient->asBoolean();} bool isClientActive(){return wifiClient->asBoolean();}

View File

@@ -1,7 +1,6 @@
#include <esp_wifi.h> #include <esp_wifi.h>
#include "GWWifi.h" #include "GWWifi.h"
GwWifi::GwWifi(const GwConfigHandler *config,GwLog *log, bool fixedApPass){ GwWifi::GwWifi(const GwConfigHandler *config,GwLog *log, bool fixedApPass){
this->config=config; this->config=config;
this->logger=log; this->logger=log;
@@ -9,6 +8,28 @@ GwWifi::GwWifi(const GwConfigHandler *config,GwLog *log, bool fixedApPass){
wifiSSID=config->getConfigItem(config->wifiSSID,true); wifiSSID=config->getConfigItem(config->wifiSSID,true);
wifiPass=config->getConfigItem(config->wifiPass,true); wifiPass=config->getConfigItem(config->wifiPass,true);
this->fixedApPass=fixedApPass; this->fixedApPass=fixedApPass;
wifiMutex=xSemaphoreCreateMutex();
if (wifiMutex==nullptr){
LOG_DEBUG(GwLog::ERROR,"GwWifi: unable to create mutex");
}
}
GwWifi::~GwWifi(){
if (wifiMutex!=nullptr){
vSemaphoreDelete(wifiMutex);
wifiMutex=nullptr;
}
}
bool GwWifi::acquireMutex(){
if (wifiMutex==nullptr) return false;
return xSemaphoreTake(wifiMutex,WIFI_MUTEX_TIMEOUT)==pdTRUE;
}
void GwWifi::releaseMutex(){
if (wifiMutex!=nullptr){
xSemaphoreGive(wifiMutex);
}
} }
void GwWifi::setup(){ void GwWifi::setup(){
LOG_DEBUG(GwLog::LOG,"Wifi setup"); LOG_DEBUG(GwLog::LOG,"Wifi setup");
@@ -85,8 +106,14 @@ bool GwWifi::connectInternal(){
if (wifiClient->asBoolean()){ if (wifiClient->asBoolean()){
clientIsConnected=false; clientIsConnected=false;
LOG_DEBUG(GwLog::LOG,"creating wifiClient ssid=%s",wifiSSID->asString().c_str()); LOG_DEBUG(GwLog::LOG,"creating wifiClient ssid=%s",wifiSSID->asString().c_str());
// CRITICAL SECTION: WiFi-Operationen müssen serialisiert werden
if (!acquireMutex()){
LOG_DEBUG(GwLog::ERROR,"GwWifi: mutex timeout in connectInternal");
return false;
}
WiFi.setAutoReconnect(false); //#102 WiFi.setAutoReconnect(false); //#102
wl_status_t rt=WiFi.begin(wifiSSID->asCString(),wifiPass->asCString()); wl_status_t rt=WiFi.begin(wifiSSID->asCString(),wifiPass->asCString());
releaseMutex();
LOG_DEBUG(GwLog::LOG,"wifiClient connect returns %d",(int)rt); LOG_DEBUG(GwLog::LOG,"wifiClient connect returns %d",(int)rt);
lastConnectStart=millis(); lastConnectStart=millis();
return true; return true;
@@ -104,8 +131,20 @@ void GwWifi::loop(){
if (lastConnectStart > now || (lastConnectStart + RETRY_MILLIS) < now) if (lastConnectStart > now || (lastConnectStart + RETRY_MILLIS) < now)
{ {
LOG_DEBUG(GwLog::LOG,"wifiClient: retry connect to %s", wifiSSID->asCString()); LOG_DEBUG(GwLog::LOG,"wifiClient: retry connect to %s", wifiSSID->asCString());
WiFi.disconnect();
connectInternal(); // CRITICAL SECTION: WiFi-Operationen müssen serialisiert werden
if (acquireMutex()){
WiFi.disconnect(true);
delay(300);
esp_wifi_stop();
delay(100);
esp_wifi_start();
releaseMutex();
connectInternal();
}
else{
LOG_DEBUG(GwLog::ERROR,"GwWifi: mutex timeout in loop");
}
} }
} }
else{ else{
@@ -126,11 +165,42 @@ void GwWifi::loop(){
} }
} }
} }
bool GwWifi::clientConnected(){ bool GwWifi::clientConnected(){
return WiFi.status() == WL_CONNECTED; // CRITICAL SECTION: WiFi.status() muss geschützt werden
if (!acquireMutex()){
LOG_DEBUG(GwLog::ERROR,"GwWifi: mutex timeout in clientConnected");
return false; // Conservative: nehme an, nicht verbunden
}
bool result = WiFi.status() == WL_CONNECTED;
releaseMutex();
return result;
}; };
bool GwWifi::connectClient(){ bool GwWifi::connectClient(){
// CRITICAL SECTION: Disconnect und Connect müssen atomar sein
if (!acquireMutex()){
LOG_DEBUG(GwLog::ERROR,"GwWifi: mutex timeout in connectClient");
return false;
}
WiFi.disconnect(); WiFi.disconnect();
releaseMutex();
return connectInternal();
}
bool GwWifi::connectClientAsync(){
// Non-blocking version: Versuche Mutex zu nehmen, gib aber sofort auf
// Ideal für Tasks, die nicht blockieren dürfen
if (wifiMutex==nullptr){
LOG_DEBUG(GwLog::ERROR,"GwWifi: mutex not initialized in connectClientAsync");
return false;
}
if (xSemaphoreTake(wifiMutex, 0)!=pdTRUE){
LOG_DEBUG(GwLog::LOG,"GwWifi: connectClientAsync skipped - WiFi busy");
return false; // WiFi ist aktuell busy, versuche es später nochmal
}
WiFi.disconnect();
xSemaphoreGive(wifiMutex);
return connectInternal(); return connectInternal();
} }

View File

@@ -14,6 +14,30 @@ https://controllerstech.com/ws2812-leds-using-spi/
*/ */
String Color::toHex() {
char hexColor[8];
sprintf(hexColor, "#%02X%02X%02X", r, g, b);
return String(hexColor);
}
String Color::toName() {
static std::map<int, String> const names = {
{0xff0000, "Red"},
{0x00ff00, "Green"},
{0x0000ff, "Blue",},
{0xff9900, "Orange"},
{0xffff00, "Yellow"},
{0x3366ff, "Aqua"},
{0xff0066, "Violet"},
{0xffffff, "White"}
};
int color = (r << 16) + (g << 8) + b;
auto it = names.find(color);
if (it == names.end()) {
return toHex();
}
return it->second;
}
static uint8_t mulcolor(uint8_t f1, uint8_t f2){ static uint8_t mulcolor(uint8_t f1, uint8_t f2){
uint16_t rt=f1; uint16_t rt=f1;
@@ -231,4 +255,4 @@ void handleSpiLeds(void *param){
void createSpiLedTask(LedTaskData *param){ void createSpiLedTask(LedTaskData *param){
xTaskCreate(handleSpiLeds,"handleLeds",4000,param,3,NULL); xTaskCreate(handleSpiLeds,"handleLeds",4000,param,3,NULL);
} }

View File

@@ -10,7 +10,7 @@ class Color{
uint8_t g; uint8_t g;
uint8_t b; uint8_t b;
Color():r(0),g(0),b(0){} Color():r(0),g(0),b(0){}
Color(uint8_t cr, uint8_t cg,uint8_t cb): Color(uint8_t cr, uint8_t cg, uint8_t cb):
b(cb),g(cg),r(cr){} b(cb),g(cg),r(cr){}
Color(const Color &o):b(o.b),g(o.g),r(o.r){} Color(const Color &o):b(o.b),g(o.g),r(o.r){}
bool equal(const Color &o) const{ bool equal(const Color &o) const{
@@ -22,6 +22,8 @@ class Color{
bool operator != (const Color &other) const{ bool operator != (const Color &other) const{
return ! equal(other); return ! equal(other);
} }
String toHex();
String toName();
}; };
static Color COLOR_GREEN=Color(0,255,0); static Color COLOR_GREEN=Color(0,255,0);

View File

@@ -1,4 +1,7 @@
#include "NetworkClient.h" #include "NetworkClient.h"
#include "GWWifi.h" // WiFi management (thread-safe)
extern GwWifi gwWifi; // Extern declaration of global WiFi instance
extern "C" { extern "C" {
#include "puff.h" #include "puff.h"
@@ -51,8 +54,13 @@ bool NetworkClient::httpGetGzip(const String& url, uint8_t*& outData, size_t& ou
const size_t capacity = READLIMIT; // Read limit for data (can be adjusted in NetworkClient.h) const size_t capacity = READLIMIT; // Read limit for data (can be adjusted in NetworkClient.h)
uint8_t* buffer = (uint8_t*)malloc(capacity); uint8_t* buffer = (uint8_t*)malloc(capacity);
if (!gwWifi.clientConnected()) {
if (DEBUGING) {Serial.println("No WiFi connection");}
return false;
}
if (!buffer) { if (!buffer) {
if (DEBUG) {Serial.println("Malloc failed (buffer");} if (DEBUGING) {Serial.println("Malloc failed buffer");}
return false; return false;
} }
@@ -106,7 +114,7 @@ bool NetworkClient::httpGetGzip(const String& url, uint8_t*& outData, size_t& ou
len += read; len += read;
lastData = millis(); lastData = millis();
if (DEBUG) {Serial.printf("Read chunk: %d (total: %d)\n", read, (int)len);} if (DEBUGING) {Serial.printf("Read chunk: %d (total: %d)\n", read, (int)len);}
if (len < 20) continue; // Not enough data for header if (len < 20) continue; // Not enough data for header
@@ -122,7 +130,7 @@ bool NetworkClient::httpGetGzip(const String& url, uint8_t*& outData, size_t& ou
int res = puff(test, &testLen, buffer + headerOffset, &srcLen); int res = puff(test, &testLen, buffer + headerOffset, &srcLen);
if (res == 0) { if (res == 0) {
if (DEBUG) {Serial.printf("Decompress OK! Size: %lu bytes\n", testLen);} if (DEBUGING) {Serial.printf("Decompress OK! Size: %lu bytes\n", testLen);}
outData = test; outData = test;
outLen = testLen; outLen = testLen;
complete = true; complete = true;
@@ -167,7 +175,7 @@ bool NetworkClient::fetchAndDecompressJson(const String& url) {
return false; return false;
} }
if (DEBUG) {Serial.println("JSON OK!");} if (DEBUGING) {Serial.println("JSON OK!");}
_valid = true; _valid = true;
return true; return true;
} }

View File

@@ -3,7 +3,7 @@
#include <WiFi.h> #include <WiFi.h>
#include <HTTPClient.h> #include <HTTPClient.h>
#define DEBUG false // Debug flag for NetworkClient for more live information #define DEBUGING false // Debug flag for NetworkClient for more live information
#define READLIMIT 200000 // HTTP read limit in byte for gzip content (can be adjusted) #define READLIMIT 200000 // HTTP read limit in byte for gzip content (can be adjusted)
#define CONNECTIONTIMEOUT 3000 // Timeout in ms for HTTP connection #define CONNECTIONTIMEOUT 3000 // Timeout in ms for HTTP connection
#define TCPREADTIMEOUT 2000 // Timeout in ms for read HTTP client stack #define TCPREADTIMEOUT 2000 // Timeout in ms for read HTTP client stack

View File

@@ -923,7 +923,7 @@ void solarGraphic(uint x, uint y, int pcolor, int bcolor){
} }
// Generator graphic with fill level // Generator graphic
void generatorGraphic(uint x, uint y, int pcolor, int bcolor){ void generatorGraphic(uint x, uint y, int pcolor, int bcolor){
// Show battery // Show battery
int xb = x; // X position int xb = x; // X position
@@ -940,6 +940,74 @@ void generatorGraphic(uint x, uint y, int pcolor, int bcolor){
getdisplay().print("G"); getdisplay().print("G");
} }
// Display rudder position as horizontal bargraph with configurable +/- range (degrees)
void displayRudderPosition(int rudderPosition, uint8_t rangeDeg, uint16_t cx, uint16_t cy, uint16_t fg, uint16_t bg){
const int w = 360;
const int h = 20;
const int t = 3; // Line thickness
const int halfw = w/2;
const int halfh = h/2;
// Calculate top-left of bar (cx,cy are center of 0°)
int left = int(cx) - halfw;
int top = int(cy) - halfh;
// clamp provided range to allowed bounds [10,45]
if (rangeDeg < 10) rangeDeg = 10;
if (rangeDeg > 45) rangeDeg = 45;
// Pixels per degree for +/-rangeDeg -> total span = 2*rangeDeg
const float pxPerDeg = float(w) / (2.0f * float(rangeDeg));
// Draw outer border (thickness t)
for (int i = 0; i < t; i++) {
getdisplay().drawRect(left + i, top + i, w - 2 * i, h - 2 * i, fg);
}
// Fill inner area with background
getdisplay().fillRect(left + t, top + t, w - 2 * t, h - 2 * t, bg);
// Draw center line
getdisplay().drawRect(cx - 1, top + 1, 3 , h - 2, fg);
// Clamp rudder position to -rangeDeg..rangeDeg
if (rudderPosition > (int)rangeDeg) rudderPosition = (int)rangeDeg;
if (rudderPosition < -((int)rangeDeg)) rudderPosition = -((int)rangeDeg);
// Compute fill width in pixels
int fillPx = int(round(rudderPosition * pxPerDeg)); // positive -> right
// Fill area from center to position (if non-zero)
int centerx = cx;
int innerTop = top + t;
int innerH = h - 2 * t;
if (fillPx > 0) {
// Right side
getdisplay().fillRect(centerx, innerTop, fillPx, innerH, fg);
} else if (fillPx < 0) {
// Left side
getdisplay().fillRect(centerx + fillPx, innerTop, -fillPx, innerH, fg);
}
// Draw tick marks every 5° and labels outside the bar
getdisplay().setTextColor(fg);
getdisplay().setFont(&Ubuntu_Bold8pt8b);
for (int angle = -((int)rangeDeg); angle <= (int)rangeDeg; angle += 5) {
int xpos = int(round(centerx + angle * pxPerDeg));
// Vertical tick inside bar
getdisplay().drawLine(xpos, top, xpos, top + h + 2, fg);
// Label outside: below the bar
String lbl = String(angle);
int16_t bx, by;
uint16_t bw, bh;
getdisplay().getTextBounds(lbl, 0, 0, &bx, &by, &bw, &bh);
int16_t tx = xpos - bw/2;
int16_t ty = top + h + bh + 5; // A little spacing
getdisplay().setCursor(tx, ty);
getdisplay().print(lbl);
}
}
// Function to handle HTTP image request // Function to handle HTTP image request
// http://192.168.15.1/api/user/OBP60Task/screenshot // http://192.168.15.1/api/user/OBP60Task/screenshot
void doImageRequest(GwApi *api, int *pageno, const PageStruct pages[MAX_PAGE_NUMBER], AsyncWebServerRequest *request) { void doImageRequest(GwApi *api, int *pageno, const PageStruct pages[MAX_PAGE_NUMBER], AsyncWebServerRequest *request) {

View File

@@ -128,6 +128,10 @@ void solarGraphic(uint x, uint y, int pcolor, int bcolor); // S
void generatorGraphic(uint x, uint y, int pcolor, int bcolor); // Generator graphic void generatorGraphic(uint x, uint y, int pcolor, int bcolor); // Generator graphic
void startLedTask(GwApi *api); void startLedTask(GwApi *api);
// Display rudder position as horizontal bargraph with configurable +/- range (degrees)
// 'rangeDeg' is unsigned and will be clamped to [10,45]
void displayRudderPosition(int rudderPosition, uint8_t rangeDeg, uint16_t cx, uint16_t cy, uint16_t fg, uint16_t bg);
void doImageRequest(GwApi *api, int *pageno, const PageStruct pages[MAX_PAGE_NUMBER], AsyncWebServerRequest *request); void doImageRequest(GwApi *api, int *pageno, const PageStruct pages[MAX_PAGE_NUMBER], AsyncWebServerRequest *request);
// Icons // Icons

View File

@@ -835,7 +835,7 @@ FormattedData formatValue(GwApi::BoatValue *value, CommonData &commondata, bool
result.cvalue = dplace; result.cvalue = dplace;
} }
//######################################################## //########################################################
else if (value->getFormat() == "formatXdr:A:D"){ else if ((value->getFormat() == "formatXdr:A:D") || ((value->getFormat() == "formatXdr:A:rd"))){
double angle = 0; double angle = 0;
if (usesimudata == false) { if (usesimudata == false) {
angle = value->value; angle = value->value;

View File

@@ -1,7 +1,7 @@
// General hardware definitions // General hardware definitions
// CAN and RS485 bus pin definitions see obp60task.h // CAN and RS485 bus pin definitions see obp60task.h
#ifdef HARDWARE_V21 #if defined HARDWARE_V20 || HARDWARE_V21
// Direction pin for RS485 NMEA0183 // Direction pin for RS485 NMEA0183
#define OBP_DIRECTION_PIN 18 #define OBP_DIRECTION_PIN 18
// I2C // I2C

View File

@@ -58,7 +58,7 @@ void initKeys(CommonData &commonData) {
commonData.keydata[5].h = height; commonData.keydata[5].h = height;
} }
#ifdef HARDWARE_V21 #if defined HARDWARE_V20 || HARDWARE_V21
// Keypad functions for original OBP60 hardware // Keypad functions for original OBP60 hardware
int readKeypad(GwLog* logger, uint thSensitivity, bool use_syspage) { int readKeypad(GwLog* logger, uint thSensitivity, bool use_syspage) {

View File

@@ -135,7 +135,7 @@ bool CalibrationData::calibrateInstance(GwApi::BoatValue* boatDataValue)
double dataValue = 0; double dataValue = 0;
std::string format = ""; std::string format = "";
// we test this earlier, but for safety reason ... // we test this earlier, but for safety reasons ...
if (calibrationMap.find(instance) == calibrationMap.end()) { if (calibrationMap.find(instance) == calibrationMap.end()) {
LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s not in calibration list", instance.c_str()); LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s not in calibration list", instance.c_str());
return false; return false;
@@ -151,7 +151,7 @@ bool CalibrationData::calibrateInstance(GwApi::BoatValue* boatDataValue)
slope = calibrationMap[instance].slope; slope = calibrationMap[instance].slope;
dataValue = boatDataValue->value; dataValue = boatDataValue->value;
format = boatDataValue->getFormat().c_str(); format = boatDataValue->getFormat().c_str();
LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s: value: %f, format: %s", instance.c_str(), dataValue, format.c_str()); // LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s: value: %f, format: %s", instance.c_str(), dataValue, format.c_str());
if (format == "formatWind") { // instance is of type angle if (format == "formatWind") { // instance is of type angle
dataValue = (dataValue * slope) + offset; dataValue = (dataValue * slope) + offset;
@@ -174,7 +174,7 @@ bool CalibrationData::calibrateInstance(GwApi::BoatValue* boatDataValue)
calibrationMap[instance].value = dataValue; // store the calibrated value in the list calibrationMap[instance].value = dataValue; // store the calibrated value in the list
calibrationMap[instance].isCalibrated = true; calibrationMap[instance].isCalibrated = true;
LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s: Offset: %f, Slope: %f, Result: %f", instance.c_str(), offset, slope, calibrationMap[instance].value); // LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s: Offset: %f, Slope: %f, Result: %f", instance.c_str(), offset, slope, calibrationMap[instance].value);
return true; return true;
} }
@@ -189,7 +189,7 @@ bool CalibrationData::smoothInstance(GwApi::BoatValue* boatDataValue)
// we test this earlier, but for safety reason ... // we test this earlier, but for safety reason ...
if (calibrationMap.find(instance) == calibrationMap.end()) { if (calibrationMap.find(instance) == calibrationMap.end()) {
LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s not in calibration list", instance.c_str()); // LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s not in calibration list", instance.c_str());
return false; return false;
} }
@@ -211,7 +211,7 @@ bool CalibrationData::smoothInstance(GwApi::BoatValue* boatDataValue)
calibrationMap[instance].value = dataValue; // store the smoothed value in the list calibrationMap[instance].value = dataValue; // store the smoothed value in the list
calibrationMap[instance].isCalibrated = true; calibrationMap[instance].isCalibrated = true;
LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s: smooth: %f, oldValue: %f, result: %f", instance.c_str(), smoothFactor, oldValue, calibrationMap[instance].value); // LOG_DEBUG(GwLog::DEBUG, "BoatDataCalibration: %s: smooth: %f, oldValue: %f, result: %f", instance.c_str(), smoothFactor, oldValue, calibrationMap[instance].value);
return true; return true;
} }
@@ -241,7 +241,7 @@ void HstryBuf::add(double value)
{ {
if (value >= hstryMin && value <= hstryMax) { if (value >= hstryMin && value <= hstryMax) {
hstryBuf.add(value); hstryBuf.add(value);
LOG_DEBUG(GwLog::DEBUG, "HstryBuf::add: name: %s, value: %.3f", hstryBuf.getName(), value); // LOG_DEBUG(GwLog::DEBUG, "HstryBuf::add: name: %s, value: %.3f", hstryBuf.getName(), value);
} }
} }
@@ -405,7 +405,7 @@ void WindUtils::calcTwdSA(const double* AWA, const double* AWS,
double stw = -*STW; double stw = -*STW;
addPolar(AWD, AWS, CTW, &stw, TWD, TWS); addPolar(AWD, AWS, CTW, &stw, TWD, TWS);
// Normalize TWD and TWA to 0-360°/2PI // Normalize TWD to [0..360°] (2PI) and TWA to [-180..180] (PI)
*TWD = to2PI(*TWD); *TWD = to2PI(*TWD);
*TWA = toPI(*TWD - *HDT); *TWA = toPI(*TWD - *HDT);
} }
@@ -487,8 +487,8 @@ bool WindUtils::addWinds()
double hdtVal = hdtBVal->valid ? hdtBVal->value : DBL_MAX; double hdtVal = hdtBVal->valid ? hdtBVal->value : DBL_MAX;
double hdmVal = hdmBVal->valid ? hdmBVal->value : DBL_MAX; double hdmVal = hdmBVal->valid ? hdmBVal->value : DBL_MAX;
double varVal = varBVal->valid ? varBVal->value : DBL_MAX; double varVal = varBVal->valid ? varBVal->value : DBL_MAX;
LOG_DEBUG(GwLog::DEBUG, "WindUtils:addWinds: AWA %.1f, AWS %.1f, COG %.1f, STW %.1f, SOG %.2f, HDT %.1f, HDM %.1f, VAR %.1f", awaBVal->value * RAD_TO_DEG, awsBVal->value * 3.6 / 1.852, //LOG_DEBUG(GwLog::DEBUG, "WindUtils:addWinds: AWA %.1f, AWS %.1f, COG %.1f, STW %.1f, SOG %.2f, HDT %.1f, HDM %.1f, VAR %.1f", awaBVal->value * RAD_TO_DEG, awsBVal->value * 3.6 / 1.852,
cogBVal->value * RAD_TO_DEG, stwBVal->value * 3.6 / 1.852, sogBVal->value * 3.6 / 1.852, hdtBVal->value * RAD_TO_DEG, hdmBVal->value * RAD_TO_DEG, varBVal->value * RAD_TO_DEG); // cogBVal->value * RAD_TO_DEG, stwBVal->value * 3.6 / 1.852, sogBVal->value * 3.6 / 1.852, hdtBVal->value * RAD_TO_DEG, hdmBVal->value * RAD_TO_DEG, varBVal->value * RAD_TO_DEG);
// Check if TWD can be calculated from TWA and HDT/HDM // Check if TWD can be calculated from TWA and HDT/HDM
if (twaBVal->valid) { if (twaBVal->valid) {
@@ -528,8 +528,8 @@ bool WindUtils::addWinds()
} }
} }
} }
LOG_DEBUG(GwLog::DEBUG, "WindUtils:addWinds: twCalculated %d, TWD %.1f, TWA %.1f, TWS %.2f kn, AWD: %.1f", twCalculated, twdBVal->value * RAD_TO_DEG, // LOG_DEBUG(GwLog::DEBUG, "WindUtils:addWinds: twCalculated %d, TWD %.1f, TWA %.1f, TWS %.2f kn, AWD: %.1f", twCalculated, twdBVal->value * RAD_TO_DEG,
twaBVal->value * RAD_TO_DEG, twsBVal->value * 3.6 / 1.852, awdBVal->value * RAD_TO_DEG); // twaBVal->value * RAD_TO_DEG, twsBVal->value * 3.6 / 1.852, awdBVal->value * RAD_TO_DEG);
return twCalculated; return twCalculated;
} }

View File

@@ -371,7 +371,7 @@ void sensorTask(void *param){
GwApi::BoatValue *hdop=new GwApi::BoatValue(GwBoatData::_HDOP); GwApi::BoatValue *hdop=new GwApi::BoatValue(GwBoatData::_HDOP);
GwApi::BoatValue *valueList[]={gpsdays, gpsseconds, hdop}; GwApi::BoatValue *valueList[]={gpsdays, gpsseconds, hdop};
// Internal RTC with NTP init // Internal iRTC with NTP init
ESP32Time rtc(0); ESP32Time rtc(0);
if (api->getConfig()->getString(api->getConfig()->timeSource) == "iRTC") { if (api->getConfig()->getString(api->getConfig()->timeSource) == "iRTC") {
GwApi::Status status; GwApi::Status status;
@@ -425,25 +425,25 @@ void sensorTask(void *param){
N2K = GPS time on N2K od 183 bus N2K = GPS time on N2K od 183 bus
0 = device not ready 0 = device not ready
1 = device ready 1 = device ready
X = undependend X = independend
() = source for set time N2K () = source for set time N2K
-> = set RTC via iRTC -> = set RTC via iRTC
<- = set RTC via GPS <- = set RTC via GPS
iRTC RTC GPS N2K iRTC RTC GPS N2K
0 0 0 (1) 0 0 0 (1)
0 0 (1) (X) 0 0 (1) X
0 (1) 0 (X) 0 (1) 0 X
0 1 <-(1) (X) 0 1 <-(1) X
(1) 0 0 (X) (1) 0 0 X
1 0 (1) (X) 1 0 (1) X
1 ->(1) 0 (X) 1 ->(1) 0 X
1 1 <-(1) (X) 1 1 <-(1) X
*/ */
// If RTC DS1388 ready, then copy iRTC and GPS data to RTC all 5min // If RTC DS1388 ready, then copy iRTC and GPS data to RTC all 1 min
if(millis() > starttime11 + 5*60*1000){ if(millis() > starttime11 + 1*60*1000){
starttime11 = millis(); starttime11 = millis();
// Set RTC chip via iRTC (NTP) // Set RTC chip via iRTC (NTP)
if(iRTC_ready == true && RTC_ready == true && GPS_ready == false){ if(iRTC_ready == true && RTC_ready == true && GPS_ready == false){
@@ -475,7 +475,7 @@ void sensorTask(void *param){
// Adjust RTC time as unix time value // Adjust RTC time as unix time value
ds1388.adjust(adjusttime); ds1388.adjust(adjusttime);
} }
} }
} }
// Set RTC chip via N2K or 183 in case the internal GPS is off (only one time) // Set RTC chip via N2K or 183 in case the internal GPS is off (only one time)
@@ -497,7 +497,7 @@ void sensorTask(void *param){
// Send RTC date and time to N2K all 500ms // Send RTC date and time to N2K all 500ms
if (millis() > starttime12 + 500) { if (millis() > starttime12 + 500) {
starttime12 = millis(); starttime12 = millis();
// Send date and time from RTC chip // Send date and time from RTC chip if GPS not ready
if (rtcOn == "DS1388" && RTC_ready) { if (rtcOn == "DS1388" && RTC_ready) {
DateTime dt = ds1388.now(); DateTime dt = ds1388.now();
sensors.rtcTime.tm_year = dt.year() - 1900; // Save values in SensorData sensors.rtcTime.tm_year = dt.year() - 1900; // Save values in SensorData
@@ -524,7 +524,7 @@ void sensorTask(void *param){
// N2K sysTime is double in n2klib // N2K sysTime is double in n2klib
double sysTime = (dt.hour() * 3600) + (dt.minute() * 60) + dt.second(); double sysTime = (dt.hour() * 3600) + (dt.minute() * 60) + dt.second();
if(!isnan(daysAt1970) && !isnan(sysTime)){ if(!isnan(daysAt1970) && !isnan(sysTime)){
//api->getLogger()->logDebug(GwLog::LOG,"RTC time: %04d/%02d/%02d %02d:%02d:%02d",sensors.rtcTime.tm_year+1900,sensors.rtcTime.tm_mon, sensors.rtcTime.tm_mday, sensors.rtcTime.tm_hour, sensors.rtcTime.tm_min, sensors.rtcTime.tm_sec); //api->getLogger()->logDebug(GwLog::LOG,"RTC time: %04d/%02d/%02d %02d:%02d:%02d",sensors.rtcTime.tm_year+1900,sensors.rtcTime.tm_mon+1, sensors.rtcTime.tm_mday, sensors.rtcTime.tm_hour, sensors.rtcTime.tm_min, sensors.rtcTime.tm_sec);
//api->getLogger()->logDebug(GwLog::LOG,"Send PGN126992: %10d %10d",daysAt1970, (uint16_t)sysTime); //api->getLogger()->logDebug(GwLog::LOG,"Send PGN126992: %10d %10d",daysAt1970, (uint16_t)sysTime);
SetN2kPGN126992(N2kMsg,0,daysAt1970,sysTime,N2ktimes_LocalCrystalClock); SetN2kPGN126992(N2kMsg,0,daysAt1970,sysTime,N2ktimes_LocalCrystalClock);
api->sendN2kMessage(N2kMsg); api->sendN2kMessage(N2kMsg);
@@ -533,25 +533,26 @@ void sensorTask(void *param){
} }
// Send date and time from software RTC (iRTC) // Send date and time from software RTC (iRTC)
if (iRTC_ready == true && RTC_ready == false && GPS_ready == false) { if (iRTC_ready == true && RTC_ready == false && GPS_ready == false) {
// Use internal RTC feature sensors.rtcTime = rtc.getTimeStruct();
sensors.rtcTime = rtc.getTimeStruct(); // Save software RTC values in SensorData
// TODO implement daysAt1970 and sysTime as methods of DateTime
const short daysOfYear[12] = {0,31,59,90,120,151,181,212,243,273,304,334}; const short daysOfYear[12] = {0,31,59,90,120,151,181,212,243,273,304,334};
uint16_t switchYear = ((sensors.rtcTime.tm_year-1)-1968)/4 - ((sensors.rtcTime.tm_year-1)-1900)/100 + ((sensors.rtcTime.tm_year-1)-1600)/400; int year = sensors.rtcTime.tm_year + 1900;
long daysAt1970 = (sensors.rtcTime.tm_year-1970)*365 + switchYear + daysOfYear[sensors.rtcTime.tm_mon-1] + sensors.rtcTime.tm_mday-1; int month = sensors.rtcTime.tm_mon;
// If switch year then add one day int day = sensors.rtcTime.tm_mday;
if ((sensors.rtcTime.tm_mon > 2) && (sensors.rtcTime.tm_year % 4 == 0 && (sensors.rtcTime.tm_year % 100 != 0 || sensors.rtcTime.tm_year % 400 == 0))) { uint16_t switchYear = ((year - 1) - 1968) / 4 - ((year - 1) - 1900) / 100 + ((year - 1) - 1600) / 400;
long daysAt1970 = (year - 1970) * 365L + switchYear + daysOfYear[month] + day - 1;
// Leap day add if date is after Feb (i.e. month >= March)
if (month >= 2 && (year % 4 == 0 && (year % 100 != 0 || year % 400 == 0))) {
daysAt1970 += 1; daysAt1970 += 1;
} }
// N2K sysTime is double in n2klib double sysTime = sensors.rtcTime.tm_hour * 3600.0 + sensors.rtcTime.tm_min * 60.0 + sensors.rtcTime.tm_sec;
double sysTime = (sensors.rtcTime.tm_hour * 3600) + (sensors.rtcTime.tm_min * 60) + sensors.rtcTime.tm_sec; //api->getLogger()->logDebug(GwLog::LOG, "iRTC time: %04d/%02d/%02d %02d:%02d:%02d", year, month + 1, day, sensors.rtcTime.tm_hour, sensors.rtcTime.tm_min, sensors.rtcTime.tm_sec);
if(!isnan(daysAt1970) && !isnan(sysTime)){ //api->getLogger()->logDebug(GwLog::LOG,"Send PGN126992: %10d %10d",daysAt1970, (uint16_t)sysTime);
//api->getLogger()->logDebug(GwLog::LOG,"RTC time: %04d/%02d/%02d %02d:%02d:%02d",sensors.rtcTime.tm_year+1900,sensors.rtcTime.tm_mon, sensors.rtcTime.tm_mday, sensors.rtcTime.tm_hour, sensors.rtcTime.tm_min, sensors.rtcTime.tm_sec); SetN2kPGN126992(N2kMsg, 0, daysAt1970, sysTime, N2ktimes_LocalCrystalClock);
//api->getLogger()->logDebug(GwLog::LOG,"Send PGN126992: %10d %10d",daysAt1970, (uint16_t)sysTime); api->sendN2kMessage(N2kMsg);
SetN2kPGN126992(N2kMsg,0,daysAt1970,sysTime,N2ktimes_LocalCrystalClock);
api->sendN2kMessage(N2kMsg);
}
} }
} }
// Send 1Wire data for all temperature sensors to N2K all 2s // Send 1Wire data for all temperature sensors to N2K all 2s

View File

@@ -161,8 +161,8 @@ bool Chart::setChartDimensions(const char direction, const int8_t size)
break; break;
} }
} }
LOG_DEBUG(GwLog::ERROR, "obp60:setChartDimensions %s: direction: %c, size: %d, dWidth: %d, dHeight: %d, timAxis: %d, valAxis: %d, cRoot{%d, %d}, top: %d, bottom: %d, hGap: %d, vGap: %d", //LOG_DEBUG(GwLog::DEBUG, "obp60:setChartDimensions %s: direction: %c, size: %d, dWidth: %d, dHeight: %d, timAxis: %d, valAxis: %d, cRoot{%d, %d}, top: %d, bottom: %d, hGap: %d, vGap: %d",
dataBuf.getName(), direction, size, dWidth, dHeight, timAxis, valAxis, cRoot.x, cRoot.y, top, bottom, hGap, vGap); // dataBuf.getName(), direction, size, dWidth, dHeight, timAxis, valAxis, cRoot.x, cRoot.y, top, bottom, hGap, vGap);
return true; return true;
} }
@@ -176,7 +176,7 @@ void Chart::drawChrt(const char chrtDir, const int8_t chrtIntv, GwApi::BoatValue
// LOG_DEBUG(GwLog::DEBUG, "Chart:drawChart: min: %.1f, mid: %.1f, max: %.1f, rng: %.1f", chrtMin, chrtMid, chrtMax, chrtRng); // LOG_DEBUG(GwLog::DEBUG, "Chart:drawChart: min: %.1f, mid: %.1f, max: %.1f, rng: %.1f", chrtMin, chrtMid, chrtMax, chrtRng);
calcChrtBorders(chrtMin, chrtMid, chrtMax, chrtRng); calcChrtBorders(chrtMin, chrtMid, chrtMax, chrtRng);
chrtScale = double(valAxis) / chrtRng; // Chart scale: pixels per value step chrtScale = double(valAxis) / chrtRng; // Chart scale: pixels per value step
LOG_DEBUG(GwLog::DEBUG, "Chart:drawChart: min: %.1f, mid: %.1f, max: %.1f, rng: %.1f", chrtMin, chrtMid, chrtMax, chrtRng); // LOG_DEBUG(GwLog::DEBUG, "Chart:drawChart: min: %.1f, mid: %.1f, max: %.1f, rng: %.1f", chrtMin, chrtMid, chrtMax, chrtRng);
// Do we have valid buffer data? // Do we have valid buffer data?
if (dataBuf.getMax() == dbMAX_VAL) { // only <MAX_VAL> values in buffer -> no valid wind data available if (dataBuf.getMax() == dbMAX_VAL) { // only <MAX_VAL> values in buffer -> no valid wind data available
@@ -261,8 +261,8 @@ void Chart::calcChrtBorders(double& rngMin, double& rngMid, double& rngMax, doub
} }
recalcRngMid = false; // Reset flag for <rngMid> determination recalcRngMid = false; // Reset flag for <rngMid> determination
LOG_DEBUG(GwLog::DEBUG, "calcChrtRange: rngMin: %.1f°, rngMid: %.1f°, rngMax: %.1f°, rng: %.1f°, rngStep: %.1f°", rngMin * RAD_TO_DEG, rngMid * RAD_TO_DEG, rngMax * RAD_TO_DEG, // LOG_DEBUG(GwLog::DEBUG, "calcChrtRange: rngMin: %.1f°, rngMid: %.1f°, rngMax: %.1f°, rng: %.1f°, rngStep: %.1f°", rngMin * RAD_TO_DEG, rngMid * RAD_TO_DEG, rngMax * RAD_TO_DEG,
rng * RAD_TO_DEG, rngStep * RAD_TO_DEG); // rng * RAD_TO_DEG, rngStep * RAD_TO_DEG);
} }
} }
@@ -287,8 +287,8 @@ void Chart::calcChrtBorders(double& rngMin, double& rngMid, double& rngMax, doub
rng = halfRng * 2.0; rng = halfRng * 2.0;
LOG_DEBUG(GwLog::DEBUG, "calcChrtBorders: rngMin: %.1f°, rngMid: %.1f°, rngMax: %.1f°, tmpRng: %.1f°, rng: %.1f°, rngStep: %.1f°", rngMin * RAD_TO_DEG, rngMid * RAD_TO_DEG, rngMax * RAD_TO_DEG, // LOG_DEBUG(GwLog::DEBUG, "calcChrtBorders: rngMin: %.1f°, rngMid: %.1f°, rngMax: %.1f°, tmpRng: %.1f°, rng: %.1f°, rngStep: %.1f°", rngMin * RAD_TO_DEG, rngMid * RAD_TO_DEG, rngMax * RAD_TO_DEG,
tmpRng * RAD_TO_DEG, rng * RAD_TO_DEG, rngStep * RAD_TO_DEG); // tmpRng * RAD_TO_DEG, rng * RAD_TO_DEG, rngStep * RAD_TO_DEG);
} else { // chart data is of any other type } else { // chart data is of any other type
@@ -320,8 +320,8 @@ void Chart::calcChrtBorders(double& rngMin, double& rngMid, double& rngMax, doub
rngMid = (rngMin + rngMax) / 2.0; rngMid = (rngMin + rngMax) / 2.0;
rng = rngMax - rngMin; rng = rngMax - rngMin;
LOG_DEBUG(GwLog::DEBUG, "calcChrtRange-end: currMinVal: %.1f, currMaxVal: %.1f, rngMin: %.1f, rngMid: %.1f, rngMax: %.1f, rng: %.1f, rngStep: %.1f, zeroValue: %.1f, dbMIN_VAL: %.1f", // LOG_DEBUG(GwLog::DEBUG, "calcChrtRange-end: currMinVal: %.1f, currMaxVal: %.1f, rngMin: %.1f, rngMid: %.1f, rngMax: %.1f, rng: %.1f, rngStep: %.1f, zeroValue: %.1f, dbMIN_VAL: %.1f",
currMinVal, currMaxVal, rngMin, rngMid, rngMax, rng, rngStep, zeroValue, dbMIN_VAL); // currMinVal, currMaxVal, rngMin, rngMid, rngMax, rng, rngStep, zeroValue, dbMIN_VAL);
} }
} }
@@ -397,6 +397,8 @@ void Chart::drawChartLines(const char direction, const int8_t chrtIntv, const do
} }
break; break;
} }
taskYIELD(); // we run for 50-150ms; be polite to other tasks with same priority
} }
} }
@@ -656,7 +658,7 @@ void Chart::prntHorizChartThreeValueAxisLabel(const GFXfont* font)
if (font == &Ubuntu_Bold10pt8b) { if (font == &Ubuntu_Bold10pt8b) {
xOffset = 39; xOffset = 39;
yOffset = 15; yOffset = 16;
} else if (font == &Ubuntu_Bold12pt8b) { } else if (font == &Ubuntu_Bold12pt8b) {
xOffset = 51; xOffset = 51;
yOffset = 18; yOffset = 18;
@@ -718,7 +720,7 @@ void Chart::prntHorizChartMultiValueAxisLabel(const GFXfont* font)
axSlots = valAxis / static_cast<double>(VALAXIS_STEP); // number of axis labels (and we want to have a double calculation, no integer) axSlots = valAxis / static_cast<double>(VALAXIS_STEP); // number of axis labels (and we want to have a double calculation, no integer)
axIntv = chrtRng / axSlots; axIntv = chrtRng / axSlots;
axLabel = chrtMin + axIntv; axLabel = chrtMin + axIntv;
LOG_DEBUG(GwLog::DEBUG, "Chart::printHorizMultiValueAxisLabel: chrtRng: %.2f, th-chrtRng: %.2f, axSlots: %.2f, axIntv: %.2f, axLabel: %.2f, chrtMin: %.2f, chrtMid: %.2f, chrtMax: %.2f", chrtRng, this->chrtRng, axSlots, axIntv, axLabel, this->chrtMin, chrtMid, chrtMax); // LOG_DEBUG(GwLog::DEBUG, "Chart::printHorizMultiValueAxisLabel: chrtRng: %.2f, th-chrtRng: %.2f, axSlots: %.2f, axIntv: %.2f, axLabel: %.2f, chrtMin: %.2f, chrtMid: %.2f, chrtMax: %.2f", chrtRng, this->chrtRng, axSlots, axIntv, axLabel, this->chrtMin, chrtMid, chrtMax);
int loopStrt, loopEnd, loopStp; int loopStrt, loopEnd, loopStp;
if (chrtDataFmt == SPEED || chrtDataFmt == TEMPERATURE || chrtDataFmt == OTHER) { if (chrtDataFmt == SPEED || chrtDataFmt == TEMPERATURE || chrtDataFmt == OTHER) {

View File

@@ -5,8 +5,9 @@
// These constants have to match the declaration below in : // These constants have to match the declaration below in :
// PageDescription registerPageAutopilot( // PageDescription registerPageAutopilot(
// {"HDM","HDT", "COG", "STW", "SOG", "DBT","XTE", "DTW", "BTW"}, // Bus values we need in the page // {"HDM","HDT", "COG", "STW", "SOG", "DBT","XTE", "DTW", "BTW", "RPOS", "ROT"}, // Bus values we need in the page
const int HowManyValues = 9;
const int HowManyValues = 11;
const int AverageValues = 4; const int AverageValues = 4;
@@ -19,10 +20,13 @@ const int ShowDBT = 5;
const int ShowXTE = 6; const int ShowXTE = 6;
const int ShowDTW = 7; const int ShowDTW = 7;
const int ShowBTW = 8; const int ShowBTW = 8;
const int ShowRPOS = 9;
const int ShowROT = 10;
const int Compass_X0 = 200; // X center point of compass band const int Compass_X0 = 200; // X center point of compass band
const int Compass_Y0 = 220; // Y position of compass lines const int Compass_Y0 = 90; // Y position of compass lines
const int Compass_LineLength = 22; // Length of compass lines //const int Compass_LineLength = 22; // Length of compass lines
const int Compass_LineLength = 15; // Length of compass lines
const float Compass_LineDelta = 8.0;// Compass band: 1deg = 5 Pixels, 10deg = 50 Pixels const float Compass_LineDelta = 8.0;// Compass band: 1deg = 5 Pixels, 10deg = 50 Pixels
class PageAutopilot : public Page class PageAutopilot : public Page
@@ -38,8 +42,11 @@ class PageAutopilot : public Page
virtual void setupKeys(){ virtual void setupKeys(){
Page::setupKeys(); Page::setupKeys();
commonData->keydata[0].label = "CMP"; commonData->keydata[0].label = "-10";
commonData->keydata[1].label = "SRC"; commonData->keydata[1].label = "-1";
commonData->keydata[2].label = "Auto";
commonData->keydata[3].label = "+1";
commonData->keydata[4].label = "+10";
} }
virtual int handleKey(int key){ virtual int handleKey(int key){
@@ -69,8 +76,8 @@ class PageAutopilot : public Page
GwLog *logger = commonData->logger; GwLog *logger = commonData->logger;
// Old values for hold function // Old values for hold function
static String OldDataText[HowManyValues] = {"", "", "","", "", "","", "", ""}; static String OldDataText[HowManyValues] = {"", "", "", "", "", "","", "", "", "", ""};
static String OldDataUnits[HowManyValues] = {"", "", "","", "", "","", "", ""}; static String OldDataUnits[HowManyValues] = {"", "", "", "", "", "","", "", "", "", ""};
// Get config data // Get config data
String lengthformat = config->getString(config->lengthFormat); String lengthformat = config->getString(config->lengthFormat);
@@ -106,15 +113,13 @@ class PageAutopilot : public Page
setBlinkingLED(false); setBlinkingLED(false);
setFlashLED(false); setFlashLED(false);
} }
if (bvalue == NULL) return PAGE_OK; // WTF why this statement?
//*********************************************************** //***********************************************************
// Set display in partial refresh mode // Set display in partial refresh mode
getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update
getdisplay().setTextColor(commonData->fgcolor); getdisplay().setTextColor(commonData->fgcolor);
/*
// Horizontal line 2 pix top & bottom // Horizontal line 2 pix top & bottom
// Print data on top half // Print data on top half
getdisplay().fillRect(0, 130, 400, 2, commonData->fgcolor); getdisplay().fillRect(0, 130, 400, 2, commonData->fgcolor);
@@ -138,7 +143,7 @@ class PageAutopilot : public Page
OldDataText[WhichDataDisplay] = DataText[WhichDataDisplay]; // Save the old value OldDataText[WhichDataDisplay] = DataText[WhichDataDisplay]; // Save the old value
OldDataUnits[WhichDataDisplay] = DataUnits[WhichDataDisplay]; // Save the old unit OldDataUnits[WhichDataDisplay] = DataUnits[WhichDataDisplay]; // Save the old unit
} }
*/
// Now draw compass band // Now draw compass band
// Get the data // Get the data
double TheAngle = DataValue[WhichDataCompass]; double TheAngle = DataValue[WhichDataCompass];
@@ -152,13 +157,13 @@ class PageAutopilot : public Page
buffer[0]=0; buffer[0]=0;
getdisplay().setFont(&Ubuntu_Bold16pt8b); getdisplay().setFont(&Ubuntu_Bold16pt8b);
getdisplay().setCursor(10, Compass_Y0-60); getdisplay().setCursor(10, Compass_Y0-40);
getdisplay().print(DataName[WhichDataCompass]); // Page name getdisplay().print(DataName[WhichDataCompass]); // Page name
// Draw compass base line and pointer // Draw compass base line and pointer
getdisplay().fillRect(0, Compass_Y0, 400, 3, commonData->fgcolor); getdisplay().fillRect(0, Compass_Y0, 400, 3, commonData->fgcolor);
getdisplay().fillTriangle(Compass_X0,Compass_Y0-40,Compass_X0-10,Compass_Y0-80,Compass_X0+10,Compass_Y0-80,commonData->fgcolor); //getdisplay().fillTriangle(Compass_X0,Compass_Y0-40,Compass_X0-10,Compass_Y0-80,Compass_X0+10,Compass_Y0-80,commonData->fgcolor);
getdisplay().fillTriangle(Compass_X0,Compass_Y0-30,Compass_X0-10,Compass_Y0-60,Compass_X0+10,Compass_Y0-60,commonData->fgcolor);
// Draw trendlines // Draw trendlines
for ( int i = 1; i < abs(TheTrend) / 2; i++){ for ( int i = 1; i < abs(TheTrend) / 2; i++){
int x1; int x1;
@@ -238,6 +243,8 @@ class PageAutopilot : public Page
// if ( x_test > 390) // if ( x_test > 390)
// x_test = 320; // x_test = 320;
displayRudderPosition(DataValue[ShowSOG], 20, 200, 160, commonData->fgcolor, commonData->bgcolor);
return PAGE_UPDATE; return PAGE_UPDATE;
}; };
@@ -256,7 +263,7 @@ PageDescription registerPageAutopilot(
"Autopilot", // Page name "Autopilot", // Page name
createPage, // Action createPage, // Action
0, // Number of bus values depends on selection in Web configuration 0, // Number of bus values depends on selection in Web configuration
{"HDM","HDT", "COG", "STW", "SOG", "DBT","XTE", "DTW", "BTW"}, // Bus values we need in the page {"HDM","HDT", "COG", "STW", "SOG", "DBT","XTE", "DTW", "BTW", "RPOS", "ROT"}, // Bus values we need in the page
true // Show display header on/off true // Show display header on/off
); );

View File

@@ -15,7 +15,7 @@
* K4: * K4:
* K5: TZ (Local/UTC) * K5: TZ (Local/UTC)
* *
* Timer mode: * Regatta timer mode:
* - Format HH:MM:SS (24h, leading zeros) * - Format HH:MM:SS (24h, leading zeros)
* - Keys in timer mode: * - Keys in timer mode:
* K1: MODE (A/D/T) * K1: MODE (A/D/T)
@@ -53,6 +53,8 @@ class PageClock : public Page
static int timerHours; static int timerHours;
static int timerMinutes; static int timerMinutes;
static int timerSeconds; static int timerSeconds;
// Preset seconds for sync button (default 4 minutes)
static const int timerPresetSeconds = 4 * 60;
// Initial timer setting at start (so we can restore it) // Initial timer setting at start (so we can restore it)
static int timerStartHours; static int timerStartHours;
static int timerStartMinutes; static int timerStartMinutes;
@@ -135,9 +137,10 @@ public:
// Timer mode: MODE, POS, +, -, RUN // Timer mode: MODE, POS, +, -, RUN
commonData->keydata[0].label = "MODE"; commonData->keydata[0].label = "MODE";
commonData->keydata[1].label = "POS"; commonData->keydata[1].label = "POS";
commonData->keydata[2].label = "+"; // K3: '+' while editing, 'SYNC' while running to set a preset countdown
commonData->keydata[2].label = timerRunning ? "SYNC" : "+";
commonData->keydata[3].label = "-"; commonData->keydata[3].label = "-";
commonData->keydata[4].label = "START"; commonData->keydata[4].label = timerRunning ? "RESET" : "START";
} else { } else {
// Clock modes: like original // Clock modes: like original
commonData->keydata[0].label = "MODE"; commonData->keydata[0].label = "MODE";
@@ -184,7 +187,26 @@ public:
incrementSelected(); incrementSelected();
return 0; return 0;
} }
if (key == 3 && timerRunning) { // No action if timer running if (key == 3 && timerRunning) {
// When timer is running, K3 acts as a synchronization button:
// set remaining countdown to the preset value (e.g. 4 minutes).
if (commonData->data.rtcValid) {
int preset = timerPresetSeconds;
// update start-setting so STOP will restore this preset
timerStartHours = preset / 3600;
timerStartMinutes = (preset % 3600) / 60;
timerStartSeconds = preset % 60;
struct tm rtcCopy = commonData->data.rtcTime;
time_t nowEpoch = mktime(&rtcCopy);
timerEndEpoch = nowEpoch + preset;
// Update visible timer fields immediately
timerHours = timerStartHours;
timerMinutes = timerStartMinutes;
timerSeconds = timerStartSeconds;
// commonData->keydata[4].label = "RESET";
}
return 0; return 0;
} }
@@ -220,6 +242,7 @@ public:
timerMinutes = timerStartMinutes; timerMinutes = timerStartMinutes;
timerSeconds = timerStartSeconds; timerSeconds = timerStartSeconds;
timerRunning = false; timerRunning = false;
showSelectionMarker = true;
// marker will become visible again only after POS press // marker will become visible again only after POS press
} }
return 0; return 0;
@@ -360,8 +383,8 @@ public:
struct tm* local_tm = localtime(&tv); struct tm* local_tm = localtime(&tv);
if (mode == 'T') { if (mode == 'T') {
// TIMER MODE: countdown timer HH:MM:SS in the center with 7-segment font // REGATTA TIMER MODE: countdown timer HH:MM:SS in the center with 7-segment font
//************************************************************************ //*******************************************************************************
int dispH = timerHours; int dispH = timerHours;
int dispM = timerMinutes; int dispM = timerMinutes;
@@ -381,7 +404,9 @@ public:
if (remaining <= 0) { if (remaining <= 0) {
remaining = 0; remaining = 0;
timerRunning = false; timerRunning = false;
commonData->keydata[3].label = "-";
commonData->keydata[4].label = "START"; commonData->keydata[4].label = "START";
showSelectionMarker = true;
// Buzzer alarm (100% power) // Buzzer alarm (100% power)
setBuzzerPower(100); setBuzzerPower(100);
buzzer(TONE2, 800); buzzer(TONE2, 800);
@@ -393,6 +418,7 @@ public:
timerSeconds = timerStartSeconds; timerSeconds = timerStartSeconds;
} }
else{ else{
commonData->keydata[3].label = "";
commonData->keydata[4].label = "RESET"; commonData->keydata[4].label = "RESET";
} }
int rem = static_cast<int>(remaining); int rem = static_cast<int>(remaining);
@@ -431,8 +457,8 @@ public:
int16_t textX = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(wb)) / 2; int16_t textX = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(wb)) / 2;
int16_t textY = centerY + hb / 2; int16_t textY = centerY + hb / 2;
//getdisplay().setCursor(textX, textY); //getdisplay().setCursor(textX, textY); // horzontal jitter
getdisplay().setCursor(47, textY); getdisplay().setCursor(47, textY); // static X position
getdisplay().print(timeStr); getdisplay().print(timeStr);
// Selection marker (only visible when not running and POS pressed) // Selection marker (only visible when not running and POS pressed)
@@ -451,8 +477,8 @@ public:
// Page label // Page label
getdisplay().setFont(&Ubuntu_Bold16pt8b); getdisplay().setFont(&Ubuntu_Bold16pt8b);
getdisplay().setCursor(65, 70); getdisplay().setCursor(100, 70);
getdisplay().print("Count Down Timer"); getdisplay().print("Regatta Timer");
} else if (mode == 'D') { } else if (mode == 'D') {
// DIGITAL CLOCK MODE: large 7-segment time based on GPS/RTC // DIGITAL CLOCK MODE: large 7-segment time based on GPS/RTC
@@ -499,8 +525,8 @@ public:
int16_t x = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(wb)) / 2; int16_t x = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(wb)) / 2;
int16_t y = 150 + hb / 2; int16_t y = 150 + hb / 2;
//getdisplay().setCursor(x, y); //getdisplay().setCursor(x, y); // horizontal jitter
getdisplay().setCursor(47, y); getdisplay().setCursor(47, y); // static X position
getdisplay().print(timeStr); // Display actual time getdisplay().print(timeStr); // Display actual time
// Small indicators: timezone and source // Small indicators: timezone and source

View File

@@ -1,467 +0,0 @@
#if defined BOARD_OBP60S3 || defined BOARD_OBP40S3
#include "Pagedata.h"
#include "OBP60Extensions.h"
/*
* TODO mode: race timer: keys
* - prepare: set countdown to 5min
* reset: abort current countdown and start over with 5min preparation
* - 5min: key press
* - 4min: key press to sync
* - 1min: buzzer signal
* - start: buzzer signal for start
*
*/
class PageClock : public Page
{
bool simulation = false;
int simtime;
bool keylock = false;
#ifdef BOARD_OBP60S3
char source = 'G'; // time source (R)TC | (G)PS | (N)TP
#endif
#ifdef BOARD_OBP40S3
char source = 'R'; // time source (R)TC | (G)PS | (N)TP
#endif
char mode = 'A'; // display mode (A)nalog | (D)igital | race (T)imer
char tz = 'L'; // time zone (L)ocal | (U)TC
double timezone = 0; // there are timezones with non int offsets, e.g. 5.5 or 5.75
double homelat;
double homelon;
bool homevalid = false; // homelat and homelon are valid
public:
PageClock(CommonData &common){
commonData = &common;
common.logger->logDebug(GwLog::LOG,"Instantiate PageClock");
simulation = common.config->getBool(common.config->useSimuData);
timezone = common.config->getString(common.config->timeZone).toDouble();
homelat = common.config->getString(common.config->homeLAT).toDouble();
homelon = common.config->getString(common.config->homeLON).toDouble();
homevalid = homelat >= -180.0 and homelat <= 180 and homelon >= -90.0 and homelon <= 90.0;
simtime = 38160; // time value 11:36
}
virtual void setupKeys(){
Page::setupKeys();
commonData->keydata[0].label = "SRC";
commonData->keydata[1].label = "MODE";
commonData->keydata[4].label = "TZ";
}
// Key functions
virtual int handleKey(int key){
// Time source
if (key == 1) {
switch (source) {
case 'G': source = 'R'; break;
case 'R': source = 'G'; break;
default: source = 'G'; break;
}
return 0;
}
if (key == 2) {
switch (mode) {
case 'A': mode = 'D'; break;
case 'D': mode = 'T'; break;
case 'T': mode = 'A'; break;
default: mode = 'A'; break;
}
return 0;
}
// Time zone: Local / UTC
if (key == 5) {
switch (tz) {
case 'L': tz = 'U'; break;
case 'U': tz = 'L'; break;
default: tz = 'L'; break;
}
return 0;
}
// Keylock function
if(key == 11){ // Code for keylock
keylock = !keylock; // Toggle keylock
return 0; // Commit the key
}
return key;
}
int displayPage(PageData &pageData)
{
GwConfigHandler *config = commonData->config;
GwLog *logger = commonData->logger;
static String svalue1old = "";
static String unit1old = "";
static String svalue2old = "";
static String unit2old = "";
static String svalue3old = "";
static String unit3old = "";
static String svalue5old = "";
static String svalue6old = "";
double value1 = 0;
double value2 = 0;
double value3 = 0;
// Get config data
String lengthformat = config->getString(config->lengthFormat);
String dateformat = config->getString(config->dateFormat);
bool holdvalues = config->getBool(config->holdvalues);
String flashLED = config->getString(config->flashLED);
String backlightMode = config->getString(config->backlight);
// Get boat values for GPS time
GwApi::BoatValue *bvalue1 = pageData.values[0]; // First element in list (only one value by PageOneValue)
String name1 = bvalue1->getName().c_str(); // Value name
name1 = name1.substring(0, 6); // String length limit for value name
if(simulation == false){
value1 = bvalue1->value; // Value as double in SI unit
}
else{
value1 = simtime++; // Simulation data for time value 11:36 in seconds
} // Other simulation data see OBP60Formatter.cpp
bool valid1 = bvalue1->valid; // Valid information
String svalue1 = formatValue(bvalue1, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
String unit1 = formatValue(bvalue1, *commonData).unit; // Unit of value
if(valid1 == true){
svalue1old = svalue1; // Save old value
unit1old = unit1; // Save old unit
}
// Get boat values for GPS date
GwApi::BoatValue *bvalue2 = pageData.values[1]; // Second element in list (only one value by PageOneValue)
String name2 = bvalue2->getName().c_str(); // Value name
name2 = name2.substring(0, 6); // String length limit for value name
value2 = bvalue2->value; // Value as double in SI unit
bool valid2 = bvalue2->valid; // Valid information
String svalue2 = formatValue(bvalue2, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
String unit2 = formatValue(bvalue2, *commonData).unit; // Unit of value
if(valid2 == true){
svalue2old = svalue2; // Save old value
unit2old = unit2; // Save old unit
}
// Get boat values for HDOP date
GwApi::BoatValue *bvalue3 = pageData.values[2]; // Third element in list (only one value by PageOneValue)
String name3 = bvalue3->getName().c_str(); // Value name
name3 = name3.substring(0, 6); // String length limit for value name
value3 = bvalue3->value; // Value as double in SI unit
bool valid3 = bvalue3->valid; // Valid information
String svalue3 = formatValue(bvalue3, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
String unit3 = formatValue(bvalue3, *commonData).unit; // Unit of value
if(valid3 == true){
svalue3old = svalue3; // Save old value
unit3old = unit3; // Save old unit
}
// Optical warning by limit violation (unused)
if(String(flashLED) == "Limit Violation"){
setBlinkingLED(false);
setFlashLED(false);
}
// Logging boat values
if (bvalue1 == NULL) return PAGE_OK; // WTF why this statement?
LOG_DEBUG(GwLog::LOG,"Drawing at PageClock, %s:%f, %s:%f", name1.c_str(), value1, name2.c_str(), value2);
// Draw page
//***********************************************************
// Set display in partial refresh mode
getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update
getdisplay().setTextColor(commonData->fgcolor);
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
struct tm *local_tm = localtime(&tv);
// Show values GPS date
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(10, 65);
if (holdvalues == false) {
if (source == 'G') {
// GPS value
getdisplay().print(svalue2);
} else if (commonData->data.rtcValid) {
// RTC value
if (tz == 'L') {
getdisplay().print(formatDate(dateformat, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
}
else {
getdisplay().print(formatDate(dateformat, commonData->data.rtcTime.tm_year + 1900, commonData->data.rtcTime.tm_mon + 1, commonData->data.rtcTime.tm_mday));
}
} else {
getdisplay().print("---");
}
} else {
getdisplay().print(svalue2old);
}
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(10, 95);
getdisplay().print("Date"); // Name
// Horizintal separator left
getdisplay().fillRect(0, 149, 60, 3, commonData->fgcolor);
// Show values GPS time
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(10, 250);
if (holdvalues == false) {
if (source == 'G') {
getdisplay().print(svalue1); // Value
}
else if (commonData->data.rtcValid) {
if (tz == 'L') {
getdisplay().print(formatTime('s', local_tm->tm_hour, local_tm->tm_min, local_tm->tm_sec));
}
else {
getdisplay().print(formatTime('s', commonData->data.rtcTime.tm_hour, commonData->data.rtcTime.tm_min, commonData->data.rtcTime.tm_sec));
}
} else {
getdisplay().print("---");
}
}
else {
getdisplay().print(svalue1old);
}
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(10, 220);
getdisplay().print("Time"); // Name
// Show values sunrise
String sunrise = "---";
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
sunrise = String(commonData->sundata.sunriseHour) + ":" + String(commonData->sundata.sunriseMinute + 100).substring(1);
svalue5old = sunrise;
} else if (simulation) {
sunrise = String("06:42");
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(335, 65);
if(holdvalues == false) getdisplay().print(sunrise); // Value
else getdisplay().print(svalue5old);
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(335, 95);
getdisplay().print("SunR"); // Name
// Horizintal separator right
getdisplay().fillRect(340, 149, 80, 3, commonData->fgcolor);
// Show values sunset
String sunset = "---";
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
sunset = String(commonData->sundata.sunsetHour) + ":" + String(commonData->sundata.sunsetMinute + 100).substring(1);
svalue6old = sunset;
} else if (simulation) {
sunset = String("21:03");
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(335, 250);
if(holdvalues == false) getdisplay().print(sunset); // Value
else getdisplay().print(svalue6old);
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(335, 220);
getdisplay().print("SunS"); // Name
//*******************************************************************************************
// Draw clock
int rInstrument = 110; // Radius of clock
float pi = 3.141592;
getdisplay().fillCircle(200, 150, rInstrument + 10, commonData->fgcolor); // Outer circle
getdisplay().fillCircle(200, 150, rInstrument + 7, commonData->bgcolor); // Outer circle
for(int i=0; i<360; i=i+1)
{
// Scaling values
float x = 200 + (rInstrument-30)*sin(i/180.0*pi); // x-coordinate dots
float y = 150 - (rInstrument-30)*cos(i/180.0*pi); // y-coordinate cots
const char *ii = "";
switch (i)
{
case 0: ii="12"; break;
case 30 : ii=""; break;
case 60 : ii=""; break;
case 90 : ii="3"; break;
case 120 : ii=""; break;
case 150 : ii=""; break;
case 180 : ii="6"; break;
case 210 : ii=""; break;
case 240 : ii=""; break;
case 270 : ii="9"; break;
case 300 : ii=""; break;
case 330 : ii=""; break;
default: break;
}
// Print text centered on position x, y
int16_t x1, y1; // Return values of getTextBounds
uint16_t w, h; // Return values of getTextBounds
getdisplay().getTextBounds(ii, int(x), int(y), &x1, &y1, &w, &h); // Calc width of new string
getdisplay().setCursor(x-w/2, y+h/2);
if(i % 30 == 0){
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().print(ii);
}
// Draw sub scale with dots
float sinx = 0;
float cosx = 0;
if(i % 6 == 0){
float x1c = 200 + rInstrument*sin(i/180.0*pi);
float y1c = 150 - rInstrument*cos(i/180.0*pi);
getdisplay().fillCircle((int)x1c, (int)y1c, 2, commonData->fgcolor);
sinx=sin(i/180.0*pi);
cosx=cos(i/180.0*pi);
}
// Draw sub scale with lines (two triangles)
if(i % 30 == 0){
float dx=2; // Line thickness = 2*dx+1
float xx1 = -dx;
float xx2 = +dx;
float yy1 = -(rInstrument-10);
float yy2 = -(rInstrument+10);
getdisplay().fillTriangle(200+(int)(cosx*xx1-sinx*yy1),150+(int)(sinx*xx1+cosx*yy1),
200+(int)(cosx*xx2-sinx*yy1),150+(int)(sinx*xx2+cosx*yy1),
200+(int)(cosx*xx1-sinx*yy2),150+(int)(sinx*xx1+cosx*yy2),commonData->fgcolor);
getdisplay().fillTriangle(200+(int)(cosx*xx2-sinx*yy1),150+(int)(sinx*xx2+cosx*yy1),
200+(int)(cosx*xx1-sinx*yy2),150+(int)(sinx*xx1+cosx*yy2),
200+(int)(cosx*xx2-sinx*yy2),150+(int)(sinx*xx2+cosx*yy2),commonData->fgcolor);
}
}
// Print Unit in clock
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(175, 110);
if(holdvalues == false){
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
}
else{
getdisplay().print(unit2old); // date unit
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(185, 190);
if (source == 'G') {
getdisplay().print("GPS");
} else {
getdisplay().print("RTC");
}
// Clock values
double hour = 0;
double minute = 0;
if (source == 'R') {
if (tz == 'L') {
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
struct tm *local_tm = localtime(&tv);
minute = local_tm->tm_min;
hour = local_tm->tm_hour;
} else {
minute = commonData->data.rtcTime.tm_min;
hour = commonData->data.rtcTime.tm_hour;
}
hour += minute / 60;
} else {
if (tz == 'L') {
value1 += timezone * 3600;
}
if (value1 > 86400) {value1 -= 86400;}
if (value1 < 0) {value1 += 86400;}
hour = (value1 / 3600.0);
// minute = (hour - int(hour)) * 3600.0 / 60.0; // Analog minute pointer smooth moving
minute = int((hour - int(hour)) * 3600.0 / 60.0); // Jumping minute pointer from minute to minute
}
if (hour > 12) {
hour -= 12.0;
}
LOG_DEBUG(GwLog::DEBUG,"... PageClock, value1: %f hour: %f minute:%f", value1, hour, minute);
// Draw hour pointer
float startwidth = 8; // Start width of pointer
if(valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true){
float sinx=sin(hour * 30.0 * pi / 180); // Hour
float cosx=cos(hour * 30.0 * pi / 180);
// Normal pointer
// Pointer as triangle with center base 2*width
float xx1 = -startwidth;
float xx2 = startwidth;
float yy1 = -startwidth;
float yy2 = -(rInstrument * 0.5);
getdisplay().fillTriangle(200+(int)(cosx*xx1-sinx*yy1),150+(int)(sinx*xx1+cosx*yy1),
200+(int)(cosx*xx2-sinx*yy1),150+(int)(sinx*xx2+cosx*yy1),
200+(int)(cosx*0-sinx*yy2),150+(int)(sinx*0+cosx*yy2),commonData->fgcolor);
// Inverted pointer
// Pointer as triangle with center base 2*width
float endwidth = 2; // End width of pointer
float ix1 = endwidth;
float ix2 = -endwidth;
float iy1 = -(rInstrument * 0.5);
float iy2 = -endwidth;
getdisplay().fillTriangle(200+(int)(cosx*ix1-sinx*iy1),150+(int)(sinx*ix1+cosx*iy1),
200+(int)(cosx*ix2-sinx*iy1),150+(int)(sinx*ix2+cosx*iy1),
200+(int)(cosx*0-sinx*iy2),150+(int)(sinx*0+cosx*iy2),commonData->fgcolor);
}
// Draw minute pointer
startwidth = 8; // Start width of pointer
if(valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true){
float sinx=sin(minute * 6.0 * pi / 180); // Minute
float cosx=cos(minute * 6.0 * pi / 180);
// Normal pointer
// Pointer as triangle with center base 2*width
float xx1 = -startwidth;
float xx2 = startwidth;
float yy1 = -startwidth;
float yy2 = -(rInstrument - 15);
getdisplay().fillTriangle(200+(int)(cosx*xx1-sinx*yy1),150+(int)(sinx*xx1+cosx*yy1),
200+(int)(cosx*xx2-sinx*yy1),150+(int)(sinx*xx2+cosx*yy1),
200+(int)(cosx*0-sinx*yy2),150+(int)(sinx*0+cosx*yy2),commonData->fgcolor);
// Inverted pointer
// Pointer as triangle with center base 2*width
float endwidth = 2; // End width of pointer
float ix1 = endwidth;
float ix2 = -endwidth;
float iy1 = -(rInstrument - 15);
float iy2 = -endwidth;
getdisplay().fillTriangle(200+(int)(cosx*ix1-sinx*iy1),150+(int)(sinx*ix1+cosx*iy1),
200+(int)(cosx*ix2-sinx*iy1),150+(int)(sinx*ix2+cosx*iy1),
200+(int)(cosx*0-sinx*iy2),150+(int)(sinx*0+cosx*iy2),commonData->fgcolor);
}
// Center circle
getdisplay().fillCircle(200, 150, startwidth + 6, commonData->bgcolor);
getdisplay().fillCircle(200, 150, startwidth + 4, commonData->fgcolor);
return PAGE_UPDATE;
};
};
static Page *createPage(CommonData &common){
return new PageClock(common);
}
/**
* with the code below we make this page known to the PageTask
* we give it a type (name) that can be selected in the config
* we define which function is to be called
* and we provide the number of user parameters we expect (0 here)
* and will will provide the names of the fixed values we need
*/
PageDescription registerPageClock(
"Clock", // Page name
createPage, // Action
0, // Number of bus values depends on selection in Web configuration
{"GPST", "GPSD", "HDOP"}, // Bus values we need in the page
true // Show display header on/off
);
#endif

View File

@@ -1,548 +0,0 @@
#if defined BOARD_OBP60S3 || defined BOARD_OBP40S3
#include "Pagedata.h"
#include "OBP60Extensions.h"
/*
* Variant of PageClock with switchable analog / digital clock display.
* mode: (A)nalog | (D)igital | race (T)imer (T not implemented yet, falls back to analog)
*/
class PageClock2 : public Page
{
bool simulation = false;
int simtime;
bool keylock = false;
#ifdef BOARD_OBP60S3
char source = 'G'; // time source (R)TC | (G)PS | (N)TP
#endif
#ifdef BOARD_OBP40S3
char source = 'R'; // time source (R)TC | (G)PS | (N)TP
#endif
char mode = 'A'; // display mode (A)nalog | (D)igital | race (T)imer
char tz = 'L'; // time zone (L)ocal | (U)TC
double timezone = 0; // there are timezones with non int offsets, e.g. 5.5 or 5.75
double homelat;
double homelon;
bool homevalid = false; // homelat and homelon are valid
public:
PageClock2(CommonData& common)
{
commonData = &common;
common.logger->logDebug(GwLog::LOG, "Instantiate PageClock2");
simulation = common.config->getBool(common.config->useSimuData);
timezone = common.config->getString(common.config->timeZone).toDouble();
homelat = common.config->getString(common.config->homeLAT).toDouble();
homelon = common.config->getString(common.config->homeLON).toDouble();
homevalid = homelat >= -180.0 and homelat <= 180 and homelon >= -90.0 and homelon <= 90.0;
simtime = 38160; // time value 11:36
}
virtual void setupKeys()
{
Page::setupKeys();
commonData->keydata[0].label = "SRC";
commonData->keydata[1].label = "MODE";
commonData->keydata[4].label = "TZ";
}
// Key functions
virtual int handleKey(int key)
{
// Time source
if (key == 1) {
switch (source) {
case 'G':
source = 'R';
break;
case 'R':
source = 'G';
break;
default:
source = 'G';
break;
}
return 0;
}
if (key == 2) {
switch (mode) {
case 'A':
mode = 'D';
break;
case 'D':
mode = 'T';
break;
case 'T':
mode = 'A';
break;
default:
mode = 'A';
break;
}
return 0;
}
// Time zone: Local / UTC
if (key == 5) {
switch (tz) {
case 'L':
tz = 'U';
break;
case 'U':
tz = 'L';
break;
default:
tz = 'L';
break;
}
return 0;
}
// Keylock function
if (key == 11) { // Code for keylock
keylock = !keylock; // Toggle keylock
return 0; // Commit the key
}
return key;
}
int displayPage(PageData& pageData)
{
GwConfigHandler* config = commonData->config;
static String svalue1old = "";
static String unit1old = "";
static String svalue2old = "";
static String unit2old = "";
static String svalue3old = "";
static String unit3old = "";
static String svalue5old = "";
static String svalue6old = "";
double value1 = 0;
double value2 = 0;
double value3 = 0;
// Get config data
String lengthformat = config->getString(config->lengthFormat);
String dateformat = config->getString(config->dateFormat);
bool holdvalues = config->getBool(config->holdvalues);
String flashLED = config->getString(config->flashLED);
String backlightMode = config->getString(config->backlight);
// Get boat values for GPS time
GwApi::BoatValue* bvalue1 = pageData.values[0]; // First element in list (only one value by PageOneValue)
String name1 = bvalue1->getName().c_str(); // Value name
name1 = name1.substring(0, 6); // String length limit for value name
if (simulation == false) {
value1 = bvalue1->value; // Value as double in SI unit
} else {
value1 = simtime++; // Simulation data for time value 11:36 in seconds
} // Other simulation data see OBP60Formatter.cpp
bool valid1 = bvalue1->valid; // Valid information
String svalue1 = formatValue(bvalue1, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
String unit1 = formatValue(bvalue1, *commonData).unit; // Unit of value
if (valid1 == true) {
svalue1old = svalue1; // Save old value
unit1old = unit1; // Save old unit
}
// Get boat values for GPS date
GwApi::BoatValue* bvalue2 = pageData.values[1]; // Second element in list (only one value by PageOneValue)
String name2 = bvalue2->getName().c_str(); // Value name
name2 = name2.substring(0, 6); // String length limit for value name
value2 = bvalue2->value; // Value as double in SI unit
bool valid2 = bvalue2->valid; // Valid information
String svalue2 = formatValue(bvalue2, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
String unit2 = formatValue(bvalue2, *commonData).unit; // Unit of value
if (valid2 == true) {
svalue2old = svalue2; // Save old value
unit2old = unit2; // Save old unit
}
// Get boat values for HDOP date
GwApi::BoatValue* bvalue3 = pageData.values[2]; // Third element in list (only one value by PageOneValue)
String name3 = bvalue3->getName().c_str(); // Value name
name3 = name3.substring(0, 6); // String length limit for value name
value3 = bvalue3->value; // Value as double in SI unit
bool valid3 = bvalue3->valid; // Valid information
String svalue3 = formatValue(bvalue3, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
String unit3 = formatValue(bvalue3, *commonData).unit; // Unit of value
if (valid3 == true) {
svalue3old = svalue3; // Save old value
unit3old = unit3; // Save old unit
}
// Optical warning by limit violation (unused)
if (String(flashLED) == "Limit Violation") {
setBlinkingLED(false);
setFlashLED(false);
}
// Logging boat values
if (bvalue1 == NULL)
return PAGE_OK; // WTF why this statement?
LOG_DEBUG(GwLog::LOG, "Drawing at PageClock2, %s:%f, %s:%f", name1.c_str(), value1, name2.c_str(), value2);
// Draw page
//***********************************************************
// Set display in partial refresh mode
getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update
getdisplay().setTextColor(commonData->fgcolor);
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
struct tm* local_tm = localtime(&tv);
// Show values GPS date
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(10, 65);
if (holdvalues == false) {
if (source == 'G') {
// GPS value
getdisplay().print(svalue2);
} else if (commonData->data.rtcValid) {
// RTC value
if (tz == 'L') {
getdisplay().print(formatDate(dateformat, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
} else {
getdisplay().print(formatDate(dateformat, commonData->data.rtcTime.tm_year + 1900, commonData->data.rtcTime.tm_mon + 1, commonData->data.rtcTime.tm_mday));
}
} else {
getdisplay().print("---");
}
} else {
getdisplay().print(svalue2old);
}
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(10, 95);
getdisplay().print("Date"); // Name
// Horizintal separator left
getdisplay().fillRect(0, 149, 60, 3, commonData->fgcolor);
// Show values GPS time (small text bottom left, same as original)
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(10, 250);
if (holdvalues == false) {
if (source == 'G') {
getdisplay().print(svalue1); // Value
} else if (commonData->data.rtcValid) {
if (tz == 'L') {
getdisplay().print(formatTime('s', local_tm->tm_hour, local_tm->tm_min, local_tm->tm_sec));
} else {
getdisplay().print(formatTime('s', commonData->data.rtcTime.tm_hour, commonData->data.rtcTime.tm_min, commonData->data.rtcTime.tm_sec));
}
} else {
getdisplay().print("---");
}
} else {
getdisplay().print(svalue1old);
}
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(10, 220);
getdisplay().print("Time"); // Name
// Show values sunrise
String sunrise = "---";
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
sunrise = String(commonData->sundata.sunriseHour) + ":" + String(commonData->sundata.sunriseMinute + 100).substring(1);
svalue5old = sunrise;
} else if (simulation) {
sunrise = String("06:42");
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(335, 65);
if (holdvalues == false)
getdisplay().print(sunrise); // Value
else
getdisplay().print(svalue5old);
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(335, 95);
getdisplay().print("SunR"); // Name
// Horizintal separator right
getdisplay().fillRect(340, 149, 80, 3, commonData->fgcolor);
// Show values sunset
String sunset = "---";
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
sunset = String(commonData->sundata.sunsetHour) + ":" + String(commonData->sundata.sunsetMinute + 100).substring(1);
svalue6old = sunset;
} else if (simulation) {
sunset = String("21:03");
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(335, 250);
if (holdvalues == false)
getdisplay().print(sunset); // Value
else
getdisplay().print(svalue6old);
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(335, 220);
getdisplay().print("SunS"); // Name
//*******************************************************************************************
if (mode == 'D') {
// Digital clock mode: large 7-segment time centered on display
// Determine current time in hours/minutes/seconds (24h)
int hour24 = 0;
int minute24 = 0;
int second24 = 0;
if (source == 'R' && commonData->data.rtcValid) {
// RTC based
time_t tv2 = mktime(&commonData->data.rtcTime);
if (tz == 'L') {
tv2 += static_cast<time_t>(timezone * 3600);
}
struct tm* tm2 = localtime(&tv2);
hour24 = tm2->tm_hour;
minute24 = tm2->tm_min;
second24 = tm2->tm_sec;
} else {
// GPS / simulation based
double t = value1;
if (tz == 'L') {
t += timezone * 3600;
}
if (t >= 86400)
t -= 86400;
if (t < 0)
t += 86400;
hour24 = static_cast<int>(t / 3600.0);
int rest = static_cast<int>(t) - hour24 * 3600;
minute24 = rest / 60;
second24 = rest % 60;
}
char buf[9]; // "HH:MM:SS" + '\0'
snprintf(buf, sizeof(buf), "%02d:%02d:%02d", hour24, minute24, second24);
String timeStr = String(buf);
// Clear central area and draw large digital time
getdisplay().fillRect(0, 110, getdisplay().width(), 80, commonData->bgcolor);
getdisplay().setFont(&DSEG7Classic_BoldItalic60pt7b);
int16_t x1b, y1b;
uint16_t wb, hb;
getdisplay().getTextBounds(timeStr, 0, 0, &x1b, &y1b, &wb, &hb);
int16_t x = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(wb)) / 2;
int16_t y = 150 + hb / 2; // vertically around center (y=150)
getdisplay().setCursor(x, y);
getdisplay().print(timeStr);
// Small indicators inside the digital area
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(180, 110);
if (holdvalues == false) {
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
} else {
getdisplay().print(unit2old); // date unit
}
getdisplay().setCursor(185, 190);
if (source == 'G') {
getdisplay().print("GPS");
} else {
getdisplay().print("RTC");
}
} else {
// Analog clock mode (A/T) - original drawing
int rInstrument = 110; // Radius of clock
float pi = 3.141592;
getdisplay().fillCircle(200, 150, rInstrument + 10, commonData->fgcolor); // Outer circle
getdisplay().fillCircle(200, 150, rInstrument + 7, commonData->bgcolor); // Outer circle
for (int i = 0; i < 360; i = i + 1)
{
// Scaling values
float x = 200 + (rInstrument - 30) * sin(i / 180.0 * pi); // x-coordinate dots
float y = 150 - (rInstrument - 30) * cos(i / 180.0 * pi); // y-coordinate dots
const char* ii = "";
switch (i)
{
case 0: ii = "12"; break;
case 90: ii = "3"; break;
case 180: ii = "6"; break;
case 270: ii = "9"; break;
default: break;
}
// Print text centered on position x, y
int16_t x1c, y1c; // Return values of getTextBounds
uint16_t wc, hc; // Return values of getTextBounds
getdisplay().getTextBounds(ii, int(x), int(y), &x1c, &y1c, &wc, &hc); // Calc width of new string
getdisplay().setCursor(x - wc / 2, y + hc / 2);
if (i % 90 == 0) {
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().print(ii);
}
// Draw sub scale with dots
float sinx = 0;
float cosx = 0;
if (i % 6 == 0) {
float x1d = 200 + rInstrument * sin(i / 180.0 * pi);
float y1d = 150 - rInstrument * cos(i / 180.0 * pi);
getdisplay().fillCircle((int)x1d, (int)y1d, 2, commonData->fgcolor);
sinx = sin(i / 180.0 * pi);
cosx = cos(i / 180.0 * pi);
}
// Draw sub scale with lines (two triangles)
if (i % 30 == 0) {
float dx = 2; // Line thickness = 2*dx+1
float xx1 = -dx;
float xx2 = +dx;
float yy1 = -(rInstrument - 10);
float yy2 = -(rInstrument + 10);
getdisplay().fillTriangle(200 + (int)(cosx * xx1 - sinx * yy1), 150 + (int)(sinx * xx1 + cosx * yy1),
200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * xx1 - sinx * yy2), 150 + (int)(sinx * xx1 + cosx * yy2), commonData->fgcolor);
getdisplay().fillTriangle(200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * xx1 - sinx * yy2), 150 + (int)(sinx * xx1 + cosx * yy2),
200 + (int)(cosx * xx2 - sinx * yy2), 150 + (int)(sinx * xx2 + cosx * yy2), commonData->fgcolor);
}
}
// Print Unit in clock
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(175, 110);
if (holdvalues == false) {
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
} else {
getdisplay().print(unit2old); // date unit
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(185, 190);
if (source == 'G') {
getdisplay().print("GPS");
} else {
getdisplay().print("RTC");
}
// Clock values
double hour = 0;
double minute = 0;
if (source == 'R') {
if (tz == 'L') {
time_t tv2 = mktime(&commonData->data.rtcTime) + timezone * 3600;
struct tm* local_tm2 = localtime(&tv2);
minute = local_tm2->tm_min;
hour = local_tm2->tm_hour;
} else {
minute = commonData->data.rtcTime.tm_min;
hour = commonData->data.rtcTime.tm_hour;
}
hour += minute / 60;
} else {
if (tz == 'L') {
value1 += timezone * 3600;
}
if (value1 > 86400) { value1 -= 86400; }
if (value1 < 0) { value1 += 86400; }
hour = (value1 / 3600.0);
// minute = (hour - int(hour)) * 3600.0 / 60.0; // Analog minute pointer smooth moving
minute = int((hour - int(hour)) * 3600.0 / 60.0); // Jumping minute pointer from minute to minute
}
if (hour > 12) {
hour -= 12.0;
}
LOG_DEBUG(GwLog::DEBUG, "... PageClock2, value1: %f hour: %f minute:%f", value1, hour, minute);
// Draw hour pointer
float startwidth = 8; // Start width of pointer
if (valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true) {
float sinx = sin(hour * 30.0 * pi / 180); // Hour
float cosx = cos(hour * 30.0 * pi / 180);
// Normal pointer
// Pointer as triangle with center base 2*width
float xx1 = -startwidth;
float xx2 = startwidth;
float yy1 = -startwidth;
float yy2 = -(rInstrument * 0.5);
getdisplay().fillTriangle(200 + (int)(cosx * xx1 - sinx * yy1), 150 + (int)(sinx * xx1 + cosx * yy1),
200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * 0 - sinx * yy2), 150 + (int)(sinx * 0 + cosx * yy2), commonData->fgcolor);
// Inverted pointer
// Pointer as triangle with center base 2*width
float endwidth = 2; // End width of pointer
float ix1 = endwidth;
float ix2 = -endwidth;
float iy1 = -(rInstrument * 0.5);
float iy2 = -endwidth;
getdisplay().fillTriangle(200 + (int)(cosx * ix1 - sinx * iy1), 150 + (int)(sinx * ix1 + cosx * iy1),
200 + (int)(cosx * ix2 - sinx * iy1), 150 + (int)(sinx * ix2 + cosx * iy1),
200 + (int)(cosx * 0 - sinx * iy2), 150 + (int)(sinx * 0 + cosx * iy2), commonData->fgcolor);
}
// Draw minute pointer
startwidth = 8; // Start width of pointer
if (valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true) {
float sinx = sin(minute * 6.0 * pi / 180); // Minute
float cosx = cos(minute * 6.0 * pi / 180);
// Normal pointer
// Pointer as triangle with center base 2*width
float xx1 = -startwidth;
float xx2 = startwidth;
float yy1 = -startwidth;
float yy2 = -(rInstrument - 15);
getdisplay().fillTriangle(200 + (int)(cosx * xx1 - sinx * yy1), 150 + (int)(sinx * xx1 + cosx * yy1),
200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * 0 - sinx * yy2), 150 + (int)(sinx * 0 + cosx * yy2), commonData->fgcolor);
// Inverted pointer
// Pointer as triangle with center base 2*width
float endwidth = 2; // End width of pointer
float ix1 = endwidth;
float ix2 = -endwidth;
float iy1 = -(rInstrument - 15);
float iy2 = -endwidth;
getdisplay().fillTriangle(200 + (int)(cosx * ix1 - sinx * iy1), 150 + (int)(sinx * ix1 + cosx * iy1),
200 + (int)(cosx * ix2 - sinx * iy1), 150 + (int)(sinx * ix2 + cosx * iy1),
200 + (int)(cosx * 0 - sinx * iy2), 150 + (int)(sinx * 0 + cosx * iy2), commonData->fgcolor);
}
// Center circle
getdisplay().fillCircle(200, 150, startwidth + 6, commonData->bgcolor);
getdisplay().fillCircle(200, 150, startwidth + 4, commonData->fgcolor);
}
return PAGE_UPDATE;
};
};
static Page* createPage(CommonData& common)
{
return new PageClock2(common);
}
/**
* with the code below we make this page known to the PageTask
* we give it a type (name) that can be selected in the config
* we define which function is to be called
* we provide the number of user parameters we expect (0 here)
* and we provide the names of the fixed values we need
*/
PageDescription registerPageClock2(
"Clock2", // Page name
createPage, // Action
0, // Number of bus values depends on selection in Web configuration
{"GPST", "GPSD", "HDOP"}, // Bus values we need in the page
true // Show display header on/off
);
#endif

View File

@@ -1,777 +0,0 @@
#if defined BOARD_OBP60S3 || defined BOARD_OBP40S3
#include "Pagedata.h"
#include "OBP60Extensions.h"
/*
* PageClock3: Clock page with
* - Analog mode (mode == 'A')
* - Digital mode (mode == 'D')
* - Countdown timer mode (mode == 'T')
*
* Timer mode:
* - Format HH:MM:SS (24h, leading zeros)
* - Keys in timer mode:
* K1: MODE (A/D/T)
* K2: POS (select field: HH / MM / SS)
* K3: + (increment selected field)
* K4: - (decrement selected field)
* K5: RUN (start/stop countdown)
* - Selection marker: line under active field (width 2px, not wider than digits)
* - Editing only possible when timer is not running
* - When page is left, running timer continues in background using RTC time
* (on re-entry, remaining time is recalculated from RTC)
*/
class PageClock3 : public Page
{
bool simulation = false;
int simtime;
bool keylock = false;
#ifdef BOARD_OBP60S3
char source = 'G'; // time source (R)TC | (G)PS | (N)TP
#endif
#ifdef BOARD_OBP40S3
char source = 'R'; // time source (R)TC | (G)PS | (N)TP
#endif
char mode = 'A'; // display mode (A)nalog | (D)igital | race (T)imer
char tz = 'L'; // time zone (L)ocal | (U)TC
double timezone = 0; // there are timezones with non int offsets, e.g. 5.5 or 5.75
double homelat;
double homelon;
bool homevalid = false; // homelat and homelon are valid
// Timer state (static so it survives page switches)
static bool timerInitialized;
static bool timerRunning;
static int timerHours;
static int timerMinutes;
static int timerSeconds;
static int selectedField; // 0 = hours, 1 = minutes, 2 = seconds
static bool showSelectionMarker;
static time_t timerEndEpoch; // absolute end time based on RTC
void setupTimerDefaults()
{
if (!timerInitialized) {
timerInitialized = true;
timerRunning = false;
timerHours = 0;
timerMinutes = 0;
timerSeconds = 0;
selectedField = 0;
showSelectionMarker = true;
timerEndEpoch = 0;
}
}
static int clamp(int value, int minVal, int maxVal)
{
if (value < minVal) return minVal;
if (value > maxVal) return maxVal;
return value;
}
void incrementSelected()
{
if (selectedField == 0) {
timerHours = clamp(timerHours + 1, 0, 23);
} else if (selectedField == 1) {
timerMinutes = clamp(timerMinutes + 1, 0, 59);
} else {
timerSeconds = clamp(timerSeconds + 1, 0, 59);
}
}
void decrementSelected()
{
if (selectedField == 0) {
timerHours = clamp(timerHours - 1, 0, 23);
} else if (selectedField == 1) {
timerMinutes = clamp(timerMinutes - 1, 0, 59);
} else {
timerSeconds = clamp(timerSeconds - 1, 0, 59);
}
}
int totalTimerSeconds() const
{
return timerHours * 3600 + timerMinutes * 60 + timerSeconds;
}
public:
PageClock3(CommonData& common)
{
commonData = &common;
common.logger->logDebug(GwLog::LOG, "Instantiate PageClock3");
simulation = common.config->getBool(common.config->useSimuData);
timezone = common.config->getString(common.config->timeZone).toDouble();
homelat = common.config->getString(common.config->homeLAT).toDouble();
homelon = common.config->getString(common.config->homeLON).toDouble();
homevalid = homelat >= -180.0 and homelat <= 180 and homelon >= -90.0 and homelon <= 90.0;
simtime = 38160; // time value 11:36
setupTimerDefaults();
}
virtual void setupKeys()
{
Page::setupKeys();
if (mode == 'T') {
// Timer mode: MODE, POS, +, -, RUN
commonData->keydata[0].label = "MODE";
commonData->keydata[1].label = "POS";
commonData->keydata[2].label = "+";
commonData->keydata[3].label = "-";
commonData->keydata[4].label = "RUN";
} else {
// Clock modes: like original
commonData->keydata[0].label = "SRC";
commonData->keydata[1].label = "MODE";
commonData->keydata[4].label = "TZ";
}
}
// Key functions
virtual int handleKey(int key)
{
setupTimerDefaults();
// Keylock function
if (key == 11) { // Code for keylock
keylock = !keylock; // Toggle keylock
return 0; // Commit the key
}
if (mode == 'T') {
// Timer mode key handling
// MODE (K1): cycle display mode A/D/T
if (key == 1) {
switch (mode) {
case 'A': mode = 'D'; break;
case 'D': mode = 'T'; break;
case 'T': mode = 'A'; break;
default: mode = 'A'; break;
}
setupKeys();
return 0;
}
// POS (K2): select field HH / MM / SS (only if timer not running)
if (key == 2 && !timerRunning) {
selectedField = (selectedField + 1) % 3;
showSelectionMarker = true;
return 0;
}
// + (K3): increment selected field (only if timer not running)
if (key == 3 && !timerRunning) {
incrementSelected();
return 0;
}
// - (K4): decrement selected field (only if timer not running)
if (key == 4 && !timerRunning) {
decrementSelected();
return 0;
}
// RUN (K5): start/stop timer
if (key == 5) {
if (!timerRunning) {
// Start timer if a non-zero duration is set
int total = totalTimerSeconds();
if (total > 0 && commonData->data.rtcValid) {
struct tm rtcCopy = commonData->data.rtcTime;
time_t nowEpoch = mktime(&rtcCopy);
timerEndEpoch = nowEpoch + total;
timerRunning = true;
showSelectionMarker = false;
}
} else {
// Stop timer: compute remaining time and keep as new setting
if (commonData->data.rtcValid) {
struct tm rtcCopy = commonData->data.rtcTime;
time_t nowEpoch = mktime(&rtcCopy);
time_t remaining = timerEndEpoch - nowEpoch;
if (remaining < 0) remaining = 0;
int rem = static_cast<int>(remaining);
timerHours = rem / 3600;
rem -= timerHours * 3600;
timerMinutes = rem / 60;
timerSeconds = rem % 60;
}
timerRunning = false;
// marker will become visible again only after POS press
}
return 0;
}
// In timer mode, other keys are passed through
return key;
}
// Clock (A/D) modes key handling like original PageClock
// Time source (K1)
if (key == 1) {
switch (source) {
case 'G': source = 'R'; break;
case 'R': source = 'G'; break;
default: source = 'G'; break;
}
return 0;
}
// MODE (K2)
if (key == 2) {
switch (mode) {
case 'A': mode = 'D'; break;
case 'D': mode = 'T'; break;
case 'T': mode = 'A'; break;
default: mode = 'A'; break;
}
setupKeys();
return 0;
}
// Time zone: Local / UTC (K5)
if (key == 5) {
switch (tz) {
case 'L': tz = 'U'; break;
case 'U': tz = 'L'; break;
default: tz = 'L'; break;
}
return 0;
}
return key;
}
int displayPage(PageData& pageData)
{
GwConfigHandler* config = commonData->config;
GwLog* logger = commonData->logger;
setupTimerDefaults();
setupKeys(); // ensure correct key labels for current mode
static String svalue1old = "";
static String unit1old = "";
static String svalue2old = "";
static String unit2old = "";
static String svalue3old = "";
static String unit3old = "";
static String svalue5old = "";
static String svalue6old = "";
double value1 = 0;
double value2 = 0;
double value3 = 0;
// Get config data
String lengthformat = config->getString(config->lengthFormat);
String dateformat = config->getString(config->dateFormat);
bool holdvalues = config->getBool(config->holdvalues);
String flashLED = config->getString(config->flashLED);
String backlightMode = config->getString(config->backlight);
// Get boat values for GPS time
GwApi::BoatValue* bvalue1 = pageData.values[0]; // First element in list
String name1 = bvalue1->getName().c_str(); // Value name
name1 = name1.substring(0, 6); // String length limit for value name
if (simulation == false) {
value1 = bvalue1->value; // Value as double in SI unit
} else {
value1 = simtime++; // Simulation data for time value 11:36 in seconds
} // Other simulation data see OBP60Formatter.cpp
bool valid1 = bvalue1->valid; // Valid information
String svalue1 = formatValue(bvalue1, *commonData).svalue; // Formatted value
String unit1 = formatValue(bvalue1, *commonData).unit; // Unit of value
if (valid1 == true) {
svalue1old = svalue1; // Save old value
unit1old = unit1; // Save old unit
}
// Get boat values for GPS date
GwApi::BoatValue* bvalue2 = pageData.values[1]; // Second element in list
String name2 = bvalue2->getName().c_str(); // Value name
name2 = name2.substring(0, 6); // String length limit for value name
value2 = bvalue2->value; // Value as double in SI unit
bool valid2 = bvalue2->valid; // Valid information
String svalue2 = formatValue(bvalue2, *commonData).svalue; // Formatted value
String unit2 = formatValue(bvalue2, *commonData).unit; // Unit of value
if (valid2 == true) {
svalue2old = svalue2; // Save old value
unit2old = unit2; // Save old unit
}
// Get boat values for HDOP
GwApi::BoatValue* bvalue3 = pageData.values[2]; // Third element in list
String name3 = bvalue3->getName().c_str(); // Value name
name3 = name3.substring(0, 6); // String length limit for value name
value3 = bvalue3->value; // Value as double in SI unit
bool valid3 = bvalue3->valid; // Valid information
String svalue3 = formatValue(bvalue3, *commonData).svalue; // Formatted value
String unit3 = formatValue(bvalue3, *commonData).unit; // Unit of value
if (valid3 == true) {
svalue3old = svalue3; // Save old value
unit3old = unit3; // Save old unit
}
// Optical warning by limit violation (unused)
if (String(flashLED) == "Limit Violation") {
setBlinkingLED(false);
setFlashLED(false);
}
// Logging boat values
if (bvalue1 == NULL) return PAGE_OK;
LOG_DEBUG(GwLog::LOG, "Drawing at PageClock3, %s:%f, %s:%f", name1.c_str(), value1, name2.c_str(), value2);
// Draw page
//***********************************************************
// Set display in partial refresh mode
getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update
getdisplay().setTextColor(commonData->fgcolor);
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
struct tm* local_tm = localtime(&tv);
// Show values GPS date
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(10, 65);
if (holdvalues == false) {
if (source == 'G') {
// GPS value
getdisplay().print(svalue2);
} else if (commonData->data.rtcValid) {
// RTC value
if (tz == 'L') {
getdisplay().print(formatDate(dateformat, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
} else {
getdisplay().print(formatDate(dateformat, commonData->data.rtcTime.tm_year + 1900, commonData->data.rtcTime.tm_mon + 1, commonData->data.rtcTime.tm_mday));
}
} else {
getdisplay().print("---");
}
} else {
getdisplay().print(svalue2old);
}
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(10, 95);
getdisplay().print("Date"); // Name
// Horizontal separator left
getdisplay().fillRect(0, 149, 60, 3, commonData->fgcolor);
// Show values GPS time (small text bottom left)
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(10, 250);
if (holdvalues == false) {
if (source == 'G') {
getdisplay().print(svalue1); // Value
} else if (commonData->data.rtcValid) {
if (tz == 'L') {
getdisplay().print(formatTime('s', local_tm->tm_hour, local_tm->tm_min, local_tm->tm_sec));
} else {
getdisplay().print(formatTime('s', commonData->data.rtcTime.tm_hour, commonData->data.rtcTime.tm_min, commonData->data.rtcTime.tm_sec));
}
} else {
getdisplay().print("---");
}
} else {
getdisplay().print(svalue1old);
}
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(10, 220);
getdisplay().print("Time"); // Name
// Show values sunrise
String sunrise = "---";
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
sunrise = String(commonData->sundata.sunriseHour) + ":" + String(commonData->sundata.sunriseMinute + 100).substring(1);
svalue5old = sunrise;
} else if (simulation) {
sunrise = String("06:42");
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(335, 65);
if (holdvalues == false) getdisplay().print(sunrise); // Value
else getdisplay().print(svalue5old);
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(335, 95);
getdisplay().print("SunR"); // Name
// Horizontal separator right
getdisplay().fillRect(340, 149, 80, 3, commonData->fgcolor);
// Show values sunset
String sunset = "---";
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
sunset = String(commonData->sundata.sunsetHour) + ":" + String(commonData->sundata.sunsetMinute + 100).substring(1);
svalue6old = sunset;
} else if (simulation) {
sunset = String("21:03");
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(335, 250);
if (holdvalues == false) getdisplay().print(sunset); // Value
else getdisplay().print(svalue6old);
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(335, 220);
getdisplay().print("SunS"); // Name
//*******************************************************************************************
if (mode == 'T') {
// TIMER MODE: countdown timer HH:MM:SS in the center with 7-segment font
int dispH = timerHours;
int dispM = timerMinutes;
int dispS = timerSeconds;
// Update remaining time if timer is running (based on RTC)
if (timerRunning && commonData->data.rtcValid) {
struct tm rtcCopy = commonData->data.rtcTime;
time_t nowEpoch = mktime(&rtcCopy);
time_t remaining = timerEndEpoch - nowEpoch;
if (remaining <= 0) {
remaining = 0;
timerRunning = false;
}
int rem = static_cast<int>(remaining);
dispH = rem / 3600;
rem -= dispH * 3600;
dispM = rem / 60;
dispS = rem % 60;
}
char buf[9]; // "HH:MM:SS"
snprintf(buf, sizeof(buf), "%02d:%02d:%02d", dispH, dispM, dispS);
String timeStr = String(buf);
// Clear central area and draw large digital time
getdisplay().fillRect(0, 110, getdisplay().width(), 80, commonData->bgcolor);
getdisplay().setFont(&DSEG7Classic_BoldItalic60pt7b);
// Determine widths for digits and colon to position selection underline exactly
int16_t x0, y0;
uint16_t wDigit, hDigit;
uint16_t wColon, hColon;
getdisplay().getTextBounds("00", 0, 0, &x0, &y0, &wDigit, &hDigit);
getdisplay().getTextBounds(":", 0, 0, &x0, &y0, &wColon, &hColon);
uint16_t totalWidth = 3 * wDigit + 2 * wColon;
int16_t baseX = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(totalWidth)) / 2;
int16_t centerY = 150;
// Draw time string centered
int16_t x1b, y1b;
uint16_t wb, hb;
getdisplay().getTextBounds(timeStr, 0, 0, &x1b, &y1b, &wb, &hb);
int16_t textX = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(wb)) / 2;
int16_t textY = centerY + hb / 2;
getdisplay().setCursor(textX, textY);
getdisplay().print(timeStr);
// Selection marker (only visible when not running and POS pressed)
if (!timerRunning && showSelectionMarker) {
int16_t selX = baseX;
if (selectedField == 1) {
selX = baseX + wDigit + wColon; // minutes start
} else if (selectedField == 2) {
selX = baseX + 2 * wDigit + 2 * wColon; // seconds start
}
int16_t underlineY = centerY + hb / 2 + 2;
getdisplay().fillRect(selX, underlineY, wDigit, 2, commonData->fgcolor);
}
// Small indicators: timezone and source
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(180, 110);
if (holdvalues == false) {
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
} else {
getdisplay().print(unit2old); // date unit
}
getdisplay().setCursor(185, 190);
if (source == 'G') {
getdisplay().print("GPS");
} else {
getdisplay().print("RTC");
}
} else if (mode == 'D') {
// DIGITAL CLOCK MODE: large 7-segment time based on GPS/RTC
int hour24 = 0;
int minute24 = 0;
int second24 = 0;
if (source == 'R' && commonData->data.rtcValid) {
time_t tv2 = mktime(&commonData->data.rtcTime);
if (tz == 'L') {
tv2 += static_cast<time_t>(timezone * 3600);
}
struct tm* tm2 = localtime(&tv2);
hour24 = tm2->tm_hour;
minute24 = tm2->tm_min;
second24 = tm2->tm_sec;
} else {
double t = value1;
if (tz == 'L') {
t += timezone * 3600;
}
if (t >= 86400) t -= 86400;
if (t < 0) t += 86400;
hour24 = static_cast<int>(t / 3600.0);
int rest = static_cast<int>(t) - hour24 * 3600;
minute24 = rest / 60;
second24 = rest % 60;
}
char buf[9]; // "HH:MM:SS"
snprintf(buf, sizeof(buf), "%02d:%02d:%02d", hour24, minute24, second24);
String timeStr = String(buf);
getdisplay().fillRect(0, 110, getdisplay().width(), 80, commonData->bgcolor);
getdisplay().setFont(&DSEG7Classic_BoldItalic60pt7b);
int16_t x1b, y1b;
uint16_t wb, hb;
getdisplay().getTextBounds(timeStr, 0, 0, &x1b, &y1b, &wb, &hb);
int16_t x = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(wb)) / 2;
int16_t y = 150 + hb / 2;
getdisplay().setCursor(x, y);
getdisplay().print(timeStr);
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(180, 110);
if (holdvalues == false) {
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
} else {
getdisplay().print(unit2old); // date unit
}
getdisplay().setCursor(185, 190);
if (source == 'G') {
getdisplay().print("GPS");
} else {
getdisplay().print("RTC");
}
} else {
// ANALOG CLOCK MODE (mode == 'A')
int rInstrument = 110; // Radius of clock
float pi = 3.141592;
getdisplay().fillCircle(200, 150, rInstrument + 10, commonData->fgcolor); // Outer circle
getdisplay().fillCircle(200, 150, rInstrument + 7, commonData->bgcolor); // Outer circle
for (int i = 0; i < 360; i = i + 1)
{
// Scaling values
float x = 200 + (rInstrument - 30) * sin(i / 180.0 * pi); // x-coordinate dots
float y = 150 - (rInstrument - 30) * cos(i / 180.0 * pi); // y-coordinate dots
const char* ii = "";
switch (i)
{
case 0: ii = "12"; break;
case 90: ii = "3"; break;
case 180: ii = "6"; break;
case 270: ii = "9"; break;
default: break;
}
// Print text centered on position x, y
int16_t x1c, y1c; // Return values of getTextBounds
uint16_t wc, hc; // Return values of getTextBounds
getdisplay().getTextBounds(ii, int(x), int(y), &x1c, &y1c, &wc, &hc); // Calc width of new string
getdisplay().setCursor(x - wc / 2, y + hc / 2);
if (i % 90 == 0) {
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().print(ii);
}
// Draw sub scale with dots
float sinx = 0;
float cosx = 0;
if (i % 6 == 0) {
float x1d = 200 + rInstrument * sin(i / 180.0 * pi);
float y1d = 150 - rInstrument * cos(i / 180.0 * pi);
getdisplay().fillCircle((int)x1d, (int)y1d, 2, commonData->fgcolor);
sinx = sin(i / 180.0 * pi);
cosx = cos(i / 180.0 * pi);
}
// Draw sub scale with lines (two triangles)
if (i % 30 == 0) {
float dx = 2; // Line thickness = 2*dx+1
float xx1 = -dx;
float xx2 = +dx;
float yy1 = -(rInstrument - 10);
float yy2 = -(rInstrument + 10);
getdisplay().fillTriangle(200 + (int)(cosx * xx1 - sinx * yy1), 150 + (int)(sinx * xx1 + cosx * yy1),
200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * xx1 - sinx * yy2), 150 + (int)(sinx * xx1 + cosx * yy2), commonData->fgcolor);
getdisplay().fillTriangle(200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * xx1 - sinx * yy2), 150 + (int)(sinx * xx1 + cosx * yy2),
200 + (int)(cosx * xx2 - sinx * yy2), 150 + (int)(sinx * xx2 + cosx * yy2), commonData->fgcolor);
}
}
// Print Unit in clock
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(175, 110);
if (holdvalues == false) {
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
} else {
getdisplay().print(unit2old); // date unit
}
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(185, 190);
if (source == 'G') {
getdisplay().print("GPS");
} else {
getdisplay().print("RTC");
}
// Clock values
double hour = 0;
double minute = 0;
if (source == 'R') {
if (tz == 'L') {
time_t tv2 = mktime(&commonData->data.rtcTime) + timezone * 3600;
struct tm* local_tm2 = localtime(&tv2);
minute = local_tm2->tm_min;
hour = local_tm2->tm_hour;
} else {
minute = commonData->data.rtcTime.tm_min;
hour = commonData->data.rtcTime.tm_hour;
}
hour += minute / 60;
} else {
if (tz == 'L') {
value1 += timezone * 3600;
}
if (value1 > 86400) { value1 -= 86400; }
if (value1 < 0) { value1 += 86400; }
hour = (value1 / 3600.0);
// minute = (hour - int(hour)) * 3600.0 / 60.0; // Analog minute pointer smooth moving
minute = int((hour - int(hour)) * 3600.0 / 60.0); // Jumping minute pointer from minute to minute
}
if (hour > 12) {
hour -= 12.0;
}
LOG_DEBUG(GwLog::DEBUG, "... PageClock3, value1: %f hour: %f minute:%f", value1, hour, minute);
// Draw hour pointer
float startwidth = 8; // Start width of pointer
if (valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true) {
float sinx = sin(hour * 30.0 * pi / 180); // Hour
float cosx = cos(hour * 30.0 * pi / 180);
// Normal pointer
// Pointer as triangle with center base 2*width
float xx1 = -startwidth;
float xx2 = startwidth;
float yy1 = -startwidth;
float yy2 = -(rInstrument * 0.5);
getdisplay().fillTriangle(200 + (int)(cosx * xx1 - sinx * yy1), 150 + (int)(sinx * xx1 + cosx * yy1),
200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * 0 - sinx * yy2), 150 + (int)(sinx * 0 + cosx * yy2), commonData->fgcolor);
// Inverted pointer
// Pointer as triangle with center base 2*width
float endwidth = 2; // End width of pointer
float ix1 = endwidth;
float ix2 = -endwidth;
float iy1 = -(rInstrument * 0.5);
float iy2 = -endwidth;
getdisplay().fillTriangle(200 + (int)(cosx * ix1 - sinx * iy1), 150 + (int)(sinx * ix1 + cosx * iy1),
200 + (int)(cosx * ix2 - sinx * iy1), 150 + (int)(sinx * ix2 + cosx * iy1),
200 + (int)(cosx * 0 - sinx * iy2), 150 + (int)(sinx * 0 + cosx * iy2), commonData->fgcolor);
}
// Draw minute pointer
startwidth = 8; // Start width of pointer
if (valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true) {
float sinx = sin(minute * 6.0 * pi / 180); // Minute
float cosx = cos(minute * 6.0 * pi / 180);
// Normal pointer
// Pointer as triangle with center base 2*width
float xx1 = -startwidth;
float xx2 = startwidth;
float yy1 = -startwidth;
float yy2 = -(rInstrument - 15);
getdisplay().fillTriangle(200 + (int)(cosx * xx1 - sinx * yy1), 150 + (int)(sinx * xx1 + cosx * yy1),
200 + (int)(cosx * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
200 + (int)(cosx * 0 - sinx * yy2), 150 + (int)(sinx * 0 + cosx * yy2), commonData->fgcolor);
// Inverted pointer
// Pointer as triangle with center base 2*width
float endwidth = 2; // End width of pointer
float ix1 = endwidth;
float ix2 = -endwidth;
float iy1 = -(rInstrument - 15);
float iy2 = -endwidth;
getdisplay().fillTriangle(200 + (int)(cosx * ix1 - sinx * iy1), 150 + (int)(sinx * ix1 + cosx * iy1),
200 + (int)(cosx * ix2 - sinx * iy1), 150 + (int)(sinx * ix2 + cosx * iy1),
200 + (int)(cosx * 0 - sinx * iy2), 150 + (int)(sinx * 0 + cosx * iy2), commonData->fgcolor);
}
// Center circle
getdisplay().fillCircle(200, 150, startwidth + 6, commonData->bgcolor);
getdisplay().fillCircle(200, 150, startwidth + 4, commonData->fgcolor);
}
return PAGE_UPDATE;
};
};
// Static member definitions
bool PageClock3::timerInitialized = false;
bool PageClock3::timerRunning = false;
int PageClock3::timerHours = 0;
int PageClock3::timerMinutes = 0;
int PageClock3::timerSeconds = 0;
int PageClock3::selectedField = 0;
bool PageClock3::showSelectionMarker = true;
time_t PageClock3::timerEndEpoch = 0;
static Page* createPage(CommonData& common)
{
return new PageClock3(common);
}
/**
* with the code below we make this page known to the PageTask
* we give it a type (name) that can be selected in the config
* we define which function is to be called
* we provide the number of user parameters we expect (0 here)
* and we provide the names of the fixed values we need
*/
PageDescription registerPageClock3(
"Clock3", // Page name
createPage, // Action
0, // Number of bus values depends on selection in Web configuration
{"GPST", "GPSD", "HDOP"}, // Bus values we need in the page
true // Show display header on/off
);
#endif

View File

@@ -1,224 +0,0 @@
#if defined BOARD_OBP60S3 || defined BOARD_OBP40S3
#include "Pagedata.h"
#include "OBP60Extensions.h"
/**
* Simple digital clock page.
*
* - Shows system time as large digital value in the center
* - Uses same data sources and configuration as PageClock (GPS / RTC, time zone)
* - Keys:
* K1: toggle time source (GPS / RTC)
* K5: toggle time zone (Local / UTC)
* K11: keylock
*/
class PageClockDigital : public Page
{
bool simulation = false;
int simtime = 0;
char source; // time source (R)TC | (G)PS
char tz = 'L'; // time zone (L)ocal | (U)TC
double timezone = 0.0;
public:
PageClockDigital(CommonData& common)
{
commonData = &common;
common.logger->logDebug(GwLog::LOG, "Instantiate PageClockDigital");
simulation = common.config->getBool(common.config->useSimuData);
timezone = common.config->getString(common.config->timeZone).toDouble();
#ifdef BOARD_OBP60S3
source = 'G'; // default to GPS time on OBP60
#endif
#ifdef BOARD_OBP40S3
source = 'R'; // default to RTC time on OBP40
#endif
simtime = 38160; // time value 11:36 for simulation (seconds)
}
virtual void setupKeys()
{
Page::setupKeys();
commonData->keydata[0].label = "SRC";
commonData->keydata[4].label = "TZ";
}
// Key functions
virtual int handleKey(int key)
{
// Time source
if (key == 1) {
switch (source) {
case 'G':
source = 'R';
break;
case 'R':
source = 'G';
break;
default:
source = 'G';
break;
}
return 0;
}
// Time zone: Local / UTC
if (key == 5) {
switch (tz) {
case 'L':
tz = 'U';
break;
case 'U':
tz = 'L';
break;
default:
tz = 'L';
break;
}
return 0;
}
// Keylock function
if (key == 11) { // Code for keylock
commonData->keylock = !commonData->keylock;
return 0; // Commit the key
}
return key;
}
int displayPage(PageData& pageData)
{
GwConfigHandler* config = commonData->config;
static String svalueTimeOld = "";
static String svalueDateOld = "";
// Get config data
bool holdvalues = config->getBool(config->holdvalues);
String flashLED = config->getString(config->flashLED);
// Get boat values for GPS time and date (same as PageClock)
if (pageData.values.size() < 2) {
return PAGE_OK;
}
GwApi::BoatValue* bvalueTime = pageData.values[0];
GwApi::BoatValue* bvalueDate = pageData.values[1];
if (bvalueTime == nullptr || bvalueDate == nullptr) {
return PAGE_OK;
}
double valueTime = 0;
if (!simulation) {
valueTime = bvalueTime->value; // Value as double in SI unit (seconds)
} else {
valueTime = simtime++; // Simulation data
}
bool validTime = bvalueTime->valid;
String svalueTime = formatValue(bvalueTime, *commonData).svalue; // formatted time string
if (validTime) {
svalueTimeOld = svalueTime; // Save old value
}
bool validDate = bvalueDate->valid;
String svalueDate = formatValue(bvalueDate, *commonData).svalue; // formatted date string
if (validDate) {
svalueDateOld = svalueDate; // Save old value
}
// Optical warning by limit violation (unused)
if (flashLED == "Limit Violation") {
setBlinkingLED(false);
setFlashLED(false);
}
// Draw page
//***********************************************************
// Set display in partial refresh mode
getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update
getdisplay().setTextColor(commonData->fgcolor);
// Build time string depending on source and configuration
String timeStr = "---";
if (!holdvalues) {
if (source == 'G') {
// GPS value as formatted by formatter
timeStr = svalueTime;
} else if (commonData->data.rtcValid) {
// RTC value
time_t tv = mktime(&commonData->data.rtcTime);
if (tz == 'L') {
tv += static_cast<time_t>(timezone * 3600);
}
struct tm* local_tm = localtime(&tv);
timeStr = formatTime('s', local_tm->tm_hour, local_tm->tm_min, local_tm->tm_sec);
}
} else {
timeStr = svalueTimeOld;
}
// Clear central area and draw large digital time
getdisplay().fillRect(0, 80, getdisplay().width(), 140, commonData->bgcolor);
getdisplay().setFont(&DSEG7Classic_BoldItalic60pt7b);
int16_t x1, y1;
uint16_t w, h;
getdisplay().getTextBounds(timeStr, 0, 0, &x1, &y1, &w, &h);
int16_t x = (static_cast<int16_t>(getdisplay().width()) - static_cast<int16_t>(w)) / 2;
int16_t y = (static_cast<int16_t>(getdisplay().height()) + static_cast<int16_t>(h)) / 2;
getdisplay().setCursor(x, y);
getdisplay().print(timeStr);
// Show date in the upper left corner
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(10, 40);
getdisplay().print("Date");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(10, 60);
if (!holdvalues) {
getdisplay().print(svalueDate);
} else {
getdisplay().print(svalueDateOld);
}
// Show small labels for source and timezone in the lower right corner
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(getdisplay().width() - 80, getdisplay().height() - 40);
getdisplay().print(source == 'G' ? "GPS" : "RTC");
getdisplay().setCursor(getdisplay().width() - 80, getdisplay().height() - 20);
getdisplay().print(tz == 'L' ? "LOC" : "UTC");
return PAGE_UPDATE;
};
};
static Page* createPage(CommonData& common)
{
return new PageClockDigital(common);
}
/**
* Register page so it can be selected in the configuration.
* Uses the same fixed values as PageClock.
*/
PageDescription registerPageClockDigital(
"ClockDigital", // Page name
createPage, // Action
0, // Number of user parameters
{"GPST", "GPSD", "HDOP"}, // Bus values we need in the page
true // Show display header on/off
);
#endif

View File

@@ -162,9 +162,13 @@ public:
constexpr int ZOOM_KEY = 1; constexpr int ZOOM_KEY = 1;
#endif #endif
if (dataHstryBuf) { // show "Mode" key only if chart supported boat data type is available if (dataHstryBuf) { // show "Mode" key only if chart-supported boat data type is available
commonData->keydata[0].label = "MODE"; commonData->keydata[0].label = "MODE";
commonData->keydata[ZOOM_KEY].label = "ZOOM"; if (pageMode != VALUE) { // show "ZOOM" key only if chart is visible
commonData->keydata[ZOOM_KEY].label = "ZOOM";
} else {
commonData->keydata[ZOOM_KEY].label = "";
}
} else { } else {
commonData->keydata[0].label = ""; commonData->keydata[0].label = "";
commonData->keydata[ZOOM_KEY].label = ""; commonData->keydata[ZOOM_KEY].label = "";
@@ -189,14 +193,15 @@ public:
pageMode = VALUE; pageMode = VALUE;
break; break;
} }
setupKeys(); // Adjust key definition depending on <pageMode> and chart-supported boat data type
return 0; // Commit the key return 0; // Commit the key
} }
// Set time frame to show for history chart // Set time frame to show for chart
#if defined BOARD_OBP60S3 #if defined BOARD_OBP60S3
if (key == 5) { if (key == 5 && pageMode != VALUE) {
#elif defined BOARD_OBP40S3 #elif defined BOARD_OBP40S3
if (key == 2) { if (key == 2 && pageMode != VALUE) {
#endif #endif
if (dataIntv == 1) { if (dataIntv == 1) {
dataIntv = 2; dataIntv = 2;
@@ -247,7 +252,7 @@ public:
} }
} }
setupKeys(); // adjust <mode> key depending on chart supported boat data type setupKeys(); // Adjust key definition depending on <pageMode> and chart-supported boat data type
} }
int displayPage(PageData& pageData) int displayPage(PageData& pageData)

View File

@@ -15,6 +15,7 @@
#include "images/logo64.xbm" #include "images/logo64.xbm"
#include <esp32/clk.h> #include <esp32/clk.h>
#include "qrcode.h" #include "qrcode.h"
#include <vector>
#ifdef BOARD_OBP40S3 #ifdef BOARD_OBP40S3
#include "dirent.h" #include "dirent.h"
@@ -37,9 +38,11 @@ private:
String buzzer_mode; String buzzer_mode;
uint8_t buzzer_power; uint8_t buzzer_power;
String cpuspeed; String cpuspeed;
String powermode;
String rtc_module; String rtc_module;
String gps_module; String gps_module;
String env_module; String env_module;
String flashLED;
String batt_sensor; String batt_sensor;
String solar_sensor; String solar_sensor;
@@ -48,15 +51,445 @@ private:
double homelat; double homelat;
double homelon; double homelon;
char mode = 'N'; // (N)ormal, (S)ettings, (D)evice list, (C)ard char mode = 'N'; // (N)ormal, (S)ettings, (C)onfiguration, (D)evice list, c(A)rd
#ifdef PATCH_N2K
struct device {
uint64_t NAME;
uint8_t id;
char hex_name[17];
uint16_t manuf_code;
const char *model;
};
std::vector<device> devicelist;
#endif
void incMode() {
if (mode == 'N') { // Normal
mode = 'S';
} else if (mode == 'S') { // Settings
mode = 'C';
} else if (mode == 'C') { // Config
mode = 'D';
} else if (mode == 'D') { // Device list
if (use_sdcard) {
mode = 'A'; // SD-Card
} else {
mode = 'N';
}
} else {
mode = 'N';
}
}
void decMode() {
if (mode == 'N') {
if (use_sdcard) {
mode = 'A'; // SD-Card
} else {
mode = 'D'; // Device list
}
} else if (mode == 'S') { // Settings
mode = 'N';
} else if (mode == 'C') { // Config
mode = 'S';
} else if (mode == 'D') { // Device list
mode = 'C';
} else {
mode = 'D';
}
}
void displayModeNormal() {
// Default system page view
uint16_t y0 = 155;
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(8, 48);
getdisplay().print("System Information");
getdisplay().drawXBitmap(320, 25, logo64_bits, logo64_width, logo64_height, commonData->fgcolor);
getdisplay().setFont(&Ubuntu_Bold8pt8b);
char ssid[13];
snprintf(ssid, 13, "%04X%08X", (uint16_t)(chipid >> 32), (uint32_t)chipid);
displayBarcode(String(ssid), 320, 200, 2);
getdisplay().setCursor(8, 70);
getdisplay().print(String("MCUDEVICE-") + String(ssid));
getdisplay().setCursor(8, 95);
getdisplay().print("Firmware version: ");
getdisplay().setCursor(150, 95);
getdisplay().print(VERSINFO);
getdisplay().setCursor(8, 113);
getdisplay().print("Board version: ");
getdisplay().setCursor(150, 113);
getdisplay().print(BOARDINFO);
getdisplay().print(String(" HW ") + String(PCBINFO));
getdisplay().setCursor(8, 131);
getdisplay().print("Display version: ");
getdisplay().setCursor(150, 131);
getdisplay().print(DISPLAYINFO);
getdisplay().print("; GxEPD2 v");
getdisplay().print(GXEPD2INFO);
getdisplay().setCursor(8, 265);
#ifdef BOARD_OBP60S3
getdisplay().print("Press STBY to enter deep sleep mode");
#endif
#ifdef BOARD_OBP40S3
getdisplay().print("Press wheel to enter deep sleep mode");
#endif
// Flash memory size
uint32_t flash_size = ESP.getFlashChipSize();
getdisplay().setCursor(8, y0);
getdisplay().print("FLASH:");
getdisplay().setCursor(90, y0);
getdisplay().print(String(flash_size / 1024) + String(" kB"));
// PSRAM memory size
uint32_t psram_size = ESP.getPsramSize();
getdisplay().setCursor(8, y0 + 16);
getdisplay().print("PSRAM:");
getdisplay().setCursor(90, y0 + 16);
getdisplay().print(String(psram_size / 1024) + String(" kB"));
// FRAM available / status
getdisplay().setCursor(8, y0 + 32);
getdisplay().print("FRAM:");
getdisplay().setCursor(90, y0 + 32);
getdisplay().print(hasFRAM ? "available" : "not found");
#ifdef BOARD_OBP40S3
// SD-Card
getdisplay().setCursor(8, y0 + 48);
getdisplay().print("SD-Card:");
getdisplay().setCursor(90, y0 + 48);
if (hasSDCard) {
uint64_t cardsize = ((uint64_t) sdcard->csd.capacity) * sdcard->csd.sector_size / (1024 * 1024);
getdisplay().printf("%llu MB", cardsize);
} else {
getdisplay().print("off");
}
#endif
// Uptime
int64_t uptime = esp_timer_get_time() / 1000000;
String uptime_unit;
if (uptime < 120) {
uptime_unit = " seconds";
} else {
if (uptime < 2 * 3600) {
uptime /= 60;
uptime_unit = " minutes";
} else if (uptime < 2 * 3600 * 24) {
uptime /= 3600;
uptime_unit = " hours";
} else {
uptime /= 86400;
uptime_unit = " days";
}
}
getdisplay().setCursor(8, y0 + 80);
getdisplay().print("Uptime:");
getdisplay().setCursor(90, y0 + 80);
getdisplay().print(uptime);
getdisplay().print(uptime_unit);
// CPU speed config / active
getdisplay().setCursor(202, y0);
getdisplay().print("CPU speed:");
getdisplay().setCursor(300, y0);
getdisplay().print(cpuspeed);
getdisplay().print(" / ");
int cpu_freq = esp_clk_cpu_freq() / 1000000;
getdisplay().print(String(cpu_freq));
// total RAM free
int Heap_free = esp_get_free_heap_size();
getdisplay().setCursor(202, y0 + 16);
getdisplay().print("Total free:");
getdisplay().setCursor(300, y0 + 16);
getdisplay().print(String(Heap_free));
// RAM free for task
int RAM_free = uxTaskGetStackHighWaterMark(NULL);
getdisplay().setCursor(202, y0 + 32);
getdisplay().print("Task free:");
getdisplay().setCursor(300, y0 + 32);
getdisplay().print(String(RAM_free));
}
void displayModeConfig() {
// Configuration interface
uint16_t x0 = 16;
uint16_t y0 = 80;
uint16_t dy = 20;
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(8, 48);
getdisplay().print("System configuration");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(x0, y0);
getdisplay().print("CPU speed: 80 | 160 | 240");
getdisplay().setCursor(x0, y0 + 1 * dy);
getdisplay().print("Power mode: Max | 5V | Min");
getdisplay().setCursor(x0, y0 + 2 * dy);
getdisplay().print("Accesspoint: On | Off");
// TODO Change NVRAM-preferences settings here
getdisplay().setCursor(x0, y0 + 4 * dy);
getdisplay().print("Simulation: On | Off");
}
void displayModeSettings() {
// View some of the current settings
const uint16_t x0 = 8;
const uint16_t y0 = 72;
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(x0, 48);
getdisplay().print("System settings");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
// left column
getdisplay().setCursor(x0, y0);
getdisplay().print("Simulation:");
getdisplay().setCursor(120, y0);
getdisplay().print(simulation ? "on" : "off");
getdisplay().setCursor(x0, y0 + 16);
getdisplay().print("Environment:");
getdisplay().setCursor(120, y0 + 16);
getdisplay().print(env_module);
getdisplay().setCursor(x0, y0 + 32);
getdisplay().print("Buzzer:");
getdisplay().setCursor(120, y0 + 32);
getdisplay().print(buzzer_mode);
getdisplay().setCursor(x0, y0 + 64);
getdisplay().print("GPS:");
getdisplay().setCursor(120, y0 + 64);
getdisplay().print(gps_module);
getdisplay().setCursor(x0, y0 + 80);
getdisplay().print("RTC:");
getdisplay().setCursor(120, y0 + 80);
getdisplay().print(rtc_module);
getdisplay().setCursor(x0, y0 + 96);
getdisplay().print("Wifi:");
getdisplay().setCursor(120, y0 + 96);
getdisplay().print(commonData->status.wifiApOn ? "on" : "off");
// Home location
getdisplay().setCursor(x0, y0 + 128);
getdisplay().print("Home Lat.:");
getdisplay().setCursor(120, y0 + 128);
getdisplay().print(formatLatitude(homelat));
getdisplay().setCursor(x0, y0 + 144);
getdisplay().print("Home Lon.:");
getdisplay().setCursor(120, y0 + 144);
getdisplay().print(formatLongitude(homelon));
// Power
getdisplay().setCursor(x0, y0 + 176);
getdisplay().print("Power mode:");
getdisplay().setCursor(120, y0 + 176);
getdisplay().print(powermode);
// right column
getdisplay().setCursor(202, y0);
getdisplay().print("Batt. sensor:");
getdisplay().setCursor(320, y0);
getdisplay().print(batt_sensor);
// Solar sensor
getdisplay().setCursor(202, y0 + 16);
getdisplay().print("Solar sensor:");
getdisplay().setCursor(320, y0 + 16);
getdisplay().print(solar_sensor);
// Generator sensor
getdisplay().setCursor(202, y0 + 32);
getdisplay().print("Gen. sensor:");
getdisplay().setCursor(320, y0 + 32);
getdisplay().print(gen_sensor);
// TODO
// Gyro sensor (rotation)
getdisplay().setCursor(202, y0 + 48);
getdisplay().print("Rot. sensor:");
getdisplay().setCursor(320, y0 + 48);
getdisplay().print(rot_sensor);
// Temp.-sensor
// Power Mode
#ifdef BOARD_OBP60S3
// Backlight infos
getdisplay().setCursor(202, y0 + 64);
getdisplay().print("Backlight:");
getdisplay().setCursor(320, y0 + 64);
getdisplay().printf("%d%%", commonData->backlight.brightness);
// TODO test function with OBP60 device
getdisplay().setCursor(202, y0 + 80);
getdisplay().print("Bl color:");
getdisplay().setCursor(320, y0 + 80);
getdisplay().print(commonData->backlight.color.toName());
getdisplay().setCursor(202, y0 + 96);
getdisplay().print("Bl mode:");
getdisplay().setCursor(320, y0 + 96);
getdisplay().print(commonData->backlight.mode);
// TODO Buzzer mode and power
#endif
}
void displayModeSDCard() {
// SD Card info
uint16_t x0 = 20;
uint16_t y0 = 72;
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(8, 48);
getdisplay().print("SD Card info");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(x0, y0);
#ifdef BOARD_OBP60S3
// This mode should not be callable by devices without card hardware
// In case of accidential reaching this, display a friendly message
getdisplay().print("This mode is not indended to be reached!\n");
getdisplay().print("There's nothing to see here. Move on.");
#endif
#ifdef BOARD_OBP40S3
getdisplay().print("Work in progress...");
/* TODO
this code should go somewhere else. only for testing purposes here
identify card as OBP-Card:
magic.dat
version.dat
readme.txt
IMAGES/
CHARTS/
LOGS/
DATA/
hint: file access with fopen, fgets, fread, fclose
*/
// Simple test for magic file in root
getdisplay().setCursor(x0, y0 + 32);
String file_magic = MOUNT_POINT "/magic.dat";
commonData->logger->logDebug(GwLog::LOG, "Test magicfile: %s", file_magic.c_str());
struct stat st;
if (stat(file_magic.c_str(), &st) == 0) {
getdisplay().printf("File %s exists", file_magic.c_str());
} else {
getdisplay().printf("File %s not found", file_magic.c_str());
}
// Root directory check
DIR* dir = opendir(MOUNT_POINT);
int dy = 0;
if (dir != NULL) {
commonData->logger->logDebug(GwLog::LOG, "Root directory: %s", MOUNT_POINT);
struct dirent* entry;
while (((entry = readdir(dir)) != NULL) and (dy < 140)) {
getdisplay().setCursor(x0, y0 + 64 + dy);
getdisplay().print(entry->d_name);
// type 1 is file, type 2 is dir
if (entry->d_type == 2) {
getdisplay().print("/");
}
dy += 20;
commonData->logger->logDebug(GwLog::DEBUG, " %s type %d", entry->d_name, entry->d_type);
}
closedir(dir);
} else {
commonData->logger->logDebug(GwLog::LOG, "Failed to open root directory");
}
#endif
}
void displayModeDevicelist() {
// NMEA2000 device list
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(8, 48);
getdisplay().print("NMEA2000 device list");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(20, 70);
getdisplay().print("RxD: ");
getdisplay().print(String(commonData->status.n2kRx));
getdisplay().setCursor(120, 70);
getdisplay().print("TxD: ");
getdisplay().print(String(commonData->status.n2kTx));
#ifdef PATCH_N2K
uint16_t x0 = 20;
uint16_t y0 = 100;
getdisplay().setFont(&Ubuntu_Bold10pt8b);
getdisplay().setCursor(x0, y0);
getdisplay().print("ID");
getdisplay().setCursor(x0 + 50, y0);
getdisplay().print("Model");
getdisplay().setCursor(x0 + 250, y0);
getdisplay().print("Manuf.");
getdisplay().drawLine(18, y0 + 4, 360 , y0 + 4 , commonData->fgcolor);
getdisplay().setFont(&Ubuntu_Bold8pt8b);
y0 = 120;
uint8_t n_dev = 0;
for (const device& item : devicelist) {
if (n_dev > 8) {
break;
}
getdisplay().setCursor(x0, y0 + n_dev * 20);
getdisplay().print(item.id);
getdisplay().setCursor(x0 + 50, y0 + n_dev * 20);
getdisplay().print(item.model);
getdisplay().setCursor(x0 + 250, y0 + n_dev * 20);
getdisplay().print(item.manuf_code);
n_dev++;
}
getdisplay().setCursor(x0, y0 + (n_dev + 1) * 20);
if (n_dev == 0) {
getdisplay().printf("no devices found on bus");
} else {
getdisplay().drawLine(18, y0 + n_dev * 20, 360 , y0 + n_dev * 20, commonData->fgcolor);
getdisplay().printf("%d devices of %d in total", n_dev, devicelist.size());
}
#else
getdisplay().setCursor(20, 100);
getdisplay().print("NMEA2000 not exposed to obp60 task");
#endif
}
public: public:
PageSystem(CommonData &common){ PageSystem(CommonData &common){
commonData = &common; commonData = &common;
common.logger->logDebug(GwLog::LOG,"Instantiate PageSystem"); commonData->logger->logDebug(GwLog::LOG,"Instantiate PageSystem");
if (hasFRAM) { if (hasFRAM) {
mode = fram.read(FRAM_SYSTEM_MODE); mode = fram.read(FRAM_SYSTEM_MODE);
common.logger->logDebug(GwLog::DEBUG, "Loaded mode '%c' from FRAM", mode); commonData->logger->logDebug(GwLog::DEBUG, "Loaded mode '%c' from FRAM", mode);
} }
chipid = ESP.getEfuseMac(); chipid = ESP.getEfuseMac();
simulation = common.config->getBool(common.config->useSimuData); simulation = common.config->getBool(common.config->useSimuData);
@@ -67,6 +500,7 @@ public:
buzzer_mode.toLowerCase(); buzzer_mode.toLowerCase();
buzzer_power = common.config->getInt(common.config->buzzerPower); buzzer_power = common.config->getInt(common.config->buzzerPower);
cpuspeed = common.config->getString(common.config->cpuSpeed); cpuspeed = common.config->getString(common.config->cpuSpeed);
powermode = common.config->getString(common.config->powerMode);
env_module = common.config->getString(common.config->useEnvSensor); env_module = common.config->getString(common.config->useEnvSensor);
rtc_module = common.config->getString(common.config->useRTC); rtc_module = common.config->getString(common.config->useRTC);
gps_module = common.config->getString(common.config->useGPS); gps_module = common.config->getString(common.config->useGPS);
@@ -76,6 +510,7 @@ public:
rot_sensor = common.config->getString(common.config->useRotSensor); rot_sensor = common.config->getString(common.config->useRotSensor);
homelat = common.config->getString(common.config->homeLAT).toDouble(); homelat = common.config->getString(common.config->homeLAT).toDouble();
homelon = common.config->getString(common.config->homeLON).toDouble(); homelon = common.config->getString(common.config->homeLON).toDouble();
flashLED = common.config->getString(common.config->flashLED);
} }
void setupKeys() { void setupKeys() {
@@ -92,19 +527,7 @@ public:
// Switch display mode // Switch display mode
commonData->logger->logDebug(GwLog::LOG, "System keyboard handler"); commonData->logger->logDebug(GwLog::LOG, "System keyboard handler");
if (key == 2) { if (key == 2) {
if (mode == 'N') { incMode();
mode = 'S';
} else if (mode == 'S') {
mode = 'D';
} else if (mode == 'D') {
if (hasSDCard) {
mode = 'C';
} else {
mode = 'N';
}
} else {
mode = 'N';
}
if (hasFRAM) fram.write(FRAM_SYSTEM_MODE, mode); if (hasFRAM) fram.write(FRAM_SYSTEM_MODE, mode);
return 0; return 0;
} }
@@ -129,8 +552,13 @@ public:
} }
#endif #endif
#ifdef BOARD_OBP40S3 #ifdef BOARD_OBP40S3
// grab cursor keys to disable page navigation // use cursor keys for local mode navigation
if (key == 9 or key == 10) { if (key == 9) {
incMode();
return 0;
}
if (key == 10) {
decMode();
return 0; return 0;
} }
// standby / deep sleep // standby / deep sleep
@@ -168,305 +596,64 @@ public:
} }
} }
int displayPage(PageData &pageData){ void displayNew(PageData &pageData) {
GwConfigHandler *config = commonData->config; #ifdef BOARD_OBP60S3
GwLog *logger = commonData->logger; // Clear optical warning
if (flashLED == "Limit Violation") {
// Get config data
String flashLED = config->getString(config->flashLED);
// Optical warning by limit violation (unused)
if(String(flashLED) == "Limit Violation"){
setBlinkingLED(false); setBlinkingLED(false);
setFlashLED(false); setFlashLED(false);
} }
#endif
// Logging boat values #ifdef PATCH_N2K
logger->logDebug(GwLog::LOG, "Drawing at PageSystem, Mode=%c", mode); // load current device list
tN2kDeviceList *pDevList = pageData.api->getN2kDeviceList();
// TODO check if changed
if (pDevList->ReadResetIsListUpdated()) {
// only reload if changed
devicelist.clear();
for (uint8_t i = 0; i <= 252; i++) {
const tNMEA2000::tDevice *d = pDevList->FindDeviceBySource(i);
if (d == nullptr) {
continue;
}
device dev;
dev.id = i;
dev.NAME = d->GetName();
snprintf(dev.hex_name, sizeof(dev.hex_name), "%08X%08X", (uint32_t)(dev.NAME >> 32), (uint32_t)(dev.NAME & 0xFFFFFFFF));
dev.manuf_code = d->GetManufacturerCode();
dev.model = d->GetModelID();
devicelist.push_back(dev);
}
}
#endif
};
// Draw page int displayPage(PageData &pageData){
//***********************************************************
uint16_t x0 = 8; // left column // Logging page information
uint16_t y0 = 48; // data table starts here commonData->logger->logDebug(GwLog::LOG, "Drawing at PageSystem, Mode=%c", mode);
// Set display in partial refresh mode // Set display in partial refresh mode
getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update
if (mode == 'N') { // call current system page
switch (mode) {
getdisplay().setFont(&Ubuntu_Bold12pt8b); case 'N':
getdisplay().setCursor(8, 48); displayModeNormal();
getdisplay().print("System Information"); break;
case 'S':
getdisplay().drawXBitmap(320, 25, logo64_bits, logo64_width, logo64_height, commonData->fgcolor); displayModeSettings();
break;
getdisplay().setFont(&Ubuntu_Bold8pt8b); case 'C':
y0 = 155; displayModeConfig();
break;
char ssid[13]; case 'A':
snprintf(ssid, 13, "%04X%08X", (uint16_t)(chipid >> 32), (uint32_t)chipid); displayModeSDCard();
displayBarcode(String(ssid), 320, 200, 2); break;
getdisplay().setCursor(8, 70); case 'D':
getdisplay().print(String("MCUDEVICE-") + String(ssid)); displayModeDevicelist();
break;
getdisplay().setCursor(8, 95);
getdisplay().print("Firmware version: ");
getdisplay().setCursor(150, 95);
getdisplay().print(VERSINFO);
getdisplay().setCursor(8, 113);
getdisplay().print("Board version: ");
getdisplay().setCursor(150, 113);
getdisplay().print(BOARDINFO);
getdisplay().print(String(" HW ") + String(PCBINFO));
getdisplay().setCursor(8, 131);
getdisplay().print("Display version: ");
getdisplay().setCursor(150, 131);
getdisplay().print(DISPLAYINFO);
getdisplay().print("; GxEPD2 v");
getdisplay().print(GXEPD2INFO);
getdisplay().setCursor(8, 265);
#ifdef BOARD_OBP60S3
getdisplay().print("Press STBY to enter deep sleep mode");
#endif
#ifdef BOARD_OBP40S3
getdisplay().print("Press wheel to enter deep sleep mode");
#endif
// Flash memory size
uint32_t flash_size = ESP.getFlashChipSize();
getdisplay().setCursor(8, y0);
getdisplay().print("FLASH:");
getdisplay().setCursor(90, y0);
getdisplay().print(String(flash_size / 1024) + String(" kB"));
// PSRAM memory size
uint32_t psram_size = ESP.getPsramSize();
getdisplay().setCursor(8, y0 + 16);
getdisplay().print("PSRAM:");
getdisplay().setCursor(90, y0 + 16);
getdisplay().print(String(psram_size / 1024) + String(" kB"));
// FRAM available / status
getdisplay().setCursor(8, y0 + 32);
getdisplay().print("FRAM:");
getdisplay().setCursor(90, y0 + 32);
getdisplay().print(hasFRAM ? "available" : "not found");
#ifdef BOARD_OBP40S3
// SD-Card
getdisplay().setCursor(8, y0 + 48);
getdisplay().print("SD-Card:");
getdisplay().setCursor(90, y0 + 48);
if (hasSDCard) {
uint64_t cardsize = ((uint64_t) sdcard->csd.capacity) * sdcard->csd.sector_size / (1024 * 1024);
getdisplay().printf("%llu MB", cardsize);
} else {
getdisplay().print("off");
}
#endif
// Uptime
int64_t uptime = esp_timer_get_time() / 1000000;
String uptime_unit;
if (uptime < 120) {
uptime_unit = " seconds";
} else {
if (uptime < 2 * 3600) {
uptime /= 60;
uptime_unit = " minutes";
} else if (uptime < 2 * 3600 * 24) {
uptime /= 3600;
uptime_unit = " hours";
} else {
uptime /= 86400;
uptime_unit = " days";
}
}
getdisplay().setCursor(8, y0 + 80);
getdisplay().print("Uptime:");
getdisplay().setCursor(90, y0 + 80);
getdisplay().print(uptime);
getdisplay().print(uptime_unit);
// CPU speed config / active
getdisplay().setCursor(202, y0);
getdisplay().print("CPU speed:");
getdisplay().setCursor(300, y0);
getdisplay().print(cpuspeed);
getdisplay().print(" / ");
int cpu_freq = esp_clk_cpu_freq() / 1000000;
getdisplay().print(String(cpu_freq));
// total RAM free
int Heap_free = esp_get_free_heap_size();
getdisplay().setCursor(202, y0 + 16);
getdisplay().print("Total free:");
getdisplay().setCursor(300, y0 + 16);
getdisplay().print(String(Heap_free));
// RAM free for task
int RAM_free = uxTaskGetStackHighWaterMark(NULL);
getdisplay().setCursor(202, y0 + 32);
getdisplay().print("Task free:");
getdisplay().setCursor(300, y0 + 32);
getdisplay().print(String(RAM_free));
} else if (mode == 'S') {
// Settings
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(x0, 48);
getdisplay().print("System settings");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
x0 = 8;
y0 = 72;
// left column
getdisplay().setCursor(x0, y0);
getdisplay().print("Simulation:");
getdisplay().setCursor(120, y0);
getdisplay().print(simulation ? "on" : "off");
getdisplay().setCursor(x0, y0 + 16);
getdisplay().print("Environment:");
getdisplay().setCursor(120, y0 + 16);
getdisplay().print(env_module);
getdisplay().setCursor(x0, y0 + 32);
getdisplay().print("Buzzer:");
getdisplay().setCursor(120, y0 + 32);
getdisplay().print(buzzer_mode);
getdisplay().setCursor(x0, y0 + 64);
getdisplay().print("GPS:");
getdisplay().setCursor(120, y0 + 64);
getdisplay().print(gps_module);
getdisplay().setCursor(x0, y0 + 80);
getdisplay().print("RTC:");
getdisplay().setCursor(120, y0 + 80);
getdisplay().print(rtc_module);
getdisplay().setCursor(x0, y0 + 96);
getdisplay().print("Wifi:");
getdisplay().setCursor(120, y0 + 96);
getdisplay().print(commonData->status.wifiApOn ? "on" : "off");
// Home location
getdisplay().setCursor(x0, y0 + 128);
getdisplay().print("Home Lat.:");
getdisplay().setCursor(120, y0 + 128);
getdisplay().print(formatLatitude(homelat));
getdisplay().setCursor(x0, y0 + 144);
getdisplay().print("Home Lon.:");
getdisplay().setCursor(120, y0 + 144);
getdisplay().print(formatLongitude(homelon));
// right column
getdisplay().setCursor(202, y0);
getdisplay().print("Batt. sensor:");
getdisplay().setCursor(320, y0);
getdisplay().print(batt_sensor);
// Solar sensor
getdisplay().setCursor(202, y0 + 16);
getdisplay().print("Solar sensor:");
getdisplay().setCursor(320, y0 + 16);
getdisplay().print(solar_sensor);
// Generator sensor
getdisplay().setCursor(202, y0 + 32);
getdisplay().print("Gen. sensor:");
getdisplay().setCursor(320, y0 + 32);
getdisplay().print(gen_sensor);
// Gyro sensor
} else if (mode == 'C') {
// Card info
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(8, 48);
getdisplay().print("SD Card info");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
x0 = 20;
y0 = 72;
getdisplay().setCursor(x0, y0);
#ifdef BOARD_OBP60S3
// This mode should not be callable by devices without card hardware
// In case of accidential reaching this, display a friendly message
getdisplay().print("This mode is not indended to be reached!\n");
getdisplay().print("There's nothing to see here. Move on.");
#endif
#ifdef BOARD_OBP40S3
getdisplay().print("Work in progress...");
/* TODO
this code should go somewhere else. only for testing purposes here
identify card as OBP-Card:
magic.dat
version.dat
readme.txt
IMAGES/
CHARTS/
LOGS/
DATA/
hint: file access with fopen, fgets, fread, fclose
*/
// Simple test for magic file in root
getdisplay().setCursor(x0, y0 + 32);
String file_magic = MOUNT_POINT "/magic.dat";
logger->logDebug(GwLog::LOG, "Test magicfile: %s", file_magic.c_str());
struct stat st;
if (stat(file_magic.c_str(), &st) == 0) {
getdisplay().printf("File %s exists", file_magic.c_str());
} else {
getdisplay().printf("File %s not found", file_magic.c_str());
}
// Root directory check
DIR* dir = opendir(MOUNT_POINT);
int dy = 0;
if (dir != NULL) {
logger->logDebug(GwLog::LOG, "Root directory: %s", MOUNT_POINT);
struct dirent* entry;
while (((entry = readdir(dir)) != NULL) and (dy < 140)) {
getdisplay().setCursor(x0, y0 + 64 + dy);
getdisplay().print(entry->d_name);
// type 1 is file, type 2 is dir
if (entry->d_type == 2) {
getdisplay().print("/");
}
dy += 20;
logger->logDebug(GwLog::DEBUG, " %s type %d", entry->d_name, entry->d_type);
}
closedir(dir);
} else {
logger->logDebug(GwLog::LOG, "Failed to open root directory");
}
#endif
} else {
// NMEA2000 device list
getdisplay().setFont(&Ubuntu_Bold12pt8b);
getdisplay().setCursor(8, 48);
getdisplay().print("NMEA2000 device list");
getdisplay().setFont(&Ubuntu_Bold8pt8b);
getdisplay().setCursor(20, 80);
getdisplay().print("RxD: ");
getdisplay().print(String(commonData->status.n2kRx));
getdisplay().setCursor(20, 100);
getdisplay().print("TxD: ");
getdisplay().print(String(commonData->status.n2kTx));
} }
// Update display // Update display

View File

@@ -114,7 +114,7 @@ private:
} }
if (numValues == 2 && mode == FULL) { // print line only, if we want to show 2 data values if (numValues == 2 && mode == FULL) { // print line only, if we want to show 2 data values
getdisplay().fillRect(0, 145, width, 3, commonData->fgcolor); // Horizontal line 3 pix getdisplay().fillRect(0, 145, width, 3, commonData->fgcolor); // Horizontal line 3 pix
} }
} }
@@ -149,7 +149,11 @@ public:
if (dataHstryBuf[0] || dataHstryBuf[1]) { // show "Mode" key only if at least 1 chart supported boat data type is available if (dataHstryBuf[0] || dataHstryBuf[1]) { // show "Mode" key only if at least 1 chart supported boat data type is available
commonData->keydata[0].label = "MODE"; commonData->keydata[0].label = "MODE";
commonData->keydata[ZOOM_KEY].label = "ZOOM"; if (pageMode != VALUES) { // show "ZOOM" key only if chart is visible
commonData->keydata[ZOOM_KEY].label = "ZOOM";
} else {
commonData->keydata[ZOOM_KEY].label = "";
}
} else { } else {
commonData->keydata[0].label = ""; commonData->keydata[0].label = "";
commonData->keydata[ZOOM_KEY].label = ""; commonData->keydata[ZOOM_KEY].label = "";
@@ -191,14 +195,15 @@ public:
pageMode = VALUES; pageMode = VALUES;
break; break;
} }
setupKeys(); // Adjust key definition depending on <pageMode> and chart-supported boat data type
return 0; // Commit the key return 0; // Commit the key
} }
// Set time frame to show for history chart // Set time frame to show for chart
#if defined BOARD_OBP60S3 #if defined BOARD_OBP60S3
if (key == 5) { if (key == 5 && pageMode != VALUES) {
#elif defined BOARD_OBP40S3 #elif defined BOARD_OBP40S3
if (key == 2) { if (key == 2 && pageMode != VALUES) {
#endif #endif
if (dataIntv == 1) { if (dataIntv == 1) {
dataIntv = 2; dataIntv = 2;
@@ -251,7 +256,7 @@ public:
} }
} }
setupKeys(); // adjust <mode> key depending on chart supported boat data type setupKeys(); // Adjust key definition depending on <pageMode> and chart-supported boat data type
} }
int displayPage(PageData& pageData) int displayPage(PageData& pageData)
@@ -285,13 +290,13 @@ public:
showData(bValue, FULL); showData(bValue, FULL);
} else if (pageMode == VAL1_CHART) { // show data value 1 and chart } else if (pageMode == VAL1_CHART) { // show data value 1 and chart
showData({bValue[0]}, HALF); showData({ bValue[0] }, HALF);
if (dataChart[0]) { if (dataChart[0]) {
dataChart[0]->showChrt(HORIZONTAL, HALF_SIZE_BOTTOM, dataIntv, NO_PRNT_NAME, NO_PRNT_VALUE, *bValue[0]); dataChart[0]->showChrt(HORIZONTAL, HALF_SIZE_BOTTOM, dataIntv, NO_PRNT_NAME, NO_PRNT_VALUE, *bValue[0]);
} }
} else if (pageMode == VAL2_CHART) { // show data value 2 and chart } else if (pageMode == VAL2_CHART) { // show data value 2 and chart
showData({bValue[1]}, HALF); showData({ bValue[1] }, HALF);
if (dataChart[1]) { if (dataChart[1]) {
dataChart[1]->showChrt(HORIZONTAL, HALF_SIZE_BOTTOM, dataIntv, NO_PRNT_NAME, NO_PRNT_VALUE, *bValue[1]); dataChart[1]->showChrt(HORIZONTAL, HALF_SIZE_BOTTOM, dataIntv, NO_PRNT_NAME, NO_PRNT_VALUE, *bValue[1]);
} }

View File

@@ -196,7 +196,7 @@ public:
int displayPage(PageData& pageData) int displayPage(PageData& pageData)
{ {
LOG_DEBUG(GwLog::LOG, "Display PageWindPlot"); LOG_DEBUG(GwLog::LOG, "Display PageWindPlot");
ulong pageTime = millis(); // ulong pageTime = millis();
if (showTruW != oldShowTruW) { if (showTruW != oldShowTruW) {
@@ -243,7 +243,7 @@ public:
} }
} }
LOG_DEBUG(GwLog::DEBUG, "PageWindPlot: page time %ldms", millis() - pageTime); // LOG_DEBUG(GwLog::DEBUG, "PageWindPlot: page time %ldms", millis() - pageTime);
return PAGE_UPDATE; return PAGE_UPDATE;
} }
}; };

View File

@@ -1245,8 +1245,8 @@
"name": "timeSource", "name": "timeSource",
"label": "Status Time Source", "label": "Status Time Source",
"type": "list", "type": "list",
"default": "GPS", "default": "iRTC",
"description": "Data source for date and time display in status line [RTC|iRTC|GPS]", "description": "Data source for date and time display in status line [iRTC|RTC|GPS]",
"list": [ "list": [
{"l":"Internal real time clock (iRTC)","v":"iRTC"}, {"l":"Internal real time clock (iRTC)","v":"iRTC"},
{"l":"External real time clock (RTC)","v":"RTC"}, {"l":"External real time clock (RTC)","v":"RTC"},
@@ -1517,6 +1517,7 @@
"default": "Voltage", "default": "Voltage",
"description": "Type of page for page 1", "description": "Type of page for page 1",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -1818,7 +1819,7 @@
"description": "Wind source for page 1: [true|apparent]", "description": "Wind source for page 1: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 1", "category": "OBP40 Page 1",
"capabilities": { "capabilities": {
@@ -1847,6 +1848,7 @@
"default": "WindRose", "default": "WindRose",
"description": "Type of page for page 2", "description": "Type of page for page 2",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -2140,7 +2142,7 @@
"description": "Wind source for page 2: [true|apparent]", "description": "Wind source for page 2: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 2", "category": "OBP40 Page 2",
"capabilities": { "capabilities": {
@@ -2168,6 +2170,7 @@
"default": "OneValue", "default": "OneValue",
"description": "Type of page for page 3", "description": "Type of page for page 3",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -2453,7 +2456,7 @@
"description": "Wind source for page 3: [true|apparent]", "description": "Wind source for page 3: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 3", "category": "OBP40 Page 3",
"capabilities": { "capabilities": {
@@ -2480,6 +2483,7 @@
"default": "TwoValues", "default": "TwoValues",
"description": "Type of page for page 4", "description": "Type of page for page 4",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -2757,7 +2761,7 @@
"description": "Wind source for page 4: [true|apparent]", "description": "Wind source for page 4: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 4", "category": "OBP40 Page 4",
"capabilities": { "capabilities": {
@@ -2783,6 +2787,7 @@
"default": "ThreeValues", "default": "ThreeValues",
"description": "Type of page for page 5", "description": "Type of page for page 5",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3052,7 +3057,7 @@
"description": "Wind source for page 5: [true|apparent]", "description": "Wind source for page 5: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 5", "category": "OBP40 Page 5",
"capabilities": { "capabilities": {
@@ -3077,6 +3082,7 @@
"default": "FourValues", "default": "FourValues",
"description": "Type of page for page 6", "description": "Type of page for page 6",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3338,7 +3344,7 @@
"description": "Wind source for page 6: [true|apparent]", "description": "Wind source for page 6: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 6", "category": "OBP40 Page 6",
"capabilities": { "capabilities": {
@@ -3362,6 +3368,7 @@
"default": "FourValues2", "default": "FourValues2",
"description": "Type of page for page 7", "description": "Type of page for page 7",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3615,7 +3622,7 @@
"description": "Wind source for page 7: [true|apparent]", "description": "Wind source for page 7: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 7", "category": "OBP40 Page 7",
"capabilities": { "capabilities": {
@@ -3638,6 +3645,7 @@
"default": "Clock", "default": "Clock",
"description": "Type of page for page 8", "description": "Type of page for page 8",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3883,7 +3891,7 @@
"description": "Wind source for page 8: [true|apparent]", "description": "Wind source for page 8: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 8", "category": "OBP40 Page 8",
"capabilities": { "capabilities": {
@@ -3905,6 +3913,7 @@
"default": "RollPitch", "default": "RollPitch",
"description": "Type of page for page 9", "description": "Type of page for page 9",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -4142,7 +4151,7 @@
"description": "Wind source for page 9: [true|apparent]", "description": "Wind source for page 9: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 9", "category": "OBP40 Page 9",
"capabilities": { "capabilities": {
@@ -4163,6 +4172,7 @@
"default": "Battery2", "default": "Battery2",
"description": "Type of page for page 10", "description": "Type of page for page 10",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -4392,7 +4402,7 @@
"description": "Wind source for page 10: [true|apparent]", "description": "Wind source for page 10: [true|apparent]",
"list": [ "list": [
"True wind", "True wind",
"apparent wind" "Apparent wind"
], ],
"category": "OBP40 Page 10", "category": "OBP40 Page 10",
"capabilities": { "capabilities": {

View File

@@ -1235,8 +1235,9 @@
"label": "Status Time Source", "label": "Status Time Source",
"type": "list", "type": "list",
"default": "GPS", "default": "GPS",
"description": "Data source for date and time display in status line [RTC|GPS]", "description": "Data source for date and time display in status line [iRTC|RTC|GPS]",
"list": [ "list": [
{"l":"Internal real time clock (iRTC)","v":"iRTC"},
{"l":"Real time clock (RTC)","v":"RTC"}, {"l":"Real time clock (RTC)","v":"RTC"},
{"l":"Time via bus (GPS)","v":"GPS"} {"l":"Time via bus (GPS)","v":"GPS"}
], ],
@@ -1494,6 +1495,7 @@
"default": "Voltage", "default": "Voltage",
"description": "Type of page for page 1", "description": "Type of page for page 1",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -1794,6 +1796,7 @@
"default": "WindRose", "default": "WindRose",
"description": "Type of page for page 2", "description": "Type of page for page 2",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -2086,6 +2089,7 @@
"default": "OneValue", "default": "OneValue",
"description": "Type of page for page 3", "description": "Type of page for page 3",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -2370,6 +2374,7 @@
"default": "TwoValues", "default": "TwoValues",
"description": "Type of page for page 4", "description": "Type of page for page 4",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -2646,6 +2651,7 @@
"default": "ThreeValues", "default": "ThreeValues",
"description": "Type of page for page 5", "description": "Type of page for page 5",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -2914,6 +2920,7 @@
"default": "FourValues", "default": "FourValues",
"description": "Type of page for page 6", "description": "Type of page for page 6",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3174,6 +3181,7 @@
"default": "FourValues2", "default": "FourValues2",
"description": "Type of page for page 7", "description": "Type of page for page 7",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3426,6 +3434,7 @@
"default": "Clock", "default": "Clock",
"description": "Type of page for page 8", "description": "Type of page for page 8",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3670,6 +3679,7 @@
"default": "RollPitch", "default": "RollPitch",
"description": "Type of page for page 9", "description": "Type of page for page 9",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",
@@ -3906,6 +3916,7 @@
"default": "Battery2", "default": "Battery2",
"description": "Type of page for page 10", "description": "Type of page for page 10",
"list": [ "list": [
"Autopilot",
"BME280", "BME280",
"Battery", "Battery",
"Battery2", "Battery2",

View File

@@ -1,12 +1,29 @@
# PlatformIO extra script for obp60task # PlatformIO extra script for obp60task
import subprocess
def cleanup_patches(source, target, env):
for p in patchfiles:
patch = os.path.join(patchdir, p)
print(f"removing {patch}")
res = subprocess.run(["git", "apply", "-R", patch], capture_output=True, text=True)
if res.returncode != 0:
print(res.stderr)
patching = False
epdtype = "unknown" epdtype = "unknown"
pcbvers = "unknown" pcbvers = "unknown"
for x in env["BUILD_FLAGS"]: for x in env["BUILD_FLAGS"]:
if x.startswith("-D HARDWARE_"): if not x.startswith('-D'):
continue
opt = x[2:].strip()
if opt.startswith("HARDWARE_"):
pcbvers = x.split('_')[1] pcbvers = x.split('_')[1]
if x.startswith("-D DISPLAY_"): elif opt.startswith("DISPLAY_"):
epdtype = x.split('_')[1] epdtype = x.split('_')[1]
elif opt == 'ENABLE_PATCHES':
patching = True
propfilename = os.path.join(env["PROJECT_LIBDEPS_DIR"], env["PIOENV"], "GxEPD2/library.properties") propfilename = os.path.join(env["PROJECT_LIBDEPS_DIR"], env["PIOENV"], "GxEPD2/library.properties")
properties = {} properties = {}
@@ -28,3 +45,22 @@ except:
env["CPPDEFINES"].extend([("BOARD", env["BOARD"]), ("EPDTYPE", epdtype), ("PCBVERS", pcbvers), ("GXEPD2VERS", gxepd2vers)]) env["CPPDEFINES"].extend([("BOARD", env["BOARD"]), ("EPDTYPE", epdtype), ("PCBVERS", pcbvers), ("GXEPD2VERS", gxepd2vers)])
print("added hardware info to CPPDEFINES") print("added hardware info to CPPDEFINES")
if patching:
# apply patches to gateway code
print("applying gateway patches")
patchdir = os.path.join(os.path.dirname(script), "patches")
if not os.path.isdir(patchdir):
print("patchdir not found, no patches applied")
else:
patchfiles = [f for f in os.listdir(patchdir)]
if len(patchfiles) > 0:
for p in patchfiles:
patch = os.path.join(patchdir, p)
print(f"applying {patch}")
res = subprocess.run(["git", "apply", patch], capture_output=True, text=True)
if res.returncode != 0:
print(res.stderr)
env.AddPostAction("$PROGPATH", cleanup_patches)
else:
print("no patches found")

View File

@@ -332,7 +332,7 @@ void OBP60Task(GwApi *api){
// return; // return;
GwLog *logger=api->getLogger(); GwLog *logger=api->getLogger();
GwConfigHandler *config=api->getConfig(); GwConfigHandler *config=api->getConfig();
#ifdef HARDWARE_V21 #if defined HARDWARE_V20 || HARDWARE_V21
startLedTask(api); startLedTask(api);
#endif #endif
PageList allPages; PageList allPages;
@@ -341,7 +341,7 @@ void OBP60Task(GwApi *api){
commonData.logger=logger; commonData.logger=logger;
commonData.config=config; commonData.config=config;
#ifdef HARDWARE_V21 #if defined HARDWARE_V20 || HARDWARE_V21
// Keyboard coordinates for page footer // Keyboard coordinates for page footer
initKeys(commonData); initKeys(commonData);
#endif #endif
@@ -432,7 +432,7 @@ void OBP60Task(GwApi *api){
#endif #endif
LOG_DEBUG(GwLog::LOG,"...done"); LOG_DEBUG(GwLog::LOG,"...done");
int lastPage=-1; // initialize with an impiossible value, so we can detect wether we are during startup and no page has been displayed yet int lastPage=-1; // initialize with an impossible value, so we can detect wether we are during startup and no page has been displayed yet
BoatValueList boatValues; //all the boat values for the api query BoatValueList boatValues; //all the boat values for the api query
HstryBuffers hstryBufferList(1920, &boatValues, logger); // Create empty list of boat data history buffers (1.920 values = seconds = 32 min.) HstryBuffers hstryBufferList(1920, &boatValues, logger); // Create empty list of boat data history buffers (1.920 values = seconds = 32 min.)
@@ -729,7 +729,7 @@ void OBP60Task(GwApi *api){
else{ else{
getdisplay().fillScreen(commonData.fgcolor); // Clear display getdisplay().fillScreen(commonData.fgcolor); // Clear display
#ifdef DISPLAY_GDEY042T81 #ifdef DISPLAY_GDEY042T81
getdisplay().hibernate(); // Set display in hybenate mode getdisplay().hibernate(); // Set display in hibenate mode
getdisplay().init(115200, true, 2, false); // Init for Waveshare boards with "clever" reset circuit, 2ms reset pulse getdisplay().init(115200, true, 2, false); // Init for Waveshare boards with "clever" reset circuit, 2ms reset pulse
#else #else
getdisplay().init(115200); // Init for normal displays getdisplay().init(115200); // Init for normal displays
@@ -757,7 +757,7 @@ void OBP60Task(GwApi *api){
else{ else{
getdisplay().fillScreen(commonData.fgcolor); // Clear display getdisplay().fillScreen(commonData.fgcolor); // Clear display
#ifdef DISPLAY_GDEY042T81 #ifdef DISPLAY_GDEY042T81
getdisplay().hibernate(); // Set display in hybenate mode getdisplay().hibernate(); // Set display in hibernate mode
getdisplay().init(115200, true, 2, false); // Init for Waveshare boards with "clever" reset circuit, 2ms reset pulse getdisplay().init(115200, true, 2, false); // Init for Waveshare boards with "clever" reset circuit, 2ms reset pulse
#else #else
getdisplay().init(115200); // Init for normal displays getdisplay().init(115200); // Init for normal displays
@@ -782,7 +782,7 @@ void OBP60Task(GwApi *api){
else{ else{
getdisplay().fillScreen(commonData.fgcolor); // Clear display getdisplay().fillScreen(commonData.fgcolor); // Clear display
#ifdef DISPLAY_GDEY042T81 #ifdef DISPLAY_GDEY042T81
getdisplay().hibernate(); // Set display in hybenate mode getdisplay().hibernate(); // Set display in hibernate mode
getdisplay().init(115200, true, 2, false); // Init for Waveshare boards with "clever" reset circuit, 2ms reset pulse getdisplay().init(115200, true, 2, false); // Init for Waveshare boards with "clever" reset circuit, 2ms reset pulse
#else #else
getdisplay().init(115200); // Init for normal displays getdisplay().init(115200); // Init for normal displays

View File

@@ -0,0 +1,103 @@
diff --git a/lib/api/GwApi.h b/lib/api/GwApi.h
index 88f9690..9663a65 100644
--- a/lib/api/GwApi.h
+++ b/lib/api/GwApi.h
@@ -2,6 +2,8 @@
#define _GWAPI_H
#include "GwMessage.h"
#include "N2kMsg.h"
+#include "Nmea2kTwai.h"
+#include "N2kDeviceList.h"
#include "NMEA0183Msg.h"
#include "GWConfig.h"
#include "GwBoatData.h"
@@ -222,6 +224,8 @@ class GwApi{
* accessing boat data must only be executed from within the main thread
* you need to use the request pattern as shown in GwExampleTask.cpp
*/
+ virtual Nmea2kTwai *getNMEA2000()=0;
+ virtual tN2kDeviceList *getN2kDeviceList()=0;
virtual GwBoatData *getBoatData()=0;
virtual ~GwApi(){}
};
diff --git a/lib/obp60task/OBP60Extensions.h b/lib/obp60task/OBP60Extensions.h
index 604c356..2fe4496 100644
--- a/lib/obp60task/OBP60Extensions.h
+++ b/lib/obp60task/OBP60Extensions.h
@@ -15,6 +15,9 @@
#define MOUNT_POINT "/sdcard"
#endif
+// Patches to apply to gateway code
+#define PATCH_N2K
+
// FRAM address reservations 32kB: 0x0000 - 0x7FFF
// 0x0000 - 0x03ff: single variables
#define FRAM_PAGE_NO 0x0002
diff --git a/lib/usercode/GwUserCode.cpp b/lib/usercode/GwUserCode.cpp
index 1b007f8..90087d4 100644
--- a/lib/usercode/GwUserCode.cpp
+++ b/lib/usercode/GwUserCode.cpp
@@ -216,6 +216,14 @@ public:
{
return api->getLogger();
}
+ virtual Nmea2kTwai *getNMEA2000()
+ {
+ return api->getNMEA2000();
+ }
+ virtual tN2kDeviceList *getN2kDeviceList()
+ {
+ return api->getN2kDeviceList();
+ }
virtual GwBoatData *getBoatData()
{
return api->getBoatData();
@@ -428,4 +436,4 @@ void GwUserCode::handleWebRequest(const String &url,AsyncWebServerRequest *req){
}
LOG_DEBUG(GwLog::DEBUG,"no task found for web request %s[%s]",url.c_str(),tname.c_str());
req->send(404, "text/plain", "not found");
-}
\ No newline at end of file
+}
diff --git a/src/main.cpp b/src/main.cpp
index 44c715f..fdb0366 100644
--- a/src/main.cpp
+++ b/src/main.cpp
@@ -100,6 +100,7 @@ GwLog logger(LOGLEVEL,NULL);
GwConfigHandler config(&logger);
#include "Nmea2kTwai.h"
+#include <N2kDeviceList.h>
static const unsigned long CAN_RECOVERY_PERIOD=3000; //ms
static const unsigned long NMEA2000_HEARTBEAT_INTERVAL=5000;
class Nmea2kTwaiLog : public Nmea2kTwai{
@@ -126,6 +127,7 @@ class Nmea2kTwaiLog : public Nmea2kTwai{
#endif
Nmea2kTwai &NMEA2000=*(new Nmea2kTwaiLog((gpio_num_t)ESP32_CAN_TX_PIN,(gpio_num_t)ESP32_CAN_RX_PIN,CAN_RECOVERY_PERIOD,&logger));
+tN2kDeviceList *pN2kDeviceList;
#ifdef GWBUTTON_PIN
bool fixedApPass=false;
@@ -333,6 +335,12 @@ public:
status.n2kTx=countNMEA2KOut.getGlobal();
channels.fillStatus(status);
}
+ virtual Nmea2kTwai *getNMEA2000(){
+ return &NMEA2000;
+ }
+ virtual tN2kDeviceList *getN2kDeviceList(){
+ return pN2kDeviceList;
+ }
virtual GwBoatData *getBoatData(){
return &boatData;
}
@@ -935,6 +943,7 @@ void setup() {
NMEA2000.SetMsgHandler([](const tN2kMsg &n2kMsg){
handleN2kMessage(n2kMsg,N2K_CHANNEL_ID);
});
+ pN2kDeviceList = new tN2kDeviceList(&NMEA2000);
NMEA2000.Open();
logger.logDebug(GwLog::LOG,"starting addon tasks");
logger.flush();

View File

@@ -58,6 +58,7 @@ build_flags=
# -D DISPLAY_GYE042A87 #alternativ E-Ink display from Genyo Optical, R10 2.2 ohm - medium # -D DISPLAY_GYE042A87 #alternativ E-Ink display from Genyo Optical, R10 2.2 ohm - medium
# -D DISPLAY_SE0420NQ04 #alternativ E-Ink display from SID Technology, R10 2.2 ohm - bad (burn in effects) # -D DISPLAY_SE0420NQ04 #alternativ E-Ink display from SID Technology, R10 2.2 ohm - bad (burn in effects)
# -D DISPLAY_ZJY400300-042CAAMFGN #alternativ E-Ink display from ZZE Technology, R10 2.2 ohm - very good # -D DISPLAY_ZJY400300-042CAAMFGN #alternativ E-Ink display from ZZE Technology, R10 2.2 ohm - very good
# -D ENABLE_PATCHES #enable patching of gateway code
${env.build_flags} ${env.build_flags}
#CONFIG_ESP_TASK_WDT_TIMEOUT_S = 10 #Task Watchdog timeout period (seconds) [1...60] 5 default #CONFIG_ESP_TASK_WDT_TIMEOUT_S = 10 #Task Watchdog timeout period (seconds) [1...60] 5 default
upload_port = /dev/ttyACM0 #OBP60 download via USB-C direct upload_port = /dev/ttyACM0 #OBP60 download via USB-C direct
@@ -108,6 +109,7 @@ build_flags=
#-D DISPLAY_ZJY400300-042CAAMFGN #alternativ E-Ink display from ZZE Technology, R10 2.2 ohm - very good #-D DISPLAY_ZJY400300-042CAAMFGN #alternativ E-Ink display from ZZE Technology, R10 2.2 ohm - very good
-D LIPO_ACCU_1200 #Hardware extension, LiPo accu 3,7V 1200mAh -D LIPO_ACCU_1200 #Hardware extension, LiPo accu 3,7V 1200mAh
-D VOLTAGE_SENSOR #Hardware extension, LiPo voltage sensor with two resistors -D VOLTAGE_SENSOR #Hardware extension, LiPo voltage sensor with two resistors
#-D ENABLE_PATCHES #enable patching of gateway code
${env.build_flags} ${env.build_flags}
upload_port = /dev/ttyUSB0 #OBP40 download via external USB/Serail converter upload_port = /dev/ttyUSB0 #OBP40 download via external USB/Serail converter
upload_protocol = esptool #firmware upload via USB OTG seriell, by first upload need to set the ESP32-S3 in the upload mode with shortcut GND to Pin27 upload_protocol = esptool #firmware upload via USB OTG seriell, by first upload need to set the ESP32-S3 in the upload mode with shortcut GND to Pin27

View File

@@ -8,6 +8,6 @@
# Install tools # Install tools
echo "Installing tools" echo "Installing tools"
cd /workspace/esp32-nmea2000 cd /workspaces/esp32-nmea2000
pip3 install -U esptool pip3 install -U esptool
pip3 install platformio pip3 install platformio