Merge branch 'wellenvogel:master' into oldenv
This commit is contained in:
commit
f5f1bdc62f
|
@ -10,6 +10,8 @@ jobs:
|
||||||
os: [ubuntu-latest]
|
os: [ubuntu-latest]
|
||||||
|
|
||||||
runs-on: ${{ matrix.os }}
|
runs-on: ${{ matrix.os }}
|
||||||
|
env:
|
||||||
|
PIP_BREAK_SYSTEM_PACKAGES: 1
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v2
|
- uses: actions/checkout@v2
|
||||||
with:
|
with:
|
||||||
|
|
|
@ -18,6 +18,9 @@ jobs:
|
||||||
# The type of runner that the job will run on
|
# The type of runner that the job will run on
|
||||||
runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
|
|
||||||
|
env:
|
||||||
|
PIP_BREAK_SYSTEM_PACKAGES: 1
|
||||||
|
|
||||||
# Steps represent a sequence of tasks that will be executed as part of the job
|
# Steps represent a sequence of tasks that will be executed as part of the job
|
||||||
steps:
|
steps:
|
||||||
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
|
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
|
||||||
|
|
26
Readme.md
26
Readme.md
|
@ -50,6 +50,10 @@ For the list of hardware set ups refer to [Hardware](doc/Hardware.md).
|
||||||
|
|
||||||
There is a couple of prebuild binaries that you can directly flash to your device. For other combinations of hardware there is an [online build service](doc/BuildService.md) that will allow you to select your hardware and trigger a build.
|
There is a couple of prebuild binaries that you can directly flash to your device. For other combinations of hardware there is an [online build service](doc/BuildService.md) that will allow you to select your hardware and trigger a build.
|
||||||
|
|
||||||
|
Connectivity
|
||||||
|
------------
|
||||||
|
For details of the usage of serial devices and the USB connection refer to [Serial and USB](doc/serial-usb.md).<br>
|
||||||
|
For details on the networking capabilities refer to [Networking](doc/network.md).
|
||||||
|
|
||||||
Installation
|
Installation
|
||||||
------------
|
------------
|
||||||
|
@ -166,6 +170,28 @@ For details refer to the [example description](lib/exampletask/Readme.md).
|
||||||
|
|
||||||
Changelog
|
Changelog
|
||||||
---------
|
---------
|
||||||
|
[20241114](../../releases/tag/20241114)
|
||||||
|
**********
|
||||||
|
* UDP writer and reader - [#79](../../issues/79)
|
||||||
|
* extensions for [user tasks](lib/exampletask/Readme.md)
|
||||||
|
* extend the Web UI with js and css
|
||||||
|
* register handler for Web Requests
|
||||||
|
* Naming of the config file [#87](../../issues/87)
|
||||||
|
* MTW from PGN130311 [#83](../../issues/83)
|
||||||
|
* USB connection on S3 stops [#81](../../issues/81)
|
||||||
|
* remove invalid true wind calc, allow to configure some mapping - partly [#75](../../issues/75)
|
||||||
|
* correctly parse GSV messages [#50](../../issues/50)
|
||||||
|
* minor adaptations from new version [#66](../../issues/66)
|
||||||
|
* new platform version 6.8.1
|
||||||
|
* internally restructure the channel handling
|
||||||
|
* add docs for [networking](doc/network.md) and [serial/USB](doc/serial-usb.md)
|
||||||
|
* allow to configure the timeout(s) for the data display
|
||||||
|
* new library versions - nmea2000 4.22.0, nmea0183 1.10.1
|
||||||
|
* allow for builds completely without FastLED
|
||||||
|
* wipe the nvs partition on factory reset (to handle corrupted config)
|
||||||
|
* do not store the wifi settings in nvs on the system level [#78](../../issues/78)
|
||||||
|
* rename of data: HDG->HDT, MHDG->HDM
|
||||||
|
* adapt crash decoder tool to s3
|
||||||
[20240428](../../releases/tag/20240428)
|
[20240428](../../releases/tag/20240428)
|
||||||
**********
|
**********
|
||||||
* fix build error with M5 gps kit
|
* fix build error with M5 gps kit
|
||||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,80 @@
|
||||||
|
Networking
|
||||||
|
==========
|
||||||
|
The gateway includes a couple of network functions to send and receive NMEA data on network connections and to use a WebBrowser for configuration and status display.
|
||||||
|
|
||||||
|
To understand the networking functions you always have to consider 2 parts:
|
||||||
|
|
||||||
|
The "physical" connection
|
||||||
|
-------------------------
|
||||||
|
For the gateway this is always a Wifi connection.
|
||||||
|
It provides the ability to use it as an access point and/or to connect to another wifi network (wifi client).
|
||||||
|
|
||||||
|
Access Point
|
||||||
|
************
|
||||||
|
When starting up it will create an own Wifi network (access point or AP) with the name of the system. You connect to this network like to any Wifi Hotspot.
|
||||||
|
The initial password is esp32nmea2k. You should change this password on the configuration page in the Web UI.
|
||||||
|
When you connect the gateway will provide you with an IP address (DHCP) - and it will also have an own IP address in this range (default: 192.168.15.1). If this IP address (range) conflicts with other devices (especially if you run multiple gateways and connect them) you can change the range at the system tab on the configuration page.<br>
|
||||||
|
If you do not need the access point during normal operation you can set "stopApTime" so that it will shut down after this time (in minutes) if no device is connected. This will also reduce the power consumption.
|
||||||
|
|
||||||
|
Wifi Client
|
||||||
|
***********
|
||||||
|
Beside the own access point the gateway can also connect to another Wifi network. You need to configure the SSID and password at the "wifi client" tab.
|
||||||
|
On the status page you can see if the gateway is connected and which address it got within the network.
|
||||||
|
|
||||||
|
You can use both networks to connect to the gateway. It announces it's services via [bonjour](https://developer.apple.com/bonjour/). So you normally should be able to reach your system using Name.local (name being the system name, default ESP32NMEA2K). Or you can use an app that allows for bonjour browsing.
|
||||||
|
|
||||||
|
The "logical" connection
|
||||||
|
------------------------
|
||||||
|
After you connected a device to the gateway on either the access point or by using the same Wifi network you can easily access the Web UI with a browser - e.g. using the Name.local url.
|
||||||
|
|
||||||
|
To send or receive NMEA data you additionally need to configure some connection between the gateway and your device(s).
|
||||||
|
The gateway provides the following options for NMEA connections:
|
||||||
|
|
||||||
|
TCP Server
|
||||||
|
**********
|
||||||
|
When using the TCP server you must configure a connection to the gateway _on the device_ that you would like to connect. The gateway listens at port 10110 (can be changed at the TCP server tab). So on your device you need to configure the address of the gateway and this port. The address depends on the network that you use to connect your device - either the address from the gateway access point (default: 192.168.15.1) - or the address that the gateway was given in the Wifi client network (check this on the status page).<br>
|
||||||
|
If your device supports this you can also use the Name.local for the address - or let the device browse for a bonjour service.<br>
|
||||||
|
The TCP server has a limit for the number of connections (can be configured, default: 6). As for any channel you can define what it will write and read on it's connections and apply filters.
|
||||||
|
If you want to send NMEA2000 data via TCP you can enable "Seasmart out".
|
||||||
|
|
||||||
|
TCP Client
|
||||||
|
**********
|
||||||
|
With this settings you can configure the gateway to establish a connection to another device that provides data via TCP. You need to know the address and port for that device. If the other device also uses bonjour (like e.g. a second gateway device) you can also use this name instead of the address.
|
||||||
|
Like for the TCP server you can define what should be send or received with filters.
|
||||||
|
|
||||||
|
UDP Reader
|
||||||
|
**********
|
||||||
|
UDP is distinct from TCP in that it does not establish a connection directly. Instead in sends/receives messages - without checking if they have been received by someone at all. Therefore it is also not able to ensure that really all messages are reaching their destination. But as the used protocols (NMEA0183, NMEA2000) are prepared for unreliable connections any way (for serial connections you normally have no idea if the data arrives) UDP is still a valid way of connecting devices.<br>
|
||||||
|
One advantage of UDP is that you can send out messages as broadcast or multicast - thus allowing for multiple receivers.
|
||||||
|
|
||||||
|
Small hint for __multicast__:<br>
|
||||||
|
Normally in the environment the gateway will work you will not use multicast. If you want to send to multiple devices you will use broadcast. The major difference between them are 2 points:<br>
|
||||||
|
1. broadcast messages will not pass a real router (but they will be available to all devices connected to one access point)
|
||||||
|
2. broadcast messages will always be send to all devices - regardless whether they would like to receive them or not. This can create a bit more network traffic.
|
||||||
|
|
||||||
|
Multicast requires that receivers announce their interest in receiving messages (by "joining" a so called multicast group) and this way only interested devices will receive such messages - and it is possible to configure routers in a way that they route multicast messages.
|
||||||
|
|
||||||
|
To use the gateway UDP reader you must select from where you would like to receive messages. In any case you need to set up a port (default: 10110). Afterwards you need to decide on the allowed sources:
|
||||||
|
* _all_ (default): accept messages from both the access point and the wifi client network - both broadcast messages and directly addressed ones
|
||||||
|
* _ap_: only accept messages from devices that are connected to the access point
|
||||||
|
* _cli_: only accept messages from devices on the Wifi client network
|
||||||
|
* _mp-all_: you need to configure the multicast address(group) you would like to join and will receive multicast from both the access point and the wifi client network
|
||||||
|
* _mp-ap_: multicast only from the access point network
|
||||||
|
* _mp-cli_: multicast only from the wifi client network
|
||||||
|
|
||||||
|
UDP Writer
|
||||||
|
**********
|
||||||
|
The UDP writer basically is the counterpart for the UDP reader.
|
||||||
|
You also have to select where do you want the UDP messages to be sent to.
|
||||||
|
* _bc-all_ (default): Send the messages as broadcast to devices connected to the own access point and to devices on the wifi client network
|
||||||
|
* _bc-ap_: send the messages as broadcast only to the access point network
|
||||||
|
* _bc-cli_: send the messages as broadcast to the wifi client network
|
||||||
|
* _normal_: you need to configure a destination address (one device) that you want the messages to be send to
|
||||||
|
* _mc-all_: send messages as multicast to both the access point network and the wifi client network. _Hint_: Only devices that configured the same multicast address will receive such messages.
|
||||||
|
* _mc-ap_: multicast only to the access point network
|
||||||
|
* _mc-cli_: multicast only to the wifi client network.
|
||||||
|
|
||||||
|
With the combination of UDP writer and UDP reader you can easily connect multiple gateway devices without a lot of configuration. Just configure one device as UDP writer (with the default settings) and configure other devices as UDP reader (also with default settings) - this way it does not matter how you connect the devices - all devices will receive the data that is sent by the first one.<br>
|
||||||
|
__Remark:__ be carefull not to create loops when you would like to send data in both directions between 2 devices using UDP. Either use filters - or use TCP connections as they are able to send data in both directions on one connection (without creating a loop).
|
||||||
|
|
||||||
|
If you want to forward NMEA2000 data from one gateway device to another, just enable "Seasmart out" at the sender side. This will encapsulate the NMEA2000 data in a NMEA0183 compatible format. The receiver will always automatically detect this format and handle the data correctly.
|
|
@ -0,0 +1,51 @@
|
||||||
|
Serial and USB
|
||||||
|
==============
|
||||||
|
The gateway software uses the [arduino layer](https://github.com/espressif/arduino-esp32) on top of the [espressif IDF framework](https://github.com/espressif/esp-idf).
|
||||||
|
The handling of serial devices is mainly done by the implementations in the arduino-espressif layer.
|
||||||
|
The gateway code adds some buffering on top of this implementation and ensures that normally only full nmea records are sent.
|
||||||
|
If the external connection is to slow the gateway will drop complete records.
|
||||||
|
All handling of the serial channels is done in the main task of the gateway.
|
||||||
|
|
||||||
|
Serial Devices
|
||||||
|
--------------
|
||||||
|
THe arduino espressif layer provides the serial devices as [Streams](https://github.com/espressif/arduino-esp32/blob/master/cores/esp32/Stream.h#L48).
|
||||||
|
Main implementations are [HardwareSerial](https://github.com/espressif/arduino-esp32/blob/3670e2bf2aca822f2e1225fdb0e0796e490005a8/cores/esp32/HardwareSerial.h#L71) - for the UARTS and [HWCDC](https://github.com/espressif/arduino-esp32/blob/3670e2bf2aca822f2e1225fdb0e0796e490005a8/cores/esp32/HWCDC.h#L43)(C3/S3 only) - for the USB CDC hardware device.
|
||||||
|
|
||||||
|
For the github versions: arduino-espressif 3.20009 maps to github tag 2.0.9.
|
||||||
|
|
||||||
|
The arduino espressif layer creates a couple of global instances for the serial devices (potentially depending on some defines).
|
||||||
|
The important defines for C3/S3 are:
|
||||||
|
|
||||||
|
* ARDUINO_USB_MODE - the gateway always expects this to be 1
|
||||||
|
* ARDUINO_USB_CDC_ON_BOOT - 0 or 1 (CB in the table below)
|
||||||
|
|
||||||
|
The created devices for framework 3.20009:
|
||||||
|
|
||||||
|
| Device(Variable) | Type(ESP32) | C3/S3 CB=0 | C3/S3 CB=1 |
|
||||||
|
| ------------ | ------- | ------ | -----|
|
||||||
|
| Serial0 | --- | --- | HardwareSerial(0) |
|
||||||
|
| Serial1 | HardwareSerial(1) | HardwareSerial(1) | HardwareSerial(1) |
|
||||||
|
| Serial2 | HardwareSerial(2) | HardwareSerial(2) | HardwareSerial(2) |
|
||||||
|
| USBSerial | --- | HWCDC | ---- |
|
||||||
|
| Serial | HardwareSerial(0) | HardwareSerial(0) | HWCDC |
|
||||||
|
|
||||||
|
Unfortunately it seems that in newer versions of the framework the devices could change.
|
||||||
|
|
||||||
|
The gateway will use the following serial devices:
|
||||||
|
|
||||||
|
* USBserial:<br>
|
||||||
|
For debug output and NMEA as USB connection. If you do not use an S3/C3 with ARDUINO_USB_CDC_ON_BOOT=0 you need to add a <br>_define USBSerial Serial_ somewhere in your build flags or in your task header.<br>
|
||||||
|
Currently the gateway does not support setting the pins for the USB channel (that would be possible in principle only if an external PHY device is used and the USB is connected to a normal UART).
|
||||||
|
* Serial1:<br>
|
||||||
|
If you define GWSERIAL_TYPE (1,2,3,4) - see [defines](../lib/hardware/GwHardware.h#23) or GWSERIAL_MODE ("UNI","BI","TX","RX") it will be used for the first serial channel.
|
||||||
|
* Serial2:<br>
|
||||||
|
If you define GWSERIAL2_TYPE (1,2,3,4) - see [defines](../lib/hardware/GwHardware.h#23) or GWSERIAL2_MODE ("UNI","BI","TX","RX") it will be used for the second serial channel.
|
||||||
|
|
||||||
|
Hints
|
||||||
|
-----
|
||||||
|
For normal ESP32 chips you need to set <br>_define USBSerial Serial_ <br>and you can use up to 2 serial channels beside the USB channel.
|
||||||
|
For C3/S3 chips you can go for 2 options:
|
||||||
|
1. set ARDUINO_USB_CDC_ON_BOOT=1: in This case you still need to set<br> _define USBSerial Serial_<br> You can use up to 2 serial channels in the gateway core - but you still have Serial0 available for a third channel (not yet supported by the core - but can be used in your user code)
|
||||||
|
2. set ARDUINO_USB_CDC_ON_BOOT=0: in this case USBSerial is already defined as the USB channel. You can use 2 channels in the gateway core and optional you can use Serial in your user code.
|
||||||
|
|
||||||
|
If you do not set any of the GWSERIAL* defines (and they are not set by the core hardware definitions) you can freely use Serial1 and / or Serial2 in your user code.
|
|
@ -18,6 +18,8 @@ OWN_FILE="extra_script.py"
|
||||||
GEN_DIR='lib/generated'
|
GEN_DIR='lib/generated'
|
||||||
CFG_FILE='web/config.json'
|
CFG_FILE='web/config.json'
|
||||||
XDR_FILE='web/xdrconfig.json'
|
XDR_FILE='web/xdrconfig.json'
|
||||||
|
INDEXJS="index.js"
|
||||||
|
INDEXCSS="index.css"
|
||||||
CFG_INCLUDE='GwConfigDefinitions.h'
|
CFG_INCLUDE='GwConfigDefinitions.h'
|
||||||
CFG_INCLUDE_IMPL='GwConfigDefImpl.h'
|
CFG_INCLUDE_IMPL='GwConfigDefImpl.h'
|
||||||
XDR_INCLUDE='GwXdrTypeMappings.h'
|
XDR_INCLUDE='GwXdrTypeMappings.h'
|
||||||
|
@ -66,6 +68,7 @@ def isCurrent(infile,outfile):
|
||||||
def compressFile(inFile,outfile):
|
def compressFile(inFile,outfile):
|
||||||
if isCurrent(inFile,outfile):
|
if isCurrent(inFile,outfile):
|
||||||
return
|
return
|
||||||
|
print("compressing %s"%inFile)
|
||||||
with open(inFile, 'rb') as f_in:
|
with open(inFile, 'rb') as f_in:
|
||||||
with gzip.open(outfile, 'wb') as f_out:
|
with gzip.open(outfile, 'wb') as f_out:
|
||||||
shutil.copyfileobj(f_in, f_out)
|
shutil.copyfileobj(f_in, f_out)
|
||||||
|
@ -372,6 +375,32 @@ def getLibs():
|
||||||
rt.append(e)
|
rt.append(e)
|
||||||
return rt
|
return rt
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
def joinFiles(target,pattern,dirlist):
|
||||||
|
flist=[]
|
||||||
|
for dir in dirlist:
|
||||||
|
fn=os.path.join(dir,pattern)
|
||||||
|
if os.path.exists(fn):
|
||||||
|
flist.append(fn)
|
||||||
|
current=False
|
||||||
|
if os.path.exists(target):
|
||||||
|
current=True
|
||||||
|
for f in flist:
|
||||||
|
if not isCurrent(f,target):
|
||||||
|
current=False
|
||||||
|
break
|
||||||
|
if current:
|
||||||
|
print("%s is up to date"%target)
|
||||||
|
return
|
||||||
|
print("creating %s"%target)
|
||||||
|
with gzip.open(target,"wb") as oh:
|
||||||
|
for fn in flist:
|
||||||
|
print("adding %s to %s"%(fn,target))
|
||||||
|
with open(fn,"rb") as rh:
|
||||||
|
shutil.copyfileobj(rh,oh)
|
||||||
|
|
||||||
|
|
||||||
OWNLIBS=getLibs()+["FS","WiFi"]
|
OWNLIBS=getLibs()+["FS","WiFi"]
|
||||||
GLOBAL_INCLUDES=[]
|
GLOBAL_INCLUDES=[]
|
||||||
|
|
||||||
|
@ -440,6 +469,8 @@ def prebuild(env):
|
||||||
compressFile(mergedConfig,mergedConfig+".gz")
|
compressFile(mergedConfig,mergedConfig+".gz")
|
||||||
generateCfg(mergedConfig,os.path.join(outPath(),CFG_INCLUDE),False)
|
generateCfg(mergedConfig,os.path.join(outPath(),CFG_INCLUDE),False)
|
||||||
generateCfg(mergedConfig,os.path.join(outPath(),CFG_INCLUDE_IMPL),True)
|
generateCfg(mergedConfig,os.path.join(outPath(),CFG_INCLUDE_IMPL),True)
|
||||||
|
joinFiles(os.path.join(outPath(),INDEXJS+".gz"),INDEXJS,["web"]+userTaskDirs)
|
||||||
|
joinFiles(os.path.join(outPath(),INDEXCSS+".gz"),INDEXCSS,["web"]+userTaskDirs)
|
||||||
embedded=getEmbeddedFiles(env)
|
embedded=getEmbeddedFiles(env)
|
||||||
filedefs=[]
|
filedefs=[]
|
||||||
for ef in embedded:
|
for ef in embedded:
|
||||||
|
@ -453,7 +484,6 @@ def prebuild(env):
|
||||||
filedefs.append((pureName,usname,ct))
|
filedefs.append((pureName,usname,ct))
|
||||||
inFile=os.path.join(basePath(),"web",pureName)
|
inFile=os.path.join(basePath(),"web",pureName)
|
||||||
if os.path.exists(inFile):
|
if os.path.exists(inFile):
|
||||||
print("compressing %s"%inFile)
|
|
||||||
compressFile(inFile,ef)
|
compressFile(inFile,ef)
|
||||||
else:
|
else:
|
||||||
print("#WARNING: infile %s for %s not found"%(inFile,ef))
|
print("#WARNING: infile %s for %s not found"%(inFile,ef))
|
||||||
|
|
|
@ -6,7 +6,9 @@
|
||||||
#include "GWConfig.h"
|
#include "GWConfig.h"
|
||||||
#include "GwBoatData.h"
|
#include "GwBoatData.h"
|
||||||
#include "GwXDRMappings.h"
|
#include "GwXDRMappings.h"
|
||||||
|
#include "GwSynchronized.h"
|
||||||
#include <map>
|
#include <map>
|
||||||
|
#include <ESPAsyncWebServer.h>
|
||||||
class GwApi;
|
class GwApi;
|
||||||
typedef void (*GwUserTaskFunction)(GwApi *);
|
typedef void (*GwUserTaskFunction)(GwApi *);
|
||||||
//API to be used for additional tasks
|
//API to be used for additional tasks
|
||||||
|
@ -95,6 +97,8 @@ class GwApi{
|
||||||
unsigned long ser2Tx=0;
|
unsigned long ser2Tx=0;
|
||||||
unsigned long tcpSerRx=0;
|
unsigned long tcpSerRx=0;
|
||||||
unsigned long tcpSerTx=0;
|
unsigned long tcpSerTx=0;
|
||||||
|
unsigned long udpwTx=0;
|
||||||
|
unsigned long udprRx=0;
|
||||||
int tcpClients=0;
|
int tcpClients=0;
|
||||||
unsigned long tcpClRx=0;
|
unsigned long tcpClRx=0;
|
||||||
unsigned long tcpClTx=0;
|
unsigned long tcpClTx=0;
|
||||||
|
@ -169,6 +173,20 @@ class GwApi{
|
||||||
virtual void remove(int idx){}
|
virtual void remove(int idx){}
|
||||||
virtual TaskInterfaces * taskInterfaces()=0;
|
virtual TaskInterfaces * taskInterfaces()=0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* register handler for web URLs
|
||||||
|
* Please be aware that this handler function will always be called from a separate
|
||||||
|
* task. So you must ensure proper synchronization!
|
||||||
|
*/
|
||||||
|
using HandlerFunction=std::function<void(AsyncWebServerRequest *)>;
|
||||||
|
/**
|
||||||
|
* @param url: the url of that will trigger the handler.
|
||||||
|
* it will be prefixed with /api/user/<taskname>
|
||||||
|
* taskname is the name that you used in addUserTask
|
||||||
|
* @param handler: the handler function (see remark above about thread synchronization)
|
||||||
|
*/
|
||||||
|
virtual void registerRequestHandler(const String &url,HandlerFunction handler)=0;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* only allowed during init methods
|
* only allowed during init methods
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -1,6 +1,7 @@
|
||||||
#include "GwBoatData.h"
|
#include "GwBoatData.h"
|
||||||
#include <GwJsonDocument.h>
|
#include <GwJsonDocument.h>
|
||||||
#include <ArduinoJson/Json/TextFormatter.hpp>
|
#include <ArduinoJson/Json/TextFormatter.hpp>
|
||||||
|
#include "GWConfig.h"
|
||||||
#define GWTYPE_DOUBLE 1
|
#define GWTYPE_DOUBLE 1
|
||||||
#define GWTYPE_UINT32 2
|
#define GWTYPE_UINT32 2
|
||||||
#define GWTYPE_UINT16 3
|
#define GWTYPE_UINT16 3
|
||||||
|
@ -35,8 +36,48 @@ GwBoatItemBase::GwBoatItemBase(String name, String format, unsigned long invalid
|
||||||
this->format = format;
|
this->format = format;
|
||||||
this->type = 0;
|
this->type = 0;
|
||||||
this->lastUpdateSource = -1;
|
this->lastUpdateSource = -1;
|
||||||
|
this->toType=TOType::user;
|
||||||
|
}
|
||||||
|
GwBoatItemBase::GwBoatItemBase(String name, String format, GwBoatItemBase::TOType toType)
|
||||||
|
{
|
||||||
|
lastSet = 0;
|
||||||
|
this->invalidTime = INVALID_TIME;
|
||||||
|
this->toType=toType;
|
||||||
|
this->name = name;
|
||||||
|
this->format = format;
|
||||||
|
this->type = 0;
|
||||||
|
this->lastUpdateSource = -1;
|
||||||
|
}
|
||||||
|
void GwBoatItemBase::setInvalidTime(GwConfigHandler *cfg){
|
||||||
|
if (toType != TOType::user){
|
||||||
|
unsigned long timeout=GwBoatItemBase::INVALID_TIME;
|
||||||
|
switch(getToType()){
|
||||||
|
case GwBoatItemBase::TOType::ais:
|
||||||
|
timeout=cfg->getInt(GwConfigDefinitions::timoAis);
|
||||||
|
break;
|
||||||
|
case GwBoatItemBase::TOType::def:
|
||||||
|
timeout=cfg->getInt(GwConfigDefinitions::timoDefault);
|
||||||
|
break;
|
||||||
|
case GwBoatItemBase::TOType::lng:
|
||||||
|
timeout=cfg->getInt(GwConfigDefinitions::timoLong);
|
||||||
|
break;
|
||||||
|
case GwBoatItemBase::TOType::sensor:
|
||||||
|
timeout=cfg->getInt(GwConfigDefinitions::timoSensor);
|
||||||
|
break;
|
||||||
|
case GwBoatItemBase::TOType::keep:
|
||||||
|
timeout=0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
invalidTime=timeout;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
size_t GwBoatItemBase::getJsonSize() { return JSON_OBJECT_SIZE(10); }
|
size_t GwBoatItemBase::getJsonSize() { return JSON_OBJECT_SIZE(10); }
|
||||||
|
|
||||||
|
void GwBoatItemBase::GwBoatItemMap::add(const String &name,GwBoatItemBase *item){
|
||||||
|
boatData->setInvalidTime(item);
|
||||||
|
(*this)[name]=item;
|
||||||
|
}
|
||||||
|
|
||||||
#define STRING_SIZE 40
|
#define STRING_SIZE 40
|
||||||
GwBoatItemBase::StringWriter::StringWriter()
|
GwBoatItemBase::StringWriter::StringWriter()
|
||||||
{
|
{
|
||||||
|
@ -110,7 +151,17 @@ GwBoatItem<T>::GwBoatItem(String name, String formatInfo, unsigned long invalidT
|
||||||
this->type = GwBoatItemTypes::getType(dummy);
|
this->type = GwBoatItemTypes::getType(dummy);
|
||||||
if (map)
|
if (map)
|
||||||
{
|
{
|
||||||
(*map)[name] = this;
|
map->add(name,this);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
template <class T>
|
||||||
|
GwBoatItem<T>::GwBoatItem(String name, String formatInfo, GwBoatItemBase::TOType toType, GwBoatItemMap *map) : GwBoatItemBase(name, formatInfo, toType)
|
||||||
|
{
|
||||||
|
T dummy;
|
||||||
|
this->type = GwBoatItemTypes::getType(dummy);
|
||||||
|
if (map)
|
||||||
|
{
|
||||||
|
map->add(name,this);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -246,14 +297,13 @@ void GwSatInfoList::houseKeeping(unsigned long ts)
|
||||||
sats.end(),
|
sats.end(),
|
||||||
[ts, this](const GwSatInfo &info)
|
[ts, this](const GwSatInfo &info)
|
||||||
{
|
{
|
||||||
return (info.timestamp + lifeTime) < ts;
|
return info.validTill < ts;
|
||||||
}),
|
}),
|
||||||
sats.end());
|
sats.end());
|
||||||
}
|
}
|
||||||
void GwSatInfoList::update(GwSatInfo entry)
|
void GwSatInfoList::update(GwSatInfo entry, unsigned long validTill)
|
||||||
{
|
{
|
||||||
unsigned long now = millis();
|
entry.validTill = validTill;
|
||||||
entry.timestamp = now;
|
|
||||||
for (auto it = sats.begin(); it != sats.end(); it++)
|
for (auto it = sats.begin(); it != sats.end(); it++)
|
||||||
{
|
{
|
||||||
if (it->PRN == entry.PRN)
|
if (it->PRN == entry.PRN)
|
||||||
|
@ -267,7 +317,7 @@ void GwSatInfoList::update(GwSatInfo entry)
|
||||||
sats.push_back(entry);
|
sats.push_back(entry);
|
||||||
}
|
}
|
||||||
|
|
||||||
GwBoatDataSatList::GwBoatDataSatList(String name, String formatInfo, unsigned long invalidTime, GwBoatItemMap *map) : GwBoatItem<GwSatInfoList>(name, formatInfo, invalidTime, map) {}
|
GwBoatDataSatList::GwBoatDataSatList(String name, String formatInfo, GwBoatItemBase::TOType toType, GwBoatItemMap *map) : GwBoatItem<GwSatInfoList>(name, formatInfo, toType, map) {}
|
||||||
|
|
||||||
bool GwBoatDataSatList::update(GwSatInfo info, int source)
|
bool GwBoatDataSatList::update(GwSatInfo info, int source)
|
||||||
{
|
{
|
||||||
|
@ -284,7 +334,7 @@ bool GwBoatDataSatList::update(GwSatInfo info, int source)
|
||||||
}
|
}
|
||||||
lastUpdateSource = source;
|
lastUpdateSource = source;
|
||||||
uls(now);
|
uls(now);
|
||||||
data.update(info);
|
data.update(info,now+invalidTime);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
void GwBoatDataSatList::toJsonDoc(GwJsonDocument *doc, unsigned long minTime)
|
void GwBoatDataSatList::toJsonDoc(GwJsonDocument *doc, unsigned long minTime)
|
||||||
|
@ -293,9 +343,15 @@ void GwBoatDataSatList::toJsonDoc(GwJsonDocument *doc, unsigned long minTime)
|
||||||
GwBoatItem<GwSatInfoList>::toJsonDoc(doc, minTime);
|
GwBoatItem<GwSatInfoList>::toJsonDoc(doc, minTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
GwBoatData::GwBoatData(GwLog *logger)
|
GwBoatData::GwBoatData(GwLog *logger, GwConfigHandler *cfg)
|
||||||
{
|
{
|
||||||
this->logger = logger;
|
this->logger = logger;
|
||||||
|
this->config = cfg;
|
||||||
|
}
|
||||||
|
void GwBoatData::begin(){
|
||||||
|
for (auto &&it : values){
|
||||||
|
it.second->setInvalidTime(config);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
GwBoatData::~GwBoatData()
|
GwBoatData::~GwBoatData()
|
||||||
{
|
{
|
||||||
|
@ -326,7 +382,7 @@ GwBoatItem<T> *GwBoatData::getOrCreate(T initial, GwBoatItemNameProvider *provid
|
||||||
provider->getBoatItemFormat(),
|
provider->getBoatItemFormat(),
|
||||||
provider->getInvalidTime(),
|
provider->getInvalidTime(),
|
||||||
&values);
|
&values);
|
||||||
rt->update(initial);
|
rt->update(initial,-1);
|
||||||
LOG_DEBUG(GwLog::LOG, "creating boatItem %s, type %d",
|
LOG_DEBUG(GwLog::LOG, "creating boatItem %s, type %d",
|
||||||
name.c_str(), rt->getCurrentType());
|
name.c_str(), rt->getCurrentType());
|
||||||
return rt;
|
return rt;
|
||||||
|
@ -408,6 +464,10 @@ double GwBoatData::getDoubleValue(String name, double defaultv)
|
||||||
return defaultv;
|
return defaultv;
|
||||||
return it->second->getDoubleValue();
|
return it->second->getDoubleValue();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GwBoatData::setInvalidTime(GwBoatItemBase *item){
|
||||||
|
if (config != nullptr) item->setInvalidTime(config);
|
||||||
|
}
|
||||||
double formatCourse(double cv)
|
double formatCourse(double cv)
|
||||||
{
|
{
|
||||||
double rt = cv * 180.0 / M_PI;
|
double rt = cv * 180.0 / M_PI;
|
||||||
|
|
|
@ -2,6 +2,7 @@
|
||||||
#define _GWBOATDATA_H
|
#define _GWBOATDATA_H
|
||||||
|
|
||||||
#include "GwLog.h"
|
#include "GwLog.h"
|
||||||
|
#include "GWConfig.h"
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <map>
|
#include <map>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
@ -13,8 +14,18 @@
|
||||||
#define ROT_WA_FACTOR 60
|
#define ROT_WA_FACTOR 60
|
||||||
|
|
||||||
class GwJsonDocument;
|
class GwJsonDocument;
|
||||||
|
class GwBoatData;
|
||||||
|
|
||||||
class GwBoatItemBase{
|
class GwBoatItemBase{
|
||||||
public:
|
public:
|
||||||
|
using TOType=enum{
|
||||||
|
def=1,
|
||||||
|
ais=2,
|
||||||
|
sensor=3,
|
||||||
|
lng=4,
|
||||||
|
user=5,
|
||||||
|
keep=6
|
||||||
|
};
|
||||||
class StringWriter{
|
class StringWriter{
|
||||||
uint8_t *buffer =NULL;
|
uint8_t *buffer =NULL;
|
||||||
uint8_t *wp=NULL;
|
uint8_t *wp=NULL;
|
||||||
|
@ -31,7 +42,7 @@ class GwBoatItemBase{
|
||||||
bool baseFilled();
|
bool baseFilled();
|
||||||
void reset();
|
void reset();
|
||||||
};
|
};
|
||||||
static const unsigned long INVALID_TIME=60000;
|
static const long INVALID_TIME=60000;
|
||||||
//the formatter names that must be known in js
|
//the formatter names that must be known in js
|
||||||
GWSC(formatCourse);
|
GWSC(formatCourse);
|
||||||
GWSC(formatKnots);
|
GWSC(formatKnots);
|
||||||
|
@ -47,14 +58,14 @@ class GwBoatItemBase{
|
||||||
GWSC(formatRot);
|
GWSC(formatRot);
|
||||||
GWSC(formatDate);
|
GWSC(formatDate);
|
||||||
GWSC(formatTime);
|
GWSC(formatTime);
|
||||||
typedef std::map<String,GwBoatItemBase*> GwBoatItemMap;
|
|
||||||
protected:
|
protected:
|
||||||
int type;
|
int type;
|
||||||
unsigned long lastSet=0;
|
unsigned long lastSet=0;
|
||||||
unsigned long invalidTime=INVALID_TIME;
|
long invalidTime=INVALID_TIME;
|
||||||
String name;
|
String name;
|
||||||
String format;
|
String format;
|
||||||
StringWriter writer;
|
StringWriter writer;
|
||||||
|
TOType toType=TOType::def;
|
||||||
void uls(unsigned long ts=0){
|
void uls(unsigned long ts=0){
|
||||||
if (ts) lastSet=ts;
|
if (ts) lastSet=ts;
|
||||||
else lastSet=millis();
|
else lastSet=millis();
|
||||||
|
@ -65,7 +76,8 @@ class GwBoatItemBase{
|
||||||
int getCurrentType(){return type;}
|
int getCurrentType(){return type;}
|
||||||
unsigned long getLastSet() const {return lastSet;}
|
unsigned long getLastSet() const {return lastSet;}
|
||||||
bool isValid(unsigned long now=0) const ;
|
bool isValid(unsigned long now=0) const ;
|
||||||
GwBoatItemBase(String name,String format,unsigned long invalidTime=INVALID_TIME);
|
GwBoatItemBase(String name,String format,TOType toType);
|
||||||
|
GwBoatItemBase(String name,String format,unsigned long invalidTime);
|
||||||
virtual ~GwBoatItemBase(){}
|
virtual ~GwBoatItemBase(){}
|
||||||
void invalidate(){
|
void invalidate(){
|
||||||
lastSet=0;
|
lastSet=0;
|
||||||
|
@ -82,17 +94,25 @@ class GwBoatItemBase{
|
||||||
virtual double getDoubleValue()=0;
|
virtual double getDoubleValue()=0;
|
||||||
String getName(){return name;}
|
String getName(){return name;}
|
||||||
const String & getFormat() const{return format;}
|
const String & getFormat() const{return format;}
|
||||||
|
virtual void setInvalidTime(GwConfigHandler *cfg);
|
||||||
|
TOType getToType(){return toType;}
|
||||||
|
class GwBoatItemMap : public std::map<String,GwBoatItemBase*>{
|
||||||
|
GwBoatData *boatData;
|
||||||
|
public:
|
||||||
|
GwBoatItemMap(GwBoatData *bd):boatData(bd){}
|
||||||
|
void add(const String &name,GwBoatItemBase *item);
|
||||||
|
};
|
||||||
};
|
};
|
||||||
class GwBoatData;
|
|
||||||
template<class T> class GwBoatItem : public GwBoatItemBase{
|
template<class T> class GwBoatItem : public GwBoatItemBase{
|
||||||
protected:
|
protected:
|
||||||
T data;
|
T data;
|
||||||
bool lastStringValid=false;
|
bool lastStringValid=false;
|
||||||
public:
|
public:
|
||||||
GwBoatItem(String name,String formatInfo,unsigned long invalidTime=INVALID_TIME,GwBoatItemMap *map=NULL);
|
GwBoatItem(String name,String formatInfo,unsigned long invalidTime=INVALID_TIME,GwBoatItemMap *map=NULL);
|
||||||
|
GwBoatItem(String name,String formatInfo,TOType toType,GwBoatItemMap *map=NULL);
|
||||||
virtual ~GwBoatItem(){}
|
virtual ~GwBoatItem(){}
|
||||||
bool update(T nv, int source=-1);
|
bool update(T nv, int source);
|
||||||
bool updateMax(T nv,int sourceId=-1);
|
bool updateMax(T nv,int sourceId);
|
||||||
T getData(){
|
T getData(){
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
|
@ -118,14 +138,14 @@ class GwSatInfo{
|
||||||
uint32_t Elevation;
|
uint32_t Elevation;
|
||||||
uint32_t Azimut;
|
uint32_t Azimut;
|
||||||
uint32_t SNR;
|
uint32_t SNR;
|
||||||
unsigned long timestamp;
|
unsigned long validTill;
|
||||||
};
|
};
|
||||||
class GwSatInfoList{
|
class GwSatInfoList{
|
||||||
public:
|
public:
|
||||||
static const unsigned long lifeTime=32000;
|
static const GwBoatItemBase::TOType toType=GwBoatItemBase::TOType::lng;
|
||||||
std::vector<GwSatInfo> sats;
|
std::vector<GwSatInfo> sats;
|
||||||
void houseKeeping(unsigned long ts=0);
|
void houseKeeping(unsigned long ts=0);
|
||||||
void update(GwSatInfo entry);
|
void update(GwSatInfo entry, unsigned long validTill);
|
||||||
int getNumSats() const{
|
int getNumSats() const{
|
||||||
return sats.size();
|
return sats.size();
|
||||||
}
|
}
|
||||||
|
@ -139,7 +159,7 @@ class GwSatInfoList{
|
||||||
class GwBoatDataSatList : public GwBoatItem<GwSatInfoList>
|
class GwBoatDataSatList : public GwBoatItem<GwSatInfoList>
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
GwBoatDataSatList(String name, String formatInfo, unsigned long invalidTime = INVALID_TIME, GwBoatItemMap *map = NULL);
|
GwBoatDataSatList(String name, String formatInfo, GwBoatItemBase::TOType toType, GwBoatItemMap *map = NULL);
|
||||||
bool update(GwSatInfo info, int source);
|
bool update(GwSatInfo info, int source);
|
||||||
virtual void toJsonDoc(GwJsonDocument *doc, unsigned long minTime);
|
virtual void toJsonDoc(GwJsonDocument *doc, unsigned long minTime);
|
||||||
GwSatInfo *getAt(int idx){
|
GwSatInfo *getAt(int idx){
|
||||||
|
@ -164,59 +184,65 @@ public:
|
||||||
virtual unsigned long getInvalidTime(){ return GwBoatItemBase::INVALID_TIME;}
|
virtual unsigned long getInvalidTime(){ return GwBoatItemBase::INVALID_TIME;}
|
||||||
virtual ~GwBoatItemNameProvider() {}
|
virtual ~GwBoatItemNameProvider() {}
|
||||||
};
|
};
|
||||||
#define GWBOATDATA(type,name,time,fmt) \
|
#define GWBOATDATAT(type,name,toType,fmt) \
|
||||||
static constexpr const char* _##name=#name; \
|
static constexpr const char* _##name=#name; \
|
||||||
GwBoatItem<type> *name=new GwBoatItem<type>(#name,GwBoatItemBase::fmt,time,&values) ;
|
GwBoatItem<type> *name=new GwBoatItem<type>(#name,GwBoatItemBase::fmt,toType,&values) ;
|
||||||
#define GWSPECBOATDATA(clazz,name,time,fmt) \
|
#define GWBOATDATA(type,name,fmt) GWBOATDATAT(type,name,GwBoatItemBase::TOType::def,fmt)
|
||||||
clazz *name=new clazz(#name,GwBoatItemBase::fmt,time,&values) ;
|
#define GWSPECBOATDATA(clazz,name,toType,fmt) \
|
||||||
|
clazz *name=new clazz(#name,GwBoatItemBase::fmt,toType,&values) ;
|
||||||
class GwBoatData{
|
class GwBoatData{
|
||||||
private:
|
private:
|
||||||
GwLog *logger;
|
GwLog *logger=nullptr;
|
||||||
GwBoatItemBase::GwBoatItemMap values;
|
GwConfigHandler *config=nullptr;
|
||||||
|
GwBoatItemBase::GwBoatItemMap values{this};
|
||||||
public:
|
public:
|
||||||
|
|
||||||
GWBOATDATA(double,COG,4000,formatCourse)
|
GWBOATDATA(double,COG,formatCourse) // course over ground
|
||||||
GWBOATDATA(double,TWD,4000,formatCourse)
|
GWBOATDATA(double,SOG,formatKnots) // speed over ground
|
||||||
GWBOATDATA(double,SOG,4000,formatKnots)
|
GWBOATDATA(double,HDT,formatCourse) // true heading
|
||||||
GWBOATDATA(double,STW,4000,formatKnots)
|
GWBOATDATA(double,HDM,formatCourse) // magnetic heading
|
||||||
GWBOATDATA(double,TWS,4000,formatKnots)
|
GWBOATDATA(double,STW,formatKnots) // water speed
|
||||||
GWBOATDATA(double,AWS,4000,formatKnots)
|
GWBOATDATA(double,VAR,formatWind) // variation
|
||||||
GWBOATDATA(double,MaxTws,0,formatKnots)
|
GWBOATDATA(double,DEV,formatWind) // deviation
|
||||||
GWBOATDATA(double,MaxAws,0,formatKnots)
|
GWBOATDATA(double,AWA,formatWind) // apparent wind ANGLE
|
||||||
GWBOATDATA(double,AWA,4000,formatWind)
|
GWBOATDATA(double,AWS,formatKnots) // apparent wind speed
|
||||||
GWBOATDATA(double,HDG,4000,formatCourse) //true heading
|
GWBOATDATAT(double,MaxAws,GwBoatItemBase::TOType::keep,formatKnots)
|
||||||
GWBOATDATA(double,MHDG,4000,formatCourse) //magnetic heading
|
GWBOATDATA(double,TWD,formatCourse) // true wind DIRECTION
|
||||||
GWBOATDATA(double,ROT,4000,formatRot)
|
GWBOATDATA(double,TWA,formatWind) // true wind ANGLE
|
||||||
GWBOATDATA(double,VAR,4000,formatCourse) //Variation
|
GWBOATDATA(double,TWS,formatKnots) // true wind speed
|
||||||
GWBOATDATA(double,DEV,4000,formatCourse) //Deviation
|
|
||||||
GWBOATDATA(double,HDOP,4000,formatDop)
|
GWBOATDATAT(double,MaxTws,GwBoatItemBase::TOType::keep,formatKnots)
|
||||||
GWBOATDATA(double,PDOP,4000,formatDop)
|
GWBOATDATA(double,ROT,formatRot) // rate of turn
|
||||||
GWBOATDATA(double,VDOP,4000,formatDop)
|
GWBOATDATA(double,RPOS,formatWind) // rudder position
|
||||||
GWBOATDATA(double,RPOS,4000,formatWind) //RudderPosition
|
GWBOATDATA(double,PRPOS,formatWind) // secondary rudder position
|
||||||
GWBOATDATA(double,PRPOS,4000,formatWind) //second rudder pos
|
GWBOATDATA(double,LAT,formatLatitude)
|
||||||
GWBOATDATA(double,LAT,4000,formatLatitude)
|
GWBOATDATA(double,LON,formatLongitude)
|
||||||
GWBOATDATA(double,LON,4000,formatLongitude)
|
GWBOATDATA(double,ALT,formatFixed0) //altitude
|
||||||
GWBOATDATA(double,ALT,4000,formatFixed0) //altitude
|
GWBOATDATA(double,HDOP,formatDop)
|
||||||
GWBOATDATA(double,DBS,4000,formatDepth) //waterDepth (below surface)
|
GWBOATDATA(double,PDOP,formatDop)
|
||||||
GWBOATDATA(double,DBT,4000,formatDepth) //DepthTransducer
|
GWBOATDATA(double,VDOP,formatDop)
|
||||||
GWBOATDATA(double,GPST,4000,formatTime) //GpsTime
|
GWBOATDATA(double,DBS,formatDepth) //waterDepth (below surface)
|
||||||
GWBOATDATA(double,WTemp,4000,kelvinToC)
|
GWBOATDATA(double,DBT,formatDepth) //DepthTransducer
|
||||||
GWBOATDATA(double,XTE,4000,formatXte)
|
GWBOATDATA(double,GPST,formatTime) // GPS time (seconds of day)
|
||||||
GWBOATDATA(double,DTW,4000,mtr2nm) //distance wp
|
GWBOATDATA(uint32_t,GPSD,formatDate) // GPS date (days since 1979-01-01)
|
||||||
GWBOATDATA(double,BTW,4000,formatCourse) //bearing wp
|
GWBOATDATAT(int16_t,TZ,GwBoatItemBase::TOType::lng,formatFixed0)
|
||||||
GWBOATDATA(double,WPLat,4000,formatLatitude)
|
GWBOATDATA(double,WTemp,kelvinToC)
|
||||||
GWBOATDATA(double,WPLon,4000,formatLongitude)
|
GWBOATDATAT(uint32_t,Log,GwBoatItemBase::TOType::lng,mtr2nm)
|
||||||
GWBOATDATA(uint32_t,Log,16000,mtr2nm)
|
GWBOATDATAT(uint32_t,TripLog,GwBoatItemBase::TOType::lng,mtr2nm)
|
||||||
GWBOATDATA(uint32_t,TripLog,16000,mtr2nm)
|
GWBOATDATA(double,DTW,mtr2nm) // distance to waypoint
|
||||||
GWBOATDATA(uint32_t,GPSD,4000,formatDate) //Date
|
GWBOATDATA(double,BTW,formatCourse) // bearing to waypoint
|
||||||
GWBOATDATA(int16_t,TZ,8000,formatFixed0)
|
GWBOATDATA(double,XTE,formatXte) // cross track error
|
||||||
GWSPECBOATDATA(GwBoatDataSatList,SatInfo,GwSatInfoList::lifeTime,formatFixed0);
|
GWBOATDATA(double,WPLat,formatLatitude) // waypoint latitude
|
||||||
|
GWBOATDATA(double,WPLon,formatLongitude) // waypoint longitude
|
||||||
|
GWSPECBOATDATA(GwBoatDataSatList,SatInfo,GwSatInfoList::toType,formatFixed0);
|
||||||
public:
|
public:
|
||||||
GwBoatData(GwLog *logger);
|
GwBoatData(GwLog *logger, GwConfigHandler *cfg);
|
||||||
~GwBoatData();
|
~GwBoatData();
|
||||||
|
void begin();
|
||||||
template<class T> GwBoatItem<T> *getOrCreate(T initial,GwBoatItemNameProvider *provider);
|
template<class T> GwBoatItem<T> *getOrCreate(T initial,GwBoatItemNameProvider *provider);
|
||||||
template<class T> bool update(T value,int source,GwBoatItemNameProvider *provider);
|
template<class T> bool update(T value,int source,GwBoatItemNameProvider *provider);
|
||||||
template<class T> T getDataWithDefault(T defaultv, GwBoatItemNameProvider *provider);
|
template<class T> T getDataWithDefault(T defaultv, GwBoatItemNameProvider *provider);
|
||||||
|
void setInvalidTime(GwBoatItemBase *item);
|
||||||
bool isValid(String name);
|
bool isValid(String name);
|
||||||
double getDoubleValue(String name,double defaultv);
|
double getDoubleValue(String name,double defaultv);
|
||||||
GwBoatItemBase *getBase(String name);
|
GwBoatItemBase *getBase(String name);
|
||||||
|
|
|
@ -58,8 +58,6 @@ GwChannel::GwChannel(GwLog *logger,
|
||||||
this->name=name;
|
this->name=name;
|
||||||
this->sourceId=sourceId;
|
this->sourceId=sourceId;
|
||||||
this->maxSourceId=maxSourceId;
|
this->maxSourceId=maxSourceId;
|
||||||
this->countIn=new GwCounter<String>(String("count")+name+String("in"));
|
|
||||||
this->countOut=new GwCounter<String>(String("count")+name+String("out"));
|
|
||||||
this->impl=NULL;
|
this->impl=NULL;
|
||||||
this->receiver=new GwChannelMessageReceiver(logger,this);
|
this->receiver=new GwChannelMessageReceiver(logger,this);
|
||||||
this->actisenseReader=NULL;
|
this->actisenseReader=NULL;
|
||||||
|
@ -100,6 +98,12 @@ void GwChannel::begin(
|
||||||
actisenseReader->SetReadStream(channelStream);
|
actisenseReader->SetReadStream(channelStream);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (nmeaIn || readActisense){
|
||||||
|
this->countIn=new GwCounter<String>(String("count")+name+String("in"));
|
||||||
|
}
|
||||||
|
if (nmeaOut || seaSmartOut || writeActisense){
|
||||||
|
this->countOut=new GwCounter<String>(String("count")+name+String("out"));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
void GwChannel::setImpl(GwChannelInterface *impl){
|
void GwChannel::setImpl(GwChannelInterface *impl){
|
||||||
this->impl=impl;
|
this->impl=impl;
|
||||||
|
@ -135,10 +139,10 @@ void GwChannel::updateCounter(const char *msg, bool out)
|
||||||
}
|
}
|
||||||
if (key[0] == 0) return;
|
if (key[0] == 0) return;
|
||||||
if (out){
|
if (out){
|
||||||
countOut->add(key);
|
if (countOut) countOut->add(key);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
countIn->add(key);
|
if (countIn) countIn->add(key);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -209,7 +213,7 @@ void GwChannel::parseActisense(N2kHandler handler){
|
||||||
tN2kMsg N2kMsg;
|
tN2kMsg N2kMsg;
|
||||||
|
|
||||||
while (actisenseReader->GetMessageFromStream(N2kMsg)) {
|
while (actisenseReader->GetMessageFromStream(N2kMsg)) {
|
||||||
countIn->add(String(N2kMsg.PGN));
|
if(countIn) countIn->add(String(N2kMsg.PGN));
|
||||||
handler(N2kMsg,sourceId);
|
handler(N2kMsg,sourceId);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -218,14 +222,23 @@ void GwChannel::sendActisense(const tN2kMsg &msg, int sourceId){
|
||||||
if (!enabled || ! impl || ! writeActisense || ! channelStream) return;
|
if (!enabled || ! impl || ! writeActisense || ! channelStream) return;
|
||||||
//currently actisense only for channels with a single source id
|
//currently actisense only for channels with a single source id
|
||||||
//so we can check it here
|
//so we can check it here
|
||||||
if (isOwnSource(sourceId)) return;
|
if (maxSourceId < 0 && this->sourceId == sourceId) return;
|
||||||
countOut->add(String(msg.PGN));
|
if (sourceId >= this->sourceId && sourceId <= maxSourceId) return;
|
||||||
|
if(countOut) countOut->add(String(msg.PGN));
|
||||||
msg.SendInActisenseFormat(channelStream);
|
msg.SendInActisenseFormat(channelStream);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool GwChannel::isOwnSource(int id){
|
bool GwChannel::overlaps(const GwChannel *other) const{
|
||||||
if (maxSourceId < 0) return id == sourceId;
|
if (maxSourceId < 0){
|
||||||
else return (id >= sourceId && id <= maxSourceId);
|
if (other->maxSourceId < 0) return sourceId == other->sourceId;
|
||||||
|
return (other->sourceId <= sourceId && other->maxSourceId >= sourceId);
|
||||||
|
}
|
||||||
|
if (other->maxSourceId < 0){
|
||||||
|
return other->sourceId >= sourceId && other->sourceId <= maxSourceId;
|
||||||
|
}
|
||||||
|
if (other->maxSourceId < sourceId) return false;
|
||||||
|
if (other->sourceId > maxSourceId) return false;
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned long GwChannel::countRx(){
|
unsigned long GwChannel::countRx(){
|
||||||
|
|
|
@ -50,7 +50,7 @@ class GwChannel{
|
||||||
);
|
);
|
||||||
|
|
||||||
void setImpl(GwChannelInterface *impl);
|
void setImpl(GwChannelInterface *impl);
|
||||||
bool isOwnSource(int id);
|
bool overlaps(const GwChannel *) const;
|
||||||
void enable(bool enabled){
|
void enable(bool enabled){
|
||||||
this->enabled=enabled;
|
this->enabled=enabled;
|
||||||
}
|
}
|
||||||
|
@ -73,5 +73,11 @@ class GwChannel{
|
||||||
void sendActisense(const tN2kMsg &msg, int sourceId);
|
void sendActisense(const tN2kMsg &msg, int sourceId);
|
||||||
unsigned long countRx();
|
unsigned long countRx();
|
||||||
unsigned long countTx();
|
unsigned long countTx();
|
||||||
|
bool isOwnSource(int source){
|
||||||
|
if (maxSourceId < 0) return source == sourceId;
|
||||||
|
return (source >= sourceId && source <= maxSourceId);
|
||||||
|
}
|
||||||
|
String getMode(){return impl->getMode();}
|
||||||
|
int getMinId(){return sourceId;};
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -6,4 +6,5 @@ class GwChannelInterface{
|
||||||
virtual void readMessages(GwMessageFetcher *writer)=0;
|
virtual void readMessages(GwMessageFetcher *writer)=0;
|
||||||
virtual size_t sendToClients(const char *buffer, int sourceId, bool partial=false)=0;
|
virtual size_t sendToClients(const char *buffer, int sourceId, bool partial=false)=0;
|
||||||
virtual Stream * getStream(bool partialWrites){ return NULL;}
|
virtual Stream * getStream(bool partialWrites){ return NULL;}
|
||||||
|
virtual String getMode(){return "UNKNOWN";}
|
||||||
};
|
};
|
|
@ -6,6 +6,8 @@
|
||||||
#include "GwSocketServer.h"
|
#include "GwSocketServer.h"
|
||||||
#include "GwSerial.h"
|
#include "GwSerial.h"
|
||||||
#include "GwTcpClient.h"
|
#include "GwTcpClient.h"
|
||||||
|
#include "GwUdpWriter.h"
|
||||||
|
#include "GwUdpReader.h"
|
||||||
class SerInit{
|
class SerInit{
|
||||||
public:
|
public:
|
||||||
int serial=-1;
|
int serial=-1;
|
||||||
|
@ -18,15 +20,53 @@ class SerInit{
|
||||||
};
|
};
|
||||||
std::vector<SerInit> serialInits;
|
std::vector<SerInit> serialInits;
|
||||||
|
|
||||||
|
|
||||||
|
static int typeFromMode(const char *mode){
|
||||||
|
if (strcmp(mode,"UNI") == 0) return GWSERIAL_TYPE_UNI;
|
||||||
|
if (strcmp(mode,"BI") == 0) return GWSERIAL_TYPE_BI;
|
||||||
|
if (strcmp(mode,"RX") == 0) return GWSERIAL_TYPE_RX;
|
||||||
|
if (strcmp(mode,"TX") == 0) return GWSERIAL_TYPE_TX;
|
||||||
|
return GWSERIAL_TYPE_UNK;
|
||||||
|
}
|
||||||
|
|
||||||
#define CFG_SERIAL(ser,...) \
|
#define CFG_SERIAL(ser,...) \
|
||||||
__MSG("serial config " #ser); \
|
__MSG("serial config " #ser); \
|
||||||
static GwInitializer<SerInit> __serial ## ser ## _init \
|
static GwInitializer<SerInit> __serial ## ser ## _init \
|
||||||
(serialInits,SerInit(ser,__VA_ARGS__));
|
(serialInits,SerInit(ser,__VA_ARGS__));
|
||||||
#ifdef _GWI_SERIAL1
|
#ifdef _GWI_SERIAL1
|
||||||
CFG_SERIAL(1,_GWI_SERIAL1)
|
CFG_SERIAL(SERIAL1_CHANNEL_ID,_GWI_SERIAL1)
|
||||||
#endif
|
#endif
|
||||||
#ifdef _GWI_SERIAL2
|
#ifdef _GWI_SERIAL2
|
||||||
CFG_SERIAL(2,_GWI_SERIAL2)
|
CFG_SERIAL(SERIAL2_CHANNEL_ID,_GWI_SERIAL2)
|
||||||
|
#endif
|
||||||
|
// handle separate defines
|
||||||
|
// serial 1
|
||||||
|
#ifndef GWSERIAL_TX
|
||||||
|
#define GWSERIAL_TX -1
|
||||||
|
#endif
|
||||||
|
#ifndef GWSERIAL_RX
|
||||||
|
#define GWSERIAL_RX -1
|
||||||
|
#endif
|
||||||
|
#ifdef GWSERIAL_TYPE
|
||||||
|
CFG_SERIAL(SERIAL1_CHANNEL_ID, GWSERIAL_RX, GWSERIAL_TX, GWSERIAL_TYPE)
|
||||||
|
#else
|
||||||
|
#ifdef GWSERIAL_MODE
|
||||||
|
CFG_SERIAL(SERIAL1_CHANNEL_ID, GWSERIAL_RX, GWSERIAL_TX, typeFromMode(GWSERIAL_MODE))
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
// serial 2
|
||||||
|
#ifndef GWSERIAL2_TX
|
||||||
|
#define GWSERIAL2_TX -1
|
||||||
|
#endif
|
||||||
|
#ifndef GWSERIAL2_RX
|
||||||
|
#define GWSERIAL2_RX -1
|
||||||
|
#endif
|
||||||
|
#ifdef GWSERIAL2_TYPE
|
||||||
|
CFG_SERIAL(SERIAL2_CHANNEL_ID, GWSERIAL2_RX, GWSERIAL2_TX, GWSERIAL2_TYPE)
|
||||||
|
#else
|
||||||
|
#ifdef GWSERIAL2_MODE
|
||||||
|
CFG_SERIAL(SERIAL2_CHANNEL_ID, GWSERIAL2_RX, GWSERIAL2_TX, typeFromMode(GWSERIAL2_MODE))
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
class GwSerialLog : public GwLogWriter
|
class GwSerialLog : public GwLogWriter
|
||||||
{
|
{
|
||||||
|
@ -35,13 +75,12 @@ class GwSerialLog : public GwLogWriter
|
||||||
int wp = 0;
|
int wp = 0;
|
||||||
GwSerial *writer;
|
GwSerial *writer;
|
||||||
bool disabled = false;
|
bool disabled = false;
|
||||||
long flushTimeout=200;
|
|
||||||
public:
|
public:
|
||||||
GwSerialLog(GwSerial *writer, bool disabled,long flushTimeout=200)
|
GwSerialLog(GwSerial *writer, bool disabled)
|
||||||
{
|
{
|
||||||
this->writer = writer;
|
this->writer = writer;
|
||||||
this->disabled = disabled;
|
this->disabled = disabled;
|
||||||
this->flushTimeout=flushTimeout;
|
|
||||||
logBuffer = new char[bufferSize];
|
logBuffer = new char[bufferSize];
|
||||||
wp = 0;
|
wp = 0;
|
||||||
}
|
}
|
||||||
|
@ -64,15 +103,18 @@ public:
|
||||||
{
|
{
|
||||||
while (handled < wp)
|
while (handled < wp)
|
||||||
{
|
{
|
||||||
if ( !writer->flush(flushTimeout)) break;
|
if (!writer->flush())
|
||||||
|
break;
|
||||||
size_t rt = writer->sendToClients(logBuffer + handled, -1, true);
|
size_t rt = writer->sendToClients(logBuffer + handled, -1, true);
|
||||||
handled += rt;
|
handled += rt;
|
||||||
}
|
}
|
||||||
if (handled < wp){
|
if (handled < wp)
|
||||||
if (handled > 0){
|
{
|
||||||
|
if (handled > 0)
|
||||||
|
{
|
||||||
memmove(logBuffer, logBuffer + handled, wp - handled);
|
memmove(logBuffer, logBuffer + handled, wp - handled);
|
||||||
wp -= handled;
|
wp -= handled;
|
||||||
logBuffer[handled]=0;
|
logBuffer[wp] = 0;
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -82,44 +124,6 @@ public:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
template<typename T>
|
|
||||||
class SerialWrapper : public GwChannelList::SerialWrapperBase{
|
|
||||||
private:
|
|
||||||
template<class C>
|
|
||||||
void beginImpl(C *s,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1){}
|
|
||||||
void beginImpl(HardwareSerial *s,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1){
|
|
||||||
s->begin(baud,config,rxPin,txPin);
|
|
||||||
}
|
|
||||||
template<class C>
|
|
||||||
void setError(C* s, GwLog *logger){}
|
|
||||||
void setError(HardwareSerial *s,GwLog *logger){
|
|
||||||
LOG_DEBUG(GwLog::LOG,"enable serial errors for channel %d",id);
|
|
||||||
s->onReceiveError([logger,this](hardwareSerial_error_t err){
|
|
||||||
LOG_DEBUG(GwLog::ERROR,"serial error on id %d: %d",this->id,(int)err);
|
|
||||||
});
|
|
||||||
}
|
|
||||||
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32S3
|
|
||||||
void beginImpl(HWCDC *s,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1){
|
|
||||||
s->begin(baud);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
T *serial;
|
|
||||||
int id;
|
|
||||||
public:
|
|
||||||
SerialWrapper(T* s,int i):serial(s),id(i){}
|
|
||||||
virtual void begin(GwLog* logger,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1) override{
|
|
||||||
beginImpl(serial,baud,config,rxPin,txPin);
|
|
||||||
setError(serial,logger);
|
|
||||||
};
|
|
||||||
virtual Stream *getStream() override{
|
|
||||||
return serial;
|
|
||||||
}
|
|
||||||
virtual int getId() override{
|
|
||||||
return id;
|
|
||||||
}
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
GwChannelList::GwChannelList(GwLog *logger, GwConfigHandler *config){
|
GwChannelList::GwChannelList(GwLog *logger, GwConfigHandler *config){
|
||||||
this->logger=logger;
|
this->logger=logger;
|
||||||
|
@ -139,10 +143,35 @@ typedef struct {
|
||||||
const char *toN2K;
|
const char *toN2K;
|
||||||
const char *readF;
|
const char *readF;
|
||||||
const char *writeF;
|
const char *writeF;
|
||||||
|
const char *preventLog;
|
||||||
|
const char *readAct;
|
||||||
|
const char *writeAct;
|
||||||
|
const char *sendSeasmart;
|
||||||
const char *name;
|
const char *name;
|
||||||
} SerialParam;
|
int maxId;
|
||||||
|
size_t rxstatus;
|
||||||
|
size_t txstatus;
|
||||||
|
} ChannelParam;
|
||||||
|
|
||||||
static SerialParam serialParameters[]={
|
static ChannelParam channelParameters[]={
|
||||||
|
{
|
||||||
|
.id=USB_CHANNEL_ID,
|
||||||
|
.baud=GwConfigDefinitions::usbBaud,
|
||||||
|
.receive=GwConfigDefinitions::receiveUsb,
|
||||||
|
.send=GwConfigDefinitions::sendUsb,
|
||||||
|
.direction="",
|
||||||
|
.toN2K=GwConfigDefinitions::usbToN2k,
|
||||||
|
.readF=GwConfigDefinitions::usbReadFilter,
|
||||||
|
.writeF=GwConfigDefinitions::usbWriteFilter,
|
||||||
|
.preventLog=GwConfigDefinitions::usbActisense,
|
||||||
|
.readAct=GwConfigDefinitions::usbActisense,
|
||||||
|
.writeAct=GwConfigDefinitions::usbActSend,
|
||||||
|
.sendSeasmart="",
|
||||||
|
.name="USB",
|
||||||
|
.maxId=-1,
|
||||||
|
.rxstatus=offsetof(GwApi::Status,GwApi::Status::usbRx),
|
||||||
|
.txstatus=offsetof(GwApi::Status,GwApi::Status::usbTx)
|
||||||
|
},
|
||||||
{
|
{
|
||||||
.id=SERIAL1_CHANNEL_ID,
|
.id=SERIAL1_CHANNEL_ID,
|
||||||
.baud=GwConfigDefinitions::serialBaud,
|
.baud=GwConfigDefinitions::serialBaud,
|
||||||
|
@ -152,7 +181,14 @@ static SerialParam serialParameters[]={
|
||||||
.toN2K=GwConfigDefinitions::serialToN2k,
|
.toN2K=GwConfigDefinitions::serialToN2k,
|
||||||
.readF=GwConfigDefinitions::serialReadF,
|
.readF=GwConfigDefinitions::serialReadF,
|
||||||
.writeF=GwConfigDefinitions::serialWriteF,
|
.writeF=GwConfigDefinitions::serialWriteF,
|
||||||
.name="Serial"
|
.preventLog="",
|
||||||
|
.readAct="",
|
||||||
|
.writeAct="",
|
||||||
|
.sendSeasmart="",
|
||||||
|
.name="Serial",
|
||||||
|
.maxId=-1,
|
||||||
|
.rxstatus=offsetof(GwApi::Status,GwApi::Status::serRx),
|
||||||
|
.txstatus=offsetof(GwApi::Status,GwApi::Status::serTx)
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
.id=SERIAL2_CHANNEL_ID,
|
.id=SERIAL2_CHANNEL_ID,
|
||||||
|
@ -163,81 +199,162 @@ static SerialParam serialParameters[]={
|
||||||
.toN2K=GwConfigDefinitions::serial2ToN2k,
|
.toN2K=GwConfigDefinitions::serial2ToN2k,
|
||||||
.readF=GwConfigDefinitions::serial2ReadF,
|
.readF=GwConfigDefinitions::serial2ReadF,
|
||||||
.writeF=GwConfigDefinitions::serial2WriteF,
|
.writeF=GwConfigDefinitions::serial2WriteF,
|
||||||
.name="Serial2"
|
.preventLog="",
|
||||||
|
.readAct="",
|
||||||
|
.writeAct="",
|
||||||
|
.sendSeasmart="",
|
||||||
|
.name="Serial2",
|
||||||
|
.maxId=-1,
|
||||||
|
.rxstatus=offsetof(GwApi::Status,GwApi::Status::ser2Rx),
|
||||||
|
.txstatus=offsetof(GwApi::Status,GwApi::Status::ser2Tx)
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.id=MIN_TCP_CHANNEL_ID,
|
||||||
|
.baud="",
|
||||||
|
.receive=GwConfigDefinitions::readTCP,
|
||||||
|
.send=GwConfigDefinitions::sendTCP,
|
||||||
|
.direction="",
|
||||||
|
.toN2K=GwConfigDefinitions::tcpToN2k,
|
||||||
|
.readF=GwConfigDefinitions::tcpReadFilter,
|
||||||
|
.writeF=GwConfigDefinitions::tcpWriteFilter,
|
||||||
|
.preventLog="",
|
||||||
|
.readAct="",
|
||||||
|
.writeAct="",
|
||||||
|
.sendSeasmart=GwConfigDefinitions::sendSeasmart,
|
||||||
|
.name="TCPServer",
|
||||||
|
.maxId=MIN_TCP_CHANNEL_ID+10,
|
||||||
|
.rxstatus=offsetof(GwApi::Status,GwApi::Status::tcpSerRx),
|
||||||
|
.txstatus=offsetof(GwApi::Status,GwApi::Status::tcpSerTx)
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.id=TCP_CLIENT_CHANNEL_ID,
|
||||||
|
.baud="",
|
||||||
|
.receive=GwConfigDefinitions::readTCL,
|
||||||
|
.send=GwConfigDefinitions::sendTCL,
|
||||||
|
.direction="",
|
||||||
|
.toN2K=GwConfigDefinitions::tclToN2k,
|
||||||
|
.readF=GwConfigDefinitions::tclReadFilter,
|
||||||
|
.writeF=GwConfigDefinitions::tclWriteFilter,
|
||||||
|
.preventLog="",
|
||||||
|
.readAct="",
|
||||||
|
.writeAct="",
|
||||||
|
.sendSeasmart=GwConfigDefinitions::tclSeasmart,
|
||||||
|
.name="TCPClient",
|
||||||
|
.maxId=-1,
|
||||||
|
.rxstatus=offsetof(GwApi::Status,GwApi::Status::tcpClRx),
|
||||||
|
.txstatus=offsetof(GwApi::Status,GwApi::Status::tcpClTx)
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.id=UDPW_CHANNEL_ID,
|
||||||
|
.baud="",
|
||||||
|
.receive="",
|
||||||
|
.send=GwConfigDefinitions::udpwEnabled,
|
||||||
|
.direction="",
|
||||||
|
.toN2K="",
|
||||||
|
.readF="",
|
||||||
|
.writeF=GwConfigDefinitions::udpwWriteFilter,
|
||||||
|
.preventLog="",
|
||||||
|
.readAct="",
|
||||||
|
.writeAct="",
|
||||||
|
.sendSeasmart=GwConfigDefinitions::udpwSeasmart,
|
||||||
|
.name="UDPWriter",
|
||||||
|
.maxId=-1,
|
||||||
|
.rxstatus=0,
|
||||||
|
.txstatus=offsetof(GwApi::Status,GwApi::Status::udpwTx)
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.id=UDPR_CHANNEL_ID,
|
||||||
|
.baud="",
|
||||||
|
.receive=GwConfigDefinitions::udprEnabled,
|
||||||
|
.send="",
|
||||||
|
.direction="",
|
||||||
|
.toN2K=GwConfigDefinitions::udprToN2k,
|
||||||
|
.readF=GwConfigDefinitions::udprReadFilter,
|
||||||
|
.writeF="",
|
||||||
|
.preventLog="",
|
||||||
|
.readAct="",
|
||||||
|
.writeAct="",
|
||||||
|
.sendSeasmart="",
|
||||||
|
.name="UDPReader",
|
||||||
|
.maxId=-1,
|
||||||
|
.rxstatus=offsetof(GwApi::Status,GwApi::Status::udprRx),
|
||||||
|
.txstatus=0
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
static SerialParam *getSerialParam(int id){
|
template<typename T>
|
||||||
for (size_t idx=0;idx<sizeof(serialParameters)/sizeof(SerialParam*);idx++){
|
GwSerial* createSerial(GwLog *logger, T* s,int id, bool canRead=true){
|
||||||
if (serialParameters[idx].id == id) return &serialParameters[idx];
|
return new GwSerialImpl<T>(logger,s,id,canRead);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static ChannelParam * findChannelParam(int id){
|
||||||
|
ChannelParam *param=nullptr;
|
||||||
|
for (auto && p: channelParameters){
|
||||||
|
if (id == p.id){
|
||||||
|
param=&p;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return param;
|
||||||
|
}
|
||||||
|
|
||||||
|
static GwSerial * createSerialImpl(GwConfigHandler *config,GwLog *logger, int idx,int rx,int tx, bool setLog=false){
|
||||||
|
LOG_DEBUG(GwLog::DEBUG,"create serial: channel=%d, rx=%d,tx=%d",
|
||||||
|
idx,rx,tx);
|
||||||
|
ChannelParam *param=findChannelParam(idx);
|
||||||
|
if (param == nullptr){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"invalid serial channel id %d",idx);
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
void GwChannelList::addSerial(int id, int rx, int tx, int type){
|
GwSerial *serialStream=nullptr;
|
||||||
if (id == 1){
|
GwLog *streamLog=setLog?nullptr:logger;
|
||||||
addSerial(new SerialWrapper<decltype(Serial1)>(&Serial1,SERIAL1_CHANNEL_ID),type,rx,tx);
|
switch(param->id){
|
||||||
return;
|
case USB_CHANNEL_ID:
|
||||||
}
|
serialStream=createSerial(streamLog,&USBSerial,param->id);
|
||||||
if (id == 2){
|
|
||||||
addSerial(new SerialWrapper<decltype(Serial2)>(&Serial2,SERIAL2_CHANNEL_ID),type,rx,tx);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
LOG_DEBUG(GwLog::ERROR,"invalid serial config with id %d",id);
|
|
||||||
}
|
|
||||||
void GwChannelList::addSerial(GwChannelList::SerialWrapperBase *stream,int type,int rx,int tx){
|
|
||||||
const char *mode=nullptr;
|
|
||||||
switch (type)
|
|
||||||
{
|
|
||||||
case GWSERIAL_TYPE_UNI:
|
|
||||||
mode="UNI";
|
|
||||||
break;
|
break;
|
||||||
case GWSERIAL_TYPE_BI:
|
case SERIAL1_CHANNEL_ID:
|
||||||
mode="BI";
|
serialStream=createSerial(streamLog,&Serial1,param->id);
|
||||||
break;
|
break;
|
||||||
case GWSERIAL_TYPE_RX:
|
case SERIAL2_CHANNEL_ID:
|
||||||
mode="RX";
|
serialStream=createSerial(streamLog,&Serial2,param->id);
|
||||||
break;
|
|
||||||
case GWSERIAL_TYPE_TX:
|
|
||||||
mode="TX";
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (mode == nullptr) {
|
if (serialStream == nullptr){
|
||||||
LOG_DEBUG(GwLog::ERROR,"unknown serial type %d",type);
|
LOG_DEBUG(GwLog::ERROR,"invalid serial config with id %d",param->id);
|
||||||
return;
|
return nullptr;
|
||||||
}
|
}
|
||||||
addSerial(stream,mode,rx,tx);
|
serialStream->begin(config->getInt(param->baud,115200),SERIAL_8N1,rx,tx);
|
||||||
|
if (setLog){
|
||||||
|
logger->setWriter(new GwSerialLog(serialStream,config->getBool(param->preventLog,false)));
|
||||||
|
logger->prefix="GWSERIAL:";
|
||||||
}
|
}
|
||||||
void GwChannelList::addSerial(GwChannelList::SerialWrapperBase *serialStream,const String &mode,int rx,int tx){
|
return serialStream;
|
||||||
int id=serialStream->getId();
|
|
||||||
for (auto &&it:theChannels){
|
|
||||||
if (it->isOwnSource(id)){
|
|
||||||
LOG_DEBUG(GwLog::ERROR,"trying to re-add serial id=%d, ignoring",id);
|
|
||||||
return;
|
|
||||||
}
|
}
|
||||||
}
|
static GwChannel * createChannel(GwLog *logger, GwConfigHandler *config, int id,GwChannelInterface *impl, int type=GWSERIAL_TYPE_BI){
|
||||||
SerialParam *param=getSerialParam(id);
|
ChannelParam *param=findChannelParam(id);
|
||||||
if (param == nullptr){
|
if (param == nullptr){
|
||||||
logger->logDebug(GwLog::ERROR,"trying to set up an unknown serial channel: %d",id);
|
LOG_DEBUG(GwLog::ERROR,"invalid channel id %d",id);
|
||||||
return;
|
return nullptr;
|
||||||
}
|
}
|
||||||
if (rx < 0 && tx < 0){
|
|
||||||
logger->logDebug(GwLog::ERROR,"useless config for serial %d: both rx/tx undefined");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
modes[id]=String(mode);
|
|
||||||
bool canRead=false;
|
bool canRead=false;
|
||||||
bool canWrite=false;
|
bool canWrite=false;
|
||||||
if (mode == "BI"){
|
bool validType=false;
|
||||||
|
if (type == GWSERIAL_TYPE_BI){
|
||||||
canRead=config->getBool(param->receive);
|
canRead=config->getBool(param->receive);
|
||||||
canWrite=config->getBool(param->send);
|
canWrite=config->getBool(param->send);
|
||||||
|
validType=true;
|
||||||
}
|
}
|
||||||
if (mode == "TX"){
|
if (type == GWSERIAL_TYPE_TX){
|
||||||
canWrite=true;
|
canWrite=true;
|
||||||
|
validType=true;
|
||||||
}
|
}
|
||||||
if (mode == "RX"){
|
if (type == GWSERIAL_TYPE_RX){
|
||||||
canRead=true;
|
canRead=true;
|
||||||
|
validType=true;
|
||||||
}
|
}
|
||||||
if (mode == "UNI"){
|
if (type == GWSERIAL_TYPE_UNI ){
|
||||||
String cfgMode=config->getString(param->direction);
|
String cfgMode=config->getString(param->direction);
|
||||||
if (cfgMode == "receive"){
|
if (cfgMode == "receive"){
|
||||||
canRead=true;
|
canRead=true;
|
||||||
|
@ -245,138 +362,102 @@ void GwChannelList::addSerial(GwChannelList::SerialWrapperBase *serialStream,con
|
||||||
if (cfgMode == "send"){
|
if (cfgMode == "send"){
|
||||||
canWrite=true;
|
canWrite=true;
|
||||||
}
|
}
|
||||||
|
validType=true;
|
||||||
}
|
}
|
||||||
if (rx < 0) canRead=false;
|
if (! validType){
|
||||||
if (tx < 0) canWrite=false;
|
LOG_DEBUG(GwLog::ERROR,"invalid type for channel %d: %d",param->id,type);
|
||||||
LOG_DEBUG(GwLog::DEBUG,"serial set up: mode=%s,rx=%d,canRead=%d,tx=%d,canWrite=%d",
|
return nullptr;
|
||||||
mode.c_str(),rx,(int)canRead,tx,(int)canWrite);
|
}
|
||||||
serialStream->begin(logger,config->getInt(param->baud,115200),SERIAL_8N1,rx,tx);
|
GwChannel *channel = new GwChannel(logger, param->name,param->id,param->maxId);
|
||||||
GwSerial *serial = new GwSerial(logger, serialStream->getStream(), id, canRead);
|
bool sendSeaSmart=config->getBool(param->sendSeasmart);
|
||||||
LOG_DEBUG(GwLog::LOG, "starting serial %d ", id);
|
bool readAct=config->getBool(param->readAct);
|
||||||
GwChannel *channel = new GwChannel(logger, param->name, id);
|
bool writeAct=config->getBool(param->writeAct);
|
||||||
channel->setImpl(serial);
|
channel->setImpl(impl);
|
||||||
channel->begin(
|
channel->begin(
|
||||||
canRead || canWrite,
|
canRead || canWrite || readAct || writeAct|| sendSeaSmart,
|
||||||
canWrite,
|
canWrite,
|
||||||
canRead,
|
canRead,
|
||||||
config->getString(param->readF),
|
config->getString(param->readF),
|
||||||
config->getString(param->writeF),
|
config->getString(param->writeF),
|
||||||
false,
|
sendSeaSmart,
|
||||||
config->getBool(param->toN2K),
|
config->getBool(param->toN2K),
|
||||||
false,
|
readAct,
|
||||||
false);
|
writeAct);
|
||||||
LOG_DEBUG(GwLog::LOG, "%s", channel->toString().c_str());
|
LOG_INFO("created channel %s",channel->toString().c_str());
|
||||||
|
return channel;
|
||||||
|
}
|
||||||
|
void GwChannelList::addChannel(GwChannel * channel){
|
||||||
|
if (channel == nullptr) return;
|
||||||
|
for (auto &&it:theChannels){
|
||||||
|
if (it->overlaps(channel)){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"trying to add channel with overlapping ids %s (%s), ignoring",
|
||||||
|
channel->toString().c_str(),
|
||||||
|
it->toString().c_str());
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
LOG_INFO("adding channel %s", channel->toString().c_str());
|
||||||
theChannels.push_back(channel);
|
theChannels.push_back(channel);
|
||||||
}
|
}
|
||||||
void GwChannelList::preinit(){
|
void GwChannelList::preinit(){
|
||||||
for (auto &&init:serialInits){
|
for (auto &&init:serialInits){
|
||||||
|
LOG_INFO("serial config found for %d",init.serial);
|
||||||
if (init.fixedBaud >= 0){
|
if (init.fixedBaud >= 0){
|
||||||
switch(init.serial){
|
ChannelParam *param=findChannelParam(init.serial);
|
||||||
case 1:
|
if (! param){
|
||||||
{
|
LOG_ERROR("invalid serial definition %d found",init.serial)
|
||||||
LOG_DEBUG(GwLog::DEBUG,"setting fixed baud %d for serial",init.fixedBaud);
|
return;
|
||||||
config->setValue(GwConfigDefinitions::serialBaud,String(init.fixedBaud),GwConfigInterface::READONLY);
|
|
||||||
}
|
}
|
||||||
break;
|
LOG_DEBUG(GwLog::DEBUG,"setting fixed baud %d for serial %d",init.fixedBaud,init.serial);
|
||||||
case 2:
|
config->setValue(param->baud,String(init.fixedBaud),GwConfigInterface::READONLY);
|
||||||
{
|
|
||||||
LOG_DEBUG(GwLog::DEBUG,"setting fixed baud %d for serial2",init.fixedBaud);
|
|
||||||
config->setValue(GwConfigDefinitions::serial2Baud,String(init.fixedBaud),GwConfigInterface::READONLY);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
LOG_DEBUG(GwLog::ERROR,"invalid serial definition %d found",init.serial)
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
#ifndef GWUSB_TX
|
||||||
template<typename S>
|
#define GWUSB_TX -1
|
||||||
long getFlushTimeout(S &s){
|
#endif
|
||||||
return 200;
|
#ifndef GWUSB_RX
|
||||||
}
|
#define GWUSB_RX -1
|
||||||
template<>
|
#endif
|
||||||
long getFlushTimeout(HardwareSerial &s){
|
|
||||||
return 2000;
|
|
||||||
}
|
|
||||||
void GwChannelList::begin(bool fallbackSerial){
|
void GwChannelList::begin(bool fallbackSerial){
|
||||||
LOG_DEBUG(GwLog::DEBUG,"GwChannelList::begin");
|
LOG_DEBUG(GwLog::DEBUG,"GwChannelList::begin");
|
||||||
GwChannel *channel=NULL;
|
GwChannel *channel=NULL;
|
||||||
//usb
|
//usb
|
||||||
if (! fallbackSerial){
|
if (! fallbackSerial){
|
||||||
GwSerial *usb=new GwSerial(NULL,&USBSerial,USB_CHANNEL_ID);
|
GwSerial *usbSerial=createSerialImpl(config, logger,USB_CHANNEL_ID,GWUSB_RX,GWUSB_TX,true);
|
||||||
USBSerial.begin(config->getInt(config->usbBaud));
|
if (usbSerial != nullptr){
|
||||||
logger->setWriter(new GwSerialLog(usb,config->getBool(config->usbActisense),getFlushTimeout(USBSerial)));
|
GwChannel *usbChannel=createChannel(logger,config,USB_CHANNEL_ID,usbSerial,GWSERIAL_TYPE_BI);
|
||||||
logger->prefix="GWSERIAL:";
|
if (usbChannel != nullptr){
|
||||||
channel=new GwChannel(logger,"USB",USB_CHANNEL_ID);
|
addChannel(usbChannel);
|
||||||
channel->setImpl(usb);
|
}
|
||||||
channel->begin(true,
|
else{
|
||||||
config->getBool(config->sendUsb),
|
delete usbSerial;
|
||||||
config->getBool(config->receiveUsb),
|
}
|
||||||
config->getString(config->usbReadFilter),
|
}
|
||||||
config->getString(config->usbWriteFilter),
|
|
||||||
false,
|
|
||||||
config->getBool(config->usbToN2k),
|
|
||||||
config->getBool(config->usbActisense),
|
|
||||||
config->getBool(config->usbActSend)
|
|
||||||
);
|
|
||||||
theChannels.push_back(channel);
|
|
||||||
LOG_DEBUG(GwLog::LOG,"%s",channel->toString().c_str());
|
|
||||||
}
|
}
|
||||||
//TCP server
|
//TCP server
|
||||||
sockets=new GwSocketServer(config,logger,MIN_TCP_CHANNEL_ID);
|
sockets=new GwSocketServer(config,logger,MIN_TCP_CHANNEL_ID);
|
||||||
sockets->begin();
|
sockets->begin();
|
||||||
channel=new GwChannel(logger,"TCPserver",MIN_TCP_CHANNEL_ID,MIN_TCP_CHANNEL_ID+10);
|
addChannel(createChannel(logger,config,MIN_TCP_CHANNEL_ID,sockets));
|
||||||
channel->setImpl(sockets);
|
|
||||||
channel->begin(
|
|
||||||
true,
|
|
||||||
config->getBool(config->sendTCP),
|
|
||||||
config->getBool(config->readTCP),
|
|
||||||
config->getString(config->tcpReadFilter),
|
|
||||||
config->getString(config->tcpWriteFilter),
|
|
||||||
config->getBool(config->sendSeasmart),
|
|
||||||
config->getBool(config->tcpToN2k),
|
|
||||||
false,
|
|
||||||
false
|
|
||||||
);
|
|
||||||
LOG_DEBUG(GwLog::LOG,"%s",channel->toString().c_str());
|
|
||||||
theChannels.push_back(channel);
|
|
||||||
|
|
||||||
//new serial config handling
|
//new serial config handling
|
||||||
for (auto &&init:serialInits){
|
for (auto &&init:serialInits){
|
||||||
addSerial(init.serial,init.rx,init.tx,init.mode);
|
LOG_INFO("creating serial channel %d, rx=%d,tx=%d,type=%d",init.serial,init.rx,init.tx,init.mode);
|
||||||
|
GwSerial *ser=createSerialImpl(config,logger,init.serial,init.rx,init.tx);
|
||||||
|
if (ser != nullptr){
|
||||||
|
channel=createChannel(logger,config,init.serial,ser,init.mode);
|
||||||
|
if (channel != nullptr){
|
||||||
|
addChannel(channel);
|
||||||
}
|
}
|
||||||
//handle separate defines
|
else{
|
||||||
//serial 1
|
delete ser;
|
||||||
#ifndef GWSERIAL_TX
|
}
|
||||||
#define GWSERIAL_TX -1
|
}
|
||||||
#endif
|
}
|
||||||
#ifndef GWSERIAL_RX
|
|
||||||
#define GWSERIAL_RX -1
|
|
||||||
#endif
|
|
||||||
#ifdef GWSERIAL_TYPE
|
|
||||||
addSerial(new SerialWrapper<decltype(Serial1)>(&Serial1,SERIAL1_CHANNEL_ID),GWSERIAL_TYPE,GWSERIAL_RX,GWSERIAL_TX);
|
|
||||||
#else
|
|
||||||
#ifdef GWSERIAL_MODE
|
|
||||||
addSerial(new SerialWrapper<decltype(Serial1)>(&Serial1,SERIAL1_CHANNEL_ID),GWSERIAL_MODE,GWSERIAL_RX,GWSERIAL_TX);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
//serial 2
|
|
||||||
#ifndef GWSERIAL2_TX
|
|
||||||
#define GWSERIAL2_TX -1
|
|
||||||
#endif
|
|
||||||
#ifndef GWSERIAL2_RX
|
|
||||||
#define GWSERIAL2_RX -1
|
|
||||||
#endif
|
|
||||||
#ifdef GWSERIAL2_TYPE
|
|
||||||
addSerial(new SerialWrapper<decltype(Serial2)>(&Serial2,SERIAL2_CHANNEL_ID),GWSERIAL2_TYPE,GWSERIAL2_RX,GWSERIAL2_TX);
|
|
||||||
#else
|
|
||||||
#ifdef GWSERIAL2_MODE
|
|
||||||
addSerial(new SerialWrapper<decltype(Serial2)>(&Serial2,SERIAL2_CHANNEL_ID),GWSERIAL2_MODE,GWSERIAL2_RX,GWSERIAL2_TX);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
//tcp client
|
//tcp client
|
||||||
bool tclEnabled=config->getBool(config->tclEnabled);
|
bool tclEnabled=config->getBool(config->tclEnabled);
|
||||||
channel=new GwChannel(logger,"TCPClient",TCP_CLIENT_CHANNEL_ID);
|
|
||||||
if (tclEnabled){
|
if (tclEnabled){
|
||||||
client=new GwTcpClient(logger);
|
client=new GwTcpClient(logger);
|
||||||
client->begin(TCP_CLIENT_CHANNEL_ID,
|
client->begin(TCP_CLIENT_CHANNEL_ID,
|
||||||
|
@ -384,26 +465,27 @@ void GwChannelList::begin(bool fallbackSerial){
|
||||||
config->getInt(config->remotePort),
|
config->getInt(config->remotePort),
|
||||||
config->getBool(config->readTCL)
|
config->getBool(config->readTCL)
|
||||||
);
|
);
|
||||||
channel->setImpl(client);
|
|
||||||
}
|
}
|
||||||
channel->begin(
|
addChannel(createChannel(logger,config,TCP_CLIENT_CHANNEL_ID,client));
|
||||||
tclEnabled,
|
|
||||||
config->getBool(config->sendTCL),
|
//udp writer
|
||||||
config->getBool(config->readTCL),
|
if (config->getBool(GwConfigDefinitions::udpwEnabled)){
|
||||||
config->getString(config->tclReadFilter),
|
GwUdpWriter *writer=new GwUdpWriter(config,logger,UDPW_CHANNEL_ID);
|
||||||
config->getString(config->tclReadFilter),
|
writer->begin();
|
||||||
config->getBool(config->tclSeasmart),
|
addChannel(createChannel(logger,config,UDPW_CHANNEL_ID,writer));
|
||||||
config->getBool(config->tclToN2k),
|
}
|
||||||
false,
|
//udp reader
|
||||||
false
|
if (config->getBool(GwConfigDefinitions::udprEnabled)){
|
||||||
);
|
GwUdpReader *reader=new GwUdpReader(config,logger,UDPR_CHANNEL_ID);
|
||||||
theChannels.push_back(channel);
|
reader->begin();
|
||||||
LOG_DEBUG(GwLog::LOG,"%s",channel->toString().c_str());
|
addChannel(createChannel(logger,config,UDPR_CHANNEL_ID,reader));
|
||||||
|
}
|
||||||
logger->flush();
|
logger->flush();
|
||||||
}
|
}
|
||||||
String GwChannelList::getMode(int id){
|
String GwChannelList::getMode(int id){
|
||||||
auto it=modes.find(id);
|
for (auto && c: theChannels){
|
||||||
if (it != modes.end()) return it->second;
|
if (c->isOwnSource(id)) return c->getMode();
|
||||||
|
}
|
||||||
return "UNKNOWN";
|
return "UNKNOWN";
|
||||||
}
|
}
|
||||||
int GwChannelList::getJsonSize(){
|
int GwChannelList::getJsonSize(){
|
||||||
|
@ -428,36 +510,28 @@ void GwChannelList::toJson(GwJsonDocument &doc){
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
GwChannel *GwChannelList::getChannelById(int sourceId){
|
GwChannel *GwChannelList::getChannelById(int sourceId){
|
||||||
for (auto it=theChannels.begin();it != theChannels.end();it++){
|
for (auto && it: theChannels){
|
||||||
if ((*it)->isOwnSource(sourceId)) return *it;
|
if (it->isOwnSource(sourceId)) return it;
|
||||||
}
|
}
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* slightly tricky generic setter for the API status
|
||||||
|
* we expect all values to be unsigned long
|
||||||
|
* the offsets are always offsetof(GwApi::Status,GwApi::Status::xxx)
|
||||||
|
*/
|
||||||
|
static void setStatus(GwApi::Status *status,size_t offset,unsigned long v){
|
||||||
|
if (offset == 0) return;
|
||||||
|
*((unsigned long *)(((unsigned char *)status)+offset))=v;
|
||||||
|
}
|
||||||
|
|
||||||
void GwChannelList::fillStatus(GwApi::Status &status){
|
void GwChannelList::fillStatus(GwApi::Status &status){
|
||||||
GwChannel *channel=getChannelById(USB_CHANNEL_ID);
|
for (auto && channel: theChannels){
|
||||||
if (channel){
|
ChannelParam *param=findChannelParam(channel->getMinId());
|
||||||
status.usbRx=channel->countRx();
|
if (param != nullptr){
|
||||||
status.usbTx=channel->countTx();
|
setStatus(&status,param->rxstatus,channel->countRx());
|
||||||
}
|
setStatus(&status,param->txstatus,channel->countTx());
|
||||||
channel=getChannelById(SERIAL1_CHANNEL_ID);
|
}
|
||||||
if (channel){
|
|
||||||
status.serRx=channel->countRx();
|
|
||||||
status.serTx=channel->countTx();
|
|
||||||
}
|
|
||||||
channel=getChannelById(SERIAL2_CHANNEL_ID);
|
|
||||||
if (channel){
|
|
||||||
status.ser2Rx=channel->countRx();
|
|
||||||
status.ser2Tx=channel->countTx();
|
|
||||||
}
|
|
||||||
channel=getChannelById(MIN_TCP_CHANNEL_ID);
|
|
||||||
if (channel){
|
|
||||||
status.tcpSerRx=channel->countRx();
|
|
||||||
status.tcpSerTx=channel->countTx();
|
|
||||||
}
|
|
||||||
channel=getChannelById(TCP_CLIENT_CHANNEL_ID);
|
|
||||||
if (channel){
|
|
||||||
status.tcpClRx=channel->countRx();
|
|
||||||
status.tcpClTx=channel->countTx();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -8,6 +8,7 @@
|
||||||
#include "GWConfig.h"
|
#include "GWConfig.h"
|
||||||
#include "GwJsonDocument.h"
|
#include "GwJsonDocument.h"
|
||||||
#include "GwApi.h"
|
#include "GwApi.h"
|
||||||
|
#include "GwSerial.h"
|
||||||
#include <HardwareSerial.h>
|
#include <HardwareSerial.h>
|
||||||
|
|
||||||
//NMEA message channels
|
//NMEA message channels
|
||||||
|
@ -17,29 +18,22 @@
|
||||||
#define SERIAL2_CHANNEL_ID 3
|
#define SERIAL2_CHANNEL_ID 3
|
||||||
#define TCP_CLIENT_CHANNEL_ID 4
|
#define TCP_CLIENT_CHANNEL_ID 4
|
||||||
#define MIN_TCP_CHANNEL_ID 5
|
#define MIN_TCP_CHANNEL_ID 5
|
||||||
|
#define UDPW_CHANNEL_ID 20
|
||||||
|
#define UDPR_CHANNEL_ID 21
|
||||||
|
|
||||||
#define MIN_USER_TASK 200
|
#define MIN_USER_TASK 200
|
||||||
class GwSocketServer;
|
class GwSocketServer;
|
||||||
class GwTcpClient;
|
class GwTcpClient;
|
||||||
class GwChannelList{
|
class GwChannelList{
|
||||||
private:
|
private:
|
||||||
class SerialWrapperBase{
|
|
||||||
public:
|
|
||||||
virtual void begin(GwLog* logger,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1)=0;
|
|
||||||
virtual Stream *getStream()=0;
|
|
||||||
virtual int getId()=0;
|
|
||||||
};
|
|
||||||
GwLog *logger;
|
GwLog *logger;
|
||||||
GwConfigHandler *config;
|
GwConfigHandler *config;
|
||||||
typedef std::vector<GwChannel *> ChannelList;
|
typedef std::vector<GwChannel *> ChannelList;
|
||||||
ChannelList theChannels;
|
ChannelList theChannels;
|
||||||
std::map<int,String> modes;
|
|
||||||
GwSocketServer *sockets;
|
GwSocketServer *sockets;
|
||||||
GwTcpClient *client;
|
GwTcpClient *client;
|
||||||
void addSerial(SerialWrapperBase *stream,const String &mode,int rx,int tx);
|
|
||||||
void addSerial(SerialWrapperBase *stream,int type,int rx,int tx);
|
|
||||||
public:
|
public:
|
||||||
void addSerial(int id, int rx, int tx, int type);
|
void addChannel(GwChannel *);
|
||||||
GwChannelList(GwLog *logger, GwConfigHandler *config);
|
GwChannelList(GwLog *logger, GwConfigHandler *config);
|
||||||
typedef std::function<void(GwChannel *)> ChannelAction;
|
typedef std::function<void(GwChannel *)> ChannelAction;
|
||||||
void allChannels(ChannelAction action);
|
void allChannels(ChannelAction action);
|
||||||
|
|
|
@ -4,6 +4,7 @@
|
||||||
#include <ArduinoJson.h>
|
#include <ArduinoJson.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include <MD5Builder.h>
|
#include <MD5Builder.h>
|
||||||
|
#include <esp_partition.h>
|
||||||
using CfgInit=std::function<void(GwConfigHandler *)>;
|
using CfgInit=std::function<void(GwConfigHandler *)>;
|
||||||
static std::vector<CfgInit> cfgInits;
|
static std::vector<CfgInit> cfgInits;
|
||||||
#define CFG_INIT(name,value,mode) \
|
#define CFG_INIT(name,value,mode) \
|
||||||
|
@ -96,15 +97,36 @@ bool GwConfigHandler::updateValue(String name, String value){
|
||||||
if (i->asString() == value){
|
if (i->asString() == value){
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
LOG_DEBUG(GwLog::LOG,"update config %s=>%s",name.c_str(),i->isSecret()?"***":value.c_str());
|
|
||||||
prefs->begin(PREF_NAME,false);
|
prefs->begin(PREF_NAME,false);
|
||||||
prefs->putString(i->getName().c_str(),value);
|
prefs->putString(i->getName().c_str(),value);
|
||||||
|
LOG_DEBUG(GwLog::LOG,"update config %s=>%s, freeEntries=%d",name.c_str(),i->isSecret()?"***":value.c_str(),(int)(prefs->freeEntries()));
|
||||||
prefs->end();
|
prefs->end();
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
bool GwConfigHandler::reset(){
|
bool GwConfigHandler::reset(){
|
||||||
LOG_DEBUG(GwLog::LOG,"reset config");
|
LOG_DEBUG(GwLog::ERROR,"reset config");
|
||||||
|
//try to find the nvs partition
|
||||||
|
//currently we only support the default
|
||||||
|
bool wiped=false;
|
||||||
|
const esp_partition_t *nvspart=esp_partition_find_first(ESP_PARTITION_TYPE_DATA,ESP_PARTITION_SUBTYPE_DATA_NVS,"nvs");
|
||||||
|
if (nvspart != NULL){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"wiping nvs partition");
|
||||||
|
esp_err_t err=esp_partition_erase_range(nvspart,0,nvspart->size);
|
||||||
|
if (err != ESP_OK){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"wiping nvs partition failed: %d",(int)err);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
wiped=true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"nvs partition not found");
|
||||||
|
}
|
||||||
|
if (wiped){
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"unable to wipe nvs partition, trying to reset values");
|
||||||
prefs->begin(PREF_NAME,false);
|
prefs->begin(PREF_NAME,false);
|
||||||
for (int i=0;i<getNumConfig();i++){
|
for (int i=0;i<getNumConfig();i++){
|
||||||
prefs->putString(configs[i]->getName().c_str(),configs[i]->getDefault());
|
prefs->putString(configs[i]->getName().c_str(),configs[i]->getDefault());
|
||||||
|
|
|
@ -16,16 +16,63 @@
|
||||||
#define _GWCONVERTERCONFIG_H
|
#define _GWCONVERTERCONFIG_H
|
||||||
|
|
||||||
#include "GWConfig.h"
|
#include "GWConfig.h"
|
||||||
|
#include "N2kTypes.h"
|
||||||
|
#include <map>
|
||||||
|
|
||||||
|
//list of configs for the PGN 130306 wind references
|
||||||
|
static std::map<tN2kWindReference,String> windConfigs={
|
||||||
|
{N2kWind_True_water,GwConfigDefinitions::windmtra},
|
||||||
|
{N2kWind_Apparent,GwConfigDefinitions::windmawa},
|
||||||
|
{N2kWind_True_boat,GwConfigDefinitions::windmgna},
|
||||||
|
{N2kWind_Magnetic,GwConfigDefinitions::windmmgd},
|
||||||
|
{N2kWind_True_North,GwConfigDefinitions::windmtng},
|
||||||
|
};
|
||||||
|
|
||||||
class GwConverterConfig{
|
class GwConverterConfig{
|
||||||
public:
|
public:
|
||||||
|
class WindMapping{
|
||||||
|
public:
|
||||||
|
using Wind0183Type=enum{
|
||||||
|
AWA_AWS,
|
||||||
|
TWA_TWS,
|
||||||
|
TWD_TWS,
|
||||||
|
GWA_GWS,
|
||||||
|
GWD_GWS
|
||||||
|
};
|
||||||
|
tN2kWindReference n2kType;
|
||||||
|
Wind0183Type nmea0183Type;
|
||||||
|
bool valid=false;
|
||||||
|
WindMapping(){}
|
||||||
|
WindMapping(const tN2kWindReference &n2k,const Wind0183Type &n183):
|
||||||
|
n2kType(n2k),nmea0183Type(n183),valid(true){}
|
||||||
|
WindMapping(const tN2kWindReference &n2k,const String &n183):
|
||||||
|
n2kType(n2k){
|
||||||
|
if (n183 == "twa_tws"){
|
||||||
|
nmea0183Type=TWA_TWS;
|
||||||
|
valid=true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (n183 == "awa_aws"){
|
||||||
|
nmea0183Type=AWA_AWS;
|
||||||
|
valid=true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (n183 == "twd_tws"){
|
||||||
|
nmea0183Type=TWD_TWS;
|
||||||
|
valid=true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
int minXdrInterval=100;
|
int minXdrInterval=100;
|
||||||
int starboardRudderInstance=0;
|
int starboardRudderInstance=0;
|
||||||
int portRudderInstance=-1; //ignore
|
int portRudderInstance=-1; //ignore
|
||||||
int min2KInterval=50;
|
int min2KInterval=50;
|
||||||
int rmcInterval=1000;
|
int rmcInterval=1000;
|
||||||
int rmcCheckTime=4000;
|
int rmcCheckTime=4000;
|
||||||
void init(GwConfigHandler *config){
|
int winst312=256;
|
||||||
|
std::vector<WindMapping> windMappings;
|
||||||
|
void init(GwConfigHandler *config, GwLog*logger){
|
||||||
minXdrInterval=config->getInt(GwConfigDefinitions::minXdrInterval,100);
|
minXdrInterval=config->getInt(GwConfigDefinitions::minXdrInterval,100);
|
||||||
starboardRudderInstance=config->getInt(GwConfigDefinitions::stbRudderI,0);
|
starboardRudderInstance=config->getInt(GwConfigDefinitions::stbRudderI,0);
|
||||||
portRudderInstance=config->getInt(GwConfigDefinitions::portRudderI,-1);
|
portRudderInstance=config->getInt(GwConfigDefinitions::portRudderI,-1);
|
||||||
|
@ -36,6 +83,30 @@ class GwConverterConfig{
|
||||||
rmcInterval=config->getInt(GwConfigDefinitions::sendRMCi,1000);
|
rmcInterval=config->getInt(GwConfigDefinitions::sendRMCi,1000);
|
||||||
if (rmcInterval < 0) rmcInterval=0;
|
if (rmcInterval < 0) rmcInterval=0;
|
||||||
if (rmcInterval > 0 && rmcInterval <100) rmcInterval=100;
|
if (rmcInterval > 0 && rmcInterval <100) rmcInterval=100;
|
||||||
|
winst312=config->getInt(GwConfigDefinitions::winst312,256);
|
||||||
|
for (auto && it:windConfigs){
|
||||||
|
String cfg=config->getString(it.second);
|
||||||
|
WindMapping mapping(it.first,cfg);
|
||||||
|
if (mapping.valid){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"add wind mapping n2k=%d,nmea0183=%01d(%s)",
|
||||||
|
(int)(mapping.n2kType),(int)(mapping.nmea0183Type),cfg.c_str());
|
||||||
|
windMappings.push_back(mapping);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
const WindMapping findWindMapping(const tN2kWindReference &n2k) const{
|
||||||
|
for (const auto & it:windMappings){
|
||||||
|
if (it.n2kType == n2k) return it;
|
||||||
|
}
|
||||||
|
return WindMapping();
|
||||||
|
}
|
||||||
|
const WindMapping findWindMapping(const WindMapping::Wind0183Type &n183) const{
|
||||||
|
for (const auto & it:windMappings){
|
||||||
|
if (it.nmea0183Type == n183) return it;
|
||||||
|
}
|
||||||
|
return WindMapping();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
|
@ -7,6 +7,7 @@
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include "N2kMessages.h"
|
#include "N2kMessages.h"
|
||||||
#include "GwXdrTypeMappings.h"
|
#include "GwXdrTypeMappings.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* INVALID!!! - the next interface declaration will not work
|
* INVALID!!! - the next interface declaration will not work
|
||||||
* as it is not in the correct header file
|
* as it is not in the correct header file
|
||||||
|
@ -144,6 +145,26 @@ String formatValue(GwApi::BoatValue *value){
|
||||||
return String(buffer);
|
return String(buffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
class ExampleWebData{
|
||||||
|
SemaphoreHandle_t lock;
|
||||||
|
int data=0;
|
||||||
|
public:
|
||||||
|
ExampleWebData(){
|
||||||
|
lock=xSemaphoreCreateMutex();
|
||||||
|
}
|
||||||
|
~ExampleWebData(){
|
||||||
|
vSemaphoreDelete(lock);
|
||||||
|
}
|
||||||
|
void set(int v){
|
||||||
|
GWSYNCHRONIZED(&lock);
|
||||||
|
data=v;
|
||||||
|
}
|
||||||
|
int get(){
|
||||||
|
GWSYNCHRONIZED(&lock);
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
void exampleTask(GwApi *api){
|
void exampleTask(GwApi *api){
|
||||||
GwLog *logger=api->getLogger();
|
GwLog *logger=api->getLogger();
|
||||||
//get some configuration data
|
//get some configuration data
|
||||||
|
@ -172,8 +193,24 @@ void exampleTask(GwApi *api){
|
||||||
LOG_DEBUG(GwLog::LOG,"exampleNotWorking update returned %d",(int)nwrs);
|
LOG_DEBUG(GwLog::LOG,"exampleNotWorking update returned %d",(int)nwrs);
|
||||||
String voltageTransducer=api->getConfig()->getString(GwConfigDefinitions::exTransducer);
|
String voltageTransducer=api->getConfig()->getString(GwConfigDefinitions::exTransducer);
|
||||||
int voltageInstance=api->getConfig()->getInt(GwConfigDefinitions::exInstanceId);
|
int voltageInstance=api->getConfig()->getInt(GwConfigDefinitions::exInstanceId);
|
||||||
|
ExampleWebData webData;
|
||||||
|
/**
|
||||||
|
* an example web request handler
|
||||||
|
* it uses a synchronized data structure as it gets called from a different thread
|
||||||
|
* be aware that you must not block for longer times here!
|
||||||
|
*/
|
||||||
|
api->registerRequestHandler("data",[&webData](AsyncWebServerRequest *request){
|
||||||
|
int data=webData.get();
|
||||||
|
char buffer[30];
|
||||||
|
snprintf(buffer,29,"%d",data);
|
||||||
|
buffer[29]=0;
|
||||||
|
request->send(200,"text/plain",buffer);
|
||||||
|
});
|
||||||
|
int loopcounter=0;
|
||||||
while(true){
|
while(true){
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
loopcounter++;
|
||||||
|
webData.set(loopcounter);
|
||||||
/*
|
/*
|
||||||
* getting values from the internal data store (boatData) requires some special handling
|
* getting values from the internal data store (boatData) requires some special handling
|
||||||
* our tasks runs (potentially) at some time on a different core then the main code
|
* our tasks runs (potentially) at some time on a different core then the main code
|
||||||
|
|
|
@ -32,6 +32,26 @@ Files
|
||||||
This file allows to add some config definitions that are needed for our task. For the possible options have a look at the global [config.json](../../web/config.json). Be careful not to overwrite config defitions from the global file. A good practice wood be to prefix the names of definitions with parts of the library name. Always put them in a separate category so that they do not interfere with the system ones.
|
This file allows to add some config definitions that are needed for our task. For the possible options have a look at the global [config.json](../../web/config.json). Be careful not to overwrite config defitions from the global file. A good practice wood be to prefix the names of definitions with parts of the library name. Always put them in a separate category so that they do not interfere with the system ones.
|
||||||
The defined config items can later be accessed in the code (see the example in [GwExampleTask.cpp](GwExampleTask.cpp)).
|
The defined config items can later be accessed in the code (see the example in [GwExampleTask.cpp](GwExampleTask.cpp)).
|
||||||
|
|
||||||
|
* [index.js](index.js)<br>
|
||||||
|
You can add javascript code that will contribute to the UI of the system. The WebUI provides a small API that allows you to "hook" into some functions to include your own parts of the UI. This includes adding new tabs, modifying/replacing the data display items, modifying the status display or accessing the config items.
|
||||||
|
For the API refer to [../../web/index.js](../../web/index.js#L2001).
|
||||||
|
To start interacting just register for some events like api.EVENTS.init. You can check the capabilities you have defined to see if your task is active.
|
||||||
|
By registering an own formatter [api.addUserFormatter](../../web/index.js#L2054) you can influence the way boat data items are shown.
|
||||||
|
You can even go for an own display by registering for the event *dataItemCreated* and replace the dom element content with your own html. By additionally having added a user formatter you can now fill your own html with the current value.
|
||||||
|
By using [api.addTabPage](../../web/index.js#L2046) you can add new tabs that you can populate with your own code. Or you can link to an external URL.<br>
|
||||||
|
Please be aware that your js code is always combined with the code from the core into one js file.<br>
|
||||||
|
For fast testing there is a small python script that allow you to test the UI without always flushing each change.
|
||||||
|
Just run it with
|
||||||
|
```
|
||||||
|
tools/testServer.py nnn http://x.x.x.x/api
|
||||||
|
```
|
||||||
|
with nnn being the local port and x.x.x.x the address of a running system. Open `http://localhost:nnn` in your browser.<br>
|
||||||
|
After a change just start the compilation and reload the page.
|
||||||
|
|
||||||
|
* [index.css](index.css)<br>
|
||||||
|
You can add own css to influence the styling of the display.
|
||||||
|
|
||||||
|
|
||||||
Interfaces
|
Interfaces
|
||||||
----------
|
----------
|
||||||
The task init function and the task function interact with the core using an [API](../api/GwApi.h) that they get when started.
|
The task init function and the task function interact with the core using an [API](../api/GwApi.h) that they get when started.
|
||||||
|
@ -50,6 +70,7 @@ Files
|
||||||
* add capabilities (since 20231105 - as an alternative to a static DECLARE_CAPABILITY )
|
* add capabilities (since 20231105 - as an alternative to a static DECLARE_CAPABILITY )
|
||||||
* add a user task (since 20231105 - as an alternative to a static DECLARE_USERTASK)
|
* add a user task (since 20231105 - as an alternative to a static DECLARE_USERTASK)
|
||||||
* store or read task interface data (see below)
|
* store or read task interface data (see below)
|
||||||
|
* add a request handler for web requests (since 202411xx) - see registerRequestHandler in the API
|
||||||
|
|
||||||
|
|
||||||
__Interfacing between Task__
|
__Interfacing between Task__
|
||||||
|
|
|
@ -0,0 +1,3 @@
|
||||||
|
.examplecss{
|
||||||
|
background-color: coral;
|
||||||
|
}
|
|
@ -0,0 +1,101 @@
|
||||||
|
(function(){
|
||||||
|
const api=window.esp32nmea2k;
|
||||||
|
if (! api) return;
|
||||||
|
//we only do something if a special capability is set
|
||||||
|
//on our case this is "testboard"
|
||||||
|
//so we only start any action when we receive the init event
|
||||||
|
//and we successfully checked that our requested capability is there
|
||||||
|
const tabName="example";
|
||||||
|
const configName="exampleBDSel";
|
||||||
|
const infoUrl='https://github.com/wellenvogel/esp32-nmea2000/tree/master/lib/exampletask';
|
||||||
|
let boatItemName;
|
||||||
|
let boatItemElement;
|
||||||
|
api.registerListener((id, data) => {
|
||||||
|
//data is capabilities
|
||||||
|
//check if our requested capability is there (see GwExampleTask.h)
|
||||||
|
if (!data.testboard) return; //do nothing if we are not active
|
||||||
|
//add a simple additional tab page
|
||||||
|
//you will have to build the content of the page dynamically
|
||||||
|
//using normal dom manipulation methods
|
||||||
|
//you can use the helper addEl to create elements
|
||||||
|
let page = api.addTabPage(tabName, "Example");
|
||||||
|
api.addEl('div', 'hdg', page, "this is a test tab");
|
||||||
|
let vrow = api.addEl('div', 'row', page);
|
||||||
|
api.addEl('span', 'label', vrow, 'loops: ');
|
||||||
|
let lcount = api.addEl('span', 'value', vrow, '0');
|
||||||
|
//query the loop count
|
||||||
|
window.setInterval(() => {
|
||||||
|
fetch('/api/user/exampleTask/data')
|
||||||
|
.then((res) => {
|
||||||
|
if (!res.ok) throw Error("server error: " + res.status);
|
||||||
|
return res.text();
|
||||||
|
})
|
||||||
|
.then((txt) => {
|
||||||
|
//set the text content of our value element with what we received
|
||||||
|
lcount.textContent = txt;
|
||||||
|
})
|
||||||
|
.catch((e) => console.log("rq:", e));
|
||||||
|
}, 1000);
|
||||||
|
api.addEl('button', '', page, 'Info').addEventListener('click', function (ev) {
|
||||||
|
window.open(infoUrl, 'info');
|
||||||
|
})
|
||||||
|
//add a tab for an external URL
|
||||||
|
api.addTabPage('exhelp', 'Info', infoUrl);
|
||||||
|
//now as we know we are active - register all the listeners we need
|
||||||
|
api.registerListener((id, data) => {
|
||||||
|
console.log("exampletask status listener", data);
|
||||||
|
}, api.EVENTS.status)
|
||||||
|
api.registerListener((id, data) => {
|
||||||
|
if (data === tabName) {
|
||||||
|
//maybe we need some activity when our page is being activated
|
||||||
|
console.log("example tab activated");
|
||||||
|
}
|
||||||
|
}, api.EVENTS.tab);
|
||||||
|
|
||||||
|
api.registerListener((id, data) => {
|
||||||
|
//we have a configuration that
|
||||||
|
//gives us the name of a boat data item we would like to
|
||||||
|
//handle special
|
||||||
|
//in our case we just use an own formatter and add some
|
||||||
|
//css to the display field
|
||||||
|
//as this item can change we need to keep track of the
|
||||||
|
//last item we handled
|
||||||
|
let nextboatItemName = data[configName];
|
||||||
|
console.log("value of " + configName, nextboatItemName);
|
||||||
|
if (nextboatItemName) {
|
||||||
|
//register a user formatter that will be called whenever
|
||||||
|
//there is a new valid value
|
||||||
|
//we simply add an "X:" in front
|
||||||
|
api.addUserFormatter(nextboatItemName, "m(x)", function (v, valid) {
|
||||||
|
if (!valid) return;
|
||||||
|
return "X:" + v;
|
||||||
|
})
|
||||||
|
//after this call the item will be recreated
|
||||||
|
}
|
||||||
|
if (boatItemName !== undefined && boatItemName != nextboatItemName) {
|
||||||
|
//if the boat item that we handle has changed, remove
|
||||||
|
//the previous user formatter (this will recreate the item)
|
||||||
|
api.removeUserFormatter(boatItemName);
|
||||||
|
}
|
||||||
|
boatItemName = nextboatItemName;
|
||||||
|
boatItemElement = undefined;
|
||||||
|
}, api.EVENTS.config);
|
||||||
|
api.registerListener((id, data) => {
|
||||||
|
//this event is called whenever a data item has
|
||||||
|
//been created (or recreated)
|
||||||
|
//if this is the item we handle, we just add a css class
|
||||||
|
//we could also completely rebuild the dom below the element
|
||||||
|
//and use our formatter to directly write/draw the data
|
||||||
|
//avoid direct manipulation of the element (i.e. changing the classlist)
|
||||||
|
//as this element remains there all the time
|
||||||
|
if (boatItemName && boatItemName == data.name) {
|
||||||
|
boatItemElement = data.element;
|
||||||
|
//use the helper forEl to find elements within the dashboard item
|
||||||
|
//the value element has the class "dashValue"
|
||||||
|
api.forEl(".dashValue", function (el) {
|
||||||
|
el.classList.add("examplecss");
|
||||||
|
}, boatItemElement);
|
||||||
|
}
|
||||||
|
}, api.EVENTS.dataItemCreated);
|
||||||
|
}, api.EVENTS.init);
|
||||||
|
})();
|
|
@ -4,6 +4,7 @@
|
||||||
#include <functional>
|
#include <functional>
|
||||||
#include "GwMessage.h"
|
#include "GwMessage.h"
|
||||||
#include "GwLog.h"
|
#include "GwLog.h"
|
||||||
|
#include "GwApi.h"
|
||||||
class GwWebServer{
|
class GwWebServer{
|
||||||
private:
|
private:
|
||||||
AsyncWebServer *server;
|
AsyncWebServer *server;
|
||||||
|
@ -11,7 +12,7 @@ class GwWebServer{
|
||||||
GwLog *logger;
|
GwLog *logger;
|
||||||
public:
|
public:
|
||||||
typedef GwRequestMessage *(RequestCreator)(AsyncWebServerRequest *request);
|
typedef GwRequestMessage *(RequestCreator)(AsyncWebServerRequest *request);
|
||||||
using HandlerFunction=std::function<void(AsyncWebServerRequest *)>;
|
using HandlerFunction=GwApi::HandlerFunction;
|
||||||
GwWebServer(GwLog *logger, GwRequestQueue *queue,int port);
|
GwWebServer(GwLog *logger, GwRequestQueue *queue,int port);
|
||||||
~GwWebServer();
|
~GwWebServer();
|
||||||
void begin();
|
void begin();
|
||||||
|
|
|
@ -1,3 +1,4 @@
|
||||||
|
#include <esp_wifi.h>
|
||||||
#include "GWWifi.h"
|
#include "GWWifi.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -35,7 +36,29 @@ void GwWifi::setup(){
|
||||||
LOG_DEBUG(GwLog::ERROR,"unable to set access point mask %s, falling back to %s",
|
LOG_DEBUG(GwLog::ERROR,"unable to set access point mask %s, falling back to %s",
|
||||||
apMask.c_str(),AP_subnet.toString().c_str());
|
apMask.c_str(),AP_subnet.toString().c_str());
|
||||||
}
|
}
|
||||||
|
//try to remove any existing config from nvs
|
||||||
|
//this will avoid issues when updating from framework 6.3.2 to 6.8.1 - see #78
|
||||||
|
//we do not need the nvs config any way - so we set persistent to false
|
||||||
|
//unfortunately this will be to late (config from nvs has already been loaded)
|
||||||
|
//if we update from an older version that has config in the nvs
|
||||||
|
//so we need to make a dummy init, erase the flash and deinit
|
||||||
|
wifi_config_t conf_current;
|
||||||
|
wifi_init_config_t conf=WIFI_INIT_CONFIG_DEFAULT();
|
||||||
|
esp_err_t err=esp_wifi_init(&conf);
|
||||||
|
esp_wifi_get_config((wifi_interface_t)WIFI_IF_AP, &conf_current);
|
||||||
|
LOG_DEBUG(GwLog::DEBUG,"Wifi AP old config before reset ssid=%s, pass=%s, channel=%d",conf_current.ap.ssid,conf_current.ap.password,conf_current.ap.channel);
|
||||||
|
if (err){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"unable to pre-init wifi: %d",(int)err);
|
||||||
|
}
|
||||||
|
err=esp_wifi_restore();
|
||||||
|
if (err){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"unable to reset wifi: %d",(int)err);
|
||||||
|
}
|
||||||
|
err=esp_wifi_deinit();
|
||||||
|
WiFi.persistent(false);
|
||||||
WiFi.mode(WIFI_MODE_APSTA); //enable both AP and client
|
WiFi.mode(WIFI_MODE_APSTA); //enable both AP and client
|
||||||
|
esp_wifi_get_config((wifi_interface_t)WIFI_IF_AP, &conf_current);
|
||||||
|
LOG_DEBUG(GwLog::DEBUG,"Wifi AP old config after reset ssid=%s, pass=%s, channel=%d",conf_current.ap.ssid,conf_current.ap.password,conf_current.ap.channel);
|
||||||
const char *ssid=config->getConfigItem(config->systemName)->asCString();
|
const char *ssid=config->getConfigItem(config->systemName)->asCString();
|
||||||
if (fixedApPass){
|
if (fixedApPass){
|
||||||
WiFi.softAP(ssid,AP_password);
|
WiFi.softAP(ssid,AP_password);
|
||||||
|
@ -45,7 +68,7 @@ void GwWifi::setup(){
|
||||||
}
|
}
|
||||||
delay(100);
|
delay(100);
|
||||||
WiFi.softAPConfig(AP_local_ip, AP_gateway, AP_subnet);
|
WiFi.softAPConfig(AP_local_ip, AP_gateway, AP_subnet);
|
||||||
LOG_DEBUG(GwLog::LOG,"WifiAP created: ssid=%s,adress=%s",
|
LOG_DEBUG(GwLog::ERROR,"WifiAP created: ssid=%s,adress=%s",
|
||||||
ssid,
|
ssid,
|
||||||
WiFi.softAPIP().toString().c_str()
|
WiFi.softAPIP().toString().c_str()
|
||||||
);
|
);
|
||||||
|
|
|
@ -24,6 +24,7 @@
|
||||||
#define GWSERIAL_TYPE_BI 2
|
#define GWSERIAL_TYPE_BI 2
|
||||||
#define GWSERIAL_TYPE_RX 3
|
#define GWSERIAL_TYPE_RX 3
|
||||||
#define GWSERIAL_TYPE_TX 4
|
#define GWSERIAL_TYPE_TX 4
|
||||||
|
#define GWSERIAL_TYPE_UNK 0
|
||||||
#include <GwConfigItem.h>
|
#include <GwConfigItem.h>
|
||||||
#include <HardwareSerial.h>
|
#include <HardwareSerial.h>
|
||||||
#include "GwAppInfo.h"
|
#include "GwAppInfo.h"
|
||||||
|
|
|
@ -1,8 +1,19 @@
|
||||||
#include "GwLedTask.h"
|
#include "GwLedTask.h"
|
||||||
#include "GwHardware.h"
|
#include "GwHardware.h"
|
||||||
#include "GwApi.h"
|
#include "GwApi.h"
|
||||||
|
|
||||||
|
void handleLeds(GwApi *api);
|
||||||
|
void initLeds(GwApi *param)
|
||||||
|
{
|
||||||
|
#ifdef GWLED_FASTLED
|
||||||
|
param->addUserTask(handleLeds, "handleLeds");
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef GWLED_FASTLED
|
||||||
#include "FastLED.h"
|
#include "FastLED.h"
|
||||||
typedef enum {
|
typedef enum
|
||||||
|
{
|
||||||
LED_OFF,
|
LED_OFF,
|
||||||
LED_GREEN,
|
LED_GREEN,
|
||||||
LED_BLUE,
|
LED_BLUE,
|
||||||
|
@ -10,8 +21,10 @@ typedef enum {
|
||||||
LED_WHITE
|
LED_WHITE
|
||||||
} GwLedMode;
|
} GwLedMode;
|
||||||
|
|
||||||
static CRGB::HTMLColorCode colorFromMode(GwLedMode cmode){
|
static CRGB::HTMLColorCode colorFromMode(GwLedMode cmode)
|
||||||
switch(cmode){
|
{
|
||||||
|
switch (cmode)
|
||||||
|
{
|
||||||
case LED_BLUE:
|
case LED_BLUE:
|
||||||
return CRGB::Blue;
|
return CRGB::Blue;
|
||||||
case LED_GREEN:
|
case LED_GREEN:
|
||||||
|
@ -24,14 +37,9 @@ static CRGB::HTMLColorCode colorFromMode(GwLedMode cmode){
|
||||||
return CRGB::Black;
|
return CRGB::Black;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void handleLeds(GwApi *api){
|
void handleLeds(GwApi *api)
|
||||||
|
{
|
||||||
GwLog *logger = api->getLogger();
|
GwLog *logger = api->getLogger();
|
||||||
#ifndef GWLED_FASTLED
|
|
||||||
LOG_DEBUG(GwLog::LOG,"currently only fastled handling");
|
|
||||||
delay(50);
|
|
||||||
vTaskDelete(NULL);
|
|
||||||
return;
|
|
||||||
#else
|
|
||||||
CRGB leds[1];
|
CRGB leds[1];
|
||||||
#ifdef GWLED_SCHEMA
|
#ifdef GWLED_SCHEMA
|
||||||
FastLED.addLeds<GWLED_TYPE, GWLED_PIN, (EOrder)GWLED_SCHEMA>(leds, 1);
|
FastLED.addLeds<GWLED_TYPE, GWLED_PIN, (EOrder)GWLED_SCHEMA>(leds, 1);
|
||||||
|
@ -43,7 +51,7 @@ void handleLeds(GwApi *api){
|
||||||
leds[0] = colorFromMode(currentMode);
|
leds[0] = colorFromMode(currentMode);
|
||||||
FastLED.setBrightness(brightness);
|
FastLED.setBrightness(brightness);
|
||||||
FastLED.show();
|
FastLED.show();
|
||||||
LOG_DEBUG(GwLog::LOG,"led task started with mode %d",(int)currentMode);
|
LOG_DEBUG(GwLog::LOG, "led task started with mode %d, brightness=%d", (int)currentMode, (int)brightness);
|
||||||
int apiResult = 0;
|
int apiResult = 0;
|
||||||
while (true)
|
while (true)
|
||||||
{
|
{
|
||||||
|
@ -77,5 +85,5 @@ void handleLeds(GwApi *api){
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
vTaskDelete(NULL);
|
vTaskDelete(NULL);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
#endif
|
|
@ -1,8 +1,9 @@
|
||||||
#ifndef _GWLEDS_H
|
#ifndef _GWLEDS_H
|
||||||
#define _GWLEDS_H
|
#define _GWLEDS_H
|
||||||
#include "GwApi.h"
|
#include "GwApi.h"
|
||||||
//task function
|
//task init function
|
||||||
void handleLeds(GwApi *param);
|
|
||||||
|
|
||||||
DECLARE_USERTASK(handleLeds);
|
void initLeds(GwApi *param);
|
||||||
|
|
||||||
|
DECLARE_INITFUNCTION(initLeds);
|
||||||
#endif
|
#endif
|
|
@ -0,0 +1,15 @@
|
||||||
|
[platformio]
|
||||||
|
#if you want a pio run to only build
|
||||||
|
#your special environments you can set this here
|
||||||
|
#by uncommenting the next line
|
||||||
|
#default_envs = testboard
|
||||||
|
[env:nodemculed]
|
||||||
|
board = nodemcu-32s
|
||||||
|
lib_deps = ${env.lib_deps}
|
||||||
|
build_flags =
|
||||||
|
-D BOARD_HOMBERGER
|
||||||
|
-D GWLED_CODE=1
|
||||||
|
-D GWLED_PIN=33
|
||||||
|
${env.build_flags}
|
||||||
|
upload_port = /dev/esp32
|
||||||
|
upload_protocol = esptool
|
|
@ -38,5 +38,7 @@ class GwLog{
|
||||||
long long getRecordCounter(){return recordCounter;}
|
long long getRecordCounter(){return recordCounter;}
|
||||||
};
|
};
|
||||||
#define LOG_DEBUG(level,...){ if (logger != NULL && logger->isActive(level)) logger->logDebug(level,__VA_ARGS__);}
|
#define LOG_DEBUG(level,...){ if (logger != NULL && logger->isActive(level)) logger->logDebug(level,__VA_ARGS__);}
|
||||||
|
#define LOG_INFO(...){ if (logger != NULL && logger->isActive(GwLog::LOG)) logger->logDebug(GwLog::LOG,__VA_ARGS__);}
|
||||||
|
#define LOG_ERROR(...){ if (logger != NULL && logger->isActive(GwLog::ERROR)) logger->logDebug(GwLog::ERROR,__VA_ARGS__);}
|
||||||
|
|
||||||
#endif
|
#endif
|
|
@ -103,7 +103,7 @@ private:
|
||||||
if (v != NMEA0183UInt32NA){
|
if (v != NMEA0183UInt32NA){
|
||||||
return target->update(v,sourceId);
|
return target->update(v,sourceId);
|
||||||
}
|
}
|
||||||
return v;
|
return false;
|
||||||
}
|
}
|
||||||
uint32_t getUint32(GwBoatItem<uint32_t> *src){
|
uint32_t getUint32(GwBoatItem<uint32_t> *src){
|
||||||
return src->getDataWithDefault(N2kUInt32NA);
|
return src->getDataWithDefault(N2kUInt32NA);
|
||||||
|
@ -399,28 +399,29 @@ private:
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
tN2kMsg n2kMsg;
|
tN2kMsg n2kMsg;
|
||||||
tN2kWindReference n2kRef;
|
|
||||||
bool shouldSend=false;
|
bool shouldSend=false;
|
||||||
WindAngle=formatDegToRad(WindAngle);
|
WindAngle=formatDegToRad(WindAngle);
|
||||||
|
GwConverterConfig::WindMapping mapping;
|
||||||
switch(Reference){
|
switch(Reference){
|
||||||
case NMEA0183Wind_Apparent:
|
case NMEA0183Wind_Apparent:
|
||||||
n2kRef=N2kWind_Apparent;
|
|
||||||
shouldSend=updateDouble(boatData->AWA,WindAngle,msg.sourceId) &&
|
shouldSend=updateDouble(boatData->AWA,WindAngle,msg.sourceId) &&
|
||||||
updateDouble(boatData->AWS,WindSpeed,msg.sourceId);
|
updateDouble(boatData->AWS,WindSpeed,msg.sourceId);
|
||||||
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxAws->updateMax(WindSpeed);
|
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxAws->updateMax(WindSpeed,msg.sourceId);
|
||||||
|
mapping=config.findWindMapping(GwConverterConfig::WindMapping::AWA_AWS);
|
||||||
break;
|
break;
|
||||||
case NMEA0183Wind_True:
|
case NMEA0183Wind_True:
|
||||||
n2kRef=N2kWind_True_North;
|
shouldSend=updateDouble(boatData->TWA,WindAngle,msg.sourceId) &&
|
||||||
shouldSend=updateDouble(boatData->TWD,WindAngle,msg.sourceId) &&
|
|
||||||
updateDouble(boatData->TWS,WindSpeed,msg.sourceId);
|
updateDouble(boatData->TWS,WindSpeed,msg.sourceId);
|
||||||
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxTws->updateMax(WindSpeed);
|
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxTws->updateMax(WindSpeed,msg.sourceId);
|
||||||
|
mapping=config.findWindMapping(GwConverterConfig::WindMapping::TWA_TWS);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
LOG_DEBUG(GwLog::DEBUG,"unknown wind reference %d in %s",(int)Reference,msg.line);
|
LOG_DEBUG(GwLog::DEBUG,"unknown wind reference %d in %s",(int)Reference,msg.line);
|
||||||
}
|
}
|
||||||
if (shouldSend){
|
//TODO: try to compute TWD and get mapping for this one
|
||||||
SetN2kWindSpeed(n2kMsg,1,WindSpeed,WindAngle,n2kRef);
|
if (shouldSend && mapping.valid){
|
||||||
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)n2kRef));
|
SetN2kWindSpeed(n2kMsg,1,WindSpeed,WindAngle,mapping.n2kType);
|
||||||
|
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)mapping.n2kType));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void convertVWR(const SNMEA0183Msg &msg)
|
void convertVWR(const SNMEA0183Msg &msg)
|
||||||
|
@ -457,18 +458,20 @@ private:
|
||||||
bool shouldSend = false;
|
bool shouldSend = false;
|
||||||
shouldSend = updateDouble(boatData->AWA, WindAngle, msg.sourceId) &&
|
shouldSend = updateDouble(boatData->AWA, WindAngle, msg.sourceId) &&
|
||||||
updateDouble(boatData->AWS, WindSpeed, msg.sourceId);
|
updateDouble(boatData->AWS, WindSpeed, msg.sourceId);
|
||||||
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxAws->updateMax(WindSpeed);
|
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxAws->updateMax(WindSpeed,msg.sourceId);
|
||||||
if (shouldSend)
|
if (shouldSend)
|
||||||
{
|
{
|
||||||
SetN2kWindSpeed(n2kMsg, 1, WindSpeed, WindAngle, N2kWind_Apparent);
|
const GwConverterConfig::WindMapping mapping=config.findWindMapping(GwConverterConfig::WindMapping::AWA_AWS);
|
||||||
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)N2kWind_Apparent));
|
if (mapping.valid){
|
||||||
|
SetN2kWindSpeed(n2kMsg, 1, WindSpeed, WindAngle, mapping.n2kType);
|
||||||
|
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)mapping.n2kType));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void convertMWD(const SNMEA0183Msg &msg)
|
void convertMWD(const SNMEA0183Msg &msg)
|
||||||
{
|
{
|
||||||
double WindAngle = NMEA0183DoubleNA, WindAngleMagnetic=NMEA0183DoubleNA,
|
double WindDirection = NMEA0183DoubleNA, WindDirectionMagnetic=NMEA0183DoubleNA, WindSpeed = NMEA0183DoubleNA;
|
||||||
WindSpeed = NMEA0183DoubleNA;
|
|
||||||
if (msg.FieldCount() < 8 )
|
if (msg.FieldCount() < 8 )
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::DEBUG, "failed to parse MWD %s", msg.line);
|
LOG_DEBUG(GwLog::DEBUG, "failed to parse MWD %s", msg.line);
|
||||||
|
@ -476,11 +479,11 @@ private:
|
||||||
}
|
}
|
||||||
if (msg.FieldLen(0) > 0 && msg.Field(1)[0] == 'T')
|
if (msg.FieldLen(0) > 0 && msg.Field(1)[0] == 'T')
|
||||||
{
|
{
|
||||||
WindAngle = formatDegToRad(atof(msg.Field(0)));
|
WindDirection = formatDegToRad(atof(msg.Field(0)));
|
||||||
}
|
}
|
||||||
if (msg.FieldLen(2) > 0 && msg.Field(3)[0] == 'M')
|
if (msg.FieldLen(2) > 0 && msg.Field(3)[0] == 'M')
|
||||||
{
|
{
|
||||||
WindAngleMagnetic = formatDegToRad(atof(msg.Field(2)));
|
WindDirectionMagnetic = formatDegToRad(atof(msg.Field(2)));
|
||||||
}
|
}
|
||||||
if (msg.FieldLen(4) > 0 && msg.Field(5)[0] == 'N')
|
if (msg.FieldLen(4) > 0 && msg.Field(5)[0] == 'N')
|
||||||
{
|
{
|
||||||
|
@ -497,32 +500,38 @@ private:
|
||||||
}
|
}
|
||||||
tN2kMsg n2kMsg;
|
tN2kMsg n2kMsg;
|
||||||
bool shouldSend = false;
|
bool shouldSend = false;
|
||||||
if (WindAngle != NMEA0183DoubleNA){
|
if (WindDirection != NMEA0183DoubleNA){
|
||||||
shouldSend = updateDouble(boatData->TWD, WindAngle, msg.sourceId) &&
|
shouldSend = updateDouble(boatData->TWD, WindDirection, msg.sourceId) &&
|
||||||
updateDouble(boatData->TWS, WindSpeed, msg.sourceId);
|
updateDouble(boatData->TWS, WindSpeed, msg.sourceId);
|
||||||
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxTws->updateMax(WindSpeed);
|
if (WindSpeed != NMEA0183DoubleNA) boatData->MaxTws->updateMax(WindSpeed,msg.sourceId);
|
||||||
|
if(shouldSend && boatData->HDT->isValid()) {
|
||||||
|
double twa = WindDirection-boatData->HDT->getData();
|
||||||
|
if(twa<0) { twa+=2*M_PI; }
|
||||||
|
updateDouble(boatData->TWA, twa, msg.sourceId);
|
||||||
|
const GwConverterConfig::WindMapping mapping=config.findWindMapping(GwConverterConfig::WindMapping::TWA_TWS);
|
||||||
|
if (mapping.valid){
|
||||||
|
SetN2kWindSpeed(n2kMsg, 1, WindSpeed, twa, mapping.n2kType);
|
||||||
|
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)mapping.n2kType));
|
||||||
|
}
|
||||||
|
const GwConverterConfig::WindMapping mapping2=config.findWindMapping(GwConverterConfig::WindMapping::TWD_TWS);
|
||||||
|
if (mapping2.valid){
|
||||||
|
SetN2kWindSpeed(n2kMsg, 1, WindSpeed, WindDirection, mapping2.n2kType);
|
||||||
|
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)mapping2.n2kType));
|
||||||
}
|
}
|
||||||
if (shouldSend)
|
|
||||||
{
|
|
||||||
SetN2kWindSpeed(n2kMsg, 1, WindSpeed, WindAngle, N2kWind_True_North);
|
|
||||||
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)N2kWind_True_North));
|
|
||||||
}
|
}
|
||||||
if (WindAngleMagnetic != NMEA0183DoubleNA && shouldSend){
|
|
||||||
SetN2kWindSpeed(n2kMsg, 1, WindSpeed, WindAngleMagnetic, N2kWind_Magnetic);
|
|
||||||
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((int)N2kWind_Magnetic));
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void convertHDM(const SNMEA0183Msg &msg){
|
void convertHDM(const SNMEA0183Msg &msg){
|
||||||
double MHDG=NMEA0183DoubleNA;
|
double HDM=NMEA0183DoubleNA;
|
||||||
if (!NMEA0183ParseHDM_nc(msg, MHDG))
|
if (!NMEA0183ParseHDM_nc(msg, HDM))
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::DEBUG, "failed to parse HDM %s", msg.line);
|
LOG_DEBUG(GwLog::DEBUG, "failed to parse HDM %s", msg.line);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (! UD(MHDG)) return;
|
if (! UD(HDM)) return;
|
||||||
tN2kMsg n2kMsg;
|
tN2kMsg n2kMsg;
|
||||||
SetN2kMagneticHeading(n2kMsg,1,MHDG,
|
SetN2kMagneticHeading(n2kMsg,1,HDM,
|
||||||
boatData->VAR->getDataWithDefault(N2kDoubleNA),
|
boatData->VAR->getDataWithDefault(N2kDoubleNA),
|
||||||
boatData->DEV->getDataWithDefault(N2kDoubleNA)
|
boatData->DEV->getDataWithDefault(N2kDoubleNA)
|
||||||
);
|
);
|
||||||
|
@ -530,28 +539,29 @@ private:
|
||||||
}
|
}
|
||||||
|
|
||||||
void convertHDT(const SNMEA0183Msg &msg){
|
void convertHDT(const SNMEA0183Msg &msg){
|
||||||
double HDG=NMEA0183DoubleNA;
|
double HDT=NMEA0183DoubleNA;
|
||||||
if (!NMEA0183ParseHDT_nc(msg, HDG))
|
if (!NMEA0183ParseHDT_nc(msg, HDT))
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::DEBUG, "failed to parse HDT %s", msg.line);
|
LOG_DEBUG(GwLog::DEBUG, "failed to parse HDT %s", msg.line);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (! UD(HDG)) return;
|
if (! UD(HDT)) return;
|
||||||
tN2kMsg n2kMsg;
|
tN2kMsg n2kMsg;
|
||||||
SetN2kTrueHeading(n2kMsg,1,HDG);
|
SetN2kTrueHeading(n2kMsg,1,HDT);
|
||||||
send(n2kMsg,msg.sourceId);
|
send(n2kMsg,msg.sourceId);
|
||||||
}
|
}
|
||||||
|
|
||||||
void convertHDG(const SNMEA0183Msg &msg){
|
void convertHDG(const SNMEA0183Msg &msg){
|
||||||
double MHDG=NMEA0183DoubleNA;
|
double HDM=NMEA0183DoubleNA;
|
||||||
double VAR=NMEA0183DoubleNA;
|
|
||||||
double DEV=NMEA0183DoubleNA;
|
double DEV=NMEA0183DoubleNA;
|
||||||
|
double VAR=NMEA0183DoubleNA;
|
||||||
if (msg.FieldCount() < 5)
|
if (msg.FieldCount() < 5)
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::DEBUG, "failed to parse HDG %s", msg.line);
|
LOG_DEBUG(GwLog::DEBUG, "failed to parse HDG %s", msg.line);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (msg.FieldLen(0)>0){
|
if (msg.FieldLen(0)>0){
|
||||||
MHDG=formatDegToRad(atof(msg.Field(0)));
|
HDM=formatDegToRad(atof(msg.Field(0)));
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
return;
|
return;
|
||||||
|
@ -565,11 +575,11 @@ private:
|
||||||
if (msg.Field(4)[0] == 'W') VAR=-VAR;
|
if (msg.Field(4)[0] == 'W') VAR=-VAR;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (! UD(MHDG)) return;
|
if (! UD(HDM)) return;
|
||||||
UD(VAR);
|
UD(VAR);
|
||||||
UD(DEV);
|
UD(DEV);
|
||||||
tN2kMsg n2kMsg;
|
tN2kMsg n2kMsg;
|
||||||
SetN2kMagneticHeading(n2kMsg,1,MHDG,DEV,VAR);
|
SetN2kMagneticHeading(n2kMsg,1,HDM,DEV,VAR);
|
||||||
send(n2kMsg,msg.sourceId,"127250M");
|
send(n2kMsg,msg.sourceId,"127250M");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -592,10 +602,10 @@ private:
|
||||||
}
|
}
|
||||||
//offset == 0? SK does not allow this
|
//offset == 0? SK does not allow this
|
||||||
if (Offset != NMEA0183DoubleNA && Offset>=0 ){
|
if (Offset != NMEA0183DoubleNA && Offset>=0 ){
|
||||||
if (! boatData->DBS->update(DepthBelowTransducer+Offset)) return;
|
if (! boatData->DBS->update(DepthBelowTransducer+Offset,msg.sourceId)) return;
|
||||||
}
|
}
|
||||||
if (Offset == NMEA0183DoubleNA) Offset=N2kDoubleNA;
|
if (Offset == NMEA0183DoubleNA) Offset=N2kDoubleNA;
|
||||||
if (! boatData->DBT->update(DepthBelowTransducer)) return;
|
if (! boatData->DBT->update(DepthBelowTransducer,msg.sourceId)) return;
|
||||||
tN2kMsg n2kMsg;
|
tN2kMsg n2kMsg;
|
||||||
SetN2kWaterDepth(n2kMsg,1,DepthBelowTransducer,Offset);
|
SetN2kWaterDepth(n2kMsg,1,DepthBelowTransducer,Offset);
|
||||||
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((Offset != N2kDoubleNA)?1:0));
|
send(n2kMsg,msg.sourceId,String(n2kMsg.PGN)+String((Offset != N2kDoubleNA)?1:0));
|
||||||
|
@ -705,11 +715,11 @@ private:
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
tN2kMsg n2kMsg;
|
tN2kMsg n2kMsg;
|
||||||
if (updateDouble(boatData->HDG,TrueHeading,msg.sourceId)){
|
if (updateDouble(boatData->HDT,TrueHeading,msg.sourceId)){
|
||||||
SetN2kTrueHeading(n2kMsg,1,TrueHeading);
|
SetN2kTrueHeading(n2kMsg,1,TrueHeading);
|
||||||
send(n2kMsg,msg.sourceId);
|
send(n2kMsg,msg.sourceId);
|
||||||
}
|
}
|
||||||
if(updateDouble(boatData->MHDG,MagneticHeading,msg.sourceId)){
|
if(updateDouble(boatData->HDM,MagneticHeading,msg.sourceId)){
|
||||||
SetN2kMagneticHeading(n2kMsg,1,MagneticHeading,
|
SetN2kMagneticHeading(n2kMsg,1,MagneticHeading,
|
||||||
boatData->DEV->getDataWithDefault(N2kDoubleNA),
|
boatData->DEV->getDataWithDefault(N2kDoubleNA),
|
||||||
boatData->VAR->getDataWithDefault(N2kDoubleNA)
|
boatData->VAR->getDataWithDefault(N2kDoubleNA)
|
||||||
|
@ -850,7 +860,7 @@ private:
|
||||||
LOG_DEBUG(GwLog::DEBUG,"GSV invalid current %u %s",current,msg.line);
|
LOG_DEBUG(GwLog::DEBUG,"GSV invalid current %u %s",current,msg.line);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (int idx=2;idx < msg.FieldCount();idx+=4){
|
for (int idx=3;idx < msg.FieldCount();idx+=4){
|
||||||
if (msg.FieldLen(idx) < 1 ||
|
if (msg.FieldLen(idx) < 1 ||
|
||||||
msg.FieldLen(idx+1) < 1 ||
|
msg.FieldLen(idx+1) < 1 ||
|
||||||
msg.FieldLen(idx+2) < 1 ||
|
msg.FieldLen(idx+2) < 1 ||
|
||||||
|
|
|
@ -185,13 +185,13 @@ private:
|
||||||
if (N2kIsNA(Variation)){
|
if (N2kIsNA(Variation)){
|
||||||
//no variation
|
//no variation
|
||||||
if (ref == N2khr_magnetic){
|
if (ref == N2khr_magnetic){
|
||||||
updateDouble(boatData->MHDG,Heading);
|
updateDouble(boatData->HDM,Heading);
|
||||||
if (NMEA0183SetHDM(NMEA0183Msg,Heading,talkerId)){
|
if (NMEA0183SetHDM(NMEA0183Msg,Heading,talkerId)){
|
||||||
SendMessage(NMEA0183Msg);
|
SendMessage(NMEA0183Msg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (ref == N2khr_true){
|
if (ref == N2khr_true){
|
||||||
updateDouble(boatData->HDG,Heading);
|
updateDouble(boatData->HDT,Heading);
|
||||||
if (NMEA0183SetHDT(NMEA0183Msg,Heading,talkerId)){
|
if (NMEA0183SetHDT(NMEA0183Msg,Heading,talkerId)){
|
||||||
SendMessage(NMEA0183Msg);
|
SendMessage(NMEA0183Msg);
|
||||||
}
|
}
|
||||||
|
@ -206,8 +206,8 @@ private:
|
||||||
if (ref == N2khr_true){
|
if (ref == N2khr_true){
|
||||||
MagneticHeading=Heading-Variation;
|
MagneticHeading=Heading-Variation;
|
||||||
}
|
}
|
||||||
updateDouble(boatData->MHDG,MagneticHeading);
|
updateDouble(boatData->HDM,MagneticHeading);
|
||||||
updateDouble(boatData->HDG,Heading);
|
updateDouble(boatData->HDT,Heading);
|
||||||
if (!N2kIsNA(MagneticHeading)){
|
if (!N2kIsNA(MagneticHeading)){
|
||||||
if (NMEA0183SetHDG(NMEA0183Msg, MagneticHeading,_Deviation,
|
if (NMEA0183SetHDG(NMEA0183Msg, MagneticHeading,_Deviation,
|
||||||
Variation,talkerId))
|
Variation,talkerId))
|
||||||
|
@ -252,8 +252,8 @@ private:
|
||||||
tNMEA0183Msg NMEA0183Msg;
|
tNMEA0183Msg NMEA0183Msg;
|
||||||
updateDouble(boatData->STW, WaterReferenced);
|
updateDouble(boatData->STW, WaterReferenced);
|
||||||
unsigned long now = millis();
|
unsigned long now = millis();
|
||||||
double MagneticHeading = (boatData->HDG->isValid(now) && boatData->VAR->isValid(now)) ? boatData->HDG->getData() + boatData->VAR->getData() : NMEA0183DoubleNA;
|
double MagneticHeading = (boatData->HDT->isValid(now) && boatData->VAR->isValid(now)) ? boatData->HDT->getData() + boatData->VAR->getData() : NMEA0183DoubleNA;
|
||||||
if (NMEA0183SetVHW(NMEA0183Msg, boatData->HDG->getDataWithDefault(NMEA0183DoubleNA), MagneticHeading, WaterReferenced,talkerId))
|
if (NMEA0183SetVHW(NMEA0183Msg, boatData->HDT->getDataWithDefault(NMEA0183DoubleNA), MagneticHeading, WaterReferenced,talkerId))
|
||||||
{
|
{
|
||||||
SendMessage(NMEA0183Msg);
|
SendMessage(NMEA0183Msg);
|
||||||
}
|
}
|
||||||
|
@ -468,37 +468,73 @@ private:
|
||||||
{
|
{
|
||||||
unsigned char SID;
|
unsigned char SID;
|
||||||
tN2kWindReference WindReference;
|
tN2kWindReference WindReference;
|
||||||
tNMEA0183WindReference NMEA0183Reference = NMEA0183Wind_True;
|
|
||||||
|
|
||||||
double x, y;
|
|
||||||
double WindAngle=N2kDoubleNA, WindSpeed=N2kDoubleNA;
|
double WindAngle=N2kDoubleNA, WindSpeed=N2kDoubleNA;
|
||||||
|
tNMEA0183WindReference NMEA0183Reference;
|
||||||
if (ParseN2kWindSpeed(N2kMsg, SID, WindSpeed, WindAngle, WindReference))
|
if (ParseN2kWindSpeed(N2kMsg, SID, WindSpeed, WindAngle, WindReference)) {
|
||||||
{
|
|
||||||
tNMEA0183Msg NMEA0183Msg;
|
tNMEA0183Msg NMEA0183Msg;
|
||||||
|
GwConverterConfig::WindMapping mapping=config.findWindMapping(WindReference);
|
||||||
|
bool shouldSend = false;
|
||||||
|
|
||||||
if (WindReference == N2kWind_Apparent)
|
// MWV sentence contains apparent/true ANGLE and SPEED
|
||||||
|
// https://gpsd.gitlab.io/gpsd/NMEA.html#_mwv_wind_speed_and_angle
|
||||||
|
// https://docs.vaisala.com/r/M211109EN-L/en-US/GUID-7402DEF8-5E82-446F-B63E-998F49F3D743/GUID-C77934C7-2A72-466E-BC52-CE6B8CC7ACB6
|
||||||
|
if (mapping.valid)
|
||||||
|
{
|
||||||
|
if (mapping.nmea0183Type == GwConverterConfig::WindMapping::AWA_AWS)
|
||||||
{
|
{
|
||||||
NMEA0183Reference = NMEA0183Wind_Apparent;
|
NMEA0183Reference = NMEA0183Wind_Apparent;
|
||||||
updateDouble(boatData->AWA, WindAngle);
|
updateDouble(boatData->AWA, WindAngle);
|
||||||
updateDouble(boatData->AWS, WindSpeed);
|
updateDouble(boatData->AWS, WindSpeed);
|
||||||
setMax(boatData->MaxAws, boatData->AWS);
|
setMax(boatData->MaxAws, boatData->AWS);
|
||||||
|
shouldSend = true;
|
||||||
}
|
}
|
||||||
if (WindReference == N2kWind_True_North)
|
if (mapping.nmea0183Type == GwConverterConfig::WindMapping::TWA_TWS)
|
||||||
|
{
|
||||||
|
NMEA0183Reference = NMEA0183Wind_True;
|
||||||
|
updateDouble(boatData->TWA, WindAngle);
|
||||||
|
updateDouble(boatData->TWS, WindSpeed);
|
||||||
|
setMax(boatData->MaxTws, boatData->TWS);
|
||||||
|
shouldSend = true;
|
||||||
|
if (boatData->HDT->isValid())
|
||||||
|
{
|
||||||
|
double twd = WindAngle + boatData->HDT->getData();
|
||||||
|
if (twd > 2 * M_PI)
|
||||||
|
{
|
||||||
|
twd -= 2 * M_PI;
|
||||||
|
}
|
||||||
|
updateDouble(boatData->TWD, twd);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (mapping.nmea0183Type == GwConverterConfig::WindMapping::TWD_TWS)
|
||||||
{
|
{
|
||||||
NMEA0183Reference = NMEA0183Wind_True;
|
NMEA0183Reference = NMEA0183Wind_True;
|
||||||
updateDouble(boatData->TWD, WindAngle);
|
updateDouble(boatData->TWD, WindAngle);
|
||||||
updateDouble(boatData->TWS, WindSpeed);
|
updateDouble(boatData->TWS, WindSpeed);
|
||||||
|
setMax(boatData->MaxTws, boatData->TWS);
|
||||||
|
if (boatData->HDT->isValid())
|
||||||
|
{
|
||||||
|
shouldSend = true;
|
||||||
|
double twa = WindAngle - boatData->HDT->getData();
|
||||||
|
if (twa > 2 * M_PI)
|
||||||
|
{
|
||||||
|
twa -= 2 * M_PI;
|
||||||
|
}
|
||||||
|
updateDouble(boatData->TWA, twa);
|
||||||
|
WindAngle=twa;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (NMEA0183SetMWV(NMEA0183Msg, formatCourse(WindAngle), NMEA0183Reference, WindSpeed,talkerId))
|
if (shouldSend && NMEA0183SetMWV(NMEA0183Msg, formatCourse(WindAngle), NMEA0183Reference, WindSpeed, talkerId))
|
||||||
|
{
|
||||||
SendMessage(NMEA0183Msg);
|
SendMessage(NMEA0183Msg);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (WindReference == N2kWind_Apparent && boatData->SOG->isValid())
|
/* if (WindReference == N2kWind_Apparent && boatData->SOG->isValid())
|
||||||
{ // Lets calculate and send TWS/TWA if SOG is available
|
{ // Lets calculate and send TWS/TWA if SOG is available
|
||||||
|
|
||||||
x = WindSpeed * cos(WindAngle);
|
double x = WindSpeed * cos(WindAngle);
|
||||||
y = WindSpeed * sin(WindAngle);
|
double y = WindSpeed * sin(WindAngle);
|
||||||
|
|
||||||
updateDouble(boatData->TWD, atan2(y, -boatData->SOG->getData() + x));
|
updateDouble(boatData->TWD, atan2(y, -boatData->SOG->getData() + x));
|
||||||
updateDouble(boatData->TWS, sqrt((y * y) + ((-boatData->SOG->getData() + x) * (-boatData->SOG->getData() + x))));
|
updateDouble(boatData->TWS, sqrt((y * y) + ((-boatData->SOG->getData() + x) * (-boatData->SOG->getData() + x))));
|
||||||
|
@ -534,7 +570,7 @@ private:
|
||||||
return;
|
return;
|
||||||
|
|
||||||
SendMessage(NMEA0183Msg);
|
SendMessage(NMEA0183Msg);
|
||||||
}
|
} */
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
//*****************************************************************************
|
//*****************************************************************************
|
||||||
|
@ -657,12 +693,14 @@ private:
|
||||||
double _Heading=N2kDoubleNA;
|
double _Heading=N2kDoubleNA;
|
||||||
double _ROT=N2kDoubleNA;
|
double _ROT=N2kDoubleNA;
|
||||||
tN2kAISNavStatus _NavStatus;
|
tN2kAISNavStatus _NavStatus;
|
||||||
|
tN2kAISTransceiverInformation _AISTransceiverInformation;
|
||||||
|
uint8_t _SID;
|
||||||
|
|
||||||
uint8_t _MessageType = 1;
|
uint8_t _MessageType = 1;
|
||||||
tNMEA0183AISMsg NMEA0183AISMsg;
|
tNMEA0183AISMsg NMEA0183AISMsg;
|
||||||
|
|
||||||
if (ParseN2kPGN129038(N2kMsg, SID, _Repeat, _UserID, _Latitude, _Longitude, _Accuracy, _RAIM, _Seconds,
|
if (ParseN2kPGN129038(N2kMsg, SID, _Repeat, _UserID, _Latitude, _Longitude, _Accuracy, _RAIM, _Seconds,
|
||||||
_COG, _SOG, _Heading, _ROT, _NavStatus))
|
_COG, _SOG, _Heading, _ROT, _NavStatus,_AISTransceiverInformation,_SID))
|
||||||
{
|
{
|
||||||
|
|
||||||
// Debug
|
// Debug
|
||||||
|
@ -746,12 +784,13 @@ private:
|
||||||
tN2kGNSStype _GNSStype;
|
tN2kGNSStype _GNSStype;
|
||||||
tN2kAISTransceiverInformation _AISinfo;
|
tN2kAISTransceiverInformation _AISinfo;
|
||||||
tN2kAISDTE _DTE;
|
tN2kAISDTE _DTE;
|
||||||
|
uint8_t _SID;
|
||||||
|
|
||||||
tNMEA0183AISMsg NMEA0183AISMsg;
|
tNMEA0183AISMsg NMEA0183AISMsg;
|
||||||
|
|
||||||
if (ParseN2kPGN129794(N2kMsg, _MessageID, _Repeat, _UserID, _IMONumber, _Callsign, _Name, _VesselType,
|
if (ParseN2kPGN129794(N2kMsg, _MessageID, _Repeat, _UserID, _IMONumber, _Callsign, 8, _Name,21, _VesselType,
|
||||||
_Length, _Beam, _PosRefStbd, _PosRefBow, _ETAdate, _ETAtime, _Draught, _Destination,
|
_Length, _Beam, _PosRefStbd, _PosRefBow, _ETAdate, _ETAtime, _Draught, _Destination,21,
|
||||||
_AISversion, _GNSStype, _DTE, _AISinfo))
|
_AISversion, _GNSStype, _DTE, _AISinfo,_SID))
|
||||||
{
|
{
|
||||||
|
|
||||||
#ifdef SERIAL_PRINT_AIS_FIELDS
|
#ifdef SERIAL_PRINT_AIS_FIELDS
|
||||||
|
@ -855,9 +894,10 @@ private:
|
||||||
bool _Display, _DSC, _Band, _Msg22, _State;
|
bool _Display, _DSC, _Band, _Msg22, _State;
|
||||||
tN2kAISMode _Mode;
|
tN2kAISMode _Mode;
|
||||||
tN2kAISTransceiverInformation _AISTranceiverInformation;
|
tN2kAISTransceiverInformation _AISTranceiverInformation;
|
||||||
|
uint8_t _SID;
|
||||||
|
|
||||||
if (ParseN2kPGN129039(N2kMsg, _MessageID, _Repeat, _UserID, _Latitude, _Longitude, _Accuracy, _RAIM,
|
if (ParseN2kPGN129039(N2kMsg, _MessageID, _Repeat, _UserID, _Latitude, _Longitude, _Accuracy, _RAIM,
|
||||||
_Seconds, _COG, _SOG, _AISTranceiverInformation, _Heading, _Unit, _Display, _DSC, _Band, _Msg22, _Mode, _State))
|
_Seconds, _COG, _SOG, _AISTranceiverInformation, _Heading, _Unit, _Display, _DSC, _Band, _Msg22, _Mode, _State,_SID))
|
||||||
{
|
{
|
||||||
|
|
||||||
tNMEA0183AISMsg NMEA0183AISMsg;
|
tNMEA0183AISMsg NMEA0183AISMsg;
|
||||||
|
@ -896,8 +936,10 @@ private:
|
||||||
tN2kAISRepeat _Repeat;
|
tN2kAISRepeat _Repeat;
|
||||||
uint32_t _UserID; // MMSI
|
uint32_t _UserID; // MMSI
|
||||||
char _Name[21];
|
char _Name[21];
|
||||||
|
tN2kAISTransceiverInformation _AISInfo;
|
||||||
|
uint8_t _SID;
|
||||||
|
|
||||||
if (ParseN2kPGN129809(N2kMsg, _MessageID, _Repeat, _UserID, _Name))
|
if (ParseN2kPGN129809(N2kMsg, _MessageID, _Repeat, _UserID, _Name,21,_AISInfo,_SID))
|
||||||
{
|
{
|
||||||
|
|
||||||
tNMEA0183AISMsg NMEA0183AISMsg;
|
tNMEA0183AISMsg NMEA0183AISMsg;
|
||||||
|
@ -923,9 +965,11 @@ private:
|
||||||
double _Beam=N2kDoubleNA;
|
double _Beam=N2kDoubleNA;
|
||||||
double _PosRefStbd=N2kDoubleNA;
|
double _PosRefStbd=N2kDoubleNA;
|
||||||
double _PosRefBow=N2kDoubleNA;
|
double _PosRefBow=N2kDoubleNA;
|
||||||
|
tN2kAISTransceiverInformation _AISInfo;
|
||||||
|
uint8_t _SID;
|
||||||
|
|
||||||
if (ParseN2kPGN129810(N2kMsg, _MessageID, _Repeat, _UserID, _VesselType, _Vendor, _Callsign,
|
if (ParseN2kPGN129810(N2kMsg, _MessageID, _Repeat, _UserID, _VesselType, _Vendor,4, _Callsign,8,
|
||||||
_Length, _Beam, _PosRefStbd, _PosRefBow, _MothershipID))
|
_Length, _Beam, _PosRefStbd, _PosRefBow, _MothershipID,_AISInfo,_SID))
|
||||||
{
|
{
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -1121,8 +1165,8 @@ private:
|
||||||
int16_t ETADate=0;
|
int16_t ETADate=0;
|
||||||
double BearingOriginToDestinationWaypoint=N2kDoubleNA;
|
double BearingOriginToDestinationWaypoint=N2kDoubleNA;
|
||||||
double BearingPositionToDestinationWaypoint=N2kDoubleNA;
|
double BearingPositionToDestinationWaypoint=N2kDoubleNA;
|
||||||
uint8_t OriginWaypointNumber;
|
uint32_t OriginWaypointNumber;
|
||||||
uint8_t DestinationWaypointNumber;
|
uint32_t DestinationWaypointNumber;
|
||||||
double DestinationLatitude=N2kDoubleNA;
|
double DestinationLatitude=N2kDoubleNA;
|
||||||
double DestinationLongitude=N2kDoubleNA;
|
double DestinationLongitude=N2kDoubleNA;
|
||||||
double WaypointClosingVelocity=N2kDoubleNA;
|
double WaypointClosingVelocity=N2kDoubleNA;
|
||||||
|
@ -1288,6 +1332,20 @@ private:
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
int i=0;
|
int i=0;
|
||||||
|
if (TempSource == N2kts_SeaTemperature) {
|
||||||
|
updateDouble(boatData->WTemp, Temperature);
|
||||||
|
tNMEA0183Msg NMEA0183Msg;
|
||||||
|
|
||||||
|
if (!NMEA0183Msg.Init("MTW", talkerId))
|
||||||
|
return;
|
||||||
|
if (!NMEA0183Msg.AddDoubleField(KelvinToC(Temperature)))
|
||||||
|
return;
|
||||||
|
if (!NMEA0183Msg.AddStrField("C"))
|
||||||
|
return;
|
||||||
|
|
||||||
|
SendMessage(NMEA0183Msg);
|
||||||
|
}
|
||||||
|
|
||||||
GwXDRFoundMapping mapping=xdrMappings->getMapping(XDRTEMP,TempSource,0,0);
|
GwXDRFoundMapping mapping=xdrMappings->getMapping(XDRTEMP,TempSource,0,0);
|
||||||
if (updateDouble(&mapping,Temperature)){
|
if (updateDouble(&mapping,Temperature)){
|
||||||
LOG_DEBUG(GwLog::DEBUG+1,"found temperature mapping %s",mapping.definition->toString().c_str());
|
LOG_DEBUG(GwLog::DEBUG+1,"found temperature mapping %s",mapping.definition->toString().c_str());
|
||||||
|
@ -1320,6 +1378,21 @@ private:
|
||||||
LOG_DEBUG(GwLog::DEBUG,"unable to parse PGN %d",msg.PGN);
|
LOG_DEBUG(GwLog::DEBUG,"unable to parse PGN %d",msg.PGN);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
if (TemperatureSource == N2kts_SeaTemperature &&
|
||||||
|
(config.winst312 == TemperatureInstance || config.winst312 == 256)) {
|
||||||
|
updateDouble(boatData->WTemp, Temperature);
|
||||||
|
tNMEA0183Msg NMEA0183Msg;
|
||||||
|
|
||||||
|
if (!NMEA0183Msg.Init("MTW", talkerId))
|
||||||
|
return;
|
||||||
|
if (!NMEA0183Msg.AddDoubleField(KelvinToC(Temperature)))
|
||||||
|
return;
|
||||||
|
if (!NMEA0183Msg.AddStrField("C"))
|
||||||
|
return;
|
||||||
|
|
||||||
|
SendMessage(NMEA0183Msg);
|
||||||
|
}
|
||||||
|
|
||||||
GwXDRFoundMapping mapping=xdrMappings->getMapping(XDRTEMP,(int)TemperatureSource,0,TemperatureInstance);
|
GwXDRFoundMapping mapping=xdrMappings->getMapping(XDRTEMP,(int)TemperatureSource,0,TemperatureInstance);
|
||||||
if (updateDouble(&mapping,Temperature)){
|
if (updateDouble(&mapping,Temperature)){
|
||||||
LOG_DEBUG(GwLog::DEBUG+1,"found temperature mapping %s",mapping.definition->toString().c_str());
|
LOG_DEBUG(GwLog::DEBUG+1,"found temperature mapping %s",mapping.definition->toString().c_str());
|
||||||
|
|
|
@ -219,7 +219,7 @@ bool SetAISClassBMessage18(tNMEA0183AISMsg &NMEA0183AISMsg, uint8_t MessageID, u
|
||||||
bool SetAISClassBMessage24PartA(tNMEA0183AISMsg &NMEA0183AISMsg, uint8_t MessageID, uint8_t Repeat, uint32_t UserID, char *Name) {
|
bool SetAISClassBMessage24PartA(tNMEA0183AISMsg &NMEA0183AISMsg, uint8_t MessageID, uint8_t Repeat, uint32_t UserID, char *Name) {
|
||||||
|
|
||||||
bool found = false;
|
bool found = false;
|
||||||
for (int i = 0; i < vships.size(); i++) {
|
for (size_t i = 0; i < vships.size(); i++) {
|
||||||
if ( vships[i]->_userID == UserID ) {
|
if ( vships[i]->_userID == UserID ) {
|
||||||
found = true;
|
found = true;
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -21,7 +21,7 @@ GwBuffer::~GwBuffer(){
|
||||||
}
|
}
|
||||||
void GwBuffer::reset(String reason)
|
void GwBuffer::reset(String reason)
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::LOG,"reseting buffer %s, reason %s",this->name.c_str(),reason.c_str());
|
if (! reason.isEmpty())LOG_DEBUG(GwLog::LOG,"reseting buffer %s, reason %s",this->name.c_str(),reason.c_str());
|
||||||
writePointer = buffer;
|
writePointer = buffer;
|
||||||
readPointer = buffer;
|
readPointer = buffer;
|
||||||
lp("reset");
|
lp("reset");
|
||||||
|
|
|
@ -18,9 +18,9 @@ class GwMessageFetcher{
|
||||||
* buffer to safely inserte data if it fits
|
* buffer to safely inserte data if it fits
|
||||||
* and to write out data if possible
|
* and to write out data if possible
|
||||||
*/
|
*/
|
||||||
typedef size_t (*GwBufferHandleFunction)(uint8_t *buffer, size_t len, void *param);
|
|
||||||
class GwBuffer{
|
class GwBuffer{
|
||||||
public:
|
public:
|
||||||
|
using GwBufferHandleFunction=std::function<size_t(uint8_t *buffer, size_t len, void *param)>;
|
||||||
static const size_t TX_BUFFER_SIZE=1620; // app. 20 NMEA messages
|
static const size_t TX_BUFFER_SIZE=1620; // app. 20 NMEA messages
|
||||||
static const size_t RX_BUFFER_SIZE=600; // enough for 1 NMEA message or actisense message or seasmart message
|
static const size_t RX_BUFFER_SIZE=600; // enough for 1 NMEA message or actisense message or seasmart message
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -33,7 +33,7 @@ class GwBuffer{
|
||||||
uint8_t *buffer;
|
uint8_t *buffer;
|
||||||
uint8_t *writePointer;
|
uint8_t *writePointer;
|
||||||
uint8_t *readPointer;
|
uint8_t *readPointer;
|
||||||
size_t offset(uint8_t* ptr){
|
size_t offset(uint8_t* ptr) const{
|
||||||
return (size_t)(ptr-buffer);
|
return (size_t)(ptr-buffer);
|
||||||
}
|
}
|
||||||
GwLog *logger;
|
GwLog *logger;
|
||||||
|
|
|
@ -7,10 +7,10 @@ class GwSynchronized{
|
||||||
public:
|
public:
|
||||||
GwSynchronized(SemaphoreHandle_t *locker){
|
GwSynchronized(SemaphoreHandle_t *locker){
|
||||||
this->locker=locker;
|
this->locker=locker;
|
||||||
xSemaphoreTake(*locker, portMAX_DELAY);
|
if (locker != nullptr) xSemaphoreTake(*locker, portMAX_DELAY);
|
||||||
}
|
}
|
||||||
~GwSynchronized(){
|
~GwSynchronized(){
|
||||||
xSemaphoreGive(*locker);
|
if (locker != nullptr) xSemaphoreGive(*locker);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,5 @@
|
||||||
#include "GwSerial.h"
|
#include "GwSerial.h"
|
||||||
|
#include "GwHardware.h"
|
||||||
|
|
||||||
class GwSerialStream: public Stream{
|
class GwSerialStream: public Stream{
|
||||||
private:
|
private:
|
||||||
|
@ -40,11 +41,13 @@ class GwSerialStream: public Stream{
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
GwSerial::GwSerial(GwLog *logger, Stream *s, int id,bool allowRead):serial(s)
|
GwSerial::GwSerial(GwLog *logger, Stream * stream,int id,int type,bool allowRead)
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::DEBUG,"creating GwSerial %p id %d",this,id);
|
LOG_DEBUG(GwLog::DEBUG,"creating GwSerial %p id %d",this,id);
|
||||||
this->id=id;
|
|
||||||
this->logger = logger;
|
this->logger = logger;
|
||||||
|
this->id=id;
|
||||||
|
this->stream=stream;
|
||||||
|
this->type=type;
|
||||||
String bufName="Ser(";
|
String bufName="Ser(";
|
||||||
bufName+=String(id);
|
bufName+=String(id);
|
||||||
bufName+=")";
|
bufName+=")";
|
||||||
|
@ -62,6 +65,20 @@ GwSerial::~GwSerial()
|
||||||
if (readBuffer) delete readBuffer;
|
if (readBuffer) delete readBuffer;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
String GwSerial::getMode(){
|
||||||
|
switch (type){
|
||||||
|
case GWSERIAL_TYPE_UNI:
|
||||||
|
return "UNI";
|
||||||
|
case GWSERIAL_TYPE_BI:
|
||||||
|
return "BI";
|
||||||
|
case GWSERIAL_TYPE_RX:
|
||||||
|
return "RX";
|
||||||
|
case GWSERIAL_TYPE_TX:
|
||||||
|
return "TX";
|
||||||
|
}
|
||||||
|
return "UNKNOWN";
|
||||||
|
}
|
||||||
|
|
||||||
bool GwSerial::isInitialized() { return initialized; }
|
bool GwSerial::isInitialized() { return initialized; }
|
||||||
size_t GwSerial::enqueue(const uint8_t *data, size_t len, bool partial)
|
size_t GwSerial::enqueue(const uint8_t *data, size_t len, bool partial)
|
||||||
{
|
{
|
||||||
|
@ -70,9 +87,9 @@ size_t GwSerial::enqueue(const uint8_t *data, size_t len, bool partial)
|
||||||
}
|
}
|
||||||
GwBuffer::WriteStatus GwSerial::write(){
|
GwBuffer::WriteStatus GwSerial::write(){
|
||||||
if (! isInitialized()) return GwBuffer::ERROR;
|
if (! isInitialized()) return GwBuffer::ERROR;
|
||||||
size_t numWrite=serial->availableForWrite();
|
size_t numWrite=availableForWrite();
|
||||||
size_t rt=buffer->fetchData(numWrite,[](uint8_t *buffer,size_t len, void *p){
|
size_t rt=buffer->fetchData(numWrite,[](uint8_t *buffer,size_t len, void *p){
|
||||||
return ((GwSerial *)p)->serial->write(buffer,len);
|
return ((GwSerial *)p)->stream->write(buffer,len);
|
||||||
},this);
|
},this);
|
||||||
if (rt != 0){
|
if (rt != 0){
|
||||||
LOG_DEBUG(GwLog::DEBUG+1,"Serial %d write %d",id,rt);
|
LOG_DEBUG(GwLog::DEBUG+1,"Serial %d write %d",id,rt);
|
||||||
|
@ -93,11 +110,11 @@ void GwSerial::loop(bool handleRead,bool handleWrite){
|
||||||
write();
|
write();
|
||||||
if (! isInitialized()) return;
|
if (! isInitialized()) return;
|
||||||
if (! handleRead) return;
|
if (! handleRead) return;
|
||||||
size_t available=serial->available();
|
size_t available=stream->available();
|
||||||
if (! available) return;
|
if (! available) return;
|
||||||
if (allowRead){
|
if (allowRead){
|
||||||
size_t rd=readBuffer->fillData(available,[](uint8_t *buffer, size_t len, void *p)->size_t{
|
size_t rd=readBuffer->fillData(available,[](uint8_t *buffer, size_t len, void *p)->size_t{
|
||||||
return ((GwSerial *)p)->serial->readBytes(buffer,len);
|
return ((GwSerial *)p)->stream->readBytes(buffer,len);
|
||||||
},this);
|
},this);
|
||||||
if (rd != 0){
|
if (rd != 0){
|
||||||
LOG_DEBUG(GwLog::DEBUG+2,"GwSerial %d read %d bytes",id,rd);
|
LOG_DEBUG(GwLog::DEBUG+2,"GwSerial %d read %d bytes",id,rd);
|
||||||
|
@ -106,7 +123,7 @@ void GwSerial::loop(bool handleRead,bool handleWrite){
|
||||||
else{
|
else{
|
||||||
uint8_t buffer[10];
|
uint8_t buffer[10];
|
||||||
if (available > 10) available=10;
|
if (available > 10) available=10;
|
||||||
serial->readBytes(buffer,available);
|
stream->readBytes(buffer,available);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void GwSerial::readMessages(GwMessageFetcher *writer){
|
void GwSerial::readMessages(GwMessageFetcher *writer){
|
||||||
|
@ -115,10 +132,11 @@ void GwSerial::readMessages(GwMessageFetcher *writer){
|
||||||
writer->handleBuffer(readBuffer);
|
writer->handleBuffer(readBuffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool GwSerial::flush(long max){
|
bool GwSerial::flush(){
|
||||||
if (! isInitialized()) return false;
|
if (! isInitialized()) return false;
|
||||||
|
long max=getFlushTimeout();
|
||||||
if (! availableWrite) {
|
if (! availableWrite) {
|
||||||
if ( serial->availableForWrite() < 1){
|
if ( availableForWrite() < 1){
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
availableWrite=true;
|
availableWrite=true;
|
||||||
|
@ -128,7 +146,7 @@ bool GwSerial::flush(long max){
|
||||||
if (write() != GwBuffer::AGAIN) return true;
|
if (write() != GwBuffer::AGAIN) return true;
|
||||||
vTaskDelay(1);
|
vTaskDelay(1);
|
||||||
}
|
}
|
||||||
availableWrite=(serial->availableForWrite() > 0);
|
availableWrite=(availableForWrite() > 0);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
Stream * GwSerial::getStream(bool partialWrite){
|
Stream * GwSerial::getStream(bool partialWrite){
|
||||||
|
|
|
@ -4,31 +4,119 @@
|
||||||
#include "GwLog.h"
|
#include "GwLog.h"
|
||||||
#include "GwBuffer.h"
|
#include "GwBuffer.h"
|
||||||
#include "GwChannelInterface.h"
|
#include "GwChannelInterface.h"
|
||||||
|
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32S3
|
||||||
|
#include "hal/usb_serial_jtag_ll.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define USBCDC_RESTART_TIME 100
|
||||||
class GwSerialStream;
|
class GwSerialStream;
|
||||||
class GwSerial : public GwChannelInterface{
|
class GwSerial : public GwChannelInterface{
|
||||||
private:
|
protected:
|
||||||
GwBuffer *buffer;
|
GwBuffer *buffer;
|
||||||
GwBuffer *readBuffer=NULL;
|
GwBuffer *readBuffer=NULL;
|
||||||
GwLog *logger;
|
GwLog *logger;
|
||||||
|
Stream *stream;
|
||||||
bool initialized=false;
|
bool initialized=false;
|
||||||
bool allowRead=true;
|
bool allowRead=true;
|
||||||
GwBuffer::WriteStatus write();
|
GwBuffer::WriteStatus write();
|
||||||
int id=-1;
|
int id=-1;
|
||||||
int overflows=0;
|
int overflows=0;
|
||||||
size_t enqueue(const uint8_t *data, size_t len,bool partial=false);
|
size_t enqueue(const uint8_t *data, size_t len,bool partial=false);
|
||||||
Stream *serial;
|
|
||||||
bool availableWrite=false; //if this is false we will wait for availabkleWrite until we flush again
|
bool availableWrite=false; //if this is false we will wait for availabkleWrite until we flush again
|
||||||
|
virtual long getFlushTimeout(){return 2000;}
|
||||||
|
virtual int availableForWrite()=0;
|
||||||
|
int type=0;
|
||||||
public:
|
public:
|
||||||
static const int bufferSize=200;
|
GwSerial(GwLog *logger,Stream *stream,int id,int type,bool allowRead=true);
|
||||||
GwSerial(GwLog *logger,Stream *stream,int id,bool allowRead=true);
|
virtual ~GwSerial();
|
||||||
~GwSerial();
|
|
||||||
bool isInitialized();
|
bool isInitialized();
|
||||||
virtual size_t sendToClients(const char *buf,int sourceId,bool partial=false);
|
virtual size_t sendToClients(const char *buf,int sourceId,bool partial=false);
|
||||||
virtual void loop(bool handleRead=true,bool handleWrite=true);
|
virtual void loop(bool handleRead=true,bool handleWrite=true);
|
||||||
virtual void readMessages(GwMessageFetcher *writer);
|
virtual void readMessages(GwMessageFetcher *writer);
|
||||||
bool flush(long millis=200);
|
bool flush();
|
||||||
virtual Stream *getStream(bool partialWrites);
|
virtual Stream *getStream(bool partialWrites);
|
||||||
bool getAvailableWrite(){return availableWrite;}
|
bool getAvailableWrite(){return availableWrite;}
|
||||||
|
virtual void begin(unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1)=0;
|
||||||
|
virtual String getMode() override;
|
||||||
friend GwSerialStream;
|
friend GwSerialStream;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
class GwSerialImpl : public GwSerial{
|
||||||
|
private:
|
||||||
|
unsigned long lastWritable=0;
|
||||||
|
template<class C>
|
||||||
|
void beginImpl(C *s,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1){}
|
||||||
|
void beginImpl(HardwareSerial *s,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1){
|
||||||
|
s->begin(baud,config,rxPin,txPin);
|
||||||
|
}
|
||||||
|
template<class C>
|
||||||
|
void setError(C* s, GwLog *logger){}
|
||||||
|
void setError(HardwareSerial *s,GwLog *logger){
|
||||||
|
LOG_DEBUG(GwLog::LOG,"enable serial errors for channel %d",id);
|
||||||
|
s->onReceiveError([logger,this](hardwareSerial_error_t err){
|
||||||
|
LOG_DEBUG(GwLog::ERROR,"serial error on id %d: %d",this->id,(int)err);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32S3
|
||||||
|
void beginImpl(HWCDC *s,unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1){
|
||||||
|
s->begin(baud);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
template<class C>
|
||||||
|
long getFlushTimeoutImpl(const C*){return 2000;}
|
||||||
|
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32S3
|
||||||
|
long getFlushTimeoutImpl(HWCDC *){return 200;}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
template<class C>
|
||||||
|
int availableForWrite(C* c){
|
||||||
|
return c->availableForWrite();
|
||||||
|
}
|
||||||
|
|
||||||
|
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32S3
|
||||||
|
/**
|
||||||
|
* issue #81
|
||||||
|
* workaround for the HWCDC beeing stuck at some point in time
|
||||||
|
* with availableForWrite == 0 but the ISR being disabled
|
||||||
|
* we simply give a small delay of 100ms for availableForWrite being 0
|
||||||
|
* and afterwards retrigger the ISR
|
||||||
|
*/
|
||||||
|
int availableForWrite(HWCDC* c){
|
||||||
|
int rt=c->availableForWrite();
|
||||||
|
if (rt > 0) {
|
||||||
|
lastWritable=millis();
|
||||||
|
return rt;
|
||||||
|
}
|
||||||
|
unsigned long now=millis();
|
||||||
|
if (now > (lastWritable+USBCDC_RESTART_TIME)){
|
||||||
|
lastWritable=now;
|
||||||
|
if (c->isConnected()){
|
||||||
|
//this retriggers the ISR
|
||||||
|
usb_serial_jtag_ll_ena_intr_mask(USB_SERIAL_JTAG_INTR_SERIAL_IN_EMPTY);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return rt;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
T *serial;
|
||||||
|
protected:
|
||||||
|
virtual long getFlushTimeout() override{
|
||||||
|
return getFlushTimeoutImpl(serial);
|
||||||
|
}
|
||||||
|
virtual int availableForWrite(){
|
||||||
|
return availableForWrite(serial);
|
||||||
|
}
|
||||||
|
public:
|
||||||
|
GwSerialImpl(GwLog* logger,T* s,int i,int type,bool allowRead=true): GwSerial(logger,s,i,type,allowRead),serial(s){}
|
||||||
|
virtual ~GwSerialImpl(){}
|
||||||
|
virtual void begin(unsigned long baud, uint32_t config=SERIAL_8N1, int8_t rxPin=-1, int8_t txPin=-1) override{
|
||||||
|
beginImpl(serial,baud,config,rxPin,txPin);
|
||||||
|
setError(serial,logger);
|
||||||
|
};
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
|
@ -17,4 +17,12 @@ class GwSocketHelper{
|
||||||
if (setsockopt(socket, IPPROTO_TCP, TCP_KEEPCNT, &val, sizeof(val)) != ESP_OK) return false;
|
if (setsockopt(socket, IPPROTO_TCP, TCP_KEEPCNT, &val, sizeof(val)) != ESP_OK) return false;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
static bool isMulticast(const String &addr){
|
||||||
|
in_addr iaddr;
|
||||||
|
if (inet_pton(AF_INET,addr.c_str(),&iaddr) != 1) return false;
|
||||||
|
return IN_MULTICAST(ntohl(iaddr.s_addr));
|
||||||
|
}
|
||||||
|
static bool equals(const in_addr &left, const in_addr &right){
|
||||||
|
return left.s_addr == right.s_addr;
|
||||||
|
}
|
||||||
};
|
};
|
|
@ -0,0 +1,167 @@
|
||||||
|
#include "GwUdpReader.h"
|
||||||
|
#include <ESPmDNS.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include "GwBuffer.h"
|
||||||
|
#include "GwSocketConnection.h"
|
||||||
|
#include "GwSocketHelper.h"
|
||||||
|
#include "GWWifi.h"
|
||||||
|
|
||||||
|
|
||||||
|
GwUdpReader::GwUdpReader(const GwConfigHandler *config, GwLog *logger, int minId)
|
||||||
|
{
|
||||||
|
this->config = config;
|
||||||
|
this->logger = logger;
|
||||||
|
this->minId = minId;
|
||||||
|
port=config->getInt(GwConfigDefinitions::udprPort);
|
||||||
|
buffer= new GwBuffer(logger,GwBuffer::RX_BUFFER_SIZE,"udprd");
|
||||||
|
}
|
||||||
|
|
||||||
|
void GwUdpReader::createAndBind(){
|
||||||
|
if (fd >= 0){
|
||||||
|
::close(fd);
|
||||||
|
}
|
||||||
|
if (currentStationIp.isEmpty() && (type == T_STA || type == T_MCSTA)) return;
|
||||||
|
fd=socket(AF_INET,SOCK_DGRAM,IPPROTO_IP);
|
||||||
|
if (fd < 0){
|
||||||
|
LOG_ERROR("UDPR: unable to create udp socket: %d",errno);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
int enable = 1;
|
||||||
|
setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &enable, sizeof(int));
|
||||||
|
if (type == T_STA)
|
||||||
|
{
|
||||||
|
if (inet_pton(AF_INET, currentStationIp.c_str(), &listenA.sin_addr) != 1)
|
||||||
|
{
|
||||||
|
LOG_ERROR("UDPR: invalid station ip address %s", currentStationIp.c_str());
|
||||||
|
close(fd);
|
||||||
|
fd = -1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (bind(fd,(struct sockaddr *)&listenA,sizeof(listenA)) < 0){
|
||||||
|
LOG_ERROR("UDPR: unable to bind: %d",errno);
|
||||||
|
close(fd);
|
||||||
|
fd=-1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
LOG_INFO("UDPR: socket created and bound");
|
||||||
|
if (type != T_MCALL && type != T_MCAP && type != T_MCSTA) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
struct ip_mreq mc;
|
||||||
|
mc.imr_multiaddr=listenA.sin_addr;
|
||||||
|
if (type == T_MCALL || type == T_MCAP){
|
||||||
|
mc.imr_interface=apAddr;
|
||||||
|
int res=setsockopt(fd,IPPROTO_IP,IP_ADD_MEMBERSHIP,&mc,sizeof(mc));
|
||||||
|
if (res != 0){
|
||||||
|
LOG_ERROR("UDPR: unable to add MC membership for AP:%d",errno);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
LOG_INFO("UDPR: membership for for AP");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (!currentStationIp.isEmpty() && (type == T_MCALL || type == T_MCSTA))
|
||||||
|
{
|
||||||
|
mc.imr_interface = staAddr;
|
||||||
|
int res = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mc, sizeof(mc));
|
||||||
|
if (res != 0)
|
||||||
|
{
|
||||||
|
LOG_ERROR("UDPR: unable to add MC membership for STA:%d", errno);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
LOG_INFO("UDPR: membership for STA %s",currentStationIp.c_str());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void GwUdpReader::begin()
|
||||||
|
{
|
||||||
|
if (type != T_UNKNOWN) return; //already started
|
||||||
|
type=(UType)(config->getInt(GwConfigDefinitions::udprType));
|
||||||
|
LOG_INFO("UDPR begin, mode=%d",(int)type);
|
||||||
|
port=config->getInt(GwConfigDefinitions::udprPort);
|
||||||
|
listenA.sin_family=AF_INET;
|
||||||
|
listenA.sin_port=htons(port);
|
||||||
|
listenA.sin_addr.s_addr=htonl(INADDR_ANY); //default
|
||||||
|
String ap=WiFi.softAPIP().toString();
|
||||||
|
if (inet_pton(AF_INET, ap.c_str(), &apAddr) != 1)
|
||||||
|
{
|
||||||
|
LOG_ERROR("UDPR: invalid ap ip address %s", ap.c_str());
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (type == T_MCALL || type == T_MCAP || type == T_MCSTA){
|
||||||
|
String mcAddr=config->getString(GwConfigDefinitions::udprMC);
|
||||||
|
if (inet_pton(AF_INET, mcAddr.c_str(), &listenA.sin_addr) != 1)
|
||||||
|
{
|
||||||
|
LOG_ERROR("UDPR: invalid mc address %s", mcAddr.c_str());
|
||||||
|
close(fd);
|
||||||
|
fd = -1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
LOG_INFO("UDPR: using multicast address %s",mcAddr.c_str());
|
||||||
|
}
|
||||||
|
if (type == T_AP){
|
||||||
|
listenA.sin_addr=apAddr;
|
||||||
|
}
|
||||||
|
String sta;
|
||||||
|
if (WiFi.isConnected()) sta=WiFi.localIP().toString();
|
||||||
|
setStationAdd(sta);
|
||||||
|
createAndBind();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool GwUdpReader::setStationAdd(const String &sta){
|
||||||
|
if (sta == currentStationIp) return false;
|
||||||
|
currentStationIp=sta;
|
||||||
|
if (inet_pton(AF_INET, currentStationIp.c_str(), &staAddr) != 1){
|
||||||
|
LOG_ERROR("UDPR: invalid station ip address %s", currentStationIp.c_str());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
LOG_INFO("UDPR: new station IP %s",currentStationIp.c_str());
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
void GwUdpReader::loop(bool handleRead, bool handleWrite)
|
||||||
|
{
|
||||||
|
if (handleRead){
|
||||||
|
if (type == T_STA || type == T_MCALL || type == T_MCSTA){
|
||||||
|
//only change anything if we considered the station IP
|
||||||
|
String nextStationIp;
|
||||||
|
if (WiFi.isConnected()){
|
||||||
|
nextStationIp=WiFi.localIP().toString();
|
||||||
|
}
|
||||||
|
if (setStationAdd(nextStationIp)){
|
||||||
|
LOG_INFO("UDPR: wifi client IP changed, restart");
|
||||||
|
createAndBind();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void GwUdpReader::readMessages(GwMessageFetcher *writer)
|
||||||
|
{
|
||||||
|
if (fd < 0) return;
|
||||||
|
//we expect one NMEA message in one UDP packet
|
||||||
|
buffer->reset();
|
||||||
|
size_t rd=buffer->fillData(buffer->freeSpace(),
|
||||||
|
[this](uint8_t *rcvb,size_t rcvlen,void *param)->size_t{
|
||||||
|
struct sockaddr_in from;
|
||||||
|
socklen_t fromLen=sizeof(from);
|
||||||
|
ssize_t res=recvfrom(fd,rcvb,rcvlen,MSG_DONTWAIT,
|
||||||
|
(struct sockaddr*)&from,&fromLen);
|
||||||
|
if (res <= 0) return 0;
|
||||||
|
if (GwSocketHelper::equals(from.sin_addr,apAddr)) return 0;
|
||||||
|
if (!currentStationIp.isEmpty() && (GwSocketHelper::equals(from.sin_addr,staAddr))) return 0;
|
||||||
|
return res;
|
||||||
|
},this);
|
||||||
|
if (buffer->usedSpace() > 0)(GwLog::DEBUG,"UDPR: received %d bytes",buffer->usedSpace());
|
||||||
|
writer->handleBuffer(buffer);
|
||||||
|
}
|
||||||
|
size_t GwUdpReader::sendToClients(const char *buf, int source,bool partial)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
GwUdpReader::~GwUdpReader()
|
||||||
|
{
|
||||||
|
}
|
|
@ -0,0 +1,45 @@
|
||||||
|
#ifndef _GWUDPREADER_H
|
||||||
|
#define _GWUDPREADER_H
|
||||||
|
#include "GWConfig.h"
|
||||||
|
#include "GwLog.h"
|
||||||
|
#include "GwBuffer.h"
|
||||||
|
#include "GwChannelInterface.h"
|
||||||
|
#include <memory>
|
||||||
|
#include <sys/socket.h>
|
||||||
|
#include <arpa/inet.h>
|
||||||
|
|
||||||
|
class GwUdpReader: public GwChannelInterface{
|
||||||
|
public:
|
||||||
|
using UType=enum{
|
||||||
|
T_ALL=0,
|
||||||
|
T_AP=1,
|
||||||
|
T_STA=2,
|
||||||
|
T_MCALL=4,
|
||||||
|
T_MCAP=5,
|
||||||
|
T_MCSTA=6,
|
||||||
|
T_UNKNOWN=-1
|
||||||
|
};
|
||||||
|
private:
|
||||||
|
const GwConfigHandler *config;
|
||||||
|
GwLog *logger;
|
||||||
|
int minId;
|
||||||
|
int port;
|
||||||
|
int fd=-1;
|
||||||
|
struct sockaddr_in listenA;
|
||||||
|
String listenIp;
|
||||||
|
String currentStationIp;
|
||||||
|
struct in_addr apAddr;
|
||||||
|
struct in_addr staAddr;
|
||||||
|
UType type=T_UNKNOWN;
|
||||||
|
void createAndBind();
|
||||||
|
bool setStationAdd(const String &sta);
|
||||||
|
GwBuffer *buffer=nullptr;
|
||||||
|
public:
|
||||||
|
GwUdpReader(const GwConfigHandler *config,GwLog *logger,int minId);
|
||||||
|
~GwUdpReader();
|
||||||
|
void begin();
|
||||||
|
virtual void loop(bool handleRead=true,bool handleWrite=true);
|
||||||
|
virtual size_t sendToClients(const char *buf,int sourceId, bool partialWrite=false);
|
||||||
|
virtual void readMessages(GwMessageFetcher *writer);
|
||||||
|
};
|
||||||
|
#endif
|
|
@ -0,0 +1,203 @@
|
||||||
|
#include "GwUdpWriter.h"
|
||||||
|
#include <ESPmDNS.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include "GwBuffer.h"
|
||||||
|
#include "GwSocketConnection.h"
|
||||||
|
#include "GwSocketHelper.h"
|
||||||
|
#include "GWWifi.h"
|
||||||
|
|
||||||
|
GwUdpWriter::WriterSocket::WriterSocket(GwLog *l,int p,const String &src,const String &dst, SourceMode sm) :
|
||||||
|
sourceMode(sm), source(src), destination(dst), port(p),logger(l)
|
||||||
|
{
|
||||||
|
if (inet_pton(AF_INET, dst.c_str(), &dstA.sin_addr) != 1)
|
||||||
|
{
|
||||||
|
LOG_ERROR("UDPW: invalid destination ip address %s", dst.c_str());
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (sourceMode != SourceMode::S_UNBOUND)
|
||||||
|
{
|
||||||
|
if (inet_pton(AF_INET, src.c_str(), &srcA) != 1)
|
||||||
|
{
|
||||||
|
LOG_ERROR("UDPW: invalid source ip address %s", src.c_str());
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
dstA.sin_family=AF_INET;
|
||||||
|
dstA.sin_port=htons(port);
|
||||||
|
fd=socket(AF_INET,SOCK_DGRAM,IPPROTO_IP);
|
||||||
|
if (fd < 0){
|
||||||
|
LOG_ERROR("UDPW: unable to create udp socket: %d",errno);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
int enable = 1;
|
||||||
|
setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &enable, sizeof(int));
|
||||||
|
setsockopt(fd, SOL_SOCKET, SO_BROADCAST, &enable, sizeof(int));
|
||||||
|
switch (sourceMode)
|
||||||
|
{
|
||||||
|
case SourceMode::S_SRC:
|
||||||
|
{
|
||||||
|
sockaddr_in bindA;
|
||||||
|
bindA.sin_family = AF_INET;
|
||||||
|
bindA.sin_port = htons(0); // let system select
|
||||||
|
bindA.sin_addr = srcA;
|
||||||
|
if (bind(fd, (struct sockaddr *)&bindA, sizeof(bindA)) != 0)
|
||||||
|
{
|
||||||
|
LOG_ERROR("UDPW: bind failed for address %s: %d", source.c_str(), errno);
|
||||||
|
::close(fd);
|
||||||
|
fd = -1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case SourceMode::S_MC:
|
||||||
|
{
|
||||||
|
if (setsockopt(fd,IPPROTO_IP,IP_MULTICAST_IF,&srcA,sizeof(srcA)) != 0){
|
||||||
|
LOG_ERROR("UDPW: unable to set MC source %s: %d",source.c_str(),errno);
|
||||||
|
::close(fd);
|
||||||
|
fd=-1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
int loop=0;
|
||||||
|
setsockopt(fd,IPPROTO_IP,IP_MULTICAST_LOOP,&loop,sizeof(loop));
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
//not bound
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
bool GwUdpWriter::WriterSocket::changed(const String &newSrc, const String &newDst){
|
||||||
|
if (newDst != destination) return true;
|
||||||
|
if (sourceMode == SourceMode::S_UNBOUND) return false;
|
||||||
|
return newSrc != source;
|
||||||
|
}
|
||||||
|
size_t GwUdpWriter::WriterSocket::send(const char *buf,size_t len){
|
||||||
|
if (fd < 0) return 0;
|
||||||
|
ssize_t err = sendto(fd,buf,len,0,(struct sockaddr *)&dstA, sizeof(dstA));
|
||||||
|
if (err < 0){
|
||||||
|
LOG_DEBUG(GwLog::DEBUG,"UDPW %s error sending: %d",destination.c_str(), errno);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return err;
|
||||||
|
}
|
||||||
|
|
||||||
|
GwUdpWriter::GwUdpWriter(const GwConfigHandler *config, GwLog *logger, int minId)
|
||||||
|
{
|
||||||
|
this->config = config;
|
||||||
|
this->logger = logger;
|
||||||
|
this->minId = minId;
|
||||||
|
port=config->getInt(GwConfigDefinitions::udpwPort);
|
||||||
|
|
||||||
|
}
|
||||||
|
void GwUdpWriter::checkStaSocket(){
|
||||||
|
String src;
|
||||||
|
String bc;
|
||||||
|
if (type == T_BCAP || type == T_MCAP || type == T_NORM || type == T_UNKNOWN ) return;
|
||||||
|
bool connected=false;
|
||||||
|
if (WiFi.isConnected()){
|
||||||
|
src=WiFi.localIP().toString();
|
||||||
|
bc=WiFi.broadcastIP().toString();
|
||||||
|
connected=true;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
if (staSocket == nullptr) return;
|
||||||
|
}
|
||||||
|
String dst;
|
||||||
|
WriterSocket::SourceMode sm=WriterSocket::SourceMode::S_SRC;
|
||||||
|
switch (type){
|
||||||
|
case T_BCALL:
|
||||||
|
case T_BCSTA:
|
||||||
|
sm=WriterSocket::SourceMode::S_SRC;
|
||||||
|
dst=bc;
|
||||||
|
break;
|
||||||
|
case T_MCALL:
|
||||||
|
case T_MCSTA:
|
||||||
|
dst=config->getString(GwConfigDefinitions::udpwMC);
|
||||||
|
sm=WriterSocket::SourceMode::S_MC;
|
||||||
|
break;
|
||||||
|
|
||||||
|
}
|
||||||
|
if (staSocket != nullptr)
|
||||||
|
{
|
||||||
|
if (!connected || staSocket->changed(src, dst))
|
||||||
|
{
|
||||||
|
staSocket->close();
|
||||||
|
delete staSocket;
|
||||||
|
staSocket = nullptr;
|
||||||
|
LOG_INFO("changing/stopping UDPW(sta) socket");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (staSocket == nullptr && connected)
|
||||||
|
{
|
||||||
|
LOG_INFO("creating new UDP(sta) socket src=%s, dst=%s", src.c_str(), dst.c_str());
|
||||||
|
staSocket = new WriterSocket(logger, port, src, dst, WriterSocket::SourceMode::S_SRC);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void GwUdpWriter::begin()
|
||||||
|
{
|
||||||
|
if (type != T_UNKNOWN) return; //already started
|
||||||
|
type=(UType)(config->getInt(GwConfigDefinitions::udpwType));
|
||||||
|
LOG_INFO("UDPW begin, mode=%d",(int)type);
|
||||||
|
String src=WiFi.softAPIP().toString();
|
||||||
|
String dst;
|
||||||
|
WriterSocket::SourceMode sm=WriterSocket::SourceMode::S_UNBOUND;
|
||||||
|
bool createApSocket=false;
|
||||||
|
switch(type){
|
||||||
|
case T_BCALL:
|
||||||
|
case T_BCAP:
|
||||||
|
createApSocket=true;
|
||||||
|
dst=WiFi.softAPBroadcastIP().toString();
|
||||||
|
sm=WriterSocket::SourceMode::S_SRC;
|
||||||
|
break;
|
||||||
|
case T_MCALL:
|
||||||
|
case T_MCAP:
|
||||||
|
createApSocket=true;
|
||||||
|
dst=config->getString(GwConfigDefinitions::udpwMC);
|
||||||
|
sm=WriterSocket::SourceMode::S_SRC;
|
||||||
|
break;
|
||||||
|
case T_NORM:
|
||||||
|
createApSocket=true;
|
||||||
|
dst=config->getString(GwConfigDefinitions::udpwAddress);
|
||||||
|
sm=WriterSocket::SourceMode::S_UNBOUND;
|
||||||
|
}
|
||||||
|
if (createApSocket){
|
||||||
|
LOG_INFO("creating new UDPW(ap) socket src=%s, dst=%s", src.c_str(), dst.c_str());
|
||||||
|
apSocket=new WriterSocket(logger,port,src,dst,sm);
|
||||||
|
}
|
||||||
|
checkStaSocket();
|
||||||
|
}
|
||||||
|
|
||||||
|
void GwUdpWriter::loop(bool handleRead, bool handleWrite)
|
||||||
|
{
|
||||||
|
if (handleWrite){
|
||||||
|
checkStaSocket();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void GwUdpWriter::readMessages(GwMessageFetcher *writer)
|
||||||
|
{
|
||||||
|
|
||||||
|
}
|
||||||
|
size_t GwUdpWriter::sendToClients(const char *buf, int source,bool partial)
|
||||||
|
{
|
||||||
|
if (source == minId) return 0;
|
||||||
|
size_t len=strlen(buf);
|
||||||
|
bool hasSent=false;
|
||||||
|
size_t res=0;
|
||||||
|
if (apSocket != nullptr){
|
||||||
|
res=apSocket->send(buf,len);
|
||||||
|
if (res > 0) hasSent=true;
|
||||||
|
}
|
||||||
|
if (staSocket != nullptr){
|
||||||
|
res=staSocket->send(buf,len);
|
||||||
|
if (res > 0) hasSent=true;
|
||||||
|
}
|
||||||
|
return hasSent?len:0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
GwUdpWriter::~GwUdpWriter()
|
||||||
|
{
|
||||||
|
}
|
|
@ -0,0 +1,73 @@
|
||||||
|
#ifndef _GWUDPWRITER_H
|
||||||
|
#define _GWUDPWRITER_H
|
||||||
|
#include "GWConfig.h"
|
||||||
|
#include "GwLog.h"
|
||||||
|
#include "GwBuffer.h"
|
||||||
|
#include "GwChannelInterface.h"
|
||||||
|
#include <memory>
|
||||||
|
#include <sys/socket.h>
|
||||||
|
#include <arpa/inet.h>
|
||||||
|
|
||||||
|
class GwUdpWriter: public GwChannelInterface{
|
||||||
|
public:
|
||||||
|
using UType=enum{
|
||||||
|
T_BCALL=0,
|
||||||
|
T_BCAP=1,
|
||||||
|
T_BCSTA=2,
|
||||||
|
T_NORM=3,
|
||||||
|
T_MCALL=4,
|
||||||
|
T_MCAP=5,
|
||||||
|
T_MCSTA=6,
|
||||||
|
T_UNKNOWN=-1
|
||||||
|
};
|
||||||
|
private:
|
||||||
|
class WriterSocket{
|
||||||
|
public:
|
||||||
|
int fd=-1;
|
||||||
|
struct in_addr srcA;
|
||||||
|
struct sockaddr_in dstA;
|
||||||
|
String source;
|
||||||
|
String destination;
|
||||||
|
int port;
|
||||||
|
GwLog *logger;
|
||||||
|
using SourceMode=enum {
|
||||||
|
S_UNBOUND=0,
|
||||||
|
S_MC,
|
||||||
|
S_SRC
|
||||||
|
};
|
||||||
|
SourceMode sourceMode;
|
||||||
|
WriterSocket(GwLog *logger,int p,const String &src,const String &dst, SourceMode sm);
|
||||||
|
void close(){
|
||||||
|
if (fd > 0){
|
||||||
|
::close(fd);
|
||||||
|
}
|
||||||
|
fd=-1;
|
||||||
|
}
|
||||||
|
~WriterSocket(){
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
bool changed(const String &newSrc, const String &newDst);
|
||||||
|
size_t send(const char *buf,size_t len);
|
||||||
|
};
|
||||||
|
const GwConfigHandler *config;
|
||||||
|
GwLog *logger;
|
||||||
|
/**
|
||||||
|
* we use fd/address to send to the AP network
|
||||||
|
* and fd2,address2 to send to the station network
|
||||||
|
* for type "normal" we only use fd
|
||||||
|
*/
|
||||||
|
WriterSocket *apSocket=nullptr; //also for T_NORM
|
||||||
|
WriterSocket *staSocket=nullptr;
|
||||||
|
int minId;
|
||||||
|
int port;
|
||||||
|
UType type=T_UNKNOWN;
|
||||||
|
void checkStaSocket();
|
||||||
|
public:
|
||||||
|
GwUdpWriter(const GwConfigHandler *config,GwLog *logger,int minId);
|
||||||
|
~GwUdpWriter();
|
||||||
|
void begin();
|
||||||
|
virtual void loop(bool handleRead=true,bool handleWrite=true);
|
||||||
|
virtual size_t sendToClients(const char *buf,int sourceId, bool partialWrite=false);
|
||||||
|
virtual void readMessages(GwMessageFetcher *writer);
|
||||||
|
};
|
||||||
|
#endif
|
|
@ -191,6 +191,7 @@ class TaskApi : public GwApiInternal
|
||||||
SemaphoreHandle_t *mainLock;
|
SemaphoreHandle_t *mainLock;
|
||||||
SemaphoreHandle_t localLock;
|
SemaphoreHandle_t localLock;
|
||||||
std::map<int,GwCounter<String>> counter;
|
std::map<int,GwCounter<String>> counter;
|
||||||
|
std::map<String,GwApi::HandlerFunction> webHandlers;
|
||||||
String name;
|
String name;
|
||||||
bool counterUsed=false;
|
bool counterUsed=false;
|
||||||
int counterIdx=0;
|
int counterIdx=0;
|
||||||
|
@ -315,6 +316,10 @@ public:
|
||||||
virtual bool addXdrMapping(const GwXDRMappingDef &def){
|
virtual bool addXdrMapping(const GwXDRMappingDef &def){
|
||||||
return api->addXdrMapping(def);
|
return api->addXdrMapping(def);
|
||||||
}
|
}
|
||||||
|
virtual void registerRequestHandler(const String &url,HandlerFunction handler){
|
||||||
|
GWSYNCHRONIZED(&localLock);
|
||||||
|
webHandlers[url]=handler;
|
||||||
|
}
|
||||||
virtual void addCapability(const String &name, const String &value){
|
virtual void addCapability(const String &name, const String &value){
|
||||||
if (! isInit) return;
|
if (! isInit) return;
|
||||||
userCapabilities[name]=value;
|
userCapabilities[name]=value;
|
||||||
|
@ -335,6 +340,16 @@ public:
|
||||||
virtual void setCalibrationValue(const String &name, double value){
|
virtual void setCalibrationValue(const String &name, double value){
|
||||||
api->setCalibrationValue(name,value);
|
api->setCalibrationValue(name,value);
|
||||||
}
|
}
|
||||||
|
virtual bool handleWebRequest(const String &url,AsyncWebServerRequest *req){
|
||||||
|
GWSYNCHRONIZED(&localLock);
|
||||||
|
auto it=webHandlers.find(url);
|
||||||
|
if (it == webHandlers.end()){
|
||||||
|
api->getLogger()->logDebug(GwLog::LOG,"no web handler task=%s url=%s",name.c_str(),url.c_str());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
it->second(req);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -405,3 +420,18 @@ int GwUserCode::getJsonSize(){
|
||||||
}
|
}
|
||||||
return rt;
|
return rt;
|
||||||
}
|
}
|
||||||
|
void GwUserCode::handleWebRequest(const String &url,AsyncWebServerRequest *req){
|
||||||
|
int sep1=url.indexOf('/');
|
||||||
|
String tname;
|
||||||
|
if (sep1 > 0){
|
||||||
|
tname=url.substring(0,sep1);
|
||||||
|
for (auto &&it:userTasks){
|
||||||
|
if (it.api && it.name == tname){
|
||||||
|
if (it.api->handleWebRequest(url.substring(sep1+1),req)) return;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
LOG_DEBUG(GwLog::DEBUG,"no task found for web request %s[%s]",url.c_str(),tname.c_str());
|
||||||
|
req->send(404, "text/plain", "not found");
|
||||||
|
}
|
|
@ -11,6 +11,7 @@ class GwApiInternal : public GwApi{
|
||||||
~GwApiInternal(){}
|
~GwApiInternal(){}
|
||||||
virtual void fillStatus(GwJsonDocument &status){};
|
virtual void fillStatus(GwJsonDocument &status){};
|
||||||
virtual int getJsonSize(){return 0;};
|
virtual int getJsonSize(){return 0;};
|
||||||
|
virtual bool handleWebRequest(const String &url,AsyncWebServerRequest *req){return false;}
|
||||||
};
|
};
|
||||||
class GwUserTask{
|
class GwUserTask{
|
||||||
public:
|
public:
|
||||||
|
@ -50,5 +51,6 @@ class GwUserCode{
|
||||||
Capabilities *getCapabilities();
|
Capabilities *getCapabilities();
|
||||||
void fillStatus(GwJsonDocument &status);
|
void fillStatus(GwJsonDocument &status);
|
||||||
int getJsonSize();
|
int getJsonSize();
|
||||||
|
void handleWebRequest(const String &url,AsyncWebServerRequest *);
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
|
@ -355,6 +355,7 @@ void GwXDRMappings::begin()
|
||||||
GwXDRFoundMapping GwXDRMappings::selectMapping(GwXDRMapping::MappingList *list, int instance, const char *key)
|
GwXDRFoundMapping GwXDRMappings::selectMapping(GwXDRMapping::MappingList *list, int instance, const char *key)
|
||||||
{
|
{
|
||||||
GwXDRMapping *candidate = NULL;
|
GwXDRMapping *candidate = NULL;
|
||||||
|
unsigned long invalidTime=config->getInt(GwConfigDefinitions::timoSensor);
|
||||||
for (auto mit = list->begin(); mit != list->end(); mit++)
|
for (auto mit = list->begin(); mit != list->end(); mit++)
|
||||||
{
|
{
|
||||||
GwXDRMappingDef *def = (*mit)->definition;
|
GwXDRMappingDef *def = (*mit)->definition;
|
||||||
|
@ -369,7 +370,7 @@ GwXDRFoundMapping GwXDRMappings::selectMapping(GwXDRMapping::MappingList *list,
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::DEBUG + 1, "selected mapping %s for %s, i=%d",
|
LOG_DEBUG(GwLog::DEBUG + 1, "selected mapping %s for %s, i=%d",
|
||||||
def->toString().c_str(), key, instance);
|
def->toString().c_str(), key, instance);
|
||||||
return GwXDRFoundMapping(*mit, instance);
|
return GwXDRFoundMapping(*mit,invalidTime, instance);
|
||||||
}
|
}
|
||||||
if (instance < 0)
|
if (instance < 0)
|
||||||
{
|
{
|
||||||
|
@ -393,7 +394,7 @@ GwXDRFoundMapping GwXDRMappings::selectMapping(GwXDRMapping::MappingList *list,
|
||||||
{
|
{
|
||||||
LOG_DEBUG(GwLog::DEBUG + 1, "selected mapping %s for %s, i=%d",
|
LOG_DEBUG(GwLog::DEBUG + 1, "selected mapping %s for %s, i=%d",
|
||||||
candidate->definition->toString().c_str(), key, instance);
|
candidate->definition->toString().c_str(), key, instance);
|
||||||
return GwXDRFoundMapping(candidate, instance>=0?instance:candidate->definition->instanceId);
|
return GwXDRFoundMapping(candidate, invalidTime,instance>=0?instance:candidate->definition->instanceId);
|
||||||
}
|
}
|
||||||
LOG_DEBUG(GwLog::DEBUG + 1, "no instance mapping found for key=%s, i=%d", key, instance);
|
LOG_DEBUG(GwLog::DEBUG + 1, "no instance mapping found for key=%s, i=%d", key, instance);
|
||||||
return GwXDRFoundMapping();
|
return GwXDRFoundMapping();
|
||||||
|
@ -472,8 +473,9 @@ String GwXDRMappings::getXdrEntry(String mapping, double value,int instance){
|
||||||
}
|
}
|
||||||
GwXDRType *type = findType(code, &typeIndex);
|
GwXDRType *type = findType(code, &typeIndex);
|
||||||
bool first=true;
|
bool first=true;
|
||||||
|
unsigned long invalidTime=config->getInt(GwConfigDefinitions::timoSensor);
|
||||||
while (type){
|
while (type){
|
||||||
GwXDRFoundMapping found(def,type);
|
GwXDRFoundMapping found(def,type,invalidTime);
|
||||||
found.instanceId=instance;
|
found.instanceId=instance;
|
||||||
if (first) first=false;
|
if (first) first=false;
|
||||||
else rt+=",";
|
else rt+=",";
|
||||||
|
|
|
@ -167,15 +167,18 @@ class GwXDRFoundMapping : public GwBoatItemNameProvider{
|
||||||
GwXDRType *type=NULL;
|
GwXDRType *type=NULL;
|
||||||
int instanceId=-1;
|
int instanceId=-1;
|
||||||
bool empty=true;
|
bool empty=true;
|
||||||
GwXDRFoundMapping(GwXDRMappingDef *definition,GwXDRType *type){
|
unsigned long timeout=0;
|
||||||
|
GwXDRFoundMapping(GwXDRMappingDef *definition,GwXDRType *type, unsigned long timeout){
|
||||||
this->definition=definition;
|
this->definition=definition;
|
||||||
this->type=type;
|
this->type=type;
|
||||||
|
this->timeout=timeout;
|
||||||
empty=false;
|
empty=false;
|
||||||
}
|
}
|
||||||
GwXDRFoundMapping(GwXDRMapping* mapping,int instance=0){
|
GwXDRFoundMapping(GwXDRMapping* mapping,unsigned long timeout,int instance){
|
||||||
this->definition=mapping->definition;
|
this->definition=mapping->definition;
|
||||||
this->type=mapping->type;
|
this->type=mapping->type;
|
||||||
this->instanceId=instance;
|
this->instanceId=instance;
|
||||||
|
this->timeout=timeout;
|
||||||
empty=false;
|
empty=false;
|
||||||
}
|
}
|
||||||
GwXDRFoundMapping(){}
|
GwXDRFoundMapping(){}
|
||||||
|
@ -195,6 +198,9 @@ class GwXDRFoundMapping : public GwBoatItemNameProvider{
|
||||||
return "formatXdr:"+type->xdrtype+":"+type->boatDataUnit;
|
return "formatXdr:"+type->xdrtype+":"+type->boatDataUnit;
|
||||||
};
|
};
|
||||||
virtual ~GwXDRFoundMapping(){}
|
virtual ~GwXDRFoundMapping(){}
|
||||||
|
virtual unsigned long getInvalidTime() override{
|
||||||
|
return timeout;
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
//the class GwXDRMappings is not intended to be deleted
|
//the class GwXDRMappings is not intended to be deleted
|
||||||
|
|
|
@ -16,25 +16,28 @@ default_envs=
|
||||||
extra_configs=
|
extra_configs=
|
||||||
lib/*task*/platformio.ini
|
lib/*task*/platformio.ini
|
||||||
|
|
||||||
[env]
|
[basedeps]
|
||||||
platform = espressif32 @ 6.3.2
|
|
||||||
framework = arduino
|
|
||||||
;platform_packages=
|
|
||||||
; framework-arduinoespressif32 @ 3.20011.230801
|
|
||||||
; framework-espidf @ 3.50101.0
|
|
||||||
lib_deps =
|
lib_deps =
|
||||||
ttlappalainen/NMEA2000-library @ 4.18.9
|
ttlappalainen/NMEA2000-library @ 4.22.0
|
||||||
ttlappalainen/NMEA0183 @ 1.9.1
|
ttlappalainen/NMEA0183 @ 1.10.1
|
||||||
ArduinoJson @ 6.18.5
|
ArduinoJson @ 6.18.5
|
||||||
AsyncTCP-esphome @ 2.0.1
|
AsyncTCP-esphome @ 2.0.1
|
||||||
ottowinter/ESPAsyncWebServer-esphome@2.0.1
|
ottowinter/ESPAsyncWebServer-esphome@2.0.1
|
||||||
fastled/FastLED @ 3.6.0
|
|
||||||
FS
|
FS
|
||||||
Preferences
|
Preferences
|
||||||
ESPmDNS
|
ESPmDNS
|
||||||
WiFi
|
WiFi
|
||||||
Update
|
Update
|
||||||
|
|
||||||
|
[env]
|
||||||
|
platform = espressif32 @ 6.8.1
|
||||||
|
framework = arduino
|
||||||
|
;platform_packages=
|
||||||
|
; framework-arduinoespressif32 @ 3.20017.0
|
||||||
|
; framework-espidf @ 3.50101.0
|
||||||
|
lib_deps =
|
||||||
|
${basedeps.lib_deps}
|
||||||
|
fastled/FastLED @ 3.6.0
|
||||||
|
|
||||||
|
|
||||||
board_build.embed_files =
|
board_build.embed_files =
|
||||||
|
|
13
src/main.cpp
13
src/main.cpp
|
@ -138,7 +138,7 @@ bool fixedApPass=true;
|
||||||
#endif
|
#endif
|
||||||
GwWifi gwWifi(&config,&logger,fixedApPass);
|
GwWifi gwWifi(&config,&logger,fixedApPass);
|
||||||
GwChannelList channels(&logger,&config);
|
GwChannelList channels(&logger,&config);
|
||||||
GwBoatData boatData(&logger);
|
GwBoatData boatData(&logger,&config);
|
||||||
GwXDRMappings xdrMappings(&logger,&config);
|
GwXDRMappings xdrMappings(&logger,&config);
|
||||||
bool sendOutN2k=true;
|
bool sendOutN2k=true;
|
||||||
|
|
||||||
|
@ -348,6 +348,8 @@ public:
|
||||||
}
|
}
|
||||||
return xdrMappings.addFixedMapping(mapping);
|
return xdrMappings.addFixedMapping(mapping);
|
||||||
}
|
}
|
||||||
|
virtual void registerRequestHandler(const String &url,HandlerFunction handler){
|
||||||
|
}
|
||||||
virtual void addCapability(const String &name, const String &value){}
|
virtual void addCapability(const String &name, const String &value){}
|
||||||
virtual bool addUserTask(GwUserTaskFunction task,const String Name, int stackSize=2000){
|
virtual bool addUserTask(GwUserTaskFunction task,const String Name, int stackSize=2000){
|
||||||
return false;
|
return false;
|
||||||
|
@ -768,6 +770,7 @@ void loopFunction(void *){
|
||||||
//delay(1);
|
//delay(1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
const String USERPREFIX="/api/user/";
|
||||||
void setup() {
|
void setup() {
|
||||||
mainLock=xSemaphoreCreateMutex();
|
mainLock=xSemaphoreCreateMutex();
|
||||||
uint8_t chipid[6];
|
uint8_t chipid[6];
|
||||||
|
@ -784,6 +787,7 @@ void setup() {
|
||||||
logger.prefix="FALLBACK:";
|
logger.prefix="FALLBACK:";
|
||||||
logger.setWriter(new DefaultLogWriter());
|
logger.setWriter(new DefaultLogWriter());
|
||||||
#endif
|
#endif
|
||||||
|
boatData.begin();
|
||||||
userCodeHandler.startInitTasks(MIN_USER_TASK);
|
userCodeHandler.startInitTasks(MIN_USER_TASK);
|
||||||
channels.preinit();
|
channels.preinit();
|
||||||
config.stopChanges();
|
config.stopChanges();
|
||||||
|
@ -845,12 +849,17 @@ void setup() {
|
||||||
buffer[29]=0;
|
buffer[29]=0;
|
||||||
request->send(200,"text/plain",buffer);
|
request->send(200,"text/plain",buffer);
|
||||||
});
|
});
|
||||||
|
webserver.registerHandler((USERPREFIX+"*").c_str(),[&USERPREFIX](AsyncWebServerRequest *req){
|
||||||
|
String turl=req->url().substring(USERPREFIX.length());
|
||||||
|
logger.logDebug(GwLog::DEBUG,"user web request for %s",turl.c_str());
|
||||||
|
userCodeHandler.handleWebRequest(turl,req);
|
||||||
|
});
|
||||||
|
|
||||||
webserver.begin();
|
webserver.begin();
|
||||||
xdrMappings.begin();
|
xdrMappings.begin();
|
||||||
logger.flush();
|
logger.flush();
|
||||||
GwConverterConfig converterConfig;
|
GwConverterConfig converterConfig;
|
||||||
converterConfig.init(&config);
|
converterConfig.init(&config,&logger);
|
||||||
nmea0183Converter= N2kDataToNMEA0183::create(&logger, &boatData,
|
nmea0183Converter= N2kDataToNMEA0183::create(&logger, &boatData,
|
||||||
[](const tNMEA0183Msg &msg, int sourceId){
|
[](const tNMEA0183Msg &msg, int sourceId){
|
||||||
SendNMEA0183Message(msg,sourceId,false);
|
SendNMEA0183Message(msg,sourceId,false);
|
||||||
|
|
Binary file not shown.
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,29 @@
|
||||||
|
#! /usr/bin/env perl
|
||||||
|
use strict;
|
||||||
|
use POSIX qw(strftime);
|
||||||
|
my ($dev,$speed)=@ARGV;
|
||||||
|
if (not defined $dev){
|
||||||
|
die "usage: $0 dev"
|
||||||
|
}
|
||||||
|
if (! -e $dev) {
|
||||||
|
die "$dev not found"
|
||||||
|
}
|
||||||
|
if (defined $speed){
|
||||||
|
print("setting speed $speed");
|
||||||
|
system("stty speed $speed < $dev") == 0 or die "unable to set speed";
|
||||||
|
}
|
||||||
|
system("stty raw < $dev") == 0 or die "unable to set raw mode for $dev";
|
||||||
|
open(my $fh,"<",$dev) or die "unable to open $dev";
|
||||||
|
my $last=0;
|
||||||
|
while (<$fh>){
|
||||||
|
my $x=time();
|
||||||
|
if ($last != 0){
|
||||||
|
if ($x > ($last+5)){
|
||||||
|
print("****gap***\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
printf strftime("%Y/%m/%d-%H%M%S",localtime($x));
|
||||||
|
printf("[%04.2f]: ",$x-$last);
|
||||||
|
$last=$x;
|
||||||
|
print $_;
|
||||||
|
}
|
|
@ -56,7 +56,16 @@ class RequestHandler(http.server.SimpleHTTPRequestHandler):
|
||||||
def do_POST(self):
|
def do_POST(self):
|
||||||
if not self.do_proxy():
|
if not self.do_proxy():
|
||||||
super().do_POST()
|
super().do_POST()
|
||||||
|
def guess_type(self,path):
|
||||||
|
if path.endswith('.gz'):
|
||||||
|
return super().guess_type(path[0:-3])
|
||||||
|
return super().guess_type(path)
|
||||||
|
def end_headers(self):
|
||||||
|
if hasattr(self,"isgz") and self.isgz:
|
||||||
|
self.send_header("Content-Encoding","gzip")
|
||||||
|
super().end_headers()
|
||||||
def translate_path(self, path):
|
def translate_path(self, path):
|
||||||
|
self.isgz=False
|
||||||
"""Translate a /-separated PATH to the local filename syntax.
|
"""Translate a /-separated PATH to the local filename syntax.
|
||||||
|
|
||||||
Components that mean special things to the local file system
|
Components that mean special things to the local file system
|
||||||
|
@ -90,6 +99,9 @@ class RequestHandler(http.server.SimpleHTTPRequestHandler):
|
||||||
rpath += '/'
|
rpath += '/'
|
||||||
if os.path.exists(rpath):
|
if os.path.exists(rpath):
|
||||||
return rpath
|
return rpath
|
||||||
|
if os.path.exists(rpath+".gz"):
|
||||||
|
self.isgz=True
|
||||||
|
return rpath+".gz"
|
||||||
if isSecond:
|
if isSecond:
|
||||||
return rpath
|
return rpath
|
||||||
isSecond=True
|
isSecond=True
|
||||||
|
|
309
web/config.json
309
web/config.json
|
@ -228,6 +228,46 @@
|
||||||
"check": "checkMinMax",
|
"check": "checkMinMax",
|
||||||
"category": "converter"
|
"category": "converter"
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "timeouts",
|
||||||
|
"type": "array",
|
||||||
|
"replace": [
|
||||||
|
{
|
||||||
|
"n": "Default",
|
||||||
|
"d": "4000",
|
||||||
|
"l": "default",
|
||||||
|
"t": "NMEA"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"n": "Sensor",
|
||||||
|
"d": "60000",
|
||||||
|
"l": "sensor",
|
||||||
|
"t": "sensor"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"n": "Long",
|
||||||
|
"d": "32000",
|
||||||
|
"l": "long",
|
||||||
|
"t": "special NMEA"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"n": "Ais",
|
||||||
|
"d": "120000",
|
||||||
|
"l": "ais",
|
||||||
|
"t": "ais"
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"children": [
|
||||||
|
{
|
||||||
|
"name": "timo$n",
|
||||||
|
"label": "timeout $l",
|
||||||
|
"default": "$d",
|
||||||
|
"type": "number",
|
||||||
|
"description": "data timeouts(ms) for $t data",
|
||||||
|
"category": "converter"
|
||||||
|
}
|
||||||
|
]
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "stbRudderI",
|
"name": "stbRudderI",
|
||||||
"label":"stb rudder instance",
|
"label":"stb rudder instance",
|
||||||
|
@ -250,6 +290,71 @@
|
||||||
"description": "the n2k instance to be used as port rudder 0...253, -1 to disable",
|
"description": "the n2k instance to be used as port rudder 0...253, -1 to disable",
|
||||||
"category": "converter"
|
"category": "converter"
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"name": "windmappings",
|
||||||
|
"type": "array",
|
||||||
|
"replace":[
|
||||||
|
{
|
||||||
|
"n": "tng",
|
||||||
|
"l": "true north ground",
|
||||||
|
"t": "True_North=0",
|
||||||
|
"d": "twa_tws"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"n": "mgd",
|
||||||
|
"l": "magnetic ground dir",
|
||||||
|
"t": "Magnetic=1",
|
||||||
|
"d":""
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"n": "awa",
|
||||||
|
"l": "apparent angle",
|
||||||
|
"t": "Apparent=2",
|
||||||
|
"d":"awa_aws"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"n": "gna",
|
||||||
|
"l": "ground angle",
|
||||||
|
"t": "True_boat=3",
|
||||||
|
"d": ""
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"n": "tra",
|
||||||
|
"l": "true angle",
|
||||||
|
"t": "True_water=4",
|
||||||
|
"d":""
|
||||||
|
}
|
||||||
|
|
||||||
|
],
|
||||||
|
"children":[
|
||||||
|
{
|
||||||
|
"name":"windm$n",
|
||||||
|
"type":"list",
|
||||||
|
"description": "mapping of the PGN 130306 wind reference $t",
|
||||||
|
"label":"wind $l",
|
||||||
|
"list":[
|
||||||
|
{"l": "-unset-","v":""},
|
||||||
|
{"l": "TWA/TWS","v":"twa_tws"},
|
||||||
|
{"l": "AWA/AWS", "v":"awa_aws"},
|
||||||
|
{"l": "TWD/TWS","v":"twd_tws"}
|
||||||
|
],
|
||||||
|
"category":"converter",
|
||||||
|
"default":"$d"
|
||||||
|
|
||||||
|
}
|
||||||
|
]
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "winst312",
|
||||||
|
"label": "130312 WTemp iid",
|
||||||
|
"type": "number",
|
||||||
|
"check": "checkMinMax",
|
||||||
|
"min": -1,
|
||||||
|
"max": 256,
|
||||||
|
"description": "the temp instance of PGN 130312 used for water temperature (0...255), use -1 for none, 256 for any",
|
||||||
|
"default": "256",
|
||||||
|
"category":"converter"
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"name": "usbActisense",
|
"name": "usbActisense",
|
||||||
"label": "USB mode",
|
"label": "USB mode",
|
||||||
|
@ -586,6 +691,7 @@
|
||||||
"label": "TCP port",
|
"label": "TCP port",
|
||||||
"type": "number",
|
"type": "number",
|
||||||
"default": "10110",
|
"default": "10110",
|
||||||
|
"check":"checkPort",
|
||||||
"description": "the TCP port we listen on",
|
"description": "the TCP port we listen on",
|
||||||
"category": "TCP server"
|
"category": "TCP server"
|
||||||
},
|
},
|
||||||
|
@ -661,8 +767,12 @@
|
||||||
"label": "remote port",
|
"label": "remote port",
|
||||||
"type": "number",
|
"type": "number",
|
||||||
"default": "10110",
|
"default": "10110",
|
||||||
|
"check":"checkPort",
|
||||||
"description": "the TCP port we connect to",
|
"description": "the TCP port we connect to",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "remoteAddress",
|
"name": "remoteAddress",
|
||||||
|
@ -671,7 +781,10 @@
|
||||||
"default": "",
|
"default": "",
|
||||||
"check": "checkIpAddress",
|
"check": "checkIpAddress",
|
||||||
"description": "the IP address we connect to in the form 192.168.1.2\nor an MDNS name like ESP32NMEA2K.local",
|
"description": "the IP address we connect to in the form 192.168.1.2\nor an MDNS name like ESP32NMEA2K.local",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "sendTCL",
|
"name": "sendTCL",
|
||||||
|
@ -679,7 +792,10 @@
|
||||||
"type": "boolean",
|
"type": "boolean",
|
||||||
"default": "true",
|
"default": "true",
|
||||||
"description": "send out NMEA data to remote TCP server",
|
"description": "send out NMEA data to remote TCP server",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "readTCL",
|
"name": "readTCL",
|
||||||
|
@ -687,7 +803,10 @@
|
||||||
"type": "boolean",
|
"type": "boolean",
|
||||||
"default": "true",
|
"default": "true",
|
||||||
"description": "receive NMEA data from remote TCP server",
|
"description": "receive NMEA data from remote TCP server",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "tclToN2k",
|
"name": "tclToN2k",
|
||||||
|
@ -695,7 +814,10 @@
|
||||||
"type": "boolean",
|
"type": "boolean",
|
||||||
"default": "true",
|
"default": "true",
|
||||||
"description": "convert NMEA0183 from remote TCP server to NMEA2000",
|
"description": "convert NMEA0183 from remote TCP server to NMEA2000",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "tclReadFilter",
|
"name": "tclReadFilter",
|
||||||
|
@ -703,7 +825,10 @@
|
||||||
"type": "filter",
|
"type": "filter",
|
||||||
"default": "",
|
"default": "",
|
||||||
"description": "filter for NMEA0183 data when reading from remote TCP server\nselect aison|aisoff, set a whitelist or a blacklist with NMEA sentences like RMC,RMB",
|
"description": "filter for NMEA0183 data when reading from remote TCP server\nselect aison|aisoff, set a whitelist or a blacklist with NMEA sentences like RMC,RMB",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "tclWriteFilter",
|
"name": "tclWriteFilter",
|
||||||
|
@ -711,7 +836,10 @@
|
||||||
"type": "filter",
|
"type": "filter",
|
||||||
"default": "",
|
"default": "",
|
||||||
"description": "filter for NMEA0183 data when writing to remote TCP server\nselect aison|aisoff, set a whitelist or a blacklist with NMEA sentences like RMC,RMB",
|
"description": "filter for NMEA0183 data when writing to remote TCP server\nselect aison|aisoff, set a whitelist or a blacklist with NMEA sentences like RMC,RMB",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "tclSeasmart",
|
"name": "tclSeasmart",
|
||||||
|
@ -719,7 +847,172 @@
|
||||||
"type": "boolean",
|
"type": "boolean",
|
||||||
"default": "false",
|
"default": "false",
|
||||||
"description": "send NMEA2000 as seasmart to remote TCP server",
|
"description": "send NMEA2000 as seasmart to remote TCP server",
|
||||||
"category": "TCP client"
|
"category": "TCP client",
|
||||||
|
"condition":{
|
||||||
|
"tclEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udpwEnabled",
|
||||||
|
"label": "enable",
|
||||||
|
"type": "boolean",
|
||||||
|
"default": "false",
|
||||||
|
"description":"enable the UDP writer",
|
||||||
|
"category":"UDP writer"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udpwPort",
|
||||||
|
"label": "remote port",
|
||||||
|
"type": "number",
|
||||||
|
"default": "10110",
|
||||||
|
"description": "the UDP port we send to",
|
||||||
|
"check":"checkPort",
|
||||||
|
"category": "UDP writer",
|
||||||
|
"condition":{
|
||||||
|
"udpwEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udpwType",
|
||||||
|
"label": "remote address type",
|
||||||
|
"type": "list",
|
||||||
|
"default": "0",
|
||||||
|
"description": "to which networks/addresses do we send\nbc-all: send broadcast to AP and wifi client network\nbc-ap: send broadcast to access point only\nbc-cli: send broadcast to wifi client network\nnormal: normal target address\nmc-all: multicast to AP and wifi client network\nmc-ap:multicast to AP network\nmc-cli: muticast to wifi client network",
|
||||||
|
"list":[
|
||||||
|
{"l":"bc-all","v":"0"},
|
||||||
|
{"l":"bc-ap","v":"1"},
|
||||||
|
{"l":"bc-cli","v":"2"},
|
||||||
|
{"l":"normal","v":"3"},
|
||||||
|
{"l":"mc-all","v":"4"},
|
||||||
|
{"l":"mc-ap","v":"5"},
|
||||||
|
{"l":"mc-cli","v":"6"}
|
||||||
|
],
|
||||||
|
"category": "UDP writer",
|
||||||
|
"condition":{
|
||||||
|
"udpwEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udpwAddress",
|
||||||
|
"label": "remote address",
|
||||||
|
"type": "string",
|
||||||
|
"default": "",
|
||||||
|
"check": "checkIpAddress",
|
||||||
|
"description": "the IP address we connect to in the form 192.168.1.2",
|
||||||
|
"category": "UDP writer",
|
||||||
|
"condition":{
|
||||||
|
"udpwType":["3"],
|
||||||
|
"udpwEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udpwMC",
|
||||||
|
"label": "multicast address",
|
||||||
|
"type": "string",
|
||||||
|
"default": "224.0.0.1",
|
||||||
|
"check": "checkMCAddress",
|
||||||
|
"description": "the multicast address we send to 224.0.0.0...239.255.255.255",
|
||||||
|
"category": "UDP writer",
|
||||||
|
"condition":{
|
||||||
|
"udpwType":["4","5","6"],
|
||||||
|
"udpwEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udpwWriteFilter",
|
||||||
|
"label": "NMEA write Filter",
|
||||||
|
"type": "filter",
|
||||||
|
"default": "",
|
||||||
|
"description": "filter for NMEA0183 data when writing to remote UDP server\nselect aison|aisoff, set a whitelist or a blacklist with NMEA sentences like RMC,RMB",
|
||||||
|
"category": "UDP writer",
|
||||||
|
"condition":{
|
||||||
|
"udpwEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udpwSeasmart",
|
||||||
|
"label": "Seasmart out",
|
||||||
|
"type": "boolean",
|
||||||
|
"default": "false",
|
||||||
|
"description": "send NMEA2000 as seasmart to remote UDP server",
|
||||||
|
"category": "UDP writer",
|
||||||
|
"condition":{
|
||||||
|
"udpwEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udprEnabled",
|
||||||
|
"label": "enable",
|
||||||
|
"type": "boolean",
|
||||||
|
"default": "false",
|
||||||
|
"description":"enable the UDP reader",
|
||||||
|
"category":"UDP reader"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udprPort",
|
||||||
|
"label": "local port",
|
||||||
|
"type": "number",
|
||||||
|
"default": "10110",
|
||||||
|
"check":"checkPort",
|
||||||
|
"description": "the UDP port we listen on",
|
||||||
|
"category": "UDP reader",
|
||||||
|
"condition":{
|
||||||
|
"udprEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udprType",
|
||||||
|
"label": "local address type",
|
||||||
|
"type": "list",
|
||||||
|
"default": "0",
|
||||||
|
"description": "to which networks/addresses do we listen\nall: listen on AP and wifi client network\nap: listen in access point network only\ncli: listen in wifi client network\nmc-all: receive multicast from AP and wifi client network\nmc-ap:receive multicast from AP network\nmc-cli: receive muticast wifi client network",
|
||||||
|
"list":[
|
||||||
|
{"l":"all","v":"0"},
|
||||||
|
{"l":"ap","v":"1"},
|
||||||
|
{"l":"cli","v":"2"},
|
||||||
|
{"l":"mc-all","v":"4"},
|
||||||
|
{"l":"mc-ap","v":"5"},
|
||||||
|
{"l":"mc-cli","v":"6"}
|
||||||
|
],
|
||||||
|
"category": "UDP reader",
|
||||||
|
"condition":{
|
||||||
|
"udprEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udprToN2k",
|
||||||
|
"label": "to NMEA2000",
|
||||||
|
"type": "boolean",
|
||||||
|
"default": "true",
|
||||||
|
"description": "convert NMEA0183 from UDP to NMEA2000",
|
||||||
|
"category": "UDP reader",
|
||||||
|
"condition":{
|
||||||
|
"udprEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udprMC",
|
||||||
|
"label": "multicast address",
|
||||||
|
"type": "string",
|
||||||
|
"default": "224.0.0.1",
|
||||||
|
"check": "checkMCAddress",
|
||||||
|
"description": "the multicast address we listen on 224.0.0.0...239.255.255.255",
|
||||||
|
"category": "UDP reader",
|
||||||
|
"condition":{
|
||||||
|
"udprType":["4","5","6"],
|
||||||
|
"udprEnabled":"true"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "udprReadFilter",
|
||||||
|
"label": "NMEA read Filter",
|
||||||
|
"type": "filter",
|
||||||
|
"default": "",
|
||||||
|
"description": "filter for NMEA0183 data when receiving\nselect aison|aisoff, set a whitelist or a blacklist with NMEA sentences like RMC,RMB",
|
||||||
|
"category": "UDP reader",
|
||||||
|
"condition":{
|
||||||
|
"udprEnabled":"true"
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"name": "wifiClient",
|
"name": "wifiClient",
|
||||||
|
|
|
@ -22,7 +22,7 @@ body {
|
||||||
overflow: hidden;
|
overflow: hidden;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tabPage{
|
#tabPages{
|
||||||
overflow: auto;
|
overflow: auto;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -120,6 +120,9 @@ body {
|
||||||
.hidden{
|
.hidden{
|
||||||
display: none !important;
|
display: none !important;
|
||||||
}
|
}
|
||||||
|
.dash.invalid{
|
||||||
|
display: none;
|
||||||
|
}
|
||||||
#xdrPage .row>.label{
|
#xdrPage .row>.label{
|
||||||
display: none;
|
display: none;
|
||||||
}
|
}
|
||||||
|
@ -220,6 +223,7 @@ body {
|
||||||
}
|
}
|
||||||
#tabs {
|
#tabs {
|
||||||
display: flex;
|
display: flex;
|
||||||
|
flex-wrap: wrap;
|
||||||
border-bottom: 1px solid grey;
|
border-bottom: 1px solid grey;
|
||||||
margin-bottom: 0.5em;
|
margin-bottom: 0.5em;
|
||||||
}
|
}
|
||||||
|
@ -341,3 +345,6 @@ body {
|
||||||
.error{
|
.error{
|
||||||
color: red;
|
color: red;
|
||||||
}
|
}
|
||||||
|
input.error{
|
||||||
|
background-color: rgba(255, 0, 0, 0.329);
|
||||||
|
}
|
|
@ -23,6 +23,7 @@
|
||||||
<div class="tab" data-page="updatePage">Update</div>
|
<div class="tab" data-page="updatePage">Update</div>
|
||||||
<div class="tab" data-url="https://github.com/wellenvogel/esp32-nmea2000" data-window="help" id="helpButton">Help</div>
|
<div class="tab" data-url="https://github.com/wellenvogel/esp32-nmea2000" data-window="help" id="helpButton">Help</div>
|
||||||
</div>
|
</div>
|
||||||
|
<div id="tabPages">
|
||||||
<div id="statusPage" class="tabPage">
|
<div id="statusPage" class="tabPage">
|
||||||
<div id="statusPageContent">
|
<div id="statusPageContent">
|
||||||
<div class="row">
|
<div class="row">
|
||||||
|
@ -123,6 +124,7 @@
|
||||||
<button id="uploadBin">Upload</button>
|
<button id="uploadBin">Upload</button>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
<div class="overlayContainer hidden" id="overlayContainer">
|
<div class="overlayContainer hidden" id="overlayContainer">
|
||||||
|
|
417
web/index.js
417
web/index.js
|
@ -1,10 +1,14 @@
|
||||||
let self = this;
|
(function () {
|
||||||
let lastUpdate = (new Date()).getTime();
|
let lastUpdate = (new Date()).getTime();
|
||||||
let reloadConfig = false;
|
let reloadConfig = false;
|
||||||
let needAdminPass = true;
|
let needAdminPass = true;
|
||||||
let lastSalt = "";
|
let lastSalt = "";
|
||||||
let channelList = {};
|
let channelList = {};
|
||||||
let minUser = 200;
|
let minUser = 200;
|
||||||
|
let listeners = [];
|
||||||
|
let buttonHandlers={};
|
||||||
|
let checkers={};
|
||||||
|
let userFormatters={};
|
||||||
function addEl(type, clazz, parent, text) {
|
function addEl(type, clazz, parent, text) {
|
||||||
let el = document.createElement(type);
|
let el = document.createElement(type);
|
||||||
if (clazz) {
|
if (clazz) {
|
||||||
|
@ -16,7 +20,12 @@ function addEl(type, clazz, parent, text) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
if (text) el.textContent = text;
|
if (text) el.textContent = text;
|
||||||
|
if (parent) {
|
||||||
|
if (typeof(parent) != 'object'){
|
||||||
|
parent=document.querySelector(parent);
|
||||||
|
}
|
||||||
if (parent) parent.appendChild(el);
|
if (parent) parent.appendChild(el);
|
||||||
|
}
|
||||||
return el;
|
return el;
|
||||||
}
|
}
|
||||||
function forEl(query, callback, base) {
|
function forEl(query, callback, base) {
|
||||||
|
@ -46,7 +55,7 @@ function getText(url){
|
||||||
return fetch(url)
|
return fetch(url)
|
||||||
.then(function (r) { return r.text() });
|
.then(function (r) { return r.text() });
|
||||||
}
|
}
|
||||||
function reset() {
|
buttonHandlers.reset=function() {
|
||||||
ensurePass()
|
ensurePass()
|
||||||
.then(function (hash) {
|
.then(function (hash) {
|
||||||
fetch('/api/reset?_hash=' + encodeURIComponent(hash));
|
fetch('/api/reset?_hash=' + encodeURIComponent(hash));
|
||||||
|
@ -67,18 +76,19 @@ function update() {
|
||||||
}
|
}
|
||||||
getJson('/api/status')
|
getJson('/api/status')
|
||||||
.then(function (jsonData) {
|
.then(function (jsonData) {
|
||||||
|
if (jsonData.salt !== undefined) {
|
||||||
|
lastSalt=jsonData.salt;
|
||||||
|
delete jsonData.salt;
|
||||||
|
}
|
||||||
|
if (jsonData.minUser !== undefined){
|
||||||
|
minUser=jsonData.minUser;
|
||||||
|
delete jsonData.minUser;
|
||||||
|
}
|
||||||
|
callListeners(api.EVENTS.status,jsonData);
|
||||||
let statusPage = document.getElementById('statusPageContent');
|
let statusPage = document.getElementById('statusPageContent');
|
||||||
let even = true; //first counter
|
let even = true; //first counter
|
||||||
|
if (statusPage){
|
||||||
for (let k in jsonData) {
|
for (let k in jsonData) {
|
||||||
if (k == "salt"){
|
|
||||||
lastSalt=jsonData[k];
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
if (k == "minUser"){
|
|
||||||
minUser=parseInt(jsonData[k]);
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
if (! statusPage) continue;
|
|
||||||
if (typeof (jsonData[k]) === 'object') {
|
if (typeof (jsonData[k]) === 'object') {
|
||||||
if (k.indexOf('count') == 0) {
|
if (k.indexOf('count') == 0) {
|
||||||
createCounterDisplay(statusPage, k.replace("count", "").replace(/in$/, " in").replace(/out$/, " out"), k, even);
|
createCounterDisplay(statusPage, k.replace("count", "").replace(/in$/, " in").replace(/out$/, " out"), k, even);
|
||||||
|
@ -109,6 +119,7 @@ function update() {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
lastUpdate = (new Date()).getTime();
|
lastUpdate = (new Date()).getTime();
|
||||||
if (reloadConfig) {
|
if (reloadConfig) {
|
||||||
reloadConfig = false;
|
reloadConfig = false;
|
||||||
|
@ -119,6 +130,7 @@ function update() {
|
||||||
function resetForm(ev) {
|
function resetForm(ev) {
|
||||||
getJson("/api/config")
|
getJson("/api/config")
|
||||||
.then(function (jsonData) {
|
.then(function (jsonData) {
|
||||||
|
callListeners(api.EVENTS.config,jsonData);
|
||||||
for (let k in jsonData) {
|
for (let k in jsonData) {
|
||||||
if (k == "useAdminPass") {
|
if (k == "useAdminPass") {
|
||||||
needAdminPass = jsonData[k] != 'false';
|
needAdminPass = jsonData[k] != 'false';
|
||||||
|
@ -159,7 +171,8 @@ function resetForm(ev) {
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
function checkMinMax(v,allValues,def){
|
buttonHandlers.resetForm=resetForm;
|
||||||
|
checkers.checkMinMax=function(v, allValues, def) {
|
||||||
let parsed = parseFloat(v);
|
let parsed = parseFloat(v);
|
||||||
if (isNaN(parsed)) return "must be a number";
|
if (isNaN(parsed)) return "must be a number";
|
||||||
if (def.min !== undefined) {
|
if (def.min !== undefined) {
|
||||||
|
@ -170,7 +183,13 @@ function checkMinMax(v,allValues,def){
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkSystemName(v) {
|
checkers.checkPort=function(v,allValues,def){
|
||||||
|
let parsed=parseInt(v);
|
||||||
|
if (isNaN(parsed)) return "must be a number";
|
||||||
|
if (parsed <1 || parsed >= 65536) return "port must be in the range 1..65536";
|
||||||
|
}
|
||||||
|
|
||||||
|
checkers.checkSystemName=function(v) {
|
||||||
//2...32 characters for ssid
|
//2...32 characters for ssid
|
||||||
let allowed = v.replace(/[^a-zA-Z0-9]*/g, '');
|
let allowed = v.replace(/[^a-zA-Z0-9]*/g, '');
|
||||||
if (allowed != v) return "contains invalid characters, only a-z, A-Z, 0-9";
|
if (allowed != v) return "contains invalid characters, only a-z, A-Z, 0-9";
|
||||||
|
@ -182,11 +201,11 @@ function checkApPass(v) {
|
||||||
return "password must be at least 8 characters";
|
return "password must be at least 8 characters";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
function checkAdminPass(v){
|
checkers.checkAdminPass=function(v) {
|
||||||
return checkApPass(v);
|
return checkApPass(v);
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkApIp(v,allValues){
|
checkers.checkApIp=function(v, allValues) {
|
||||||
if (!v) return "cannot be empty";
|
if (!v) return "cannot be empty";
|
||||||
let err1 = "must be in the form 192.168.x.x";
|
let err1 = "must be in the form 192.168.x.x";
|
||||||
if (!v.match(/[0-9]+\.[0-9]+\.[0-9]+\.[0-9]+/)) return err1;
|
if (!v.match(/[0-9]+\.[0-9]+\.[0-9]+\.[0-9]+/)) return err1;
|
||||||
|
@ -197,19 +216,26 @@ function checkApIp(v,allValues){
|
||||||
if (iv < 0 || iv > 255) return err1;
|
if (iv < 0 || iv > 255) return err1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
function checkNetMask(v,allValues){
|
checkers.checkNetMask=function(v, allValues) {
|
||||||
return checkApIp(v,allValues);
|
return checkers.checkApIp(v, allValues);
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkIpAddress(v,allValues,def){
|
checkers.checkIpAddress=function(v, allValues, def) {
|
||||||
if (allValues.tclEnabled != "true") return;
|
|
||||||
if (!v) return "cannot be empty";
|
if (!v) return "cannot be empty";
|
||||||
if (!v.match(/[0-9]*\.[0-9]*\.[0-9]*\.[0-9]*/)
|
if (!v.match(/[0-9]*\.[0-9]*\.[0-9]*\.[0-9]*/)
|
||||||
&& !v.match(/.*\.local/))
|
&& !v.match(/.*\.local/))
|
||||||
return "must be either in the form 192.168.1.1 or xxx.local";
|
return "must be either in the form 192.168.1.1 or xxx.local";
|
||||||
}
|
}
|
||||||
|
checkers.checkMCAddress=function(v, allValues, def) {
|
||||||
|
if (!v) return "cannot be empty";
|
||||||
|
if (!v.match(/[0-9]*\.[0-9]*\.[0-9]*\.[0-9]*/))
|
||||||
|
return "must be in the form 224.0.0.1";
|
||||||
|
let parts=v.split(".");
|
||||||
|
let o1=parseInt(parts[0]);
|
||||||
|
if (o1 < 224 || o1 > 239) return "mulicast address must be in the range 224.0.0.0 to 239.255.255.255"
|
||||||
|
|
||||||
function checkXDR(v,allValues){
|
}
|
||||||
|
checkers.checkXDR=function(v, allValues) {
|
||||||
if (!v) return;
|
if (!v) return;
|
||||||
let parts = v.split(',');
|
let parts = v.split(',');
|
||||||
if (parseInt(parts[1]) == 0) return;
|
if (parseInt(parts[1]) == 0) return;
|
||||||
|
@ -238,6 +264,7 @@ function checkXDR(v,allValues){
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
let loggedChecks={};
|
||||||
function getAllConfigs(omitPass) {
|
function getAllConfigs(omitPass) {
|
||||||
let values = document.querySelectorAll('.configForm select , .configForm input');
|
let values = document.querySelectorAll('.configForm select , .configForm input');
|
||||||
let allValues = {};
|
let allValues = {};
|
||||||
|
@ -252,22 +279,34 @@ function getAllConfigs(omitPass) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
let check = v.getAttribute('data-check');
|
let check = v.getAttribute('data-check');
|
||||||
if (check) {
|
if (check && conditionOk(name)) {
|
||||||
if (typeof (self[check]) === 'function') {
|
let cfgDef=getConfigDefition(name);
|
||||||
let res = self[check](v.value, allValues, getConfigDefition(name));
|
let checkFunction=checkers[check];
|
||||||
|
if (typeof (checkFunction) === 'function') {
|
||||||
|
if (! loggedChecks[check]){
|
||||||
|
loggedChecks[check]=true;
|
||||||
|
//console.log("check:"+check);
|
||||||
|
}
|
||||||
|
let res = checkFunction(v.value, allValues, cfgDef);
|
||||||
if (res) {
|
if (res) {
|
||||||
let value = v.value;
|
let value = v.value;
|
||||||
if (v.type === 'password') value = "******";
|
if (v.type === 'password') value = "******";
|
||||||
alert("invalid config for " + v.getAttribute('name') + "(" + value + "):\n" + res);
|
let label = v.getAttribute('data-label');
|
||||||
|
if (!label) label = v.getAttribute('name');
|
||||||
|
v.classList.add("error");
|
||||||
|
alert("invalid config for "+cfgDef.category+":" + label + "(" + value + "):\n" + res);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
else{
|
||||||
|
console.log("check not found:",check);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
allValues[name] = v.value;
|
allValues[name] = v.value;
|
||||||
}
|
}
|
||||||
return allValues;
|
return allValues;
|
||||||
}
|
}
|
||||||
function changeConfig() {
|
buttonHandlers.changeConfig=function() {
|
||||||
ensurePass()
|
ensurePass()
|
||||||
.then(function (pass) {
|
.then(function (pass) {
|
||||||
let newAdminPass;
|
let newAdminPass;
|
||||||
|
@ -306,7 +345,7 @@ function changeConfig() {
|
||||||
})
|
})
|
||||||
.catch(function (e) { alert(e); })
|
.catch(function (e) { alert(e); })
|
||||||
}
|
}
|
||||||
function factoryReset() {
|
buttonHandlers.factoryReset=function() {
|
||||||
ensurePass()
|
ensurePass()
|
||||||
.then(function (hash) {
|
.then(function (hash) {
|
||||||
if (!confirm("Really delete all configuration?\n" +
|
if (!confirm("Really delete all configuration?\n" +
|
||||||
|
@ -345,6 +384,7 @@ function createCounterDisplay(parent,label,key,isEven){
|
||||||
icon.classList.add('icon-less');
|
icon.classList.add('icon-less');
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
callListeners(api.EVENTS.counterDisplayCreated,row);
|
||||||
}
|
}
|
||||||
function validKey(key) {
|
function validKey(key) {
|
||||||
if (!key) return;
|
if (!key) return;
|
||||||
|
@ -408,6 +448,7 @@ function hideOverlay() {
|
||||||
el.textContent = '';
|
el.textContent = '';
|
||||||
}
|
}
|
||||||
function checkChange(el, row, name) {
|
function checkChange(el, row, name) {
|
||||||
|
el.classList.remove("error");
|
||||||
let loaded = el.getAttribute('data-loaded');
|
let loaded = el.getAttribute('data-loaded');
|
||||||
if (loaded !== undefined) {
|
if (loaded !== undefined) {
|
||||||
if (loaded != el.value) {
|
if (loaded != el.value) {
|
||||||
|
@ -448,10 +489,10 @@ function getConditions(name){
|
||||||
if (!(condition instanceof Array)) condition = [condition];
|
if (!(condition instanceof Array)) condition = [condition];
|
||||||
return condition;
|
return condition;
|
||||||
}
|
}
|
||||||
function checkCondition(element){
|
|
||||||
let name=element.getAttribute('name');
|
function conditionOk(name){
|
||||||
let condition = getConditions(name);
|
let condition = getConditions(name);
|
||||||
if (! condition) return;
|
if (!condition) return true;
|
||||||
let visible = false;
|
let visible = false;
|
||||||
if (!condition instanceof Array) condition = [condition];
|
if (!condition instanceof Array) condition = [condition];
|
||||||
condition.forEach(function (cel) {
|
condition.forEach(function (cel) {
|
||||||
|
@ -470,6 +511,12 @@ function checkCondition(element){
|
||||||
}
|
}
|
||||||
if (lvis) visible = true;
|
if (lvis) visible = true;
|
||||||
});
|
});
|
||||||
|
return visible;
|
||||||
|
}
|
||||||
|
|
||||||
|
function checkCondition(element) {
|
||||||
|
let name = element.getAttribute('name');
|
||||||
|
let visible=conditionOk(name);
|
||||||
let row = closestParent(element, 'row');
|
let row = closestParent(element, 'row');
|
||||||
if (!row) return;
|
if (!row) return;
|
||||||
if (visible) row.classList.remove('hidden');
|
if (visible) row.classList.remove('hidden');
|
||||||
|
@ -505,11 +552,13 @@ function createCalSetInput(configItem,frame,clazz){
|
||||||
window.clearInterval(caliv);
|
window.clearInterval(caliv);
|
||||||
}
|
}
|
||||||
}, 200);
|
}, 200);
|
||||||
showOverlay(cs,false,[{label:'Set',click:()=>{
|
showOverlay(cs, false, [{
|
||||||
|
label: 'Set', click: () => {
|
||||||
el.value = vel.textContent;
|
el.value = vel.textContent;
|
||||||
let cev = new Event('change');
|
let cev = new Event('change');
|
||||||
el.dispatchEvent(cev);
|
el.dispatchEvent(cev);
|
||||||
}}]);
|
}
|
||||||
|
}]);
|
||||||
})
|
})
|
||||||
el.setAttribute('name', configItem.name)
|
el.setAttribute('name', configItem.name)
|
||||||
return el;
|
return el;
|
||||||
|
@ -554,11 +603,13 @@ function createCalValInput(configItem,frame,clazz){
|
||||||
window.clearInterval(caliv);
|
window.clearInterval(caliv);
|
||||||
}
|
}
|
||||||
}, 200);
|
}, 200);
|
||||||
showOverlay(cs,false,[{label:'Set',click:()=>{
|
showOverlay(cs, false, [{
|
||||||
|
label: 'Set', click: () => {
|
||||||
el.value = vinp.value;
|
el.value = vinp.value;
|
||||||
let cev = new Event('change');
|
let cev = new Event('change');
|
||||||
el.dispatchEvent(cev);
|
el.dispatchEvent(cev);
|
||||||
}}]);
|
}
|
||||||
|
}]);
|
||||||
})
|
})
|
||||||
el.setAttribute('name', configItem.name)
|
el.setAttribute('name', configItem.name)
|
||||||
return el;
|
return el;
|
||||||
|
@ -995,7 +1046,7 @@ function unassignedAdd(ev) {
|
||||||
hideOverlay();
|
hideOverlay();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
function loadUnassigned(){
|
buttonHandlers.loadUnassigned=function() {
|
||||||
getText("/api/xdrUnmapped")
|
getText("/api/xdrUnmapped")
|
||||||
.then(function (txt) {
|
.then(function (txt) {
|
||||||
let ot = "";
|
let ot = "";
|
||||||
|
@ -1023,8 +1074,12 @@ function showXdrHelp(){
|
||||||
function formatDateForFilename(usePrefix, d) {
|
function formatDateForFilename(usePrefix, d) {
|
||||||
let rt = "";
|
let rt = "";
|
||||||
if (usePrefix) {
|
if (usePrefix) {
|
||||||
|
let hdl= document.getElementById('headline');
|
||||||
|
if (hdl){
|
||||||
|
rt=hdl.textContent+"_";
|
||||||
|
}
|
||||||
let fwt = document.querySelector('.status-fwtype');
|
let fwt = document.querySelector('.status-fwtype');
|
||||||
if (fwt) rt=fwt.textContent;
|
if (fwt) rt += fwt.textContent;
|
||||||
rt += "_";
|
rt += "_";
|
||||||
}
|
}
|
||||||
if (!d) d = new Date();
|
if (!d) d = new Date();
|
||||||
|
@ -1043,17 +1098,17 @@ function downloadData(data,name){
|
||||||
target.setAttribute('download', name);
|
target.setAttribute('download', name);
|
||||||
target.click();
|
target.click();
|
||||||
}
|
}
|
||||||
function exportConfig(){
|
buttonHandlers.exportConfig=function() {
|
||||||
let data = getAllConfigs(true);
|
let data = getAllConfigs(true);
|
||||||
if (!data) return;
|
if (!data) return;
|
||||||
downloadData(data, formatDateForFilename(true) + ".json");
|
downloadData(data, formatDateForFilename(true) + ".json");
|
||||||
}
|
}
|
||||||
function exportXdr(){
|
buttonHandlers.exportXdr=function() {
|
||||||
let data = {};
|
let data = {};
|
||||||
forEl('.xdrvalue', function (el) {
|
forEl('.xdrvalue', function (el) {
|
||||||
let name = el.getAttribute('name');
|
let name = el.getAttribute('name');
|
||||||
let value = el.value;
|
let value = el.value;
|
||||||
let err=checkXDR(value,data);
|
let err = checkers.checkXDR(value, data);
|
||||||
if (err) {
|
if (err) {
|
||||||
alert("error in " + name + ": " + value + "\n" + err);
|
alert("error in " + name + ": " + value + "\n" + err);
|
||||||
return;
|
return;
|
||||||
|
@ -1114,10 +1169,10 @@ function importJson(opt_keyPattern){
|
||||||
});
|
});
|
||||||
ip.click();
|
ip.click();
|
||||||
}
|
}
|
||||||
function importXdr(){
|
buttonHandlers.importXdr=function() {
|
||||||
importJson(new RegExp(/^XDR[0-9][0-9]*/));
|
importJson(new RegExp(/^XDR[0-9][0-9]*/));
|
||||||
}
|
}
|
||||||
function importConfig(){
|
buttonHandlers.importConfig=function() {
|
||||||
importJson();
|
importJson();
|
||||||
}
|
}
|
||||||
function toggleClass(el, id, classList) {
|
function toggleClass(el, id, classList) {
|
||||||
|
@ -1140,7 +1195,7 @@ function createConfigDefinitions(parent, capabilities, defs,includeXdr) {
|
||||||
configDefinitions = defs;
|
configDefinitions = defs;
|
||||||
let currentCategoryPopulated = true;
|
let currentCategoryPopulated = true;
|
||||||
defs.forEach(function (item) {
|
defs.forEach(function (item) {
|
||||||
if (!item.type) return;
|
if (!item.type || item.category === undefined) return;
|
||||||
if (item.category.match(/^xdr/)) {
|
if (item.category.match(/^xdr/)) {
|
||||||
if (!includeXdr) return;
|
if (!includeXdr) return;
|
||||||
}
|
}
|
||||||
|
@ -1228,6 +1283,7 @@ function createConfigDefinitions(parent, capabilities, defs,includeXdr) {
|
||||||
})
|
})
|
||||||
}
|
}
|
||||||
if (item.check) valueEl.setAttribute('data-check', item.check);
|
if (item.check) valueEl.setAttribute('data-check', item.check);
|
||||||
|
valueEl.setAttribute('data-label', label);
|
||||||
let btContainer = addEl('div', 'buttonContainer', row);
|
let btContainer = addEl('div', 'buttonContainer', row);
|
||||||
if (!readOnly) {
|
if (!readOnly) {
|
||||||
let bt = addEl('button', 'defaultButton', btContainer, 'X');
|
let bt = addEl('button', 'defaultButton', btContainer, 'X');
|
||||||
|
@ -1265,6 +1321,12 @@ function loadConfigDefinitions() {
|
||||||
let el = document.getElementById('helpButton');
|
let el = document.getElementById('helpButton');
|
||||||
if (el) el.setAttribute('data-url', capabilities.HELP_URL);
|
if (el) el.setAttribute('data-url', capabilities.HELP_URL);
|
||||||
}
|
}
|
||||||
|
try{
|
||||||
|
Object.freeze(capabilities);
|
||||||
|
callListeners(api.EVENTS.init,capabilities);
|
||||||
|
}catch (e){
|
||||||
|
console.log(e);
|
||||||
|
}
|
||||||
getJson("config.json")
|
getJson("config.json")
|
||||||
.then(function (defs) {
|
.then(function (defs) {
|
||||||
getJson("xdrconfig.json")
|
getJson("xdrconfig.json")
|
||||||
|
@ -1299,7 +1361,7 @@ function verifyPass(pass){
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
function adminPassCancel(){
|
buttonHandlers.adminPassCancel=function() {
|
||||||
forEl('#adminPassOverlay', function (el) { el.classList.add('hidden') });
|
forEl('#adminPassOverlay', function (el) { el.classList.add('hidden') });
|
||||||
forEl('#adminPassInput', function (el) { el.value = '' });
|
forEl('#adminPassInput', function (el) { el.value = '' });
|
||||||
}
|
}
|
||||||
|
@ -1316,7 +1378,7 @@ function saveAdminPass(pass,forceIfSet){
|
||||||
} catch (e) { }
|
} catch (e) { }
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
function forgetPass(){
|
buttonHandlers.forgetPass=function() {
|
||||||
localStorage.removeItem('adminPass');
|
localStorage.removeItem('adminPass');
|
||||||
forEl('#adminPassInput', function (el) {
|
forEl('#adminPassInput', function (el) {
|
||||||
el.value = '';
|
el.value = '';
|
||||||
|
@ -1369,7 +1431,7 @@ function ensurePass(){
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
function converterInfo() {
|
buttonHandlers.converterInfo=function() {
|
||||||
getJson("api/converterInfo").then(function (json) {
|
getJson("api/converterInfo").then(function (json) {
|
||||||
let text = "<h3>Converted entities</h3>";
|
let text = "<h3>Converted entities</h3>";
|
||||||
text += "<p><b>NMEA0183 to NMEA2000:</b><br/>";
|
text += "<p><b>NMEA0183 to NMEA2000:</b><br/>";
|
||||||
|
@ -1390,16 +1452,15 @@ function handleTab(el) {
|
||||||
}
|
}
|
||||||
let activeTab = document.getElementById(activeName);
|
let activeTab = document.getElementById(activeName);
|
||||||
if (!activeTab) return;
|
if (!activeTab) return;
|
||||||
let all = document.querySelectorAll('.tabPage');
|
forEl('.tabPage',function(pel){
|
||||||
for (let i = 0; i < all.length; i++) {
|
pel.classList.add('hidden');
|
||||||
all[i].classList.add('hidden');
|
});
|
||||||
}
|
forEl('.tab',function(tel){
|
||||||
let tabs = document.querySelectorAll('.tab');
|
tel.classList.remove('active');
|
||||||
for (let i = 0; i < all.length; i++) {
|
});
|
||||||
tabs[i].classList.remove('active');
|
|
||||||
}
|
|
||||||
el.classList.add('active');
|
el.classList.add('active');
|
||||||
activeTab.classList.remove('hidden');
|
activeTab.classList.remove('hidden');
|
||||||
|
callListeners(api.EVENTS.tab,activeName);
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
*
|
*
|
||||||
|
@ -1574,6 +1635,10 @@ let valueFormatters = {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
Object.freeze(valueFormatters);
|
||||||
|
for (let k in valueFormatters){
|
||||||
|
Object.freeze(valueFormatters[k]);
|
||||||
}
|
}
|
||||||
function resizeFont(el, reset, maxIt) {
|
function resizeFont(el, reset, maxIt) {
|
||||||
if (maxIt === undefined) maxIt = 10;
|
if (maxIt === undefined) maxIt = 10;
|
||||||
|
@ -1584,23 +1649,62 @@ function resizeFont(el,reset,maxIt){
|
||||||
el.style.fontSize = next + "px";
|
el.style.fontSize = next + "px";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
function createDashboardItem(name, def, parent) {
|
function getUnit(def,useUser){
|
||||||
if (! def.name) return;
|
let fmt = useUser?(userFormatters[def.name] || valueFormatters[def.format]):valueFormatters[def.format] ;
|
||||||
let frame = addEl('div', 'dash', parent);
|
|
||||||
let title = addEl('span', 'dashTitle', frame, name);
|
|
||||||
let value = addEl('span', 'dashValue', frame);
|
|
||||||
value.setAttribute('id', 'data_' + name);
|
|
||||||
let fmt=valueFormatters[def.format];
|
|
||||||
if (def.format) value.classList.add(def.format);
|
|
||||||
let footer = addEl('div','footer',frame);
|
|
||||||
let src= addEl('span','source',footer);
|
|
||||||
src.setAttribute('id','source_'+name);
|
|
||||||
let u = fmt ? fmt.u : ' ';
|
let u = fmt ? fmt.u : ' ';
|
||||||
if (!fmt && def.format && def.format.match(/formatXdr/)) {
|
if (!fmt && def.format && def.format.match(/formatXdr/)) {
|
||||||
u = def.format.replace(/formatXdr:[^:]*:/, '');
|
u = def.format.replace(/formatXdr:[^:]*:/, '');
|
||||||
}
|
}
|
||||||
|
return u;
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* create a dashboard item if it does not exist
|
||||||
|
* @param {*} def
|
||||||
|
* @param {*} show
|
||||||
|
* @param {*} parent
|
||||||
|
* @returns the value div of the dashboard item
|
||||||
|
*/
|
||||||
|
function createOrHideDashboardItem(def,show, parent) {
|
||||||
|
if (!def.name) return;
|
||||||
|
let frame=document.getElementById('frame_'+def.name);
|
||||||
|
let build=false;
|
||||||
|
if (frame){
|
||||||
|
if (frame.classList.contains('invalid') && show){
|
||||||
|
build=true;
|
||||||
|
frame.classList.remove('invalid');
|
||||||
|
frame.innerHTML='';
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
if (! parent) return;
|
||||||
|
frame = addEl('div', 'dash', parent);
|
||||||
|
frame.setAttribute('id','frame_'+def.name);
|
||||||
|
build=true;
|
||||||
|
}
|
||||||
|
if (! show){
|
||||||
|
if (!frame.classList.contains('invalid')){
|
||||||
|
frame.classList.add('invalid');
|
||||||
|
frame.innerHTML='';
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (build) {
|
||||||
|
let title = addEl('span', 'dashTitle', frame, def.name);
|
||||||
|
let value = addEl('span', 'dashValue', frame);
|
||||||
|
value.setAttribute('id', 'data_' + def.name);
|
||||||
|
if (def.format) value.classList.add(def.format);
|
||||||
|
let footer = addEl('div', 'footer', frame);
|
||||||
|
let src = addEl('span', 'source', footer);
|
||||||
|
src.setAttribute('id', 'source_' + def.name);
|
||||||
|
let u = getUnit(def, true)
|
||||||
addEl('span', 'unit', footer, u);
|
addEl('span', 'unit', footer, u);
|
||||||
return value;
|
callListeners(api.EVENTS.dataItemCreated,{name:def.name,element:frame});
|
||||||
|
}
|
||||||
|
let de = document.getElementById('data_' + def.name);
|
||||||
|
return de;
|
||||||
|
}
|
||||||
|
function hideDashboardItem(name){
|
||||||
|
createOrHideDashboardItem({name:name},false);
|
||||||
}
|
}
|
||||||
function parseBoatDataLine(line) {
|
function parseBoatDataLine(line) {
|
||||||
let rt = {};
|
let rt = {};
|
||||||
|
@ -1631,6 +1735,7 @@ function sourceName(v){
|
||||||
}
|
}
|
||||||
let lastSelectList = [];
|
let lastSelectList = [];
|
||||||
function updateDashboard(data) {
|
function updateDashboard(data) {
|
||||||
|
callListeners(api.EVENTS.boatData,data);
|
||||||
let frame = document.getElementById('dashboardPage');
|
let frame = document.getElementById('dashboardPage');
|
||||||
let showInvalid = true;
|
let showInvalid = true;
|
||||||
forEl('select[name=showInvalidData]', function (el) {
|
forEl('select[name=showInvalidData]', function (el) {
|
||||||
|
@ -1641,25 +1746,18 @@ function updateDashboard(data) {
|
||||||
let current = parseBoatDataLine(data[n]);
|
let current = parseBoatDataLine(data[n]);
|
||||||
if (!current.name) continue;
|
if (!current.name) continue;
|
||||||
names[current.name] = true;
|
names[current.name] = true;
|
||||||
let de = document.getElementById('data_' + current.name);
|
let show = current.valid||showInvalid;
|
||||||
let isValid=current.valid;
|
let de = createOrHideDashboardItem(current, show, frame);
|
||||||
if (! de && frame && (isValid || showInvalid)){
|
let newContent = '---';
|
||||||
de=createDashboardItem(current.name,current,frame);
|
|
||||||
}
|
|
||||||
if (de && (!isValid && !showInvalid)){
|
|
||||||
de.parentElement.remove();
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
if (de) {
|
|
||||||
let newContent='----';
|
|
||||||
if (current.valid) {
|
if (current.valid) {
|
||||||
let formatter;
|
let formatter;
|
||||||
if (current.format && current.format != "NULL") {
|
if (current.format && current.format != "NULL") {
|
||||||
let key = current.format.replace(/^\&/, '');
|
let key = current.format.replace(/^\&/, '');
|
||||||
formatter = valueFormatters[key];
|
formatter = userFormatters[current.name] || valueFormatters[key];
|
||||||
}
|
}
|
||||||
if (formatter) {
|
if (formatter && formatter.f) {
|
||||||
newContent = formatter.f(current.value);
|
newContent = formatter.f(current.value,true);
|
||||||
|
if (newContent === undefined) newContent = "";
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
let v = parseFloat(current.value);
|
let v = parseFloat(current.value);
|
||||||
|
@ -1672,7 +1770,16 @@ function updateDashboard(data) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else newContent = "---";
|
else {
|
||||||
|
let uf=userFormatters[current.name];
|
||||||
|
if (uf && uf.f){
|
||||||
|
//call the user formatter
|
||||||
|
//so that it can detect the invalid state
|
||||||
|
newContent=uf.f(undefined,false);
|
||||||
|
}
|
||||||
|
if (newContent === undefined)newContent = "---";
|
||||||
|
}
|
||||||
|
if (de) {
|
||||||
if (newContent !== de.textContent) {
|
if (newContent !== de.textContent) {
|
||||||
de.textContent = newContent;
|
de.textContent = newContent;
|
||||||
resizeFont(de, true);
|
resizeFont(de, true);
|
||||||
|
@ -1683,11 +1790,14 @@ function updateDashboard(data) {
|
||||||
src.textContent = sourceName(current.source);
|
src.textContent = sourceName(current.source);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
console.log("update");
|
//console.log("update");
|
||||||
forEl('.dashValue',function(el){
|
//remove all items that are not send any more
|
||||||
|
//this can only happen if the device restarted
|
||||||
|
//otherwise data items will not go away - they will become invalid
|
||||||
|
forEl('.dash', function (el) {
|
||||||
let id = el.getAttribute('id');
|
let id = el.getAttribute('id');
|
||||||
if (id) {
|
if (id) {
|
||||||
if (! names[id.replace(/^data_/,'')]){
|
if (!names[id.replace(/^frame_/, '')]) {
|
||||||
el.parentElement.remove();
|
el.parentElement.remove();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1714,7 +1824,7 @@ function updateDashboard(data) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
function uploadBin(ev){
|
buttonHandlers.uploadBin=function(ev) {
|
||||||
let el = document.getElementById("uploadFile");
|
let el = document.getElementById("uploadFile");
|
||||||
let progressEl = document.getElementById("uploadDone");
|
let progressEl = document.getElementById("uploadDone");
|
||||||
if (!el) return;
|
if (!el) return;
|
||||||
|
@ -1861,6 +1971,128 @@ function checkImageFile(file){
|
||||||
reader.readAsArrayBuffer(slice);
|
reader.readAsArrayBuffer(slice);
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
function addTabPage(name,label,url){
|
||||||
|
if (label === undefined) label=name;
|
||||||
|
let tab=addEl('div','tab','#tabs',label);
|
||||||
|
tab.addEventListener('click',function(ev){
|
||||||
|
handleTab(ev.target);
|
||||||
|
})
|
||||||
|
if (url !== undefined){
|
||||||
|
tab.setAttribute('data-url',url);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
tab.setAttribute('data-page',name);
|
||||||
|
let page=addEl('div','tabPage hidden','#tabPages');
|
||||||
|
page.setAttribute('id',name);
|
||||||
|
return page;
|
||||||
|
}
|
||||||
|
function addUserFormatter(name,unit,formatter){
|
||||||
|
if (unit !== undefined && formatter !== undefined){
|
||||||
|
userFormatters[name]={
|
||||||
|
u:unit,
|
||||||
|
f:formatter
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
delete userFormatters[name];
|
||||||
|
}
|
||||||
|
hideDashboardItem(name); //will recreate it on next data receive
|
||||||
|
}
|
||||||
|
const api= {
|
||||||
|
registerListener: function (callback,opt_event) {
|
||||||
|
if (opt_event === undefined){
|
||||||
|
listeners.push(callback);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
listeners.push({
|
||||||
|
event:opt_event,
|
||||||
|
callback:callback
|
||||||
|
})
|
||||||
|
}
|
||||||
|
},
|
||||||
|
/**
|
||||||
|
* helper for creating dom elements
|
||||||
|
* parameters:
|
||||||
|
* type: the element type (e.g. div)
|
||||||
|
* class: a list of classes separated by space
|
||||||
|
* parent (opt): a parent element (either a dom element vor a query selector)
|
||||||
|
* text (opt): the text to be set as textContent
|
||||||
|
* returns: the newly created element
|
||||||
|
*/
|
||||||
|
addEl: addEl,
|
||||||
|
/**
|
||||||
|
* iterator helper for a query selector
|
||||||
|
* parameters:
|
||||||
|
* query: the query selector
|
||||||
|
* callback: the callback function (will be called with the element as param)
|
||||||
|
* base (opt): a dome element to be used as the root (defaults to document)
|
||||||
|
*/
|
||||||
|
forEl: forEl,
|
||||||
|
/**
|
||||||
|
* find the closest parent that has a particular class
|
||||||
|
* parameters:
|
||||||
|
* element: the element to start with
|
||||||
|
* class: the class to be searched for
|
||||||
|
* returns: the element or undefined/null
|
||||||
|
*/
|
||||||
|
closestParent: closestParent,
|
||||||
|
/**
|
||||||
|
* add a new tab
|
||||||
|
* parameters:
|
||||||
|
* name - the name of the page
|
||||||
|
* label (opt): the label for the new page
|
||||||
|
* returns: the newly created element
|
||||||
|
*/
|
||||||
|
addTabPage: addTabPage,
|
||||||
|
/**
|
||||||
|
* add a user defined formatter for a boat data item
|
||||||
|
* parameters:
|
||||||
|
* name : the boat data item name
|
||||||
|
* unit: the unit to be displayed
|
||||||
|
* formatter: the formatter function (must return a string)
|
||||||
|
*/
|
||||||
|
addUserFormatter: addUserFormatter,
|
||||||
|
removeUserFormatter: function(name){
|
||||||
|
addUserFormatter(name);
|
||||||
|
},
|
||||||
|
/**
|
||||||
|
* a dict of formatters
|
||||||
|
* each one has 2 members:
|
||||||
|
* u: the unit
|
||||||
|
* f: the formatter function
|
||||||
|
*/
|
||||||
|
formatters: valueFormatters,
|
||||||
|
/**
|
||||||
|
* parse a line of boat data
|
||||||
|
* the line has name,format,valid,update,source,value
|
||||||
|
*/
|
||||||
|
parseBoatDataLine: parseBoatDataLine,
|
||||||
|
EVENTS: {
|
||||||
|
init: 0, //called when capabilities are loaded, data is capabilities
|
||||||
|
tab: 1, //tab page activated, data is the id of the tab page
|
||||||
|
config: 2, //called when the config data is loaded,data is the config object
|
||||||
|
boatData: 3, //called when boatData is received, data is the list of boat Data items
|
||||||
|
dataItemCreated: 4, //data is an object with
|
||||||
|
// name: the item name, element: the frame item of the boat data display
|
||||||
|
status: 5, //status received, data is the status object
|
||||||
|
counterDisplayCreated: 6 //data is the row for the display
|
||||||
|
}
|
||||||
|
};
|
||||||
|
function callListeners(event,data){
|
||||||
|
listeners.forEach((listener)=>{
|
||||||
|
if (typeof(listener) === 'function'){
|
||||||
|
listener(event,data);
|
||||||
|
}
|
||||||
|
else if (typeof(listener) === 'object'){
|
||||||
|
if (listener.event === event){
|
||||||
|
if (typeof(listener.callback) === 'function'){
|
||||||
|
listener.callback(event,data);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
})
|
||||||
|
}
|
||||||
|
window.esp32nmea2k = api;
|
||||||
window.setInterval(update, 1000);
|
window.setInterval(update, 1000);
|
||||||
window.setInterval(function () {
|
window.setInterval(function () {
|
||||||
let dp = document.getElementById('dashboardPage');
|
let dp = document.getElementById('dashboardPage');
|
||||||
|
@ -1873,7 +2105,14 @@ window.addEventListener('load', function () {
|
||||||
let buttons = document.querySelectorAll('button');
|
let buttons = document.querySelectorAll('button');
|
||||||
for (let i = 0; i < buttons.length; i++) {
|
for (let i = 0; i < buttons.length; i++) {
|
||||||
let be = buttons[i];
|
let be = buttons[i];
|
||||||
be.onclick = window[be.id]; //assume a function with the button id
|
let buttonFunction=buttonHandlers[be.id];
|
||||||
|
if (typeof(buttonFunction) === 'function'){
|
||||||
|
be.onclick = buttonFunction; //assume a function with the button id
|
||||||
|
//console.log("button: "+be.id);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
console.log("no handler for button "+be.id);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
forEl('.showMsgDetails', function (cd) {
|
forEl('.showMsgDetails', function (cd) {
|
||||||
cd.addEventListener('change', function (ev) {
|
cd.addEventListener('change', function (ev) {
|
||||||
|
@ -1901,14 +2140,6 @@ window.addEventListener('load', function () {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
} catch (e) { }
|
} catch (e) { }
|
||||||
let statusPage=document.getElementById('statusPageContent');
|
|
||||||
/*if (statusPage){
|
|
||||||
let even=true;
|
|
||||||
for (let c in counters){
|
|
||||||
createCounterDisplay(statusPage,counters[c],c,even);
|
|
||||||
even=!even;
|
|
||||||
}
|
|
||||||
}*/
|
|
||||||
forEl('#uploadFile', function (el) {
|
forEl('#uploadFile', function (el) {
|
||||||
el.addEventListener('change', function (ev) {
|
el.addEventListener('change', function (ev) {
|
||||||
if (ev.target.files.length < 1) return;
|
if (ev.target.files.length < 1) return;
|
||||||
|
@ -1931,3 +2162,5 @@ window.addEventListener('load', function () {
|
||||||
})
|
})
|
||||||
})
|
})
|
||||||
});
|
});
|
||||||
|
}());
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
import {ESPLoader,Transport} from "https://cdn.jsdelivr.net/npm/esptool-js@0.2.1/bundle.js";
|
import {ESPLoader,Transport} from "https://cdn.jsdelivr.net/npm/esptool-js@0.4.5/bundle.js";
|
||||||
/**
|
/**
|
||||||
* write all messages to the console
|
* write all messages to the console
|
||||||
*/
|
*/
|
||||||
|
@ -102,10 +102,14 @@ class ESPInstaller{
|
||||||
await this.consoleReader.cancel();
|
await this.consoleReader.cancel();
|
||||||
this.consoleReader=undefined;
|
this.consoleReader=undefined;
|
||||||
}
|
}
|
||||||
await this.consoleDevice.close();
|
|
||||||
}catch(e){
|
}catch(e){
|
||||||
console.log(`error cancel serial read ${e}`);
|
console.log(`error cancel serial read ${e}`);
|
||||||
}
|
}
|
||||||
|
try{
|
||||||
|
await this.consoleDevice.close();
|
||||||
|
}catch(e){
|
||||||
|
console.log('error closing console device', this.consoleDevice,e);
|
||||||
|
}
|
||||||
this.consoleDevice=undefined;
|
this.consoleDevice=undefined;
|
||||||
}
|
}
|
||||||
if (this.transport){
|
if (this.transport){
|
||||||
|
@ -126,13 +130,17 @@ class ESPInstaller{
|
||||||
}
|
}
|
||||||
try {
|
try {
|
||||||
this.transport = new Transport(device);
|
this.transport = new Transport(device);
|
||||||
this.esploader = new ESPLoader(this.transport, 115200, this.espLoaderTerminal);
|
this.esploader = new ESPLoader({
|
||||||
let foundChip = await this.esploader.main_fn();
|
transport:this.transport,
|
||||||
|
baudrate: 115200,
|
||||||
|
terminal: this.espLoaderTerminal});
|
||||||
|
//this.esploader.debugLogging=true;
|
||||||
|
let foundChip = await this.esploader.main();
|
||||||
if (!foundChip) {
|
if (!foundChip) {
|
||||||
throw new Error("unable to read chip id");
|
throw new Error("unable to read chip id");
|
||||||
}
|
}
|
||||||
this.espLoaderTerminal.writeLine(`chip: ${foundChip}`);
|
this.espLoaderTerminal.writeLine(`chip: ${foundChip}`);
|
||||||
await this.esploader.flash_id();
|
//await this.esploader.flashId();
|
||||||
this.chipFamily = this.esploader.chip.CHIP_NAME;
|
this.chipFamily = this.esploader.chip.CHIP_NAME;
|
||||||
this.imageChipId = this.esploader.chip.IMAGE_CHIP_ID;
|
this.imageChipId = this.esploader.chip.IMAGE_CHIP_ID;
|
||||||
this.espLoaderTerminal.writeLine(`chipFamily: ${this.chipFamily}`);
|
this.espLoaderTerminal.writeLine(`chipFamily: ${this.chipFamily}`);
|
||||||
|
@ -198,12 +206,17 @@ class ESPInstaller{
|
||||||
async writeFlash(fileList){
|
async writeFlash(fileList){
|
||||||
this.checkConnected();
|
this.checkConnected();
|
||||||
this.espLoaderTerminal.writeLine(`Flashing....`);
|
this.espLoaderTerminal.writeLine(`Flashing....`);
|
||||||
await this.esploader.write_flash(
|
await this.esploader.writeFlash({
|
||||||
fileList,
|
fileArray: fileList,
|
||||||
"keep",
|
flashSize: "keep",
|
||||||
"keep",
|
flashMode: "keep",
|
||||||
"keep",
|
flashFreq: "keep",
|
||||||
false
|
eraseAll: false,
|
||||||
|
compress: true,
|
||||||
|
/*reportProgress: (fileIndex, written, total)=>{
|
||||||
|
this.espLoaderTerminal.writeLine(`file ${fileIndex}: ${written}/${total}`);
|
||||||
|
}*/
|
||||||
|
}
|
||||||
)
|
)
|
||||||
await this.resetTransport();
|
await this.resetTransport();
|
||||||
this.espLoaderTerminal.writeLine(`Done.`);
|
this.espLoaderTerminal.writeLine(`Done.`);
|
||||||
|
|
Loading…
Reference in New Issue