mirror of
https://github.com/thooge/esp32-nmea2000-obp60.git
synced 2026-03-28 18:06:37 +01:00
Compare commits
28 Commits
ccca784ac2
...
anchor
| Author | SHA1 | Date | |
|---|---|---|---|
| 6d052f8827 | |||
| 608b782b43 | |||
| 4ab3749028 | |||
| 47d9d9f5ca | |||
|
|
43b0a780d5 | ||
| 0363ba4379 | |||
|
|
4b6e2abe33 | ||
|
|
0401d82b62 | ||
| 0b02e5b54c | |||
| 48b9380724 | |||
|
|
2fecbee492 | ||
|
|
fc5daaba37 | ||
|
|
04dc09e44a | ||
| 1d2ba2f71d | |||
|
|
bbecf5e55f | ||
|
|
ded1b2b22e | ||
|
|
a0a88fa2c9 | ||
|
|
e9bf54e99f | ||
|
|
64950c3974 | ||
|
|
fb2fbc85a4 | ||
|
|
6b92a5e69c | ||
|
|
ef4546a2e6 | ||
|
|
6870c9b8a4 | ||
|
|
a70d976a6e | ||
|
|
fbba6ffff2 | ||
|
|
d516c82041 | ||
| 5b477331de | |||
| 9b9bf76e4d |
217
lib/obp60task/ConfigMenu.cpp
Normal file
217
lib/obp60task/ConfigMenu.cpp
Normal file
@@ -0,0 +1,217 @@
|
|||||||
|
/*
|
||||||
|
Menu system for online configuration
|
||||||
|
|
||||||
|
A menu consists of a list of menuitems.
|
||||||
|
|
||||||
|
Graphical representation is stored:
|
||||||
|
upper left corner: x, y
|
||||||
|
bounding box:
|
||||||
|
A menu consists of three columns
|
||||||
|
- menu text, if selected highlighted
|
||||||
|
- menu value with optional unit
|
||||||
|
- menu description or additional data for value
|
||||||
|
|
||||||
|
*/
|
||||||
|
#include "ConfigMenu.h"
|
||||||
|
|
||||||
|
ConfigMenuItem::ConfigMenuItem(String itemtype, String itemlabel, uint16_t itemval, String itemunit) {
|
||||||
|
if (! (itemtype == "int" or itemtype == "bool")) {
|
||||||
|
valtype = "int";
|
||||||
|
} else {
|
||||||
|
valtype = itemtype;
|
||||||
|
}
|
||||||
|
label = itemlabel;
|
||||||
|
min = 0;
|
||||||
|
max = std::numeric_limits<uint16_t>::max();
|
||||||
|
value = itemval;
|
||||||
|
unit = itemunit;
|
||||||
|
step = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigMenuItem::setRange(uint16_t valmin, uint16_t valmax, std::vector<uint16_t> valsteps) {
|
||||||
|
min = valmin;
|
||||||
|
max = valmax;
|
||||||
|
steps = valsteps;
|
||||||
|
step = steps[0];
|
||||||
|
};
|
||||||
|
|
||||||
|
bool ConfigMenuItem::checkRange(uint16_t checkval) {
|
||||||
|
return (checkval >= min) and (checkval <= max);
|
||||||
|
}
|
||||||
|
|
||||||
|
String ConfigMenuItem::getLabel() {
|
||||||
|
return label;
|
||||||
|
};
|
||||||
|
|
||||||
|
uint16_t ConfigMenuItem::getValue() {
|
||||||
|
return value;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool ConfigMenuItem::setValue(uint16_t newval) {
|
||||||
|
if (valtype == "int") {
|
||||||
|
if (newval >= min and newval <= max) {
|
||||||
|
value = newval;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false; // out of range
|
||||||
|
} else if (valtype == "bool") {
|
||||||
|
value = (newval != 0) ? 1 : 0;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false; // invalid type
|
||||||
|
};
|
||||||
|
|
||||||
|
void ConfigMenuItem::incValue() {
|
||||||
|
// increase value by step
|
||||||
|
if (valtype == "int") {
|
||||||
|
if (value + step < max) {
|
||||||
|
value += step;
|
||||||
|
} else {
|
||||||
|
value = max;
|
||||||
|
}
|
||||||
|
} else if (valtype == "bool") {
|
||||||
|
value = !value;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
void ConfigMenuItem::decValue() {
|
||||||
|
// decrease value by step
|
||||||
|
if (valtype == "int") {
|
||||||
|
if (value - step > min) {
|
||||||
|
value -= step;
|
||||||
|
} else {
|
||||||
|
value = min;
|
||||||
|
}
|
||||||
|
} else if (valtype == "bool") {
|
||||||
|
value = !value;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
String ConfigMenuItem::getUnit() {
|
||||||
|
return unit;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t ConfigMenuItem::getStep() {
|
||||||
|
return step;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigMenuItem::setStep(uint16_t newstep) {
|
||||||
|
if (std::find(steps.begin(), steps.end(), newstep) == steps.end()) {
|
||||||
|
return; // invalid step: not in list of possible steps
|
||||||
|
}
|
||||||
|
step = newstep;
|
||||||
|
}
|
||||||
|
|
||||||
|
int8_t ConfigMenuItem::getPos() {
|
||||||
|
return position;
|
||||||
|
};
|
||||||
|
|
||||||
|
void ConfigMenuItem::setPos(int8_t newpos) {
|
||||||
|
position = newpos;
|
||||||
|
};
|
||||||
|
|
||||||
|
String ConfigMenuItem::getType() {
|
||||||
|
return valtype;
|
||||||
|
}
|
||||||
|
|
||||||
|
ConfigMenu::ConfigMenu(String menutitle, uint16_t menu_x, uint16_t menu_y) {
|
||||||
|
title = menutitle;
|
||||||
|
x = menu_x;
|
||||||
|
y = menu_y;
|
||||||
|
};
|
||||||
|
|
||||||
|
ConfigMenuItem* ConfigMenu::addItem(String key, String label, String valtype, uint16_t val, String valunit) {
|
||||||
|
if (items.find(key) != items.end()) {
|
||||||
|
// duplicate keys not allowed
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
ConfigMenuItem *itm = new ConfigMenuItem(valtype, label, val, valunit);
|
||||||
|
items.insert(std::pair<String, ConfigMenuItem*>(key, itm));
|
||||||
|
// Append key to index, index starting with 0
|
||||||
|
int8_t ix = items.size() - 1;
|
||||||
|
index[ix] = key;
|
||||||
|
itm->setPos(ix);
|
||||||
|
return itm;
|
||||||
|
};
|
||||||
|
|
||||||
|
void ConfigMenu::setItemDimension(uint16_t itemwidth, uint16_t itemheight) {
|
||||||
|
w = itemwidth;
|
||||||
|
h = itemheight;
|
||||||
|
};
|
||||||
|
|
||||||
|
void ConfigMenu::setItemActive(String key) {
|
||||||
|
if (items.find(key) != items.end()) {
|
||||||
|
activeitem = items[key]->getPos();
|
||||||
|
} else {
|
||||||
|
activeitem = -1;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
int8_t ConfigMenu::getActiveIndex() {
|
||||||
|
return activeitem;
|
||||||
|
}
|
||||||
|
|
||||||
|
ConfigMenuItem* ConfigMenu::getActiveItem() {
|
||||||
|
if (activeitem < 0) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
return items[index[activeitem]];
|
||||||
|
};
|
||||||
|
|
||||||
|
ConfigMenuItem* ConfigMenu::getItemByIndex(uint8_t ix) {
|
||||||
|
if (ix > index.size() - 1) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
return items[index[ix]];
|
||||||
|
};
|
||||||
|
|
||||||
|
ConfigMenuItem* ConfigMenu::getItemByKey(String key) {
|
||||||
|
if (items.find(key) == items.end()) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
return items[key];
|
||||||
|
};
|
||||||
|
|
||||||
|
uint8_t ConfigMenu::getItemCount() {
|
||||||
|
return items.size();
|
||||||
|
};
|
||||||
|
|
||||||
|
void ConfigMenu::goPrev() {
|
||||||
|
if (activeitem == 0) {
|
||||||
|
activeitem = items.size() - 1;
|
||||||
|
} else {
|
||||||
|
activeitem--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigMenu::goNext() {
|
||||||
|
if (activeitem == items.size() - 1) {
|
||||||
|
activeitem = 0;
|
||||||
|
} else {
|
||||||
|
activeitem++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
Point ConfigMenu::getXY() {
|
||||||
|
return {static_cast<double>(x), static_cast<double>(y)};
|
||||||
|
}
|
||||||
|
|
||||||
|
Rect ConfigMenu::getRect() {
|
||||||
|
return {static_cast<double>(x), static_cast<double>(y),
|
||||||
|
static_cast<double>(w), static_cast<double>(h)};
|
||||||
|
}
|
||||||
|
|
||||||
|
Rect ConfigMenu::getItemRect(int8_t index) {
|
||||||
|
return {static_cast<double>(x), static_cast<double>(y + index * h),
|
||||||
|
static_cast<double>(w), static_cast<double>(h)};
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigMenu::setCallback(void (*callback)()) {
|
||||||
|
fptrCallback = callback;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigMenu::storeValues() {
|
||||||
|
if (fptrCallback) {
|
||||||
|
fptrCallback();
|
||||||
|
}
|
||||||
|
}
|
||||||
67
lib/obp60task/ConfigMenu.h
Normal file
67
lib/obp60task/ConfigMenu.h
Normal file
@@ -0,0 +1,67 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <vector>
|
||||||
|
#include <map>
|
||||||
|
#include "Graphics.h" // for Point and Rect
|
||||||
|
|
||||||
|
class ConfigMenuItem {
|
||||||
|
private:
|
||||||
|
String label;
|
||||||
|
uint16_t value;
|
||||||
|
String unit;
|
||||||
|
String desc; // optional data to display
|
||||||
|
String valtype; // "int" | "bool" -> TODO "list"
|
||||||
|
uint16_t min;
|
||||||
|
uint16_t max;
|
||||||
|
std::vector<uint16_t> steps;
|
||||||
|
uint16_t step;
|
||||||
|
int8_t position; // counted fom 0
|
||||||
|
|
||||||
|
public:
|
||||||
|
ConfigMenuItem(String itemtype, String itemlabel, uint16_t itemval, String itemunit);
|
||||||
|
void setRange(uint16_t valmin, uint16_t valmax, std::vector<uint16_t> steps);
|
||||||
|
bool checkRange(uint16_t checkval);
|
||||||
|
String getLabel();
|
||||||
|
uint16_t getValue();
|
||||||
|
bool setValue(uint16_t newval);
|
||||||
|
void incValue();
|
||||||
|
void decValue();
|
||||||
|
String getUnit();
|
||||||
|
uint16_t getStep();
|
||||||
|
void setStep(uint16_t newstep);
|
||||||
|
int8_t getPos();
|
||||||
|
void setPos(int8_t newpos);
|
||||||
|
String getType();
|
||||||
|
};
|
||||||
|
|
||||||
|
class ConfigMenu {
|
||||||
|
private:
|
||||||
|
String title;
|
||||||
|
std::map <String,ConfigMenuItem*> items;
|
||||||
|
std::map <uint8_t,String> index;
|
||||||
|
int8_t activeitem = -1; // refers to position of item
|
||||||
|
uint16_t x;
|
||||||
|
uint16_t y;
|
||||||
|
uint16_t w;
|
||||||
|
uint16_t h;
|
||||||
|
void (*fptrCallback)();
|
||||||
|
|
||||||
|
public:
|
||||||
|
ConfigMenu(String title, uint16_t menu_x, uint16_t menu_y);
|
||||||
|
ConfigMenuItem* addItem(String key, String label, String valtype, uint16_t val, String valunit);
|
||||||
|
void setItemDimension(uint16_t itemwidth, uint16_t itemheight);
|
||||||
|
int8_t getActiveIndex();
|
||||||
|
void setItemActive(String key);
|
||||||
|
ConfigMenuItem* getActiveItem();
|
||||||
|
ConfigMenuItem* getItemByIndex(uint8_t index);
|
||||||
|
ConfigMenuItem* getItemByKey(String key);
|
||||||
|
uint8_t getItemCount();
|
||||||
|
void goPrev();
|
||||||
|
void goNext();
|
||||||
|
Point getXY();
|
||||||
|
Rect getRect();
|
||||||
|
Rect getItemRect(int8_t index);
|
||||||
|
void setCallback(void (*callback)());
|
||||||
|
void storeValues();
|
||||||
|
};
|
||||||
@@ -475,6 +475,30 @@ std::vector<String> wordwrap(String &line, uint16_t maxwidth) {
|
|||||||
return lines;
|
return lines;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Helper function to just get the exact width of a string
|
||||||
|
uint16_t getStringPixelWidth(const char* str, const GFXfont* font) {
|
||||||
|
int16_t minx = INT16_MAX;
|
||||||
|
int16_t maxx = INT16_MIN;
|
||||||
|
int16_t cursor_x = 0;
|
||||||
|
while (*str) {
|
||||||
|
char c = *str++;
|
||||||
|
if (c < font->first || c > font->last) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
GFXglyph* glyph = &font->glyph[c - font->first];
|
||||||
|
if (glyph->width > 0) {
|
||||||
|
int16_t glyphStart = cursor_x + glyph->xOffset;
|
||||||
|
int16_t glyphEnd = glyphStart + glyph->width;
|
||||||
|
if (glyphStart < minx) minx = glyphStart;
|
||||||
|
if (glyphEnd > maxx) maxx = glyphEnd;
|
||||||
|
}
|
||||||
|
cursor_x += glyph->xAdvance;
|
||||||
|
}
|
||||||
|
if (minx > maxx)
|
||||||
|
return 0;
|
||||||
|
return maxx - minx;
|
||||||
|
}
|
||||||
|
|
||||||
// Draw centered text
|
// Draw centered text
|
||||||
void drawTextCenter(int16_t cx, int16_t cy, String text) {
|
void drawTextCenter(int16_t cx, int16_t cy, String text) {
|
||||||
int16_t x1, y1;
|
int16_t x1, y1;
|
||||||
@@ -638,20 +662,19 @@ void displayHeader(CommonData &commonData, GwApi::BoatValue *date, GwApi::BoatVa
|
|||||||
// Date and time
|
// Date and time
|
||||||
String fmttype = commonData.config->getString(commonData.config->dateFormat);
|
String fmttype = commonData.config->getString(commonData.config->dateFormat);
|
||||||
String timesource = commonData.config->getString(commonData.config->timeSource);
|
String timesource = commonData.config->getString(commonData.config->timeSource);
|
||||||
double tz = commonData.config->getString(commonData.config->timeZone).toDouble();
|
|
||||||
getdisplay().setTextColor(commonData.fgcolor);
|
getdisplay().setTextColor(commonData.fgcolor);
|
||||||
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
getdisplay().setCursor(230, 15);
|
getdisplay().setCursor(230, 15);
|
||||||
if (timesource == "RTC" or timesource == "iRTC") {
|
if (timesource == "RTC" or timesource == "iRTC") {
|
||||||
// TODO take DST into account
|
// TODO take DST into account
|
||||||
if (commonData.data.rtcValid) {
|
if (commonData.data.rtcValid) {
|
||||||
time_t tv = mktime(&commonData.data.rtcTime) + (int)(tz * 3600);
|
time_t tv = mktime(&commonData.data.rtcTime) + (int)(commonData.tz * 3600);
|
||||||
struct tm *local_tm = localtime(&tv);
|
struct tm *local_tm = localtime(&tv);
|
||||||
getdisplay().print(formatTime('m', local_tm->tm_hour, local_tm->tm_min, 0));
|
getdisplay().print(formatTime('m', local_tm->tm_hour, local_tm->tm_min, 0));
|
||||||
getdisplay().print(" ");
|
getdisplay().print(" ");
|
||||||
getdisplay().print(formatDate(fmttype, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
|
getdisplay().print(formatDate(fmttype, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
|
||||||
getdisplay().print(" ");
|
getdisplay().print(" ");
|
||||||
getdisplay().print(tz == 0 ? "UTC" : "LOT");
|
getdisplay().print(commonData.tz == 0 ? "UTC" : "LOT");
|
||||||
} else {
|
} else {
|
||||||
drawTextRalign(396, 15, "RTC invalid");
|
drawTextRalign(396, 15, "RTC invalid");
|
||||||
}
|
}
|
||||||
@@ -666,7 +689,7 @@ void displayHeader(CommonData &commonData, GwApi::BoatValue *date, GwApi::BoatVa
|
|||||||
getdisplay().print(" ");
|
getdisplay().print(" ");
|
||||||
getdisplay().print(actdate);
|
getdisplay().print(actdate);
|
||||||
getdisplay().print(" ");
|
getdisplay().print(" ");
|
||||||
getdisplay().print(tz == 0 ? "UTC" : "LOT");
|
getdisplay().print(commonData.tz == 0 ? "UTC" : "LOT");
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
if(commonData.config->getBool(commonData.config->useSimuData) == true){
|
if(commonData.config->getBool(commonData.config->useSimuData) == true){
|
||||||
|
|||||||
@@ -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
|
||||||
|
|||||||
@@ -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) {
|
||||||
|
|
||||||
|
|||||||
@@ -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;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -49,8 +49,10 @@ void sensorTask(void *param){
|
|||||||
|
|
||||||
// Init sensor stuff
|
// Init sensor stuff
|
||||||
bool oneWire_ready = false; // 1Wire initialized and ready to use
|
bool oneWire_ready = false; // 1Wire initialized and ready to use
|
||||||
|
bool iRTC_ready = false; // Software RTC initialized and ready to use
|
||||||
bool RTC_ready = false; // DS1388 initialized and ready to use
|
bool RTC_ready = false; // DS1388 initialized and ready to use
|
||||||
bool GPS_ready = false; // GPS initialized and ready to use
|
bool GPS_ready = false; // GPS initialized and ready to use
|
||||||
|
bool N2K_GPS_ready = false; // GPS time on N2K bus
|
||||||
bool BME280_ready = false; // BME280 initialized and ready to use
|
bool BME280_ready = false; // BME280 initialized and ready to use
|
||||||
bool BMP280_ready = false; // BMP280 initialized and ready to use
|
bool BMP280_ready = false; // BMP280 initialized and ready to use
|
||||||
bool BMP180_ready = false; // BMP180 initialized and ready to use
|
bool BMP180_ready = false; // BMP180 initialized and ready to use
|
||||||
@@ -382,6 +384,7 @@ void sensorTask(void *param){
|
|||||||
if (getLocalTime(&timeinfo)) {
|
if (getLocalTime(&timeinfo)) {
|
||||||
api->getLogger()->logDebug(GwLog::LOG,"NTP time: %04d-%02d-%02d %02d:%02d:%02d UTC", timeinfo.tm_year+1900, timeinfo.tm_mon+1, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec);
|
api->getLogger()->logDebug(GwLog::LOG,"NTP time: %04d-%02d-%02d %02d:%02d:%02d UTC", timeinfo.tm_year+1900, timeinfo.tm_mon+1, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec);
|
||||||
rtc.setTimeStruct(timeinfo);
|
rtc.setTimeStruct(timeinfo);
|
||||||
|
iRTC_ready = true;
|
||||||
sensors.rtcValid = true;
|
sensors.rtcValid = true;
|
||||||
} else {
|
} else {
|
||||||
api->getLogger()->logDebug(GwLog::LOG,"NTP time fetch failed!");
|
api->getLogger()->logDebug(GwLog::LOG,"NTP time fetch failed!");
|
||||||
@@ -400,7 +403,7 @@ void sensorTask(void *param){
|
|||||||
if (millis() > starttime0 + 100)
|
if (millis() > starttime0 + 100)
|
||||||
{
|
{
|
||||||
starttime0 = millis();
|
starttime0 = millis();
|
||||||
// Send NMEA0183 GPS data on several bus systems all 100ms
|
// Send NMEA0183 GPS data on several bus systems (N2K an 0183) all 100ms
|
||||||
if (GPS_ready == true && hdop->value <= hdopAccuracy)
|
if (GPS_ready == true && hdop->value <= hdopAccuracy)
|
||||||
{
|
{
|
||||||
SNMEA0183Msg NMEA0183Msg;
|
SNMEA0183Msg NMEA0183Msg;
|
||||||
@@ -412,9 +415,55 @@ void sensorTask(void *param){
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// If RTC DS1388 ready, then copy GPS data to RTC all 5min
|
/*
|
||||||
if(millis() > starttime11 + 5*60*1000){
|
Time set logic for RTC and N2K
|
||||||
|
###############################
|
||||||
|
|
||||||
|
iRTC = Software RTC updatetd with NTP via internet
|
||||||
|
RTC = RTC chip on PCB
|
||||||
|
GPS = GPS Receiver on PCB
|
||||||
|
N2K = GPS time on N2K od 183 bus
|
||||||
|
0 = device not ready
|
||||||
|
1 = device ready
|
||||||
|
X = independend
|
||||||
|
() = source for set time N2K
|
||||||
|
-> = set RTC via iRTC
|
||||||
|
<- = set RTC via GPS
|
||||||
|
|
||||||
|
iRTC RTC GPS N2K
|
||||||
|
0 0 0 (1)
|
||||||
|
0 0 (1) (X)
|
||||||
|
0 (1) 0 (X)
|
||||||
|
0 1 <-(1) (X)
|
||||||
|
(1) 0 0 (X)
|
||||||
|
1 0 (1) (X)
|
||||||
|
1 ->(1) 0 (X)
|
||||||
|
1 1 <-(1) (X)
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
// If RTC DS1388 ready, then copy iRTC and GPS data to RTC all 1min
|
||||||
|
if(millis() > starttime11 + 1*60*1000){
|
||||||
starttime11 = millis();
|
starttime11 = millis();
|
||||||
|
// Set RTC chip via iRTC (NTP)
|
||||||
|
if(iRTC_ready == true && RTC_ready == true && GPS_ready == false){
|
||||||
|
GwApi::Status status;
|
||||||
|
api->getStatus(status);
|
||||||
|
// Check WiFi connection
|
||||||
|
if (status.wifiClientConnected) {
|
||||||
|
sensors.rtcTime = rtc.getTimeStruct(); // Get time from software RTC (iRTC)
|
||||||
|
DateTime now = DateTime(
|
||||||
|
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
|
||||||
|
);
|
||||||
|
ds1388.adjust(now);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Set RTC chip via internal GPS
|
||||||
if(rtcOn == "DS1388" && RTC_ready == true && GPS_ready == true){
|
if(rtcOn == "DS1388" && RTC_ready == true && GPS_ready == true){
|
||||||
api->getBoatDataValues(3,valueList);
|
api->getBoatDataValues(3,valueList);
|
||||||
if(gpsdays->valid && gpsseconds->valid && hdop->valid){
|
if(gpsdays->valid && gpsseconds->valid && hdop->valid){
|
||||||
@@ -422,40 +471,33 @@ void sensorTask(void *param){
|
|||||||
// sample input: date = "Dec 26 2009", time = "12:34:56"
|
// sample input: date = "Dec 26 2009", time = "12:34:56"
|
||||||
// ds1388.adjust(DateTime("Dec 26 2009", "12:34:56"));
|
// ds1388.adjust(DateTime("Dec 26 2009", "12:34:56"));
|
||||||
DateTime adjusttime(ts);
|
DateTime adjusttime(ts);
|
||||||
api->getLogger()->logDebug(GwLog::LOG,"Adjust RTC time: %04d/%02d/%02d %02d:%02d:%02d",adjusttime.year(), adjusttime.month(), adjusttime.day(), adjusttime.hour(), adjusttime.minute(), adjusttime.second());
|
api->getLogger()->logDebug(GwLog::LOG,"Adjust RTC time via internal GPS: %04d/%02d/%02d %02d:%02d:%02d",adjusttime.year(), adjusttime.month(), adjusttime.day(), adjusttime.hour(), adjusttime.minute(), adjusttime.second());
|
||||||
// Adjust RTC time as unix time value
|
// Adjust RTC time as unix time value
|
||||||
ds1388.adjust(adjusttime);
|
ds1388.adjust(adjusttime);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send 1Wire data for all temperature sensors all 2s
|
// Set RTC chip via N2K or 183 in case the internal GPS is off (only one time)
|
||||||
if(millis() > starttime13 + 2000 && String(oneWireOn) == "DS18B20" && oneWire_ready == true){
|
if(N2K_GPS_ready == false && RTC_ready == true && GPS_ready == false){
|
||||||
starttime13 = millis();
|
api->getBoatDataValues(3,valueList);
|
||||||
float tempC;
|
if(gpsdays->valid && gpsseconds->valid && hdop->valid){
|
||||||
ds18b20.requestTemperatures(); // Collect all temperature values (max.8)
|
long ts = tNMEA0183Msg::daysToTime_t(gpsdays->value - (30*365+7))+floor(gpsseconds->value); // Adjusted to reference year 2000 (-30 years and 7 days for switch years)
|
||||||
for(int i=0;i<numberOfDevices; i++){
|
// sample input: date = "Dec 26 2009", time = "12:34:56"
|
||||||
// Send only one 1Wire data per loop step (time reduction)
|
// ds1388.adjust(DateTime("Dec 26 2009", "12:34:56"));
|
||||||
if(i == loopCounter % numberOfDevices){
|
DateTime adjusttime(ts);
|
||||||
if(ds18b20.getAddress(tempDeviceAddress, i)){
|
api->getLogger()->logDebug(GwLog::LOG,"Adjust RTC time via N2K/183: %04d/%02d/%02d %02d:%02d:%02d",adjusttime.year(), adjusttime.month(), adjusttime.day(), adjusttime.hour(), adjusttime.minute(), adjusttime.second());
|
||||||
// Read temperature value in Celsius
|
// Adjust RTC time as unix time value
|
||||||
tempC = ds18b20.getTempC(tempDeviceAddress);
|
ds1388.adjust(adjusttime);
|
||||||
|
// N2K GPS time ready
|
||||||
|
N2K_GPS_ready = true;
|
||||||
}
|
}
|
||||||
// Send to NMEA200 bus for each sensor with instance number
|
|
||||||
if(!isnan(tempC)){
|
|
||||||
sensors.onewireTemp[i] = tempC; // Save values in SensorData
|
|
||||||
api->getLogger()->logDebug(GwLog::DEBUG,"DS18B20-%1d Temp: %.1f",i,tempC);
|
|
||||||
SetN2kPGN130316(N2kMsg, 0, i, N2kts_OutsideTemperature, CToKelvin(tempC), N2kDoubleNA);
|
|
||||||
api->sendN2kMessage(N2kMsg);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
loopCounter++;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get current RTC date and time 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 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
|
||||||
@@ -481,21 +523,62 @@ 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();
|
||||||
// WHY? isnan should always fail here
|
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,"Send PGN126992: %10d %10d",daysAt1970, (uint16_t)sysTime);
|
||||||
|
SetN2kPGN126992(N2kMsg,0,daysAt1970,sysTime,N2ktimes_LocalCrystalClock);
|
||||||
|
api->sendN2kMessage(N2kMsg);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Send date and time from software RTC (iRTC)
|
||||||
|
if (iRTC_ready == true && RTC_ready == false && GPS_ready == false) {
|
||||||
|
// Use internal RTC feature
|
||||||
|
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};
|
||||||
|
uint16_t switchYear = ((sensors.rtcTime.tm_year-1)-1968)/4 - ((sensors.rtcTime.tm_year-1)-1900)/100 + ((sensors.rtcTime.tm_year-1)-1600)/400;
|
||||||
|
long daysAt1970 = (sensors.rtcTime.tm_year-1970)*365 + switchYear + daysOfYear[sensors.rtcTime.tm_mon-1] + sensors.rtcTime.tm_mday-1;
|
||||||
|
// If switch year then add one day
|
||||||
|
if ((sensors.rtcTime.tm_mon > 2) && (sensors.rtcTime.tm_year % 4 == 0 && (sensors.rtcTime.tm_year % 100 != 0 || sensors.rtcTime.tm_year % 400 == 0))) {
|
||||||
|
daysAt1970 += 1;
|
||||||
|
}
|
||||||
|
// N2K sysTime is double in n2klib
|
||||||
|
double sysTime = (sensors.rtcTime.tm_hour * 3600) + (sensors.rtcTime.tm_min * 60) + sensors.rtcTime.tm_sec;
|
||||||
|
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, 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);
|
||||||
// }
|
|
||||||
}
|
}
|
||||||
} else if (sensors.rtcValid) {
|
|
||||||
// use internal rtc feature
|
|
||||||
sensors.rtcTime = rtc.getTimeStruct();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send supply voltage value all 1s
|
// Send 1Wire data for all temperature sensors to N2K all 2s
|
||||||
|
if(millis() > starttime13 + 2000 && String(oneWireOn) == "DS18B20" && oneWire_ready == true){
|
||||||
|
starttime13 = millis();
|
||||||
|
float tempC;
|
||||||
|
ds18b20.requestTemperatures(); // Collect all temperature values (max.8)
|
||||||
|
for(int i=0;i<numberOfDevices; i++){
|
||||||
|
// Send only one 1Wire data per loop step (time reduction)
|
||||||
|
if(i == loopCounter % numberOfDevices){
|
||||||
|
if(ds18b20.getAddress(tempDeviceAddress, i)){
|
||||||
|
// Read temperature value in Celsius
|
||||||
|
tempC = ds18b20.getTempC(tempDeviceAddress);
|
||||||
|
}
|
||||||
|
// Send to NMEA200 bus for each sensor with instance number
|
||||||
|
if(!isnan(tempC)){
|
||||||
|
sensors.onewireTemp[i] = tempC; // Save values in SensorData
|
||||||
|
api->getLogger()->logDebug(GwLog::DEBUG,"DS18B20-%1d Temp: %.1f",i,tempC);
|
||||||
|
SetN2kPGN130316(N2kMsg, 0, i, N2kts_OutsideTemperature, CToKelvin(tempC), N2kDoubleNA);
|
||||||
|
api->sendN2kMessage(N2kMsg);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
loopCounter++;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Send supply voltage value to N2K all 1s
|
||||||
if(millis() > starttime5 + 1000 && String(powsensor1) == "off"){
|
if(millis() > starttime5 + 1000 && String(powsensor1) == "off"){
|
||||||
starttime5 = millis();
|
starttime5 = millis();
|
||||||
float rawVoltage = 0; // Default value
|
float rawVoltage = 0; // Default value
|
||||||
@@ -565,7 +648,7 @@ void sensorTask(void *param){
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send data from environment sensor all 2s
|
// Send data from environment sensor to N2K all 2s
|
||||||
if(millis() > starttime6 + 2000){
|
if(millis() > starttime6 + 2000){
|
||||||
starttime6 = millis();
|
starttime6 = millis();
|
||||||
unsigned char TempSource = 2; // Inside temperature
|
unsigned char TempSource = 2; // Inside temperature
|
||||||
@@ -630,7 +713,7 @@ void sensorTask(void *param){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send rotation angle all 500ms
|
// Send rotation angle to N2K all 500ms
|
||||||
if(millis() > starttime7 + 500){
|
if(millis() > starttime7 + 500){
|
||||||
starttime7 = millis();
|
starttime7 = millis();
|
||||||
double rotationAngle=0;
|
double rotationAngle=0;
|
||||||
@@ -678,7 +761,7 @@ void sensorTask(void *param){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send battery power value all 1s
|
// Send battery power value to N2K all 1s
|
||||||
if(millis() > starttime8 + 1000 && (String(powsensor1) == "INA219" || String(powsensor1) == "INA226")){
|
if(millis() > starttime8 + 1000 && (String(powsensor1) == "INA219" || String(powsensor1) == "INA226")){
|
||||||
starttime8 = millis();
|
starttime8 = millis();
|
||||||
if(String(powsensor1) == "INA226" && INA226_1_ready == true){
|
if(String(powsensor1) == "INA226" && INA226_1_ready == true){
|
||||||
@@ -720,7 +803,7 @@ void sensorTask(void *param){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send solar power value all 1s
|
// Send solar power value to N2K all 1s
|
||||||
if(millis() > starttime9 + 1000 && (String(powsensor2) == "INA219" || String(powsensor2) == "INA226")){
|
if(millis() > starttime9 + 1000 && (String(powsensor2) == "INA219" || String(powsensor2) == "INA226")){
|
||||||
starttime9 = millis();
|
starttime9 = millis();
|
||||||
if(String(powsensor2) == "INA226" && INA226_2_ready == true){
|
if(String(powsensor2) == "INA226" && INA226_2_ready == true){
|
||||||
@@ -750,7 +833,7 @@ void sensorTask(void *param){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send generator power value all 1s
|
// Send generator power value to N2K all 1s
|
||||||
if(millis() > starttime10 + 1000 && (String(powsensor3) == "INA219" || String(powsensor3) == "INA226")){
|
if(millis() > starttime10 + 1000 && (String(powsensor3) == "INA219" || String(powsensor3) == "INA226")){
|
||||||
starttime10 = millis();
|
starttime10 = millis();
|
||||||
if(String(powsensor3) == "INA226" && INA226_3_ready == true){
|
if(String(powsensor3) == "INA226" && INA226_3_ready == true){
|
||||||
|
|||||||
@@ -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) {
|
||||||
|
|||||||
771
lib/obp60task/PageAnchor.cpp
Normal file
771
lib/obp60task/PageAnchor.cpp
Normal file
@@ -0,0 +1,771 @@
|
|||||||
|
// SPDX-License-Identifier: GPL-2.0-or-later
|
||||||
|
#if defined BOARD_OBP60S3 || defined BOARD_OBP40S3
|
||||||
|
|
||||||
|
/*
|
||||||
|
This page is in experimental stage so be warned!
|
||||||
|
North is up.
|
||||||
|
Anchor page with background map from mapservice
|
||||||
|
|
||||||
|
Boatdata used
|
||||||
|
DBS - Water depth
|
||||||
|
HDT - Boat heading, true
|
||||||
|
AWS - Wind strength; Boat not moving so we assume AWS=TWS and AWD=TWD
|
||||||
|
AWD - Wind direction
|
||||||
|
LAT/LON - Boat position, current
|
||||||
|
HDOP - Position error, horizontal
|
||||||
|
|
||||||
|
Raise function in device OBP40 has to be done inside config mode
|
||||||
|
because of limited number of buttons.
|
||||||
|
|
||||||
|
TODO
|
||||||
|
gzip for data transfer,
|
||||||
|
miniz.c from ROM?
|
||||||
|
manually inflating with tinflate from ROM
|
||||||
|
Save position in FRAM
|
||||||
|
Alarm: gps fix lost
|
||||||
|
switch unit feet/meter
|
||||||
|
force map update if new position is different from old position by
|
||||||
|
a certain level (e.g. 10m)
|
||||||
|
windlass integration
|
||||||
|
chain counter
|
||||||
|
|
||||||
|
Map service options / URL parameters
|
||||||
|
- mandatory
|
||||||
|
lat: latitude
|
||||||
|
lon: longitude
|
||||||
|
width: image width in px (400)
|
||||||
|
height: image height in px (300)
|
||||||
|
- optional
|
||||||
|
zoom: zoom level, default 15
|
||||||
|
mrot: map rotation angle in degrees
|
||||||
|
mtype: map type, default="Open Street Map"
|
||||||
|
dtype: dithering type, default="Atkinson"
|
||||||
|
cutout: image cutout type 0=none
|
||||||
|
alpha: alpha blending for cutout
|
||||||
|
tab: tab size, 0=none
|
||||||
|
border: border line zize in px, default 2
|
||||||
|
symbol: synmol number, default=2 triangle
|
||||||
|
srot: symbol rotation in degrees
|
||||||
|
ssize: symbol size in px, default=15
|
||||||
|
grid: show map grid
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <WiFi.h>
|
||||||
|
#include <HTTPClient.h>
|
||||||
|
#include "Pagedata.h"
|
||||||
|
#include "OBP60Extensions.h"
|
||||||
|
#include "ConfigMenu.h"
|
||||||
|
// #include "miniz.h" // devices without PSRAM use <rom/miniz.h>
|
||||||
|
|
||||||
|
// extern "C" {
|
||||||
|
#include "rom/miniz.h"
|
||||||
|
// }
|
||||||
|
|
||||||
|
#define anchor_width 16
|
||||||
|
#define anchor_height 16
|
||||||
|
static unsigned char anchor_bits[] PROGMEM = {
|
||||||
|
0x80, 0x01, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, 0xf0, 0x0f, 0x80, 0x01,
|
||||||
|
0x80, 0x01, 0x88, 0x11, 0x8c, 0x31, 0x8e, 0x71, 0x84, 0x21, 0x86, 0x61,
|
||||||
|
0x86, 0x61, 0xfc, 0x3f, 0xf8, 0x1f, 0x80, 0x01 };
|
||||||
|
|
||||||
|
class PageAnchor : public Page
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
char mode = 'N'; // (N)ormal, (C)onfig
|
||||||
|
int8_t editmode = -1; // marker for menu/edit/set function
|
||||||
|
ConfigMenu *menu;
|
||||||
|
|
||||||
|
//uint8_t *mapbuf = new uint8_t[10000]; // 8450 Byte without header
|
||||||
|
//int mapbuf_size = 10000;
|
||||||
|
//uint8_t *mapbuf = (uint8_t*) heap_caps_malloc(mapbuf_size, MALLOC_CAP_SPIRAM);
|
||||||
|
GFXcanvas1 *canvas;
|
||||||
|
const uint16_t map_width = 264;
|
||||||
|
const uint16_t map_height = 260;
|
||||||
|
bool map_valid = false;
|
||||||
|
char map_service = 'R'; // (O)BP Service, (L)ocal Service, (R)emote Service
|
||||||
|
double map_lat = 0; // current center of valid map
|
||||||
|
double map_lon = 0;
|
||||||
|
String server_name; // server with map service
|
||||||
|
uint16_t server_port = 80;
|
||||||
|
String tile_path;
|
||||||
|
|
||||||
|
String lengthformat;
|
||||||
|
|
||||||
|
double scale = 50; // Radius of display circle in meter, depends on lat
|
||||||
|
uint8_t zoom = 15; // map zoom level
|
||||||
|
|
||||||
|
bool alarm = false;
|
||||||
|
bool alarm_enabled = false;
|
||||||
|
uint8_t alarm_range;
|
||||||
|
|
||||||
|
uint8_t chain_length;
|
||||||
|
uint8_t chain = 0;
|
||||||
|
|
||||||
|
bool anchor_set = false;
|
||||||
|
double anchor_lat;
|
||||||
|
double anchor_lon;
|
||||||
|
double anchor_depth;
|
||||||
|
int anchor_ts; // time stamp anchor dropped
|
||||||
|
|
||||||
|
GwApi::BoatValue *bv_dbs; // depth below surface
|
||||||
|
GwApi::BoatValue *bv_hdt; // true heading
|
||||||
|
GwApi::BoatValue *bv_aws; // apparent wind speed
|
||||||
|
GwApi::BoatValue *bv_awd; // apparent wind direction
|
||||||
|
GwApi::BoatValue *bv_lat; // latitude, current
|
||||||
|
GwApi::BoatValue *bv_lon; // longitude, current
|
||||||
|
GwApi::BoatValue *bv_hdop; // horizontal position error
|
||||||
|
|
||||||
|
bool simulation = false;
|
||||||
|
int last_mapsize = 0;
|
||||||
|
String errmsg = "";
|
||||||
|
int loops;
|
||||||
|
int readbytes = 0;
|
||||||
|
|
||||||
|
void displayModeNormal(PageData &pageData) {
|
||||||
|
|
||||||
|
// get currrent boatvalues
|
||||||
|
bv_dbs = pageData.values[0]; // DBS
|
||||||
|
String sval_dbs = formatValue(bv_dbs, *commonData).svalue;
|
||||||
|
String sunit_dbs = formatValue(bv_dbs, *commonData).unit;
|
||||||
|
bv_hdt = pageData.values[1]; // HDT
|
||||||
|
String sval_hdt = formatValue(bv_hdt, *commonData).svalue;
|
||||||
|
bv_aws = pageData.values[2]; // AWS
|
||||||
|
String sval_aws = formatValue(bv_aws, *commonData).svalue;
|
||||||
|
String sunit_aws = formatValue(bv_aws, *commonData).unit;
|
||||||
|
bv_awd = pageData.values[3]; // AWD
|
||||||
|
String sval_awd = formatValue(bv_awd, *commonData).svalue;
|
||||||
|
bv_lat = pageData.values[4]; // LAT
|
||||||
|
String sval_lat = formatValue(bv_lat, *commonData).svalue;
|
||||||
|
bv_lon = pageData.values[5]; // LON
|
||||||
|
String sval_lon = formatValue(bv_lon, *commonData).svalue;
|
||||||
|
bv_hdop = pageData.values[6]; // HDOP
|
||||||
|
String sval_hdop = formatValue(bv_hdop, *commonData).svalue;
|
||||||
|
String sunit_hdop = formatValue(bv_hdop, *commonData).unit;
|
||||||
|
|
||||||
|
commonData->logger->logDebug(GwLog::DEBUG, "Drawing at PageAnchor; DBS=%f, HDT=%f, AWS=%f", bv_dbs->value, bv_hdt->value, bv_aws->value);
|
||||||
|
|
||||||
|
// Draw canvas with background map
|
||||||
|
// rhumb(map_lat, map_lon, bv_lat->value, bv_lon->value)
|
||||||
|
int posdiff = 0;
|
||||||
|
if (map_valid) {
|
||||||
|
if (bv_lat->valid and bv_lon->valid) {
|
||||||
|
// calculate movement since last map refresh
|
||||||
|
posdiff = rhumb(map_lat, map_lon, bv_lat->value, bv_lon->value);
|
||||||
|
if (posdiff > 25) {
|
||||||
|
map_lat = bv_lat->value;
|
||||||
|
map_lon = bv_lon->value;
|
||||||
|
map_valid = getBackgroundMap(map_lat, map_lon, zoom);
|
||||||
|
if (map_valid) {
|
||||||
|
// prepare visible space for anchor-symbol or boat
|
||||||
|
canvas->fillCircle(132, 130, 12, commonData->fgcolor);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
getdisplay().drawBitmap(68, 20, canvas->getBuffer(), map_width, map_height, commonData->fgcolor);
|
||||||
|
}
|
||||||
|
|
||||||
|
Point c = {200, 150}; // center = anchor position
|
||||||
|
uint16_t r = 125;
|
||||||
|
|
||||||
|
// Circle as map border
|
||||||
|
getdisplay().drawCircle(c.x, c.y, r, commonData->fgcolor);
|
||||||
|
getdisplay().drawCircle(c.x, c.y, r + 1, commonData->fgcolor);
|
||||||
|
|
||||||
|
Point b = {200, 180}; // boat position while dropping anchor
|
||||||
|
|
||||||
|
const std::vector<Point> pts_boat = { // polygon lines
|
||||||
|
{b.x - 5, b.y},
|
||||||
|
{b.x - 5, b.y - 10},
|
||||||
|
{b.x, b.y - 16},
|
||||||
|
{b.x + 5, b.y - 10},
|
||||||
|
{b.x + 5, b.y}
|
||||||
|
};
|
||||||
|
//rotatePoints then draw lines
|
||||||
|
// TODO rotate boat according to current heading
|
||||||
|
if (bv_hdt->valid) {
|
||||||
|
if (map_valid) {
|
||||||
|
Point b1 = rotatePoint(c, {b.x, b.y - 8}, bv_hdt->value * RAD_TO_DEG);
|
||||||
|
getdisplay().fillCircle(b1.x, b1.y, 10, commonData->bgcolor);
|
||||||
|
}
|
||||||
|
drawPoly(rotatePoints(c, pts_boat, bv_hdt->value * RAD_TO_DEG), commonData->fgcolor);
|
||||||
|
} else {
|
||||||
|
// no heading available: draw north oriented
|
||||||
|
if (map_valid) {
|
||||||
|
getdisplay().fillCircle(b.x, b.y - 8, 10, commonData->bgcolor);
|
||||||
|
}
|
||||||
|
drawPoly(pts_boat, commonData->fgcolor);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Draw wind arrow
|
||||||
|
const std::vector<Point> pts_wind = {
|
||||||
|
{c.x, c.y - r + 25},
|
||||||
|
{c.x - 12, c.y - r - 4},
|
||||||
|
{c.x, c.y - r + 6},
|
||||||
|
{c.x + 12, c.y - r - 4}
|
||||||
|
};
|
||||||
|
if (bv_awd->valid) {
|
||||||
|
fillPoly4(rotatePoints(c, pts_wind, bv_awd->value), commonData->fgcolor);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Title and corner value headings
|
||||||
|
getdisplay().setTextColor(commonData->fgcolor);
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold10pt8b);
|
||||||
|
// Left
|
||||||
|
getdisplay().setCursor(8, 36);
|
||||||
|
getdisplay().print("Anchor");
|
||||||
|
getdisplay().setCursor(8, 210);
|
||||||
|
getdisplay().print("Depth");
|
||||||
|
// Right
|
||||||
|
drawTextRalign(392, 80, "Chain");
|
||||||
|
drawTextRalign(392, 210, "Wind");
|
||||||
|
|
||||||
|
// Units
|
||||||
|
getdisplay().setCursor(8, 272);
|
||||||
|
getdisplay().print(sunit_dbs);
|
||||||
|
drawTextRalign(392, 272, sunit_aws);
|
||||||
|
// drawTextRalign(392, 100, lengthformat); // chain unit not implemented
|
||||||
|
|
||||||
|
// Corner values
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
|
getdisplay().setCursor(8, 54);
|
||||||
|
getdisplay().print(anchor_set ? "Dropped" : "Ready"); // Anchor state
|
||||||
|
getdisplay().setCursor(8, 72);
|
||||||
|
getdisplay().print("Alarm: "); // Alarm state
|
||||||
|
getdisplay().print(alarm_enabled ? "on" : "off");
|
||||||
|
|
||||||
|
getdisplay().setCursor(8, 120);
|
||||||
|
getdisplay().print("Zoom");
|
||||||
|
getdisplay().setCursor(8, 136);
|
||||||
|
getdisplay().print(zoom);
|
||||||
|
|
||||||
|
getdisplay().setCursor(8, 160);
|
||||||
|
getdisplay().print("diff");
|
||||||
|
getdisplay().setCursor(8, 176);
|
||||||
|
if (map_valid and bv_lat->valid and bv_lon->valid) {
|
||||||
|
getdisplay().print(String(posdiff));
|
||||||
|
} else {
|
||||||
|
getdisplay().print("n/a");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Chain out TODO lengthformat ft/m
|
||||||
|
drawTextRalign(392, 96, String(chain) + " m");
|
||||||
|
drawTextRalign(392, 96+16, "of " + String(chain_length) + " m");
|
||||||
|
|
||||||
|
getdisplay().setFont(&DSEG7Classic_BoldItalic16pt7b);
|
||||||
|
|
||||||
|
// Depth
|
||||||
|
getdisplay().setCursor(8, 250);
|
||||||
|
getdisplay().print(sval_dbs);
|
||||||
|
|
||||||
|
// Wind
|
||||||
|
getdisplay().setCursor(320, 250);
|
||||||
|
getdisplay().print(sval_aws);
|
||||||
|
|
||||||
|
// Position of boat in center of map
|
||||||
|
getdisplay().setFont(&IBM8x8px);
|
||||||
|
drawTextRalign(392, 34, sval_lat);
|
||||||
|
drawTextRalign(392, 44, sval_lon);
|
||||||
|
// quality
|
||||||
|
String hdop = "HDOP: ";
|
||||||
|
if (bv_hdop->valid) {
|
||||||
|
hdop += String(round(bv_hdop->value));
|
||||||
|
} else {
|
||||||
|
hdop += " n/a";
|
||||||
|
}
|
||||||
|
drawTextRalign(392, 54, hdop);
|
||||||
|
|
||||||
|
// zoom scale
|
||||||
|
getdisplay().drawLine(c.x + 10, c.y, c.x + r - 4, c.y, commonData->fgcolor);
|
||||||
|
// arrow left
|
||||||
|
getdisplay().drawLine(c.x + 10, c.y, c.x + 16, c.y - 4, commonData->fgcolor);
|
||||||
|
getdisplay().drawLine(c.x + 10, c.y, c.x + 16, c.y + 4, commonData->fgcolor);
|
||||||
|
// arrow right
|
||||||
|
getdisplay().drawLine(c.x + r - 4, c.y, c.x + r - 10, c.y - 4, commonData->fgcolor);
|
||||||
|
getdisplay().drawLine(c.x + r - 4, c.y, c.x + r - 10, c.y + 4, commonData->fgcolor);
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
|
drawTextCenter(c.x + r / 2, c.y + 8, String(scale, 0) + "m");
|
||||||
|
|
||||||
|
// draw anchor symbol (as bitmap)
|
||||||
|
getdisplay().drawXBitmap(c.x - anchor_width / 2, c.y - anchor_height / 2,
|
||||||
|
anchor_bits, anchor_width, anchor_height, commonData->fgcolor);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void displayModeConfig(PageData &pageData) {
|
||||||
|
|
||||||
|
getdisplay().setTextColor(commonData->fgcolor);
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
||||||
|
getdisplay().setCursor(8, 48);
|
||||||
|
getdisplay().print("Anchor configuration");
|
||||||
|
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
|
|
||||||
|
getdisplay().setCursor(8, 260);
|
||||||
|
getdisplay().print("Press BACK to leave config");
|
||||||
|
|
||||||
|
/* getdisplay().setCursor(8, 68);
|
||||||
|
getdisplay().printf("Server: %s", server_name.c_str());
|
||||||
|
getdisplay().setCursor(8, 88);
|
||||||
|
getdisplay().printf("Port: %d", server_port);
|
||||||
|
getdisplay().setCursor(8, 108);
|
||||||
|
getdisplay().printf("Tilepath: %s", tile_path.c_str());
|
||||||
|
getdisplay().setCursor(8, 128);
|
||||||
|
getdisplay().printf("Last mapsize: %d", last_mapsize);
|
||||||
|
getdisplay().setCursor(8, 148);
|
||||||
|
getdisplay().printf("Last error: %s", errmsg);
|
||||||
|
getdisplay().setCursor(8, 168);
|
||||||
|
getdisplay().printf("Loops: %d, Readbytes: %d", loops, readbytes);
|
||||||
|
*/
|
||||||
|
|
||||||
|
GwApi::BoatValue *bv_lat = pageData.values[4]; // LAT
|
||||||
|
GwApi::BoatValue *bv_lon = pageData.values[5]; // LON
|
||||||
|
if (!bv_lat->valid or !bv_lon->valid) {
|
||||||
|
getdisplay().setCursor(8, 228);
|
||||||
|
getdisplay().printf("No valid position: background map disabled");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Display menu
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
|
for (int i = 0 ; i < menu->getItemCount(); i++) {
|
||||||
|
ConfigMenuItem *itm = menu->getItemByIndex(i);
|
||||||
|
if (!itm) {
|
||||||
|
commonData->logger->logDebug(GwLog::ERROR, "Menu item not found: %d", i);
|
||||||
|
} else {
|
||||||
|
Rect r = menu->getItemRect(i);
|
||||||
|
bool inverted = (i == menu->getActiveIndex());
|
||||||
|
drawTextBoxed(r, itm->getLabel(), commonData->fgcolor, commonData->bgcolor, inverted, false);
|
||||||
|
if (inverted and editmode > 0) {
|
||||||
|
// triangle as edit marker
|
||||||
|
getdisplay().fillTriangle(r.x + r.w + 20, r.y, r.x + r.w + 30, r.y + r.h / 2, r.x + r.w + 20, r.y + r.h, commonData->fgcolor);
|
||||||
|
}
|
||||||
|
getdisplay().setCursor(r.x + r.w + 40, r.y + r.h - 4);
|
||||||
|
if (itm->getType() == "int") {
|
||||||
|
getdisplay().print(itm->getValue());
|
||||||
|
getdisplay().print(itm->getUnit());
|
||||||
|
} else {
|
||||||
|
getdisplay().print(itm->getValue() == 0 ? "No" : "Yes");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
PageAnchor(CommonData &common)
|
||||||
|
{
|
||||||
|
commonData = &common;
|
||||||
|
common.logger->logDebug(GwLog::LOG,"Instantiate PageAnchor");
|
||||||
|
|
||||||
|
String mapsource = common.config->getString(common.config->mapsource);
|
||||||
|
if (mapsource == "Local Service") {
|
||||||
|
map_service = 'L';
|
||||||
|
server_name = common.config->getString(common.config->ipAddress);
|
||||||
|
server_port = common.config->getInt(common.config->localPort);
|
||||||
|
tile_path = "";
|
||||||
|
} else if (mapsource == "Remote Service") {
|
||||||
|
map_service = 'R';
|
||||||
|
server_name = common.config->getString(common.config->mapServer);
|
||||||
|
tile_path = common.config->getString(common.config->mapTilePath);
|
||||||
|
} else { // OBP Service or undefined
|
||||||
|
map_service = 'O';
|
||||||
|
server_name = "norbert-walter.dnshome.de";
|
||||||
|
tile_path = "";
|
||||||
|
}
|
||||||
|
zoom = common.config->getInt(common.config->zoomlevel);
|
||||||
|
|
||||||
|
lengthformat = common.config->getString(common.config->lengthFormat);
|
||||||
|
chain_length = common.config->getInt(common.config->chainLength);
|
||||||
|
|
||||||
|
if (simulation) {
|
||||||
|
map_lat = 53.56938345759218;
|
||||||
|
map_lon = 9.679658234303275;
|
||||||
|
}
|
||||||
|
|
||||||
|
canvas = new GFXcanvas1(264, 260); // Byte aligned, no padding!
|
||||||
|
|
||||||
|
// Initialize config menu
|
||||||
|
menu = new ConfigMenu("Options", 40, 80);
|
||||||
|
menu->setItemDimension(150, 20);
|
||||||
|
ConfigMenuItem *newitem;
|
||||||
|
newitem = menu->addItem("chain", "Chain out", "int", 0, "m");
|
||||||
|
newitem->setRange(0, 200, {1, 2, 5, 10});
|
||||||
|
newitem = menu->addItem("alarm", "Alarm", "bool", 0, "");
|
||||||
|
newitem = menu->addItem("alarm", "Alarm range", "int", 50, "m");
|
||||||
|
newitem->setRange(0, 200, {1, 2, 5, 10});
|
||||||
|
newitem = menu->addItem("raise", "Raise Anchor", "bool", 0, "");
|
||||||
|
newitem = menu->addItem("zoom", "Zoom", "int", 15, "");
|
||||||
|
newitem->setRange(14, 17, {1});
|
||||||
|
menu->setItemActive("chain");
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void setupKeys(){
|
||||||
|
Page::setupKeys();
|
||||||
|
commonData->keydata[0].label = "CFG";
|
||||||
|
#ifdef BOARD_OBP40S3
|
||||||
|
commonData->keydata[1].label = "DROP";
|
||||||
|
#endif
|
||||||
|
#ifdef BOARD_OBP60S3
|
||||||
|
commonData->keydata[4].label = "DROP";
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO OBP40 / OBP60 different handling
|
||||||
|
int handleKey(int key) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Page Anchor handle key %d", key);
|
||||||
|
if (key == 1) { // Switch between normal and config mode
|
||||||
|
if (mode == 'N') {
|
||||||
|
mode = 'C';
|
||||||
|
#ifdef BOARD_OBP40S3
|
||||||
|
commonData->keydata[0].label = "BACK";
|
||||||
|
commonData->keydata[1].label = "EDIT";
|
||||||
|
#endif
|
||||||
|
} else {
|
||||||
|
mode = 'N';
|
||||||
|
#ifdef BOARD_OBP40S3
|
||||||
|
commonData->keydata[0].label = "CFG";
|
||||||
|
commonData->keydata[1].label = anchor_set ? "RAISE": "DROP";
|
||||||
|
#endif
|
||||||
|
#ifdef BOARD_OBP60S3
|
||||||
|
commonData->keydata[4].label = anchor_set ? "RAISE": "DROP";
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
if (key == 2) {
|
||||||
|
if (mode == 'N') {
|
||||||
|
anchor_set = !anchor_set;
|
||||||
|
commonData->keydata[1].label = anchor_set ? "ALARM": "DROP";
|
||||||
|
if (anchor_set) {
|
||||||
|
anchor_lat = bv_lat->value;
|
||||||
|
anchor_lon = bv_lon->value;
|
||||||
|
anchor_depth = bv_dbs->value;
|
||||||
|
// TODO set timestamp
|
||||||
|
// anchor_ts =
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
} else if (mode == 'C') {
|
||||||
|
// Change edit mode
|
||||||
|
if (editmode > 0) {
|
||||||
|
editmode = 0;
|
||||||
|
commonData->keydata[1].label = "EDIT";
|
||||||
|
} else {
|
||||||
|
editmode = 1;
|
||||||
|
commonData->keydata[1].label = "OK";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (key == 9) {
|
||||||
|
// OBP40 Down
|
||||||
|
if (mode == 'C') {
|
||||||
|
if (editmode > 0) {
|
||||||
|
// decrease current menu item
|
||||||
|
menu->getActiveItem()->decValue();
|
||||||
|
} else {
|
||||||
|
// move to next menu item
|
||||||
|
menu->goNext();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (key == 10) {
|
||||||
|
// OBP40 Up
|
||||||
|
if (mode == 'C') {
|
||||||
|
if (editmode > 0) {
|
||||||
|
// increase current menu item
|
||||||
|
ConfigMenuItem *itm = menu->getActiveItem();
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "step = %d", itm->getStep());
|
||||||
|
itm->incValue();
|
||||||
|
} else {
|
||||||
|
// move to previous menu item
|
||||||
|
menu->goPrev();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Code for keylock
|
||||||
|
if (key == 11) {
|
||||||
|
commonData->keylock = !commonData->keylock;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return key;
|
||||||
|
}
|
||||||
|
|
||||||
|
int rhumb(double lat1, double lon1, double lat2, double lon2) {
|
||||||
|
// calc distance in m between two geo points
|
||||||
|
static const double degToRad = M_PI / 180.0;
|
||||||
|
lat1 = degToRad * lat1;
|
||||||
|
lon1 = degToRad * lon1;
|
||||||
|
lat2 = degToRad * lat2;
|
||||||
|
lon2 = degToRad * lon2;
|
||||||
|
double dlon = lon2 - lon1;
|
||||||
|
double dlat = lat2 - lat1;
|
||||||
|
double mlat = (lat1 + lat2) / 2;
|
||||||
|
return (int) (6371000 * sqrt(pow(dlat, 2) + pow(cos(mlat) * dlon, 2)));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool getBackgroundMap(double lat, double lon, uint8_t zoom) {
|
||||||
|
// HTTP-Request for map
|
||||||
|
// TODO über pagedata -> status abfragen?
|
||||||
|
if (WiFi.status() != WL_CONNECTED) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
bool valid = false;
|
||||||
|
HTTPClient http;
|
||||||
|
const char* headerKeys[] = { "Content-Encoding", "Content-Length" };
|
||||||
|
http.collectHeaders(headerKeys, 2);
|
||||||
|
String url = "http://" + server_name + "/" + tile_path;
|
||||||
|
String parameter = "?lat=" + String(lat, 6) + "&lon=" + String(lon, 6)+ "&zoom=" + String(zoom)
|
||||||
|
+ "&width=" + String(map_width) + "&height=" + String(map_height);
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "HTTP query: %s", String(url + parameter).c_str());
|
||||||
|
http.begin(url + parameter);
|
||||||
|
http.addHeader("Accept-Encoding", "deflate");
|
||||||
|
int httpCode = http.GET();
|
||||||
|
if (httpCode > 0) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "HTTP GET result code: %d", httpCode);
|
||||||
|
if (httpCode == HTTP_CODE_OK) {
|
||||||
|
WiFiClient* stream = http.getStreamPtr();
|
||||||
|
int size = http.getSize();
|
||||||
|
String encoding = http.header("Content-Encoding");
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "HTTP size: %d, encoding: '%s'", size, encoding);
|
||||||
|
bool is_gzip = encoding.equalsIgnoreCase("deflate");
|
||||||
|
|
||||||
|
uint8_t header[14]; // max: P4<LF>wwww wwww<LF>
|
||||||
|
int header_size = 0;
|
||||||
|
bool header_read = false;
|
||||||
|
int n = 0;
|
||||||
|
int ix = 0;
|
||||||
|
|
||||||
|
uint8_t* buf = canvas->getBuffer();
|
||||||
|
|
||||||
|
if (is_gzip) {
|
||||||
|
/* gzip compressed data
|
||||||
|
* has to be decompressed into a buffer big enough
|
||||||
|
* to hold the whole data.
|
||||||
|
* so the PBM header is included
|
||||||
|
* search a method to use that as canvas without
|
||||||
|
* additional copy
|
||||||
|
*/
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Map received in gzip encoding");
|
||||||
|
|
||||||
|
#define HEADER_MAX 24
|
||||||
|
#define HTTP_CHUNK 512
|
||||||
|
uint8_t in_buf[HTTP_CHUNK];
|
||||||
|
uint8_t header_buf[HEADER_MAX];
|
||||||
|
tinfl_decompressor decomp;
|
||||||
|
tinfl_init(&decomp);
|
||||||
|
size_t bitmap_written = 0;
|
||||||
|
size_t header_written = 0;
|
||||||
|
bool header_done = false;
|
||||||
|
int row_bytes = 0;
|
||||||
|
size_t expected_bitmap = 0;
|
||||||
|
|
||||||
|
while (stream->connected() || stream->available()) {
|
||||||
|
int bytes_read = stream->read(in_buf, HTTP_CHUNK);
|
||||||
|
if (bytes_read <= 0) break;
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "stream: bytes_read=%d", bytes_read);
|
||||||
|
size_t in_ofs = 0; // offset
|
||||||
|
while (in_ofs < (size_t)bytes_read) {
|
||||||
|
size_t in_size = bytes_read - in_ofs;
|
||||||
|
size_t out_size;
|
||||||
|
uint8_t *out_ptr;
|
||||||
|
uint8_t *out_ptr_next;
|
||||||
|
if (!header_done) {
|
||||||
|
if (header_written >= HEADER_MAX) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "PBM header too large");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
out_ptr = header_buf + header_written;
|
||||||
|
out_size = HEADER_MAX - header_written;
|
||||||
|
} else {
|
||||||
|
out_ptr = buf + bitmap_written;
|
||||||
|
out_size = expected_bitmap - bitmap_written;
|
||||||
|
}
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "in_size=%d, out_size=%d", in_size, out_size);
|
||||||
|
// TODO correct loop !!!
|
||||||
|
// tinfl_status tinfl_decompress(
|
||||||
|
// tinfl_decompressor *r,
|
||||||
|
// const mz_uint8 *pIn_buf_next,
|
||||||
|
// size_t *pIn_buf_size,
|
||||||
|
// mz_uint8 *pOut_buf_start
|
||||||
|
// mz_uint8 *pOut_buf_next,
|
||||||
|
// size_t *pOut_buf_size,
|
||||||
|
// const mz_uint32 decomp_flags)
|
||||||
|
tinfl_status status = tinfl_decompress(
|
||||||
|
&decomp,
|
||||||
|
in_buf + in_ofs, // start address in input buffer
|
||||||
|
&in_size, // number of bytes to process
|
||||||
|
out_ptr, // start of output buffer
|
||||||
|
out_ptr, // next write position in output buffer
|
||||||
|
&out_size, // free size in output buffer
|
||||||
|
// TINFL_FLAG_PARSE_ZLIB_HEADER |
|
||||||
|
TINFL_FLAG_HAS_MORE_INPUT |
|
||||||
|
TINFL_FLAG_USING_NON_WRAPPING_OUTPUT_BUF
|
||||||
|
);
|
||||||
|
if (status < 0) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Decompression error (%d)", status);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
in_ofs += in_size;
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "in_size=%d, in_ofs=%d", in_size, in_ofs);
|
||||||
|
|
||||||
|
if (!header_done) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Decoding header");
|
||||||
|
header_written += out_size;
|
||||||
|
|
||||||
|
// Detect header end: two '\n'
|
||||||
|
char *first_nl = strchr((char*)header_buf, '\n');
|
||||||
|
if (!first_nl) continue;
|
||||||
|
|
||||||
|
char *second_nl = strchr(first_nl + 1, '\n');
|
||||||
|
if (!second_nl) continue;
|
||||||
|
|
||||||
|
// Null-terminate header for sscanf
|
||||||
|
header_buf[header_written < HEADER_MAX ? header_written : HEADER_MAX - 1] = 0;
|
||||||
|
|
||||||
|
// Check magic
|
||||||
|
if (strncmp((char*)header_buf, "P4", 2) != 0) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Invalid PBM magic");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Parse width and height strictly
|
||||||
|
int header_width = 0, header_height = 0;
|
||||||
|
if (sscanf((char*)header_buf, "P4\n%d %d", &header_width, &header_height) != 2) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Failed to parse PBM dimensions");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (header_width != map_width || header_height != map_height) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "PBM size mismatch: header %dx%d, requested %dx%d\n",
|
||||||
|
header_width, header_height, map_width, map_height);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Header: %dx%d", header_width, header_height);
|
||||||
|
|
||||||
|
// Compute row bytes and expected bitmap size
|
||||||
|
row_bytes = (header_width + 7) / 8;
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "row_bytes=%d", row_bytes);
|
||||||
|
expected_bitmap = (size_t)row_bytes * header_height;
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "expected_bitmap=%d", expected_bitmap);
|
||||||
|
|
||||||
|
// Copy any extra decompressed bitmap after header
|
||||||
|
size_t header_size = (second_nl + 1) - (char*)header_buf;
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "header_size=%d", header_size);
|
||||||
|
size_t extra_bitmap = header_written - header_size;
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "extra bitmap=%d", extra_bitmap);
|
||||||
|
|
||||||
|
header_done = true;
|
||||||
|
|
||||||
|
if (extra_bitmap > 0) {
|
||||||
|
memcpy(buf, header_buf + header_size, extra_bitmap);
|
||||||
|
bitmap_written = extra_bitmap;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
bitmap_written += out_size;
|
||||||
|
if (bitmap_written >= expected_bitmap) {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Image fully received");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "bitmap_written=%d", bitmap_written);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// uncompressed data
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Map received uncompressed");
|
||||||
|
while (stream->available()) {
|
||||||
|
uint8_t b = stream->read();
|
||||||
|
n += 1;
|
||||||
|
if ((! header_read) and (n < 13) ) {
|
||||||
|
header[n-1] = b;
|
||||||
|
if ((n > 3) and (b == 0x0a)) {
|
||||||
|
header_read = true;
|
||||||
|
header_size = n;
|
||||||
|
header[n] = 0;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// write image data to canvas buffer
|
||||||
|
buf[ix++] = b;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (n == size) {
|
||||||
|
valid = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "HTTP: final bytesRead=%d, header-size=%d", n, header_size);
|
||||||
|
} else {
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "HTTP result #%d", httpCode);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
commonData->logger->logDebug(GwLog::ERROR, "HTTP error #%d", httpCode);
|
||||||
|
}
|
||||||
|
http.end();
|
||||||
|
return valid;
|
||||||
|
}
|
||||||
|
|
||||||
|
void displayNew(PageData &pageData){
|
||||||
|
|
||||||
|
GwApi::BoatValue *bv_lat = pageData.values[4]; // LAT
|
||||||
|
GwApi::BoatValue *bv_lon = pageData.values[5]; // LON
|
||||||
|
|
||||||
|
// check if valid data available
|
||||||
|
if (!bv_lat->valid or !bv_lon->valid) {
|
||||||
|
map_valid = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
errmsg = "";
|
||||||
|
|
||||||
|
map_lat = bv_lat->value; // save for later comparison
|
||||||
|
map_lon = bv_lon->value;
|
||||||
|
map_valid = getBackgroundMap(map_lat, map_lon, zoom);
|
||||||
|
|
||||||
|
if (map_valid) {
|
||||||
|
// prepare visible space for anchor-symbol or boat
|
||||||
|
canvas->fillCircle(132, 130, 10, commonData->fgcolor);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
void display_side_keys() {
|
||||||
|
// An rechter Seite neben dem Rad inc, dec, set etc ?
|
||||||
|
}
|
||||||
|
|
||||||
|
int displayPage(PageData &pageData) {
|
||||||
|
|
||||||
|
// Logging boat values
|
||||||
|
commonData->logger->logDebug(GwLog::LOG, "Drawing at PageAnchor; Mode=%c", mode);
|
||||||
|
|
||||||
|
// Set display in partial refresh mode
|
||||||
|
getdisplay().setPartialWindow(0, 0, getdisplay().width(), getdisplay().height()); // Set partial update
|
||||||
|
|
||||||
|
if (mode == 'N') {
|
||||||
|
displayModeNormal(pageData);
|
||||||
|
} else if (mode == 'C') {
|
||||||
|
displayModeConfig(pageData);
|
||||||
|
}
|
||||||
|
|
||||||
|
return PAGE_UPDATE;
|
||||||
|
};
|
||||||
|
};
|
||||||
|
|
||||||
|
static Page *createPage(CommonData &common){
|
||||||
|
return new PageAnchor(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
|
||||||
|
* this will be number of BoatValue pointers in pageData.values
|
||||||
|
*/
|
||||||
|
PageDescription registerPageAnchor(
|
||||||
|
"Anchor", // Page name
|
||||||
|
createPage, // Action
|
||||||
|
0, // Number of bus values depends on selection in Web configuration
|
||||||
|
{"DBS", "HDT", "AWS", "AWD", "LAT", "LON", "HDOP"}, // Names of bus values undepends on selection in Web configuration (refer GwBoatData.h)
|
||||||
|
true // Show display header on/off
|
||||||
|
);
|
||||||
|
|
||||||
|
#endif
|
||||||
@@ -4,57 +4,270 @@
|
|||||||
#include "OBP60Extensions.h"
|
#include "OBP60Extensions.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* TODO mode: race timer: keys
|
* PageClock: Clock page with
|
||||||
* - prepare: set countdown to 5min
|
* - Analog mode (mode == 'A')
|
||||||
* reset: abort current countdown and start over with 5min preparation
|
* - Digital mode (mode == 'D')
|
||||||
* - 5min: key press
|
* - Countdown timer mode (mode == 'T')
|
||||||
* - 4min: key press to sync
|
* - Keys in mode analog and digital clock:
|
||||||
* - 1min: buzzer signal
|
* K1: MODE (A/D/T)
|
||||||
* - start: buzzer signal for start
|
* K2: POS (select field: HH / MM / SS)
|
||||||
|
* K3:
|
||||||
|
* K4:
|
||||||
|
* K5: TZ (Local/UTC)
|
||||||
*
|
*
|
||||||
|
* Regatta 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 PageClock : public Page
|
class PageClock : public Page
|
||||||
{
|
{
|
||||||
bool simulation = false;
|
bool simulation = false;
|
||||||
int simtime;
|
int simtime;
|
||||||
bool keylock = false;
|
bool keylock = false;
|
||||||
#ifdef BOARD_OBP60S3
|
#ifdef BOARD_OBP60S3
|
||||||
char source = 'G'; // time source (R)TC | (G)PS | (N)TP
|
char source = 'G'; // Time source (R)TC | (G)PS | (N)TP
|
||||||
#endif
|
#endif
|
||||||
#ifdef BOARD_OBP40S3
|
#ifdef BOARD_OBP40S3
|
||||||
char source = 'R'; // time source (R)TC | (G)PS | (N)TP
|
char source = 'R'; // time source (R)TC | (G)PS | (N)TP
|
||||||
#endif
|
#endif
|
||||||
char mode = 'A'; // display mode (A)nalog | (D)igital | race (T)imer
|
char mode = 'A'; // Display mode (A)nalog | (D)igital | race (T)imer
|
||||||
char tz = 'L'; // time zone (L)ocal | (U)TC
|
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 timezone = 0; // There are timezones with non int offsets, e.g. 5.5 or 5.75
|
||||||
double homelat;
|
double homelat;
|
||||||
double homelon;
|
double homelon;
|
||||||
bool homevalid = false; // homelat and homelon are valid
|
bool homevalid = false; // Homelat and homelon are valid
|
||||||
|
|
||||||
public:
|
// Timer state (static so it survives page switches)
|
||||||
PageClock(CommonData &common){
|
static bool timerInitialized;
|
||||||
|
static bool timerRunning;
|
||||||
|
static int timerHours;
|
||||||
|
static int timerMinutes;
|
||||||
|
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)
|
||||||
|
static int timerStartHours;
|
||||||
|
static int timerStartMinutes;
|
||||||
|
static int timerStartSeconds;
|
||||||
|
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;
|
||||||
|
timerStartHours = 0;
|
||||||
|
timerStartMinutes = 0;
|
||||||
|
timerStartSeconds = 0;
|
||||||
|
selectedField = 0;
|
||||||
|
showSelectionMarker = true;
|
||||||
|
timerEndEpoch = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Limiter for overrun settings values
|
||||||
|
static int clamp(int value, int minVal, int maxVal)
|
||||||
|
{
|
||||||
|
if (value < minVal) return maxVal;
|
||||||
|
if (value > maxVal) return minVal;
|
||||||
|
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:
|
||||||
|
PageClock(CommonData& common)
|
||||||
|
{
|
||||||
commonData = &common;
|
commonData = &common;
|
||||||
common.logger->logDebug(GwLog::LOG,"Instantiate PageClock");
|
common.logger->logDebug(GwLog::LOG, "Instantiate PageClock");
|
||||||
simulation = common.config->getBool(common.config->useSimuData);
|
simulation = common.config->getBool(common.config->useSimuData);
|
||||||
timezone = common.config->getString(common.config->timeZone).toDouble();
|
timezone = common.config->getString(common.config->timeZone).toDouble();
|
||||||
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();
|
||||||
homevalid = homelat >= -180.0 and homelat <= 180 and homelon >= -90.0 and homelon <= 90.0;
|
homevalid = homelat >= -180.0 and homelat <= 180 and homelon >= -90.0 and homelon <= 90.0;
|
||||||
simtime = 38160; // time value 11:36
|
simtime = 38160; // time value 11:36
|
||||||
|
setupTimerDefaults();
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual void setupKeys(){
|
virtual void setupKeys()
|
||||||
|
{
|
||||||
Page::setupKeys();
|
Page::setupKeys();
|
||||||
commonData->keydata[0].label = "SRC";
|
|
||||||
commonData->keydata[1].label = "MODE";
|
if (mode == 'T') {
|
||||||
|
// Timer mode: MODE, POS, +, -, RUN
|
||||||
|
commonData->keydata[0].label = "MODE";
|
||||||
|
commonData->keydata[1].label = "POS";
|
||||||
|
// K3: '+' while editing, 'SYNC' while running to set a preset countdown
|
||||||
|
commonData->keydata[2].label = timerRunning ? "SYNC" : "+";
|
||||||
|
commonData->keydata[3].label = "-";
|
||||||
|
commonData->keydata[4].label = timerRunning ? "RESET" : "START";
|
||||||
|
} else {
|
||||||
|
// Clock modes: like original
|
||||||
|
commonData->keydata[0].label = "MODE";
|
||||||
|
commonData->keydata[1].label = "SRC";
|
||||||
commonData->keydata[4].label = "TZ";
|
commonData->keydata[4].label = "TZ";
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Key functions
|
// Key functions
|
||||||
virtual int handleKey(int key){
|
virtual int handleKey(int key)
|
||||||
// Time source
|
{
|
||||||
|
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) {
|
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;
|
||||||
|
}
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
|
||||||
|
// - (K4): decrement selected field (only if timer not running)
|
||||||
|
if (key == 4 && !timerRunning) {
|
||||||
|
decrementSelected();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
if (key == 4 && timerRunning) { // No action if timer running
|
||||||
|
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) {
|
||||||
|
// Remember initial timer setting at start
|
||||||
|
timerStartHours = timerHours;
|
||||||
|
timerStartMinutes = timerMinutes;
|
||||||
|
timerStartSeconds = timerSeconds;
|
||||||
|
|
||||||
|
struct tm rtcCopy = commonData->data.rtcTime;
|
||||||
|
time_t nowEpoch = mktime(&rtcCopy);
|
||||||
|
timerEndEpoch = nowEpoch + total;
|
||||||
|
timerRunning = true;
|
||||||
|
showSelectionMarker = false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// Stop timer: restore initial start setting
|
||||||
|
timerHours = timerStartHours;
|
||||||
|
timerMinutes = timerStartMinutes;
|
||||||
|
timerSeconds = timerStartSeconds;
|
||||||
|
timerRunning = false;
|
||||||
|
showSelectionMarker = true;
|
||||||
|
// 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
|
||||||
|
|
||||||
|
// MODE (K1)
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Time source (K2)
|
||||||
|
if (key == 2) {
|
||||||
switch (source) {
|
switch (source) {
|
||||||
case 'G': source = 'R'; break;
|
case 'G': source = 'R'; break;
|
||||||
case 'R': source = 'G'; break;
|
case 'R': source = 'G'; break;
|
||||||
@@ -62,16 +275,8 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
if (key == 2) {
|
|
||||||
switch (mode) {
|
// Time zone: Local / UTC (K5)
|
||||||
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) {
|
if (key == 5) {
|
||||||
switch (tz) {
|
switch (tz) {
|
||||||
case 'L': tz = 'U'; break;
|
case 'L': tz = 'U'; break;
|
||||||
@@ -81,18 +286,16 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Keylock function
|
|
||||||
if(key == 11){ // Code for keylock
|
|
||||||
keylock = !keylock; // Toggle keylock
|
|
||||||
return 0; // Commit the key
|
|
||||||
}
|
|
||||||
return key;
|
return key;
|
||||||
}
|
}
|
||||||
|
|
||||||
int displayPage(PageData &pageData)
|
int displayPage(PageData& pageData)
|
||||||
{
|
{
|
||||||
GwConfigHandler *config = commonData->config;
|
GwConfigHandler* config = commonData->config;
|
||||||
GwLog *logger = commonData->logger;
|
GwLog* logger = commonData->logger;
|
||||||
|
|
||||||
|
setupTimerDefaults();
|
||||||
|
setupKeys(); // Ensure correct key labels for current mode
|
||||||
|
|
||||||
static String svalue1old = "";
|
static String svalue1old = "";
|
||||||
static String unit1old = "";
|
static String unit1old = "";
|
||||||
@@ -116,58 +319,57 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
String backlightMode = config->getString(config->backlight);
|
String backlightMode = config->getString(config->backlight);
|
||||||
|
|
||||||
// Get boat values for GPS time
|
// Get boat values for GPS time
|
||||||
GwApi::BoatValue *bvalue1 = pageData.values[0]; // First element in list (only one value by PageOneValue)
|
GwApi::BoatValue* bvalue1 = pageData.values[0]; // First element in list
|
||||||
String name1 = bvalue1->getName().c_str(); // Value name
|
String name1 = bvalue1->getName().c_str(); // Value name
|
||||||
name1 = name1.substring(0, 6); // String length limit for value name
|
name1 = name1.substring(0, 6); // String length limit for value name
|
||||||
if(simulation == false){
|
if (simulation == false) {
|
||||||
value1 = bvalue1->value; // Value as double in SI unit
|
value1 = bvalue1->value; // Value as double in SI unit
|
||||||
}
|
} else {
|
||||||
else{
|
|
||||||
value1 = simtime++; // Simulation data for time value 11:36 in seconds
|
value1 = simtime++; // Simulation data for time value 11:36 in seconds
|
||||||
} // Other simulation data see OBP60Formatter.cpp
|
} // Other simulation data see OBP60Formatter.cpp
|
||||||
bool valid1 = bvalue1->valid; // Valid information
|
bool valid1 = bvalue1->valid; // Valid information
|
||||||
String svalue1 = formatValue(bvalue1, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
|
String svalue1 = formatValue(bvalue1, *commonData).svalue; // Formatted value
|
||||||
String unit1 = formatValue(bvalue1, *commonData).unit; // Unit of value
|
String unit1 = formatValue(bvalue1, *commonData).unit; // Unit of value
|
||||||
if(valid1 == true){
|
if (valid1 == true) {
|
||||||
svalue1old = svalue1; // Save old value
|
svalue1old = svalue1; // Save old value
|
||||||
unit1old = unit1; // Save old unit
|
unit1old = unit1; // Save old unit
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get boat values for GPS date
|
// Get boat values for GPS date
|
||||||
GwApi::BoatValue *bvalue2 = pageData.values[1]; // Second element in list (only one value by PageOneValue)
|
GwApi::BoatValue* bvalue2 = pageData.values[1]; // Second element in list
|
||||||
String name2 = bvalue2->getName().c_str(); // Value name
|
String name2 = bvalue2->getName().c_str(); // Value name
|
||||||
name2 = name2.substring(0, 6); // String length limit for value name
|
name2 = name2.substring(0, 6); // String length limit for value name
|
||||||
value2 = bvalue2->value; // Value as double in SI unit
|
value2 = bvalue2->value; // Value as double in SI unit
|
||||||
bool valid2 = bvalue2->valid; // Valid information
|
bool valid2 = bvalue2->valid; // Valid informationgetdisplay().print("RTC");
|
||||||
String svalue2 = formatValue(bvalue2, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
|
String svalue2 = formatValue(bvalue2, *commonData).svalue; // Formatted value
|
||||||
String unit2 = formatValue(bvalue2, *commonData).unit; // Unit of value
|
String unit2 = formatValue(bvalue2, *commonData).unit; // Unit of value
|
||||||
if(valid2 == true){
|
if (valid2 == true) {
|
||||||
svalue2old = svalue2; // Save old value
|
svalue2old = svalue2; // Save old value
|
||||||
unit2old = unit2; // Save old unit
|
unit2old = unit2; // Save old unit
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get boat values for HDOP date
|
// Get boat values for HDOP
|
||||||
GwApi::BoatValue *bvalue3 = pageData.values[2]; // Third element in list (only one value by PageOneValue)
|
GwApi::BoatValue* bvalue3 = pageData.values[2]; // Third element in list
|
||||||
String name3 = bvalue3->getName().c_str(); // Value name
|
String name3 = bvalue3->getName().c_str(); // Value name
|
||||||
name3 = name3.substring(0, 6); // String length limit for value name
|
name3 = name3.substring(0, 6); // String length limit for value name
|
||||||
value3 = bvalue3->value; // Value as double in SI unit
|
value3 = bvalue3->value; // Value as double in SI unit
|
||||||
bool valid3 = bvalue3->valid; // Valid information
|
bool valid3 = bvalue3->valid; // Valid information
|
||||||
String svalue3 = formatValue(bvalue3, *commonData).svalue; // Formatted value as string including unit conversion and switching decimal places
|
String svalue3 = formatValue(bvalue3, *commonData).svalue; // Formatted value
|
||||||
String unit3 = formatValue(bvalue3, *commonData).unit; // Unit of value
|
String unit3 = formatValue(bvalue3, *commonData).unit; // Unit of value
|
||||||
if(valid3 == true){
|
if (valid3 == true) {
|
||||||
svalue3old = svalue3; // Save old value
|
svalue3old = svalue3; // Save old value
|
||||||
unit3old = unit3; // Save old unit
|
unit3old = unit3; // Save old unit
|
||||||
}
|
}
|
||||||
|
|
||||||
// Optical warning by limit violation (unused)
|
// Optical warning by limit violation (unused)
|
||||||
if(String(flashLED) == "Limit Violation"){
|
if (String(flashLED) == "Limit Violation") {
|
||||||
setBlinkingLED(false);
|
setBlinkingLED(false);
|
||||||
setFlashLED(false);
|
setFlashLED(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Logging boat values
|
// Logging boat values
|
||||||
if (bvalue1 == NULL) return PAGE_OK; // WTF why this statement?
|
if (bvalue1 == NULL) return PAGE_OK;
|
||||||
LOG_DEBUG(GwLog::LOG,"Drawing at PageClock, %s:%f, %s:%f", name1.c_str(), value1, name2.c_str(), value2);
|
LOG_DEBUG(GwLog::LOG, "Drawing at PageClock, %s:%f, %s:%f", name1.c_str(), value1, name2.c_str(), value2);
|
||||||
|
|
||||||
// Draw page
|
// Draw page
|
||||||
//***********************************************************
|
//***********************************************************
|
||||||
@@ -178,7 +380,180 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
getdisplay().setTextColor(commonData->fgcolor);
|
getdisplay().setTextColor(commonData->fgcolor);
|
||||||
|
|
||||||
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
|
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
|
||||||
struct tm *local_tm = localtime(&tv);
|
struct tm* local_tm = localtime(&tv);
|
||||||
|
|
||||||
|
if (mode == 'T') {
|
||||||
|
// REGATTA 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 <= 5 && remaining != 0){
|
||||||
|
// Short pre buzzer alarm (100% power)
|
||||||
|
setBuzzerPower(100);
|
||||||
|
buzzer(TONE2, 75);
|
||||||
|
setBuzzerPower(config->getInt(config->buzzerPower));
|
||||||
|
}
|
||||||
|
if (remaining <= 0) {
|
||||||
|
remaining = 0;
|
||||||
|
timerRunning = false;
|
||||||
|
commonData->keydata[3].label = "-";
|
||||||
|
commonData->keydata[4].label = "START";
|
||||||
|
showSelectionMarker = true;
|
||||||
|
// Buzzer alarm (100% power)
|
||||||
|
setBuzzerPower(100);
|
||||||
|
buzzer(TONE2, 800);
|
||||||
|
setBuzzerPower(config->getInt(config->buzzerPower));
|
||||||
|
|
||||||
|
// When countdown is finished, restore the initial start time
|
||||||
|
timerHours = timerStartHours;
|
||||||
|
timerMinutes = timerStartMinutes;
|
||||||
|
timerSeconds = timerStartSeconds;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
commonData->keydata[3].label = "";
|
||||||
|
commonData->keydata[4].label = "RESET";
|
||||||
|
}
|
||||||
|
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_BoldItalic30pt7b);
|
||||||
|
|
||||||
|
// 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); // horzontal jitter
|
||||||
|
getdisplay().setCursor(47, textY); // static X position
|
||||||
|
getdisplay().print(timeStr);
|
||||||
|
|
||||||
|
// Selection marker (only visible when not running and POS pressed)
|
||||||
|
if (!timerRunning && showSelectionMarker) {
|
||||||
|
int16_t selX = baseX - 8; // Hours start
|
||||||
|
if (selectedField == 1) {
|
||||||
|
selX = baseX + wDigit + wColon; // Minutes start
|
||||||
|
} else if (selectedField == 2) {
|
||||||
|
selX = baseX + 2 * wDigit + 2 * wColon + 12; // Seconds start
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t underlineY = centerY + hb / 2 + 5;
|
||||||
|
//getdisplay().fillRect(selX, underlineY, wDigit, 6, commonData->fgcolor);
|
||||||
|
getdisplay().fillRoundRect(selX, underlineY, wDigit, 6, 2, commonData->fgcolor);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Page label
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold16pt8b);
|
||||||
|
getdisplay().setCursor(100, 70);
|
||||||
|
getdisplay().print("Regatta Timer");
|
||||||
|
|
||||||
|
} 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_BoldItalic30pt7b);
|
||||||
|
|
||||||
|
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); // horizontal jitter
|
||||||
|
getdisplay().setCursor(47, y); // static X position
|
||||||
|
getdisplay().print(timeStr); // Display actual time
|
||||||
|
|
||||||
|
// Small indicators: timezone and source
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
|
|
||||||
|
getdisplay().setCursor(47, 110);
|
||||||
|
if (source == 'G') {
|
||||||
|
getdisplay().print("GPS");
|
||||||
|
} else {
|
||||||
|
getdisplay().print("RTC");
|
||||||
|
}
|
||||||
|
|
||||||
|
getdisplay().setCursor(47 + 40, 110);
|
||||||
|
if (holdvalues == false) {
|
||||||
|
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
|
||||||
|
} else {
|
||||||
|
getdisplay().print(unit2old); // date unit
|
||||||
|
}
|
||||||
|
|
||||||
|
// Page label
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold16pt8b);
|
||||||
|
getdisplay().setCursor(100, 70);
|
||||||
|
getdisplay().print("Digital Clock");
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// ANALOG CLOCK MODE (mode == 'A')
|
||||||
|
//********************************
|
||||||
|
|
||||||
// Show values GPS date
|
// Show values GPS date
|
||||||
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
@@ -191,8 +566,7 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
// RTC value
|
// RTC value
|
||||||
if (tz == 'L') {
|
if (tz == 'L') {
|
||||||
getdisplay().print(formatDate(dateformat, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
|
getdisplay().print(formatDate(dateformat, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
getdisplay().print(formatDate(dateformat, commonData->data.rtcTime.tm_year + 1900, commonData->data.rtcTime.tm_mon + 1, commonData->data.rtcTime.tm_mday));
|
getdisplay().print(formatDate(dateformat, commonData->data.rtcTime.tm_year + 1900, commonData->data.rtcTime.tm_mon + 1, commonData->data.rtcTime.tm_mday));
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
@@ -205,28 +579,25 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
getdisplay().setCursor(10, 95);
|
getdisplay().setCursor(10, 95);
|
||||||
getdisplay().print("Date"); // Name
|
getdisplay().print("Date"); // Name
|
||||||
|
|
||||||
// Horizintal separator left
|
// Horizontal separator left
|
||||||
getdisplay().fillRect(0, 149, 60, 3, commonData->fgcolor);
|
getdisplay().fillRect(0, 149, 60, 3, commonData->fgcolor);
|
||||||
|
|
||||||
// Show values GPS time
|
// Show values GPS time (small text bottom left)
|
||||||
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
getdisplay().setCursor(10, 250);
|
getdisplay().setCursor(10, 250);
|
||||||
if (holdvalues == false) {
|
if (holdvalues == false) {
|
||||||
if (source == 'G') {
|
if (source == 'G') {
|
||||||
getdisplay().print(svalue1); // Value
|
getdisplay().print(svalue1); // Value
|
||||||
}
|
} else if (commonData->data.rtcValid) {
|
||||||
else if (commonData->data.rtcValid) {
|
|
||||||
if (tz == 'L') {
|
if (tz == 'L') {
|
||||||
getdisplay().print(formatTime('s', local_tm->tm_hour, local_tm->tm_min, local_tm->tm_sec));
|
getdisplay().print(formatTime('s', local_tm->tm_hour, local_tm->tm_min, local_tm->tm_sec));
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
getdisplay().print(formatTime('s', commonData->data.rtcTime.tm_hour, commonData->data.rtcTime.tm_min, commonData->data.rtcTime.tm_sec));
|
getdisplay().print(formatTime('s', commonData->data.rtcTime.tm_hour, commonData->data.rtcTime.tm_min, commonData->data.rtcTime.tm_sec));
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
getdisplay().print("---");
|
getdisplay().print("---");
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
getdisplay().print(svalue1old);
|
getdisplay().print(svalue1old);
|
||||||
}
|
}
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
||||||
@@ -244,13 +615,13 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
|
|
||||||
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
getdisplay().setCursor(335, 65);
|
getdisplay().setCursor(335, 65);
|
||||||
if(holdvalues == false) getdisplay().print(sunrise); // Value
|
if (holdvalues == false) getdisplay().print(sunrise); // Value
|
||||||
else getdisplay().print(svalue5old);
|
else getdisplay().print(svalue5old);
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
||||||
getdisplay().setCursor(335, 95);
|
getdisplay().setCursor(335, 95);
|
||||||
getdisplay().print("SunR"); // Name
|
getdisplay().print("SunR"); // Name
|
||||||
|
|
||||||
// Horizintal separator right
|
// Horizontal separator right
|
||||||
getdisplay().fillRect(340, 149, 80, 3, commonData->fgcolor);
|
getdisplay().fillRect(340, 149, 80, 3, commonData->fgcolor);
|
||||||
|
|
||||||
// Show values sunset
|
// Show values sunset
|
||||||
@@ -264,50 +635,39 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
|
|
||||||
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
getdisplay().setFont(&Ubuntu_Bold8pt8b);
|
||||||
getdisplay().setCursor(335, 250);
|
getdisplay().setCursor(335, 250);
|
||||||
if(holdvalues == false) getdisplay().print(sunset); // Value
|
if (holdvalues == false) getdisplay().print(sunset); // Value
|
||||||
else getdisplay().print(svalue6old);
|
else getdisplay().print(svalue6old);
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
||||||
getdisplay().setCursor(335, 220);
|
getdisplay().setCursor(335, 220);
|
||||||
getdisplay().print("SunS"); // Name
|
getdisplay().print("SunS"); // Name
|
||||||
|
|
||||||
//*******************************************************************************************
|
|
||||||
|
|
||||||
// Draw clock
|
|
||||||
int rInstrument = 110; // Radius of clock
|
int rInstrument = 110; // Radius of clock
|
||||||
float pi = 3.141592;
|
float pi = 3.141592;
|
||||||
|
|
||||||
getdisplay().fillCircle(200, 150, rInstrument + 10, commonData->fgcolor); // Outer circle
|
getdisplay().fillCircle(200, 150, rInstrument + 10, commonData->fgcolor); // Outer circle
|
||||||
getdisplay().fillCircle(200, 150, rInstrument + 7, commonData->bgcolor); // Outer circle
|
getdisplay().fillCircle(200, 150, rInstrument + 7, commonData->bgcolor); // Outer circle
|
||||||
|
|
||||||
for(int i=0; i<360; i=i+1)
|
for (int i = 0; i < 360; i = i + 1)
|
||||||
{
|
{
|
||||||
// Scaling values
|
// Scaling values
|
||||||
float x = 200 + (rInstrument-30)*sin(i/180.0*pi); // x-coordinate dots
|
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
|
float y = 150 - (rInstrument - 30) * cos(i / 180.0 * pi); // y-coordinate dots
|
||||||
const char *ii = "";
|
const char* ii = "";
|
||||||
switch (i)
|
switch (i)
|
||||||
{
|
{
|
||||||
case 0: ii="12"; break;
|
case 0: ii = "12"; break;
|
||||||
case 30 : ii=""; break;
|
case 90: ii = "3"; break;
|
||||||
case 60 : ii=""; break;
|
case 180: ii = "6"; break;
|
||||||
case 90 : ii="3"; break;
|
case 270: ii = "9"; 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;
|
default: break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Print text centered on position x, y
|
// Print text centered on position x, y
|
||||||
int16_t x1, y1; // Return values of getTextBounds
|
int16_t x1c, y1c; // Return values of getTextBounds
|
||||||
uint16_t w, h; // Return values of getTextBounds
|
uint16_t wc, hc; // Return values of getTextBounds
|
||||||
getdisplay().getTextBounds(ii, int(x), int(y), &x1, &y1, &w, &h); // Calc width of new string
|
getdisplay().getTextBounds(ii, int(x), int(y), &x1c, &y1c, &wc, &hc); // Calc width of new string
|
||||||
getdisplay().setCursor(x-w/2, y+h/2);
|
getdisplay().setCursor(x - wc / 2, y + hc / 2);
|
||||||
if(i % 30 == 0){
|
if (i % 90 == 0) {
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
||||||
getdisplay().print(ii);
|
getdisplay().print(ii);
|
||||||
}
|
}
|
||||||
@@ -315,37 +675,36 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
// Draw sub scale with dots
|
// Draw sub scale with dots
|
||||||
float sinx = 0;
|
float sinx = 0;
|
||||||
float cosx = 0;
|
float cosx = 0;
|
||||||
if(i % 6 == 0){
|
if (i % 6 == 0) {
|
||||||
float x1c = 200 + rInstrument*sin(i/180.0*pi);
|
float x1d = 200 + rInstrument * sin(i / 180.0 * pi);
|
||||||
float y1c = 150 - rInstrument*cos(i/180.0*pi);
|
float y1d = 150 - rInstrument * cos(i / 180.0 * pi);
|
||||||
getdisplay().fillCircle((int)x1c, (int)y1c, 2, commonData->fgcolor);
|
getdisplay().fillCircle((int)x1d, (int)y1d, 2, commonData->fgcolor);
|
||||||
sinx=sin(i/180.0*pi);
|
sinx = sin(i / 180.0 * pi);
|
||||||
cosx=cos(i/180.0*pi);
|
cosx = cos(i / 180.0 * pi);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Draw sub scale with lines (two triangles)
|
// Draw sub scale with lines (two triangles)
|
||||||
if(i % 30 == 0){
|
if (i % 30 == 0) {
|
||||||
float dx=2; // Line thickness = 2*dx+1
|
float dx = 2; // Line thickness = 2*dx+1
|
||||||
float xx1 = -dx;
|
float xx1 = -dx;
|
||||||
float xx2 = +dx;
|
float xx2 = +dx;
|
||||||
float yy1 = -(rInstrument-10);
|
float yy1 = -(rInstrument - 10);
|
||||||
float yy2 = -(rInstrument+10);
|
float yy2 = -(rInstrument + 10);
|
||||||
getdisplay().fillTriangle(200+(int)(cosx*xx1-sinx*yy1),150+(int)(sinx*xx1+cosx*yy1),
|
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 * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
|
||||||
200+(int)(cosx*xx1-sinx*yy2),150+(int)(sinx*xx1+cosx*yy2),commonData->fgcolor);
|
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),
|
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 * xx1 - sinx * yy2), 150 + (int)(sinx * xx1 + cosx * yy2),
|
||||||
200+(int)(cosx*xx2-sinx*yy2),150+(int)(sinx*xx2+cosx*yy2),commonData->fgcolor);
|
200 + (int)(cosx * xx2 - sinx * yy2), 150 + (int)(sinx * xx2 + cosx * yy2), commonData->fgcolor);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Print Unit in clock
|
// Print Unit in clock
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
getdisplay().setFont(&Ubuntu_Bold12pt8b);
|
||||||
getdisplay().setCursor(175, 110);
|
getdisplay().setCursor(175, 110);
|
||||||
if(holdvalues == false){
|
if (holdvalues == false) {
|
||||||
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
|
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
|
||||||
}
|
} else {
|
||||||
else{
|
|
||||||
getdisplay().print(unit2old); // date unit
|
getdisplay().print(unit2old); // date unit
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -362,10 +721,10 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
double minute = 0;
|
double minute = 0;
|
||||||
if (source == 'R') {
|
if (source == 'R') {
|
||||||
if (tz == 'L') {
|
if (tz == 'L') {
|
||||||
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
|
time_t tv2 = mktime(&commonData->data.rtcTime) + timezone * 3600;
|
||||||
struct tm *local_tm = localtime(&tv);
|
struct tm* local_tm2 = localtime(&tv2);
|
||||||
minute = local_tm->tm_min;
|
minute = local_tm2->tm_min;
|
||||||
hour = local_tm->tm_hour;
|
hour = local_tm2->tm_hour;
|
||||||
} else {
|
} else {
|
||||||
minute = commonData->data.rtcTime.tm_min;
|
minute = commonData->data.rtcTime.tm_min;
|
||||||
hour = commonData->data.rtcTime.tm_hour;
|
hour = commonData->data.rtcTime.tm_hour;
|
||||||
@@ -375,8 +734,8 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
if (tz == 'L') {
|
if (tz == 'L') {
|
||||||
value1 += timezone * 3600;
|
value1 += timezone * 3600;
|
||||||
}
|
}
|
||||||
if (value1 > 86400) {value1 -= 86400;}
|
if (value1 > 86400) { value1 -= 86400; }
|
||||||
if (value1 < 0) {value1 += 86400;}
|
if (value1 < 0) { value1 += 86400; }
|
||||||
hour = (value1 / 3600.0);
|
hour = (value1 / 3600.0);
|
||||||
// minute = (hour - int(hour)) * 3600.0 / 60.0; // Analog minute pointer smooth moving
|
// 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
|
minute = int((hour - int(hour)) * 3600.0 / 60.0); // Jumping minute pointer from minute to minute
|
||||||
@@ -384,22 +743,22 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
if (hour > 12) {
|
if (hour > 12) {
|
||||||
hour -= 12.0;
|
hour -= 12.0;
|
||||||
}
|
}
|
||||||
LOG_DEBUG(GwLog::DEBUG,"... PageClock, value1: %f hour: %f minute:%f", value1, hour, minute);
|
LOG_DEBUG(GwLog::DEBUG, "... PageClock, value1: %f hour: %f minute:%f", value1, hour, minute);
|
||||||
|
|
||||||
// Draw hour pointer
|
// Draw hour pointer
|
||||||
float startwidth = 8; // Start width of pointer
|
float startwidth = 8; // Start width of pointer
|
||||||
if(valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true){
|
if (valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true) {
|
||||||
float sinx=sin(hour * 30.0 * pi / 180); // Hour
|
float sinx = sin(hour * 30.0 * pi / 180); // Hour
|
||||||
float cosx=cos(hour * 30.0 * pi / 180);
|
float cosx = cos(hour * 30.0 * pi / 180);
|
||||||
// Normal pointer
|
// Normal pointer
|
||||||
// Pointer as triangle with center base 2*width
|
// Pointer as triangle with center base 2*width
|
||||||
float xx1 = -startwidth;
|
float xx1 = -startwidth;
|
||||||
float xx2 = startwidth;
|
float xx2 = startwidth;
|
||||||
float yy1 = -startwidth;
|
float yy1 = -startwidth;
|
||||||
float yy2 = -(rInstrument * 0.5);
|
float yy2 = -(rInstrument * 0.5);
|
||||||
getdisplay().fillTriangle(200+(int)(cosx*xx1-sinx*yy1),150+(int)(sinx*xx1+cosx*yy1),
|
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 * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
|
||||||
200+(int)(cosx*0-sinx*yy2),150+(int)(sinx*0+cosx*yy2),commonData->fgcolor);
|
200 + (int)(cosx * 0 - sinx * yy2), 150 + (int)(sinx * 0 + cosx * yy2), commonData->fgcolor);
|
||||||
// Inverted pointer
|
// Inverted pointer
|
||||||
// Pointer as triangle with center base 2*width
|
// Pointer as triangle with center base 2*width
|
||||||
float endwidth = 2; // End width of pointer
|
float endwidth = 2; // End width of pointer
|
||||||
@@ -407,25 +766,25 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
float ix2 = -endwidth;
|
float ix2 = -endwidth;
|
||||||
float iy1 = -(rInstrument * 0.5);
|
float iy1 = -(rInstrument * 0.5);
|
||||||
float iy2 = -endwidth;
|
float iy2 = -endwidth;
|
||||||
getdisplay().fillTriangle(200+(int)(cosx*ix1-sinx*iy1),150+(int)(sinx*ix1+cosx*iy1),
|
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 * ix2 - sinx * iy1), 150 + (int)(sinx * ix2 + cosx * iy1),
|
||||||
200+(int)(cosx*0-sinx*iy2),150+(int)(sinx*0+cosx*iy2),commonData->fgcolor);
|
200 + (int)(cosx * 0 - sinx * iy2), 150 + (int)(sinx * 0 + cosx * iy2), commonData->fgcolor);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Draw minute pointer
|
// Draw minute pointer
|
||||||
startwidth = 8; // Start width of pointer
|
startwidth = 8; // Start width of pointer
|
||||||
if(valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true){
|
if (valid1 == true || (source == 'R' && commonData->data.rtcValid) || holdvalues == true || simulation == true) {
|
||||||
float sinx=sin(minute * 6.0 * pi / 180); // Minute
|
float sinx = sin(minute * 6.0 * pi / 180); // Minute
|
||||||
float cosx=cos(minute * 6.0 * pi / 180);
|
float cosx = cos(minute * 6.0 * pi / 180);
|
||||||
// Normal pointer
|
// Normal pointer
|
||||||
// Pointer as triangle with center base 2*width
|
// Pointer as triangle with center base 2*width
|
||||||
float xx1 = -startwidth;
|
float xx1 = -startwidth;
|
||||||
float xx2 = startwidth;
|
float xx2 = startwidth;
|
||||||
float yy1 = -startwidth;
|
float yy1 = -startwidth;
|
||||||
float yy2 = -(rInstrument - 15);
|
float yy2 = -(rInstrument - 15);
|
||||||
getdisplay().fillTriangle(200+(int)(cosx*xx1-sinx*yy1),150+(int)(sinx*xx1+cosx*yy1),
|
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 * xx2 - sinx * yy1), 150 + (int)(sinx * xx2 + cosx * yy1),
|
||||||
200+(int)(cosx*0-sinx*yy2),150+(int)(sinx*0+cosx*yy2),commonData->fgcolor);
|
200 + (int)(cosx * 0 - sinx * yy2), 150 + (int)(sinx * 0 + cosx * yy2), commonData->fgcolor);
|
||||||
// Inverted pointer
|
// Inverted pointer
|
||||||
// Pointer as triangle with center base 2*width
|
// Pointer as triangle with center base 2*width
|
||||||
float endwidth = 2; // End width of pointer
|
float endwidth = 2; // End width of pointer
|
||||||
@@ -433,28 +792,43 @@ bool homevalid = false; // homelat and homelon are valid
|
|||||||
float ix2 = -endwidth;
|
float ix2 = -endwidth;
|
||||||
float iy1 = -(rInstrument - 15);
|
float iy1 = -(rInstrument - 15);
|
||||||
float iy2 = -endwidth;
|
float iy2 = -endwidth;
|
||||||
getdisplay().fillTriangle(200+(int)(cosx*ix1-sinx*iy1),150+(int)(sinx*ix1+cosx*iy1),
|
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 * ix2 - sinx * iy1), 150 + (int)(sinx * ix2 + cosx * iy1),
|
||||||
200+(int)(cosx*0-sinx*iy2),150+(int)(sinx*0+cosx*iy2),commonData->fgcolor);
|
200 + (int)(cosx * 0 - sinx * iy2), 150 + (int)(sinx * 0 + cosx * iy2), commonData->fgcolor);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Center circle
|
// Center circle
|
||||||
getdisplay().fillCircle(200, 150, startwidth + 6, commonData->bgcolor);
|
getdisplay().fillCircle(200, 150, startwidth + 6, commonData->bgcolor);
|
||||||
getdisplay().fillCircle(200, 150, startwidth + 4, commonData->fgcolor);
|
getdisplay().fillCircle(200, 150, startwidth + 4, commonData->fgcolor);
|
||||||
|
}
|
||||||
|
|
||||||
return PAGE_UPDATE;
|
return PAGE_UPDATE;
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
static Page *createPage(CommonData &common){
|
// Static member definitions
|
||||||
|
bool PageClock::timerInitialized = false;
|
||||||
|
bool PageClock::timerRunning = false;
|
||||||
|
int PageClock::timerHours = 0;
|
||||||
|
int PageClock::timerMinutes = 0;
|
||||||
|
int PageClock::timerSeconds = 0;
|
||||||
|
int PageClock::timerStartHours = 0;
|
||||||
|
int PageClock::timerStartMinutes = 0;
|
||||||
|
int PageClock::timerStartSeconds = 0;
|
||||||
|
int PageClock::selectedField = 0;
|
||||||
|
bool PageClock::showSelectionMarker = true;
|
||||||
|
time_t PageClock::timerEndEpoch = 0;
|
||||||
|
|
||||||
|
static Page* createPage(CommonData& common)
|
||||||
|
{
|
||||||
return new PageClock(common);
|
return new PageClock(common);
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
* with the code below we make this page known to the PageTask
|
* 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 give it a type (name) that can be selected in the config
|
||||||
* we define which function is to be called
|
* we define which function is to be called
|
||||||
* and we provide the number of user parameters we expect (0 here)
|
* we provide the number of user parameters we expect (0 here)
|
||||||
* and will will provide the names of the fixed values we need
|
* and we provide the names of the fixed values we need
|
||||||
*/
|
*/
|
||||||
PageDescription registerPageClock(
|
PageDescription registerPageClock(
|
||||||
"Clock", // Page name
|
"Clock", // Page name
|
||||||
@@ -465,3 +839,4 @@ PageDescription registerPageClock(
|
|||||||
);
|
);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|||||||
@@ -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";
|
||||||
|
if (pageMode != VALUE) { // show "ZOOM" key only if chart is visible
|
||||||
commonData->keydata[ZOOM_KEY].label = "ZOOM";
|
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)
|
||||||
|
|||||||
@@ -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";
|
||||||
|
if (pageMode != VALUES) { // show "ZOOM" key only if chart is visible
|
||||||
commonData->keydata[ZOOM_KEY].label = "ZOOM";
|
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]);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -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;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -51,7 +51,7 @@ typedef struct{
|
|||||||
double rotationAngle = 0; // Rotation angle in radiant
|
double rotationAngle = 0; // Rotation angle in radiant
|
||||||
bool validRotAngle = false; // Valid flag magnet present for rotation sensor
|
bool validRotAngle = false; // Valid flag magnet present for rotation sensor
|
||||||
struct tm rtcTime; // UTC time from internal RTC
|
struct tm rtcTime; // UTC time from internal RTC
|
||||||
bool rtcValid = false;
|
bool rtcValid = false; // Internal RTC chip
|
||||||
int sunsetHour = 0;
|
int sunsetHour = 0;
|
||||||
int sunsetMinute = 0;
|
int sunsetMinute = 0;
|
||||||
int sunriseHour = 0;
|
int sunriseHour = 0;
|
||||||
@@ -110,6 +110,7 @@ typedef struct{
|
|||||||
AlarmData alarm;
|
AlarmData alarm;
|
||||||
GwApi::BoatValue *time = nullptr;
|
GwApi::BoatValue *time = nullptr;
|
||||||
GwApi::BoatValue *date = nullptr;
|
GwApi::BoatValue *date = nullptr;
|
||||||
|
float tz = 0.0; // timezone from config
|
||||||
uint16_t fgcolor;
|
uint16_t fgcolor;
|
||||||
uint16_t bgcolor;
|
uint16_t bgcolor;
|
||||||
bool keylock = false;
|
bool keylock = false;
|
||||||
|
|||||||
@@ -75,6 +75,20 @@
|
|||||||
"obp40": "true"
|
"obp40": "true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "chainLength",
|
||||||
|
"label": "Anchor Chain Length [m]",
|
||||||
|
"type": "number",
|
||||||
|
"default": "0",
|
||||||
|
"check": "checkMinMax",
|
||||||
|
"min": 0,
|
||||||
|
"max": 255,
|
||||||
|
"description": "The length of the anchor chain [0...255m]",
|
||||||
|
"category": "OBP40 Settings",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "fuelTank",
|
"name": "fuelTank",
|
||||||
"label": "Fuel Tank [l]",
|
"label": "Fuel Tank [l]",
|
||||||
@@ -678,7 +692,7 @@
|
|||||||
"type": "string",
|
"type": "string",
|
||||||
"default": "text1",
|
"default": "text1",
|
||||||
"description": "Button name",
|
"description": "Button name",
|
||||||
"category": "OBP60 IO-Modul1",
|
"category": "OBP40 IO-Modul1",
|
||||||
"capabilities": {
|
"capabilities": {
|
||||||
"obp40":"true"
|
"obp40":"true"
|
||||||
}
|
}
|
||||||
@@ -689,7 +703,7 @@
|
|||||||
"type": "string",
|
"type": "string",
|
||||||
"default": "text2",
|
"default": "text2",
|
||||||
"description": "Button name",
|
"description": "Button name",
|
||||||
"category": "OBP60 IO-Modul1",
|
"category": "OBP40 IO-Modul1",
|
||||||
"capabilities": {
|
"capabilities": {
|
||||||
"obp40":"true"
|
"obp40":"true"
|
||||||
}
|
}
|
||||||
@@ -700,7 +714,7 @@
|
|||||||
"type": "string",
|
"type": "string",
|
||||||
"default": "text3",
|
"default": "text3",
|
||||||
"description": "Button name",
|
"description": "Button name",
|
||||||
"category": "OBP60 IO-Modul1",
|
"category": "OBP40 IO-Modul1",
|
||||||
"capabilities": {
|
"capabilities": {
|
||||||
"obp40":"true"
|
"obp40":"true"
|
||||||
}
|
}
|
||||||
@@ -711,7 +725,7 @@
|
|||||||
"type": "string",
|
"type": "string",
|
||||||
"default": "text4",
|
"default": "text4",
|
||||||
"description": "Button name",
|
"description": "Button name",
|
||||||
"category": "OBP60 IO-Modul1",
|
"category": "OBP40 IO-Modul1",
|
||||||
"capabilities": {
|
"capabilities": {
|
||||||
"obp40":"true"
|
"obp40":"true"
|
||||||
}
|
}
|
||||||
@@ -722,7 +736,7 @@
|
|||||||
"type": "string",
|
"type": "string",
|
||||||
"default": "text5",
|
"default": "text5",
|
||||||
"description": "Button name",
|
"description": "Button name",
|
||||||
"category": "OBP60 IO-Modul1",
|
"category": "OBP40 IO-Modul1",
|
||||||
"capabilities": {
|
"capabilities": {
|
||||||
"obp40":"true"
|
"obp40":"true"
|
||||||
}
|
}
|
||||||
@@ -1067,7 +1081,8 @@
|
|||||||
"description": "Type of map source, cloud service or local service",
|
"description": "Type of map source, cloud service or local service",
|
||||||
"list": [
|
"list": [
|
||||||
"OBP Service",
|
"OBP Service",
|
||||||
"Local Service"
|
"Local Service",
|
||||||
|
"Remote Service"
|
||||||
],
|
],
|
||||||
"category": "OBP40 Navigation",
|
"category": "OBP40 Navigation",
|
||||||
"capabilities": {
|
"capabilities": {
|
||||||
@@ -1104,6 +1119,34 @@
|
|||||||
{ "mapsource": ["Local Service"] }
|
{ "mapsource": ["Local Service"] }
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "mapServer",
|
||||||
|
"label": "map server",
|
||||||
|
"type": "string",
|
||||||
|
"default": "",
|
||||||
|
"description": "Server for converting map tiles. Use only one hostname or IP address",
|
||||||
|
"category": "OBP40 Navigation",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
},
|
||||||
|
"condition": [
|
||||||
|
{ "mapsource": ["Remote Service"] }
|
||||||
|
]
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "mapTilePath",
|
||||||
|
"label": "map tile path",
|
||||||
|
"type": "string",
|
||||||
|
"default": "map.php",
|
||||||
|
"description": "Path to converter access e.g. index.php or map.php",
|
||||||
|
"category": "OBP40 Navigation",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
},
|
||||||
|
"condition": [
|
||||||
|
{ "mapsource": ["Remote Service"] }
|
||||||
|
]
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "maptype",
|
"name": "maptype",
|
||||||
"label": "Map Type",
|
"label": "Map Type",
|
||||||
@@ -1509,7 +1552,6 @@
|
|||||||
"obp40": "true"
|
"obp40": "true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
|
||||||
{
|
{
|
||||||
"name": "page1type",
|
"name": "page1type",
|
||||||
"label": "Type",
|
"label": "Type",
|
||||||
@@ -1517,6 +1559,7 @@
|
|||||||
"default": "Voltage",
|
"default": "Voltage",
|
||||||
"description": "Type of page for page 1",
|
"description": "Type of page for page 1",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -1818,7 +1861,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 +1890,7 @@
|
|||||||
"default": "WindRose",
|
"default": "WindRose",
|
||||||
"description": "Type of page for page 2",
|
"description": "Type of page for page 2",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -2140,7 +2184,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 +2212,7 @@
|
|||||||
"default": "OneValue",
|
"default": "OneValue",
|
||||||
"description": "Type of page for page 3",
|
"description": "Type of page for page 3",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -2453,7 +2498,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 +2525,7 @@
|
|||||||
"default": "TwoValues",
|
"default": "TwoValues",
|
||||||
"description": "Type of page for page 4",
|
"description": "Type of page for page 4",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -2757,7 +2803,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 +2829,7 @@
|
|||||||
"default": "ThreeValues",
|
"default": "ThreeValues",
|
||||||
"description": "Type of page for page 5",
|
"description": "Type of page for page 5",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3052,7 +3099,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 +3124,7 @@
|
|||||||
"default": "FourValues",
|
"default": "FourValues",
|
||||||
"description": "Type of page for page 6",
|
"description": "Type of page for page 6",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3338,7 +3386,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 +3410,7 @@
|
|||||||
"default": "FourValues2",
|
"default": "FourValues2",
|
||||||
"description": "Type of page for page 7",
|
"description": "Type of page for page 7",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3615,7 +3664,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 +3687,7 @@
|
|||||||
"default": "Clock",
|
"default": "Clock",
|
||||||
"description": "Type of page for page 8",
|
"description": "Type of page for page 8",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3883,7 +3933,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 +3955,7 @@
|
|||||||
"default": "RollPitch",
|
"default": "RollPitch",
|
||||||
"description": "Type of page for page 9",
|
"description": "Type of page for page 9",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -4142,7 +4193,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 +4214,7 @@
|
|||||||
"default": "Battery2",
|
"default": "Battery2",
|
||||||
"description": "Type of page for page 10",
|
"description": "Type of page for page 10",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -4392,7 +4444,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": {
|
||||||
|
|||||||
@@ -75,6 +75,20 @@
|
|||||||
"obp60":"true"
|
"obp60":"true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "chainLength",
|
||||||
|
"label": "Anchor Chain Length [m]",
|
||||||
|
"type": "number",
|
||||||
|
"default": "0",
|
||||||
|
"check": "checkMinMax",
|
||||||
|
"min": 0,
|
||||||
|
"max": 255,
|
||||||
|
"description": "The length of the anchor chain [0...255m]",
|
||||||
|
"category": "OBP60 Settings",
|
||||||
|
"capabilities": {
|
||||||
|
"obp60":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "fuelTank",
|
"name": "fuelTank",
|
||||||
"label": "Fuel Tank [l]",
|
"label": "Fuel Tank [l]",
|
||||||
@@ -1093,6 +1107,34 @@
|
|||||||
{ "mapsource": ["Local Service"] }
|
{ "mapsource": ["Local Service"] }
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "mapServer",
|
||||||
|
"label": "map server",
|
||||||
|
"type": "string",
|
||||||
|
"default": "",
|
||||||
|
"description": "Server for converting map tiles. Use only one hostname or IP address",
|
||||||
|
"category": "OBP60 Navigation",
|
||||||
|
"capabilities": {
|
||||||
|
"obp60": "true"
|
||||||
|
},
|
||||||
|
"condition": [
|
||||||
|
{ "mapsource": ["Remote Service"] }
|
||||||
|
]
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "mapTilePath",
|
||||||
|
"label": "map tile path",
|
||||||
|
"type": "string",
|
||||||
|
"default": "map.php",
|
||||||
|
"description": "Path to converter access e.g. index.php or map.php",
|
||||||
|
"category": "OBP40 Navigation",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
},
|
||||||
|
"condition": [
|
||||||
|
{ "mapsource": ["Remote Service"] }
|
||||||
|
]
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "maptype",
|
"name": "maptype",
|
||||||
"label": "Map Type",
|
"label": "Map Type",
|
||||||
@@ -1486,7 +1528,6 @@
|
|||||||
"obp60":"true"
|
"obp60":"true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
|
||||||
{
|
{
|
||||||
"name": "page1type",
|
"name": "page1type",
|
||||||
"label": "Type",
|
"label": "Type",
|
||||||
@@ -1494,6 +1535,7 @@
|
|||||||
"default": "Voltage",
|
"default": "Voltage",
|
||||||
"description": "Type of page for page 1",
|
"description": "Type of page for page 1",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -1794,6 +1836,7 @@
|
|||||||
"default": "WindRose",
|
"default": "WindRose",
|
||||||
"description": "Type of page for page 2",
|
"description": "Type of page for page 2",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -2086,6 +2129,7 @@
|
|||||||
"default": "OneValue",
|
"default": "OneValue",
|
||||||
"description": "Type of page for page 3",
|
"description": "Type of page for page 3",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -2370,6 +2414,7 @@
|
|||||||
"default": "TwoValues",
|
"default": "TwoValues",
|
||||||
"description": "Type of page for page 4",
|
"description": "Type of page for page 4",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -2646,6 +2691,7 @@
|
|||||||
"default": "ThreeValues",
|
"default": "ThreeValues",
|
||||||
"description": "Type of page for page 5",
|
"description": "Type of page for page 5",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -2914,6 +2960,7 @@
|
|||||||
"default": "FourValues",
|
"default": "FourValues",
|
||||||
"description": "Type of page for page 6",
|
"description": "Type of page for page 6",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3174,6 +3221,7 @@
|
|||||||
"default": "FourValues2",
|
"default": "FourValues2",
|
||||||
"description": "Type of page for page 7",
|
"description": "Type of page for page 7",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3426,6 +3474,7 @@
|
|||||||
"default": "Clock",
|
"default": "Clock",
|
||||||
"description": "Type of page for page 8",
|
"description": "Type of page for page 8",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3670,6 +3719,7 @@
|
|||||||
"default": "RollPitch",
|
"default": "RollPitch",
|
||||||
"description": "Type of page for page 9",
|
"description": "Type of page for page 9",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
@@ -3906,6 +3956,7 @@
|
|||||||
"default": "Battery2",
|
"default": "Battery2",
|
||||||
"description": "Type of page for page 10",
|
"description": "Type of page for page 10",
|
||||||
"list": [
|
"list": [
|
||||||
|
"Anchor",
|
||||||
"BME280",
|
"BME280",
|
||||||
"Battery",
|
"Battery",
|
||||||
"Battery2",
|
"Battery2",
|
||||||
|
|||||||
@@ -1,12 +1,21 @@
|
|||||||
# PlatformIO extra script for obp60task
|
# PlatformIO extra script for obp60task
|
||||||
|
|
||||||
|
import subprocess
|
||||||
|
|
||||||
|
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 +37,20 @@ 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)]
|
||||||
|
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)
|
||||||
|
else:
|
||||||
|
print("no patches found")
|
||||||
|
|||||||
@@ -264,6 +264,8 @@ void registerAllPages(PageList &list){
|
|||||||
list.add(®isterPageDigitalOut);
|
list.add(®isterPageDigitalOut);
|
||||||
extern PageDescription registerPageAutopilot;
|
extern PageDescription registerPageAutopilot;
|
||||||
list.add(®isterPageAutopilot);
|
list.add(®isterPageAutopilot);
|
||||||
|
extern PageDescription registerPageAnchor;
|
||||||
|
list.add(®isterPageAnchor);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Undervoltage detection for shutdown display
|
// Undervoltage detection for shutdown display
|
||||||
@@ -332,7 +334,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 +343,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
|
||||||
@@ -525,8 +527,8 @@ void OBP60Task(GwApi *api){
|
|||||||
// Configuration values for main loop
|
// Configuration values for main loop
|
||||||
String gpsFix = api->getConfig()->getConfigItem(api->getConfig()->flashLED,true)->asString();
|
String gpsFix = api->getConfig()->getConfigItem(api->getConfig()->flashLED,true)->asString();
|
||||||
String gpsOn=api->getConfig()->getConfigItem(api->getConfig()->useGPS,true)->asString();
|
String gpsOn=api->getConfig()->getConfigItem(api->getConfig()->useGPS,true)->asString();
|
||||||
float tz = api->getConfig()->getConfigItem(api->getConfig()->timeZone,true)->asFloat();
|
|
||||||
|
|
||||||
|
commonData.tz = api->getConfig()->getConfigItem(api->getConfig()->timeZone,true)->asFloat();
|
||||||
commonData.backlight.mode = backlightMapping(config->getConfigItem(config->backlight,true)->asString());
|
commonData.backlight.mode = backlightMapping(config->getConfigItem(config->backlight,true)->asString());
|
||||||
commonData.backlight.color = colorMapping(config->getConfigItem(config->blColor,true)->asString());
|
commonData.backlight.color = colorMapping(config->getConfigItem(config->blColor,true)->asString());
|
||||||
commonData.backlight.brightness = uint(config->getConfigItem(config->blBrightness,true)->asInt());
|
commonData.backlight.brightness = uint(config->getConfigItem(config->blBrightness,true)->asInt());
|
||||||
@@ -701,7 +703,7 @@ void OBP60Task(GwApi *api){
|
|||||||
starttime5 = millis();
|
starttime5 = millis();
|
||||||
if(time->valid == true && date->valid == true && lat->valid == true && lon->valid == true){
|
if(time->valid == true && date->valid == true && lat->valid == true && lon->valid == true){
|
||||||
// Provide sundata to all pages
|
// Provide sundata to all pages
|
||||||
commonData.sundata = calcSunsetSunrise(time->value , date->value, lat->value, lon->value, tz);
|
commonData.sundata = calcSunsetSunrise(time->value , date->value, lat->value, lon->value, commonData.tz);
|
||||||
// Backlight with sun control
|
// Backlight with sun control
|
||||||
if (commonData.backlight.mode == BacklightMode::SUN) {
|
if (commonData.backlight.mode == BacklightMode::SUN) {
|
||||||
// if(String(backlight) == "Control by Sun"){
|
// if(String(backlight) == "Control by Sun"){
|
||||||
@@ -714,7 +716,7 @@ void OBP60Task(GwApi *api){
|
|||||||
}
|
}
|
||||||
} else if (homevalid and commonData.data.rtcValid) {
|
} else if (homevalid and commonData.data.rtcValid) {
|
||||||
// No gps fix but valid home location and time configured
|
// No gps fix but valid home location and time configured
|
||||||
commonData.sundata = calcSunsetSunriseRTC(&commonData.data.rtcTime, homelat, homelon, tz);
|
commonData.sundata = calcSunsetSunriseRTC(&commonData.data.rtcTime, homelat, homelon, commonData.tz);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -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
|
||||||
@@ -106,8 +107,9 @@ build_flags=
|
|||||||
-D HARDWARE_V10 #OBP40 hardware revision V1.0 SKU:DIE07300S V1.1 (CrowPanel 4.2)
|
-D HARDWARE_V10 #OBP40 hardware revision V1.0 SKU:DIE07300S V1.1 (CrowPanel 4.2)
|
||||||
-D DISPLAY_GDEY042T81 #new E-Ink display from Good Display (Waveshare), R10 2.2 ohm - good (contast lost by shunshine)
|
-D DISPLAY_GDEY042T81 #new E-Ink display from Good Display (Waveshare), R10 2.2 ohm - good (contast lost by shunshine)
|
||||||
#-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
|
||||||
|
|||||||
@@ -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
|
||||||
|
|||||||
Reference in New Issue
Block a user