Compare commits
7 Commits
3412da8e18
...
7cf1b0e6af
Author | SHA1 | Date |
---|---|---|
![]() |
7cf1b0e6af | |
|
1aa18f3ec0 | |
|
00a8aff8ca | |
|
acf75495df | |
|
2a4c351c58 | |
|
e398c7bdce | |
|
eb3a0d5fc0 |
|
@ -421,32 +421,49 @@ void displayHeader(CommonData &commonData, GwApi::BoatValue *date, GwApi::BoatVa
|
||||||
heartbeat = !heartbeat;
|
heartbeat = !heartbeat;
|
||||||
|
|
||||||
// Date and time
|
// Date and time
|
||||||
|
String fmttype = commonData.config->getString(commonData.config->dateFormat);
|
||||||
|
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_Bold8pt7b);
|
getdisplay().setFont(&Ubuntu_Bold8pt7b);
|
||||||
getdisplay().setCursor(230, 15);
|
getdisplay().setCursor(230, 15);
|
||||||
// Show date and time if date present
|
if (timesource == "RTC" or timesource == "iRTC") {
|
||||||
if(date->valid == true){
|
// TODO take DST into account
|
||||||
String acttime = formatValue(time, commonData).svalue;
|
if (commonData.data.rtcValid) {
|
||||||
acttime = acttime.substring(0, 5);
|
time_t tv = mktime(&commonData.data.rtcTime) + (int)(tz * 3600);
|
||||||
String actdate = formatValue(date, commonData).svalue;
|
struct tm *local_tm = localtime(&tv);
|
||||||
getdisplay().print(acttime);
|
getdisplay().print(formatTime('m', local_tm->tm_hour, local_tm->tm_min, 0));
|
||||||
getdisplay().print(" ");
|
getdisplay().print(" ");
|
||||||
getdisplay().print(actdate);
|
getdisplay().print(formatDate(fmttype, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
|
||||||
getdisplay().print(" ");
|
getdisplay().print(" ");
|
||||||
if(commonData.config->getInt(commonData.config->timeZone) == 0){
|
getdisplay().print(tz == 0 ? "UTC" : "LOT");
|
||||||
getdisplay().print("UTC");
|
} else {
|
||||||
}
|
drawTextRalign(396, 15, "RTC invalid");
|
||||||
else{
|
|
||||||
getdisplay().print("LOT");
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else{
|
else if (timesource == "GPS") {
|
||||||
if(commonData.config->getBool(commonData.config->useSimuData) == true){
|
// Show date and time if date present
|
||||||
getdisplay().print("12:00 01.01.2024 LOT");
|
if(date->valid == true){
|
||||||
|
String acttime = formatValue(time, commonData).svalue;
|
||||||
|
acttime = acttime.substring(0, 5);
|
||||||
|
String actdate = formatValue(date, commonData).svalue;
|
||||||
|
getdisplay().print(acttime);
|
||||||
|
getdisplay().print(" ");
|
||||||
|
getdisplay().print(actdate);
|
||||||
|
getdisplay().print(" ");
|
||||||
|
getdisplay().print(tz == 0 ? "UTC" : "LOT");
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
getdisplay().print("No GPS data");
|
if(commonData.config->getBool(commonData.config->useSimuData) == true){
|
||||||
|
getdisplay().print("12:00 01.01.2024 LOT");
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
drawTextRalign(396, 15, "No GPS data");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
} // timesource == "GPS"
|
||||||
|
else {
|
||||||
|
getdisplay().print("No time source");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -528,8 +545,7 @@ void displayFooter(CommonData &commonData) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Sunset und sunrise calculation
|
// Sunset und sunrise calculation
|
||||||
SunData calcSunsetSunrise(GwApi *api, double time, double date, double latitude, double longitude, double timezone){
|
SunData calcSunsetSunrise(double time, double date, double latitude, double longitude, float timezone){
|
||||||
GwLog *logger=api->getLogger();
|
|
||||||
SunData returnset;
|
SunData returnset;
|
||||||
SunRise sr;
|
SunRise sr;
|
||||||
int secPerHour = 3600;
|
int secPerHour = 3600;
|
||||||
|
@ -543,8 +559,7 @@ SunData calcSunsetSunrise(GwApi *api, double time, double date, double latitude,
|
||||||
if (!isnan(time) && !isnan(date) && !isnan(latitude) && !isnan(longitude) && !isnan(timezone)) {
|
if (!isnan(time) && !isnan(date) && !isnan(latitude) && !isnan(longitude) && !isnan(timezone)) {
|
||||||
|
|
||||||
// Calculate local epoch
|
// Calculate local epoch
|
||||||
t = (date * secPerYear) + time;
|
t = (date * secPerYear) + time;
|
||||||
// api->getLogger()->logDebug(GwLog::DEBUG,"... calcSun: Lat %f, Lon %f, at: %d ", latitude, longitude, t);
|
|
||||||
sr.calculate(latitude, longitude, t); // LAT, LON, EPOCH
|
sr.calculate(latitude, longitude, t); // LAT, LON, EPOCH
|
||||||
// Sunrise
|
// Sunrise
|
||||||
if (sr.hasRise) {
|
if (sr.hasRise) {
|
||||||
|
@ -567,6 +582,37 @@ SunData calcSunsetSunrise(GwApi *api, double time, double date, double latitude,
|
||||||
return returnset;
|
return returnset;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
SunData calcSunsetSunriseRTC(struct tm *rtctime, double latitude, double longitude, float timezone) {
|
||||||
|
SunData returnset;
|
||||||
|
SunRise sr;
|
||||||
|
const int secPerHour = 3600;
|
||||||
|
const int secPerYear = 86400;
|
||||||
|
sr.hasRise = false;
|
||||||
|
sr.hasSet = false;
|
||||||
|
time_t t = mktime(rtctime) + timezone * 3600;;
|
||||||
|
time_t sunR = 0;
|
||||||
|
time_t sunS = 0;
|
||||||
|
|
||||||
|
sr.calculate(latitude, longitude, t); // LAT, LON, EPOCH
|
||||||
|
// Sunrise
|
||||||
|
if (sr.hasRise) {
|
||||||
|
sunR = (sr.riseTime + int(timezone * secPerHour) + 30) % secPerYear; // add 30 seconds: round to minutes
|
||||||
|
returnset.sunriseHour = int (sunR / secPerHour);
|
||||||
|
returnset.sunriseMinute = int((sunR - returnset.sunriseHour * secPerHour) / 60);
|
||||||
|
}
|
||||||
|
// Sunset
|
||||||
|
if (sr.hasSet) {
|
||||||
|
sunS = (sr.setTime + int(timezone * secPerHour) + 30) % secPerYear; // add 30 seconds: round to minutes
|
||||||
|
returnset.sunsetHour = int (sunS / secPerHour);
|
||||||
|
returnset.sunsetMinute = int((sunS - returnset.sunsetHour * secPerHour) / 60);
|
||||||
|
}
|
||||||
|
// Sun control (return value by sun on sky = false, sun down = true)
|
||||||
|
if ((t >= sr.riseTime) && (t <= sr.setTime))
|
||||||
|
returnset.sunDown = false;
|
||||||
|
else returnset.sunDown = true;
|
||||||
|
return returnset;
|
||||||
|
}
|
||||||
|
|
||||||
// Battery graphic with fill level
|
// Battery graphic with fill level
|
||||||
void batteryGraphic(uint x, uint y, float percent, int pcolor, int bcolor){
|
void batteryGraphic(uint x, uint y, float percent, int pcolor, int bcolor){
|
||||||
// Show battery
|
// Show battery
|
||||||
|
|
|
@ -97,7 +97,8 @@ void displayTrendLow(int16_t x, int16_t y, uint16_t size, uint16_t color);
|
||||||
void displayHeader(CommonData &commonData, GwApi::BoatValue *date, GwApi::BoatValue *time, GwApi::BoatValue *hdop); // Draw display header
|
void displayHeader(CommonData &commonData, GwApi::BoatValue *date, GwApi::BoatValue *time, GwApi::BoatValue *hdop); // Draw display header
|
||||||
void displayFooter(CommonData &commonData);
|
void displayFooter(CommonData &commonData);
|
||||||
|
|
||||||
SunData calcSunsetSunrise(GwApi *api, double time, double date, double latitude, double longitude, double timezone); // Calulate sunset and sunrise
|
SunData calcSunsetSunrise(double time, double date, double latitude, double longitude, float timezone); // Calulate sunset and sunrise
|
||||||
|
SunData calcSunsetSunriseRTC(struct tm *rtctime, double latitude, double longitude, float timezone);
|
||||||
|
|
||||||
void batteryGraphic(uint x, uint y, float percent, int pcolor, int bcolor); // Battery graphic with fill level
|
void batteryGraphic(uint x, uint y, float percent, int pcolor, int bcolor); // Battery graphic with fill level
|
||||||
void solarGraphic(uint x, uint y, int pcolor, int bcolor); // Solar graphic
|
void solarGraphic(uint x, uint y, int pcolor, int bcolor); // Solar graphic
|
||||||
|
|
|
@ -8,6 +8,35 @@
|
||||||
// simulation data
|
// simulation data
|
||||||
// hold values by missing data
|
// hold values by missing data
|
||||||
|
|
||||||
|
String formatDate(String fmttype, uint16_t year, uint8_t month, uint8_t day) {
|
||||||
|
char buffer[12];
|
||||||
|
if (fmttype == "GB") {
|
||||||
|
snprintf(buffer, 12, "%02d/%02d/%04d", day , month, year);
|
||||||
|
}
|
||||||
|
else if (fmttype == "US") {
|
||||||
|
snprintf(buffer, 12, "%02d/%02d/%04d", month, day, year);
|
||||||
|
}
|
||||||
|
else if (fmttype == "ISO") {
|
||||||
|
snprintf(buffer, 12, "%04d-%02d-%02d", year, month, day);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
snprintf(buffer, 12, "%02d.%02d.%04d", day, month, year);
|
||||||
|
}
|
||||||
|
return String(buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
String formatTime(char fmttype, uint8_t hour, uint8_t minute, uint8_t second) {
|
||||||
|
// fmttype: s: with seconds, m: only minutes
|
||||||
|
char buffer[10];
|
||||||
|
if (fmttype == 'm') {
|
||||||
|
snprintf(buffer, 10, "%02d:%02d", hour , minute);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
snprintf(buffer, 10, "%02d:%02d:%02d", hour, minute, second);
|
||||||
|
}
|
||||||
|
return String(buffer);
|
||||||
|
}
|
||||||
|
|
||||||
FormatedData formatValue(GwApi::BoatValue *value, CommonData &commondata){
|
FormatedData formatValue(GwApi::BoatValue *value, CommonData &commondata){
|
||||||
GwLog *logger = commondata.logger;
|
GwLog *logger = commondata.logger;
|
||||||
FormatedData result;
|
FormatedData result;
|
||||||
|
|
|
@ -17,9 +17,11 @@
|
||||||
#include "ObpNmea0183.h" // Check NMEA0183 sentence for uncorrect content
|
#include "ObpNmea0183.h" // Check NMEA0183 sentence for uncorrect content
|
||||||
#include "OBP60Extensions.h" // Lib for hardware extensions
|
#include "OBP60Extensions.h" // Lib for hardware extensions
|
||||||
#include "movingAvg.h" // Lib for moving average building
|
#include "movingAvg.h" // Lib for moving average building
|
||||||
|
#include "time.h" // For getting NTP time
|
||||||
|
#include <ESP32Time.h> // Internal ESP32 RTC clock
|
||||||
|
|
||||||
// Timer for hardware functions
|
// Timer for hardware functions
|
||||||
Ticker Timer1(blinkingFlashLED, 500); // Satrt Timer1 for flash LED all 500ms
|
Ticker Timer1(blinkingFlashLED, 500); // Start Timer1 for flash LED all 500ms
|
||||||
|
|
||||||
// Initialization for all sensors (RS232, I2C, 1Wire, IOs)
|
// Initialization for all sensors (RS232, I2C, 1Wire, IOs)
|
||||||
//####################################################################################
|
//####################################################################################
|
||||||
|
@ -150,6 +152,7 @@ void sensorTask(void *param){
|
||||||
// ds1388.adjust(DateTime(__DATE__, __TIME__)); // Set date and time from PC file time
|
// ds1388.adjust(DateTime(__DATE__, __TIME__)); // Set date and time from PC file time
|
||||||
}
|
}
|
||||||
RTC_ready = true;
|
RTC_ready = true;
|
||||||
|
sensors.rtcValid = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -366,6 +369,28 @@ void sensorTask(void *param){
|
||||||
GwApi::BoatValue *hdop=new GwApi::BoatValue(GwBoatData::_HDOP);
|
GwApi::BoatValue *hdop=new GwApi::BoatValue(GwBoatData::_HDOP);
|
||||||
GwApi::BoatValue *valueList[]={gpsdays, gpsseconds, hdop};
|
GwApi::BoatValue *valueList[]={gpsdays, gpsseconds, hdop};
|
||||||
|
|
||||||
|
// Internal RTC with NTP init
|
||||||
|
ESP32Time rtc(0);
|
||||||
|
if (api->getConfig()->getString(api->getConfig()->timeSource) == "iRTC") {
|
||||||
|
GwApi::Status status;
|
||||||
|
api->getStatus(status);
|
||||||
|
if (status.wifiClientConnected) {
|
||||||
|
const char *ntpServer = api->getConfig()->getCString(api->getConfig()->timeServer);
|
||||||
|
api->getLogger()->logDebug(GwLog::LOG,"Fetching date and time from NTP server '%s'.", ntpServer);
|
||||||
|
configTime(0, 0, ntpServer); // get time in UTC
|
||||||
|
struct tm 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);
|
||||||
|
rtc.setTimeStruct(timeinfo);
|
||||||
|
sensors.rtcValid = true;
|
||||||
|
} else {
|
||||||
|
api->getLogger()->logDebug(GwLog::LOG,"NTP time fetch failed!");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
api->getLogger()->logDebug(GwLog::LOG,"Wifi client not connected, NTP not available.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Sensor task loop runs with 100ms
|
// Sensor task loop runs with 100ms
|
||||||
//####################################################################################
|
//####################################################################################
|
||||||
|
|
||||||
|
@ -428,39 +453,45 @@ void sensorTask(void *param){
|
||||||
loopCounter++;
|
loopCounter++;
|
||||||
}
|
}
|
||||||
|
|
||||||
// If GPS not ready or installed then send RTC time on bus all 500ms
|
// Get current RTC date and time all 500ms
|
||||||
if(millis() > starttime12 + 500){
|
if (millis() > starttime12 + 500) {
|
||||||
starttime12 = millis();
|
starttime12 = millis();
|
||||||
if((rtcOn == "DS1388" && RTC_ready == true && GPS_ready == false) || (rtcOn == "DS1388" && RTC_ready == true && GPS_ready == true && hdop->valid == false)){
|
if (rtcOn == "DS1388" && RTC_ready) {
|
||||||
// Convert RTC time to Unix system time
|
DateTime dt = ds1388.now();
|
||||||
// https://de.wikipedia.org/wiki/Unixzeit
|
sensors.rtcTime.tm_year = dt.year() - 1900; // Save values in SensorData
|
||||||
const short daysOfYear[12] = {0,31,59,90,120,151,181,212,243,273,304,334};
|
sensors.rtcTime.tm_mon = dt.month() - 1;
|
||||||
long unixtime = ds1388.now().get();
|
sensors.rtcTime.tm_mday = dt.day();
|
||||||
uint16_t year = ds1388.now().year();
|
sensors.rtcTime.tm_hour = dt.hour();
|
||||||
uint8_t month = ds1388.now().month();
|
sensors.rtcTime.tm_min = dt.minute();
|
||||||
uint8_t hour = ds1388.now().hour();
|
sensors.rtcTime.tm_sec = dt.second();
|
||||||
uint8_t minute = ds1388.now().minute();
|
sensors.rtcTime.tm_isdst = 0; // Not considering daylight saving time
|
||||||
uint8_t second = ds1388.now().second();
|
|
||||||
uint8_t day = ds1388.now().day();
|
// If GPS not ready or installed then send RTC time on bus
|
||||||
uint16_t switchYear = ((year-1)-1968)/4 - ((year-1)-1900)/100 + ((year-1)-1600)/400;
|
// TODO If there are other time sources on the bus there should
|
||||||
long daysAt1970 = (year-1970)*365 + switchYear + daysOfYear[month-1] + day-1;
|
// be a logic not to send or to send with lower frequency
|
||||||
// If switch year then add one day
|
// or something totally different
|
||||||
if ( (month>2) && (year%4==0 && (year%100!=0 || year%400==0)) ){
|
if ((GPS_ready == false) || (GPS_ready == true && hdop->valid == false)) {
|
||||||
daysAt1970 += 1;
|
// 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};
|
||||||
double sysTime = (hour * 3600) + (minute * 60) + second;
|
uint16_t switchYear = ((dt.year()-1)-1968)/4 - ((dt.year()-1)-1900)/100 + ((dt.year()-1)-1600)/400;
|
||||||
if(!isnan(daysAt1970) && !isnan(sysTime)){
|
long daysAt1970 = (dt.year()-1970)*365 + switchYear + daysOfYear[dt.month()-1] + dt.day()-1;
|
||||||
sensors.rtcYear = year; // Save values in SensorData
|
// If switch year then add one day
|
||||||
sensors.rtcMonth = month;
|
if ((dt.month() > 2) && (dt.year() % 4 == 0 && (dt.year() % 100 != 0 || dt.year() % 400 == 0))) {
|
||||||
sensors.rtcDay = day;
|
daysAt1970 += 1;
|
||||||
sensors.rtcHour = hour;
|
}
|
||||||
sensors.rtcMinute = minute;
|
// N2K sysTime is double in n2klib
|
||||||
sensors.rtcSecond = second;
|
double sysTime = (dt.hour() * 3600) + (dt.minute() * 60) + dt.second();
|
||||||
// api->getLogger()->logDebug(GwLog::LOG,"RTC time: %04d/%02d/%02d %02d:%02d:%02d",year, month, day, hour, minute, second);
|
// WHY? isnan should always fail here
|
||||||
// api->getLogger()->logDebug(GwLog::LOG,"Send PGN126992: %10d %10d",daysAt1970, (uint16_t)sysTime);
|
//if(!isnan(daysAt1970) && !isnan(sysTime)){
|
||||||
SetN2kPGN126992(N2kMsg,0,daysAt1970,sysTime,N2ktimes_LocalCrystalClock);
|
//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->sendN2kMessage(N2kMsg);
|
//api->getLogger()->logDebug(GwLog::LOG,"Send PGN126992: %10d %10d",daysAt1970, (uint16_t)sysTime);
|
||||||
|
SetN2kPGN126992(N2kMsg,0,daysAt1970,sysTime,N2ktimes_LocalCrystalClock);
|
||||||
|
api->sendN2kMessage(N2kMsg);
|
||||||
|
// }
|
||||||
}
|
}
|
||||||
|
} else if (sensors.rtcValid) {
|
||||||
|
// use internal rtc feature
|
||||||
|
sensors.rtcTime = rtc.getTimeStruct();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -3,24 +3,83 @@
|
||||||
#include "Pagedata.h"
|
#include "Pagedata.h"
|
||||||
#include "OBP60Extensions.h"
|
#include "OBP60Extensions.h"
|
||||||
|
|
||||||
|
/*
|
||||||
|
* TODO mode: race timer: keys
|
||||||
|
* - prepare: set countdown to 5min
|
||||||
|
* reset: abort current countdown and start over with 5min preparation
|
||||||
|
* - 5min: key press
|
||||||
|
* - 4min: key press to sync
|
||||||
|
* - 1min: buzzer signal
|
||||||
|
* - start: buzzer signal for start
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
class PageClock : public Page
|
class PageClock : public Page
|
||||||
{
|
{
|
||||||
bool simulation = false;
|
bool simulation = false;
|
||||||
int simtime;
|
int simtime;
|
||||||
|
bool keylock = false;
|
||||||
|
char source = 'R'; // time source (R)TC | (G)PS | (N)TP
|
||||||
|
char mode = 'A'; // display mode (A)nalog | (D)igital | race (T)imer
|
||||||
|
char tz = 'L'; // time zone (L)ocal | (U)TC
|
||||||
|
double timezone = 0; // there are timezones with non int offsets, e.g. 5.5 or 5.75
|
||||||
|
double homelat;
|
||||||
|
double homelon;
|
||||||
|
bool homevalid = false; // homelat and homelon are valid
|
||||||
|
|
||||||
public:
|
public:
|
||||||
PageClock(CommonData &common){
|
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();
|
||||||
|
homelat = common.config->getString(common.config->homeLAT).toDouble();
|
||||||
|
homelon = common.config->getString(common.config->homeLON).toDouble();
|
||||||
|
homevalid = homelat >= -180.0 and homelat <= 180 and homelon >= -90.0 and homelon <= 90.0;
|
||||||
simtime = 38160; // time value 11:36
|
simtime = 38160; // time value 11:36
|
||||||
}
|
}
|
||||||
|
|
||||||
|
virtual void setupKeys(){
|
||||||
|
Page::setupKeys();
|
||||||
|
commonData->keydata[0].label = "SRC";
|
||||||
|
commonData->keydata[1].label = "MODE";
|
||||||
|
commonData->keydata[4].label = "TZ";
|
||||||
|
}
|
||||||
|
|
||||||
// Key functions
|
// Key functions
|
||||||
virtual int handleKey(int key){
|
virtual int handleKey(int key){
|
||||||
// Code for keylock
|
// Time source
|
||||||
if(key == 11){
|
if (key == 1) {
|
||||||
commonData->keylock = !commonData->keylock;
|
if (source == 'G') {
|
||||||
|
source = 'R';
|
||||||
|
} else {
|
||||||
|
source = 'G';
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
if (key == 2) {
|
||||||
|
if (mode == 'A') {
|
||||||
|
mode = 'D';
|
||||||
|
} else if (mode == 'D') {
|
||||||
|
mode = 'T';
|
||||||
|
} else {
|
||||||
|
mode = 'A';
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
// Time zone: Local / UTC
|
||||||
|
if (key == 5) {
|
||||||
|
if (tz == 'L') {
|
||||||
|
tz = 'U';
|
||||||
|
} else {
|
||||||
|
tz = 'L';
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Keylock function
|
||||||
|
if(key == 11){ // Code for keylock
|
||||||
|
keylock = !keylock; // Toggle keylock
|
||||||
return 0; // Commit the key
|
return 0; // Commit the key
|
||||||
}
|
}
|
||||||
return key;
|
return key;
|
||||||
|
@ -47,11 +106,10 @@ class PageClock : public Page
|
||||||
|
|
||||||
// Get config data
|
// Get config data
|
||||||
String lengthformat = config->getString(config->lengthFormat);
|
String lengthformat = config->getString(config->lengthFormat);
|
||||||
|
String dateformat = config->getString(config->dateFormat);
|
||||||
bool holdvalues = config->getBool(config->holdvalues);
|
bool holdvalues = config->getBool(config->holdvalues);
|
||||||
String flashLED = config->getString(config->flashLED);
|
String flashLED = config->getString(config->flashLED);
|
||||||
String backlightMode = config->getString(config->backlight);
|
String backlightMode = config->getString(config->backlight);
|
||||||
String stimezone = config->getString(config->timeZone);
|
|
||||||
double timezone = stimezone.toDouble();
|
|
||||||
|
|
||||||
// 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 (only one value by PageOneValue)
|
||||||
|
@ -67,7 +125,7 @@ class PageClock : public Page
|
||||||
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 as string including unit conversion and switching decimal places
|
||||||
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
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -80,7 +138,7 @@ class PageClock : public Page
|
||||||
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 as string including unit conversion and switching decimal places
|
||||||
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
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -93,14 +151,14 @@ class PageClock : public Page
|
||||||
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 as string including unit conversion and switching decimal places
|
||||||
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
|
||||||
|
@ -115,11 +173,30 @@ class PageClock : public Page
|
||||||
|
|
||||||
getdisplay().setTextColor(commonData->fgcolor);
|
getdisplay().setTextColor(commonData->fgcolor);
|
||||||
|
|
||||||
|
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
|
||||||
|
struct tm *local_tm = localtime(&tv);
|
||||||
|
|
||||||
// Show values GPS date
|
// Show values GPS date
|
||||||
getdisplay().setFont(&Ubuntu_Bold8pt7b);
|
getdisplay().setFont(&Ubuntu_Bold8pt7b);
|
||||||
getdisplay().setCursor(10, 65);
|
getdisplay().setCursor(10, 65);
|
||||||
if(holdvalues == false) getdisplay().print(svalue2); // Value
|
if (holdvalues == false) {
|
||||||
else getdisplay().print(svalue2old);
|
if (source == 'G') {
|
||||||
|
// GPS value
|
||||||
|
getdisplay().print(svalue2);
|
||||||
|
} else if (commonData->data.rtcValid) {
|
||||||
|
// RTC value
|
||||||
|
if (tz == 'L') {
|
||||||
|
getdisplay().print(formatDate(dateformat, local_tm->tm_year + 1900, local_tm->tm_mon + 1, local_tm->tm_mday));
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
getdisplay().print(formatDate(dateformat, commonData->data.rtcTime.tm_year + 1900, commonData->data.rtcTime.tm_mon + 1, commonData->data.rtcTime.tm_mday));
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
getdisplay().print("---");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
getdisplay().print(svalue2old);
|
||||||
|
}
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt7b);
|
getdisplay().setFont(&Ubuntu_Bold12pt7b);
|
||||||
getdisplay().setCursor(10, 95);
|
getdisplay().setCursor(10, 95);
|
||||||
getdisplay().print("Date"); // Name
|
getdisplay().print("Date"); // Name
|
||||||
|
@ -130,15 +207,31 @@ class PageClock : public Page
|
||||||
// Show values GPS time
|
// Show values GPS time
|
||||||
getdisplay().setFont(&Ubuntu_Bold8pt7b);
|
getdisplay().setFont(&Ubuntu_Bold8pt7b);
|
||||||
getdisplay().setCursor(10, 250);
|
getdisplay().setCursor(10, 250);
|
||||||
if(holdvalues == false) getdisplay().print(svalue1); // Value
|
if (holdvalues == false) {
|
||||||
else getdisplay().print(svalue1old);
|
if (source == 'G') {
|
||||||
|
getdisplay().print(svalue1); // Value
|
||||||
|
}
|
||||||
|
else if (commonData->data.rtcValid) {
|
||||||
|
if (tz == 'L') {
|
||||||
|
getdisplay().print(formatTime('s', local_tm->tm_hour, local_tm->tm_min, local_tm->tm_sec));
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
getdisplay().print(formatTime('s', commonData->data.rtcTime.tm_hour, commonData->data.rtcTime.tm_min, commonData->data.rtcTime.tm_sec));
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
getdisplay().print("---");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
getdisplay().print(svalue1old);
|
||||||
|
}
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt7b);
|
getdisplay().setFont(&Ubuntu_Bold12pt7b);
|
||||||
getdisplay().setCursor(10, 220);
|
getdisplay().setCursor(10, 220);
|
||||||
getdisplay().print("Time"); // Name
|
getdisplay().print("Time"); // Name
|
||||||
|
|
||||||
// Show values sunrise
|
// Show values sunrise
|
||||||
String sunrise = "---";
|
String sunrise = "---";
|
||||||
if(valid1 == true && valid2 == true && valid3 == true){
|
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
|
||||||
sunrise = String(commonData->sundata.sunriseHour) + ":" + String(commonData->sundata.sunriseMinute + 100).substring(1);
|
sunrise = String(commonData->sundata.sunriseHour) + ":" + String(commonData->sundata.sunriseMinute + 100).substring(1);
|
||||||
svalue5old = sunrise;
|
svalue5old = sunrise;
|
||||||
} else if (simulation) {
|
} else if (simulation) {
|
||||||
|
@ -158,7 +251,7 @@ class PageClock : public Page
|
||||||
|
|
||||||
// Show values sunset
|
// Show values sunset
|
||||||
String sunset = "---";
|
String sunset = "---";
|
||||||
if(valid1 == true && valid2 == true && valid3 == true){
|
if ((valid1 and valid2 and valid3 == true) or (homevalid and commonData->data.rtcValid)) {
|
||||||
sunset = String(commonData->sundata.sunsetHour) + ":" + String(commonData->sundata.sunsetMinute + 100).substring(1);
|
sunset = String(commonData->sundata.sunsetHour) + ":" + String(commonData->sundata.sunsetMinute + 100).substring(1);
|
||||||
svalue6old = sunset;
|
svalue6old = sunset;
|
||||||
} else if (simulation) {
|
} else if (simulation) {
|
||||||
|
@ -174,7 +267,7 @@ class PageClock : public Page
|
||||||
getdisplay().print("SunS"); // Name
|
getdisplay().print("SunS"); // Name
|
||||||
|
|
||||||
//*******************************************************************************************
|
//*******************************************************************************************
|
||||||
|
|
||||||
// Draw clock
|
// Draw clock
|
||||||
int rInstrument = 110; // Radius of clock
|
int rInstrument = 110; // Radius of clock
|
||||||
float pi = 3.141592;
|
float pi = 3.141592;
|
||||||
|
@ -246,27 +339,52 @@ class PageClock : public Page
|
||||||
getdisplay().setFont(&Ubuntu_Bold12pt7b);
|
getdisplay().setFont(&Ubuntu_Bold12pt7b);
|
||||||
getdisplay().setCursor(175, 110);
|
getdisplay().setCursor(175, 110);
|
||||||
if(holdvalues == false){
|
if(holdvalues == false){
|
||||||
getdisplay().print(unit2); // Unit
|
getdisplay().print(tz == 'L' ? "LOT" : "UTC");
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
getdisplay().print(unit2old); // Unit
|
getdisplay().print(unit2old); // date unit
|
||||||
|
}
|
||||||
|
|
||||||
|
getdisplay().setFont(&Ubuntu_Bold8pt7b);
|
||||||
|
getdisplay().setCursor(185, 190);
|
||||||
|
if (source == 'G') {
|
||||||
|
getdisplay().print("GPS");
|
||||||
|
} else {
|
||||||
|
getdisplay().print("RTC");
|
||||||
}
|
}
|
||||||
|
|
||||||
// Clock values
|
// Clock values
|
||||||
double hour = 0;
|
double hour = 0;
|
||||||
double minute = 0;
|
double minute = 0;
|
||||||
value1 = value1 + int(timezone*3600);
|
if (source == 'R') {
|
||||||
if (value1 > 86400) {value1 = value1 - 86400;}
|
if (tz == 'L') {
|
||||||
if (value1 < 0) {value1 = value1 + 86400;}
|
time_t tv = mktime(&commonData->data.rtcTime) + timezone * 3600;
|
||||||
hour = (value1 / 3600.0);
|
struct tm *local_tm = localtime(&tv);
|
||||||
if(hour > 12) hour = hour - 12.0;
|
minute = local_tm->tm_min;
|
||||||
// minute = (hour - int(hour)) * 3600.0 / 60.0; // Analog minute pointer smooth moving
|
hour = local_tm->tm_hour;
|
||||||
minute = int((hour - int(hour)) * 3600.0 / 60.0); // Jumping minute pointer from minute to minute
|
} else {
|
||||||
|
minute = commonData->data.rtcTime.tm_min;
|
||||||
|
hour = commonData->data.rtcTime.tm_hour;
|
||||||
|
}
|
||||||
|
hour += minute / 60;
|
||||||
|
} else {
|
||||||
|
if (tz == 'L') {
|
||||||
|
value1 += timezone * 3600;
|
||||||
|
}
|
||||||
|
if (value1 > 86400) {value1 -= 86400;}
|
||||||
|
if (value1 < 0) {value1 += 86400;}
|
||||||
|
hour = (value1 / 3600.0);
|
||||||
|
// minute = (hour - int(hour)) * 3600.0 / 60.0; // Analog minute pointer smooth moving
|
||||||
|
minute = int((hour - int(hour)) * 3600.0 / 60.0); // Jumping minute pointer from minute to minute
|
||||||
|
}
|
||||||
|
if (hour > 12) {
|
||||||
|
hour -= 12.0;
|
||||||
|
}
|
||||||
LOG_DEBUG(GwLog::DEBUG,"... PageClock, value1: %f hour: %f minute:%f", value1, hour, minute);
|
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 || 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
|
||||||
|
@ -274,7 +392,7 @@ class PageClock : public Page
|
||||||
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);
|
||||||
|
@ -292,7 +410,7 @@ class PageClock : public Page
|
||||||
|
|
||||||
// Draw minute pointer
|
// Draw minute pointer
|
||||||
startwidth = 8; // Start width of pointer
|
startwidth = 8; // Start width of pointer
|
||||||
if(valid1 == true || 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
|
||||||
|
@ -300,7 +418,7 @@ class PageClock : public Page
|
||||||
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);
|
||||||
|
|
|
@ -43,14 +43,10 @@ typedef struct{
|
||||||
double airHumidity = 0;
|
double airHumidity = 0;
|
||||||
double airPressure = 0;
|
double airPressure = 0;
|
||||||
double onewireTemp[8] = {0,0,0,0,0,0,0,0};
|
double onewireTemp[8] = {0,0,0,0,0,0,0,0};
|
||||||
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
|
||||||
int rtcYear = 0; // UTC time
|
struct tm rtcTime; // UTC time from internal RTC
|
||||||
int rtcMonth = 0;
|
bool rtcValid = false;
|
||||||
int rtcDay = 0;
|
|
||||||
int rtcHour = 0;
|
|
||||||
int rtcMinute = 0;
|
|
||||||
int rtcSecond = 0;
|
|
||||||
int sunsetHour = 0;
|
int sunsetHour = 0;
|
||||||
int sunsetMinute = 0;
|
int sunsetMinute = 0;
|
||||||
int sunriseHour = 0;
|
int sunriseHour = 0;
|
||||||
|
@ -169,13 +165,16 @@ class PageStruct{
|
||||||
PageDescription *description=NULL;
|
PageDescription *description=NULL;
|
||||||
};
|
};
|
||||||
|
|
||||||
// Structure for formated boat values
|
// Standard format functions without overhead
|
||||||
|
String formatDate(String fmttype, uint16_t year, uint8_t month, uint8_t day);
|
||||||
|
String formatTime(char fmttype, uint8_t hour, uint8_t minute, uint8_t second);
|
||||||
|
|
||||||
|
// Structure for formatted boat values
|
||||||
typedef struct{
|
typedef struct{
|
||||||
double value;
|
double value;
|
||||||
String svalue;
|
String svalue;
|
||||||
String unit;
|
String unit;
|
||||||
} FormatedData;
|
} FormatedData;
|
||||||
|
|
||||||
|
// Formatter for boat values
|
||||||
// Formater for boat values
|
|
||||||
FormatedData formatValue(GwApi::BoatValue *value, CommonData &commondata);
|
FormatedData formatValue(GwApi::BoatValue *value, CommonData &commondata);
|
||||||
|
|
|
@ -8,6 +8,17 @@
|
||||||
"description": "system name, used for the access point and for services",
|
"description": "system name, used for the access point and for services",
|
||||||
"category": "system"
|
"category": "system"
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "timeServer",
|
||||||
|
"label": "time server",
|
||||||
|
"type": "string",
|
||||||
|
"default": "pool.ntp.org",
|
||||||
|
"description": "NTP time server. Use only one hostname or IP address",
|
||||||
|
"category": "wifi client",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "timeZone",
|
"name": "timeZone",
|
||||||
"label": "Time Zone",
|
"label": "Time Zone",
|
||||||
|
@ -22,6 +33,34 @@
|
||||||
"obp60":"true"
|
"obp60":"true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "homeLAT",
|
||||||
|
"label": "Home latitude",
|
||||||
|
"type": "number",
|
||||||
|
"default": "",
|
||||||
|
"check": "checkMinMax",
|
||||||
|
"min": -90.0,
|
||||||
|
"max": 90.0,
|
||||||
|
"description": "Latitude of boat home location [-90.0...+90.0]",
|
||||||
|
"category": "OBP60 Settings",
|
||||||
|
"capabilities": {
|
||||||
|
"obp60":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "homeLON",
|
||||||
|
"label": "Home longitude",
|
||||||
|
"type": "number",
|
||||||
|
"default": "",
|
||||||
|
"check": "checkMinMax",
|
||||||
|
"min": -180.0,
|
||||||
|
"max": 180.0,
|
||||||
|
"description": "Longitude of boat home location [-180.0...+180.0]",
|
||||||
|
"category": "OBP60 Settings",
|
||||||
|
"capabilities": {
|
||||||
|
"obp60":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "draft",
|
"name": "draft",
|
||||||
"label": "Boat Draft [m]",
|
"label": "Boat Draft [m]",
|
||||||
|
@ -690,6 +729,21 @@
|
||||||
"obp60":"true"
|
"obp60":"true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "timeSource",
|
||||||
|
"label": "Status Time Source",
|
||||||
|
"type": "list",
|
||||||
|
"default": "GPS",
|
||||||
|
"description": "Data source for date and time display in status line [RTC|GPS]",
|
||||||
|
"list": [
|
||||||
|
{"l":"Real time clock (RTC)","v":"RTC"},
|
||||||
|
{"l":"Time via bus (GPS)","v":"GPS"}
|
||||||
|
],
|
||||||
|
"category": "OBP60 Display",
|
||||||
|
"capabilities": {
|
||||||
|
"obp60":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "refresh",
|
"name": "refresh",
|
||||||
"label": "Refresh",
|
"label": "Refresh",
|
||||||
|
|
|
@ -8,6 +8,17 @@
|
||||||
"description": "system name, used for the access point and for services",
|
"description": "system name, used for the access point and for services",
|
||||||
"category": "system"
|
"category": "system"
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "timeServer",
|
||||||
|
"label": "time server",
|
||||||
|
"type": "string",
|
||||||
|
"default": "pool.ntp.org",
|
||||||
|
"description": "NTP time server. Use only one hostname or IP address",
|
||||||
|
"category": "wifi client",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "timeZone",
|
"name": "timeZone",
|
||||||
"label": "Time Zone",
|
"label": "Time Zone",
|
||||||
|
@ -22,6 +33,34 @@
|
||||||
"obp40": "true"
|
"obp40": "true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "homeLAT",
|
||||||
|
"label": "Home latitude",
|
||||||
|
"type": "number",
|
||||||
|
"default": "0.00000",
|
||||||
|
"check": "checkMinMax",
|
||||||
|
"min": -90.0,
|
||||||
|
"max": 90.0,
|
||||||
|
"description": "Latitude of boat home location [-90.0...+90.0]",
|
||||||
|
"category": "OBP40 Settings",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "homeLON",
|
||||||
|
"label": "Home longitude",
|
||||||
|
"type": "number",
|
||||||
|
"default": "0.00000",
|
||||||
|
"check": "checkMinMax",
|
||||||
|
"min": -180.0,
|
||||||
|
"max": 180.0,
|
||||||
|
"description": "Longitude of boat home location [-180.0...+180.0]",
|
||||||
|
"category": "OBP40 Settings",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40": "true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "draft",
|
"name": "draft",
|
||||||
"label": "Boat Draft [m]",
|
"label": "Boat Draft [m]",
|
||||||
|
@ -705,6 +744,22 @@
|
||||||
"obp40": "true"
|
"obp40": "true"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "timeSource",
|
||||||
|
"label": "Status Time Source",
|
||||||
|
"type": "list",
|
||||||
|
"default": "GPS",
|
||||||
|
"description": "Data source for date and time display in status line [RTC|iRTC|GPS]",
|
||||||
|
"list": [
|
||||||
|
{"l":"Internal real time clock (iRTC)","v":"iRTC"},
|
||||||
|
{"l":"External real time clock (RTC)","v":"RTC"},
|
||||||
|
{"l":"External time via bus (GPS)","v":"GPS"}
|
||||||
|
],
|
||||||
|
"category": "OBP40 Display",
|
||||||
|
"capabilities": {
|
||||||
|
"obp40":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "refresh",
|
"name": "refresh",
|
||||||
"label": "Refresh",
|
"label": "Refresh",
|
||||||
|
|
|
@ -548,7 +548,7 @@ 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();
|
||||||
String tz = api->getConfig()->getConfigItem(api->getConfig()->timeZone,true)->asString();
|
float 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());
|
||||||
|
@ -559,6 +559,15 @@ void OBP60Task(GwApi *api){
|
||||||
String cpuspeed = api->getConfig()->getConfigItem(api->getConfig()->cpuSpeed,true)->asString();
|
String cpuspeed = api->getConfig()->getConfigItem(api->getConfig()->cpuSpeed,true)->asString();
|
||||||
uint hdopAccuracy = uint(api->getConfig()->getConfigItem(api->getConfig()->hdopAccuracy,true)->asInt());
|
uint hdopAccuracy = uint(api->getConfig()->getConfigItem(api->getConfig()->hdopAccuracy,true)->asInt());
|
||||||
|
|
||||||
|
double homelat = commonData.config->getString(commonData.config->homeLAT).toDouble();
|
||||||
|
double homelon = commonData.config->getString(commonData.config->homeLON).toDouble();
|
||||||
|
bool homevalid = homelat >= -180.0 and homelat <= 180 and homelon >= -90.0 and homelon <= 90.0;
|
||||||
|
if (homevalid) {
|
||||||
|
LOG_DEBUG(GwLog::LOG, "Home location set to %f : %f", homelat, homelon);
|
||||||
|
} else {
|
||||||
|
LOG_DEBUG(GwLog::LOG, "No valid home location found");
|
||||||
|
}
|
||||||
|
|
||||||
// refreshmode defined in init section
|
// refreshmode defined in init section
|
||||||
|
|
||||||
// Boat values for main loop
|
// Boat values for main loop
|
||||||
|
@ -708,7 +717,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(api, time->value , date->value, lat->value, lon->value, tz.toDouble());
|
commonData.sundata = calcSunsetSunrise(time->value , date->value, lat->value, lon->value, 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"){
|
||||||
|
@ -719,6 +728,9 @@ void OBP60Task(GwApi *api){
|
||||||
setBacklightLED(0, COLOR_BLUE); // Backlight LEDs off (blue without britghness)
|
setBacklightLED(0, COLOR_BLUE); // Backlight LEDs off (blue without britghness)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
} else if (homevalid and commonData.data.rtcValid) {
|
||||||
|
// No gps fix but valid home location and time configured
|
||||||
|
commonData.sundata = calcSunsetSunriseRTC(&commonData.data.rtcTime, homelat, homelon, tz);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@ lib_deps =
|
||||||
${basedeps.lib_deps}
|
${basedeps.lib_deps}
|
||||||
Wire
|
Wire
|
||||||
SPI
|
SPI
|
||||||
|
ESP32time
|
||||||
esphome/AsyncTCP-esphome@2.0.1
|
esphome/AsyncTCP-esphome@2.0.1
|
||||||
robtillaart/PCF8574@0.3.9
|
robtillaart/PCF8574@0.3.9
|
||||||
adafruit/Adafruit Unified Sensor @ 1.1.13
|
adafruit/Adafruit Unified Sensor @ 1.1.13
|
||||||
|
@ -71,6 +72,7 @@ lib_deps =
|
||||||
Wire
|
Wire
|
||||||
SPI
|
SPI
|
||||||
SD
|
SD
|
||||||
|
ESP32time
|
||||||
esphome/AsyncTCP-esphome@2.0.1
|
esphome/AsyncTCP-esphome@2.0.1
|
||||||
robtillaart/PCF8574@0.3.9
|
robtillaart/PCF8574@0.3.9
|
||||||
adafruit/Adafruit Unified Sensor @ 1.1.13
|
adafruit/Adafruit Unified Sensor @ 1.1.13
|
||||||
|
@ -94,8 +96,8 @@ build_flags=
|
||||||
-D DISABLE_DIAGNOSTIC_OUTPUT #Disable diagnostic output for GxEPD2 lib
|
-D DISABLE_DIAGNOSTIC_OUTPUT #Disable diagnostic output for GxEPD2 lib
|
||||||
-D BOARD_OBP40S3 #Board OBP40 V1.0 with ESP32S3 SKU:DIE07300S (CrowPanel 4.2)
|
-D BOARD_OBP40S3 #Board OBP40 V1.0 with ESP32S3 SKU:DIE07300S (CrowPanel 4.2)
|
||||||
-D DISPLAY_GDEY042T81 #new E-Ink display from Waveshare, R10 2.2 ohm
|
-D DISPLAY_GDEY042T81 #new E-Ink display from Waveshare, R10 2.2 ohm
|
||||||
-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
|
||||||
${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
|
||||||
|
|
Loading…
Reference in New Issue