kopia lustrzana https://github.com/SQ9MDD/TTGO-T-Beam-LoRa-APRS
Porównaj commity
56 Commity
refs/heads
...
master
Autor | SHA1 | Data |
---|---|---|
![]() |
5b255e1835 | |
![]() |
8fb6bc37d2 | |
![]() |
6f4b7fb363 | |
![]() |
2a3e357b37 | |
![]() |
bb7eebb40e | |
![]() |
4fa5001a67 | |
![]() |
5e64d3c0c7 | |
![]() |
14cbcac5d1 | |
![]() |
4b4c17e0c2 | |
![]() |
228037a0cc | |
![]() |
4366b3542c | |
![]() |
81ce66bd0d | |
![]() |
9ca6e66880 | |
![]() |
ffba4f2ac6 | |
![]() |
bf4f564701 | |
![]() |
3d4a25b43c | |
![]() |
65e5de10e0 | |
![]() |
17f0a92875 | |
![]() |
f1246de693 | |
![]() |
f3990566d2 | |
![]() |
0e9ac97753 | |
![]() |
60ed3c0a02 | |
![]() |
d7ae2f23b3 | |
![]() |
81c77506bf | |
![]() |
adf191ac92 | |
![]() |
58cef88e9d | |
![]() |
b760fd9a23 | |
![]() |
434e8ef0ad | |
![]() |
d8e154b09d | |
![]() |
60533e2dcb | |
![]() |
db94ef818a | |
![]() |
00b08722b5 | |
![]() |
ff4d343d8c | |
![]() |
f5b8820830 | |
![]() |
eb25ea2cbf | |
![]() |
3586b05f0b | |
![]() |
afa4121b51 | |
![]() |
052589a608 | |
![]() |
1f56e83879 | |
![]() |
ab3b3a3c37 | |
![]() |
87d8dbc558 | |
![]() |
b3adda48e9 | |
![]() |
eb43b0baf1 | |
![]() |
cff57273dd | |
![]() |
b4768250c3 | |
![]() |
36c1a09bdd | |
![]() |
99de694f96 | |
![]() |
d1ee9e44d6 | |
![]() |
16aae406b2 | |
![]() |
e572a68103 | |
![]() |
594da346ed | |
![]() |
fd6395df16 | |
![]() |
5c055cbd16 | |
![]() |
967c1d0e8d | |
![]() |
123236b968 | |
![]() |
4793fb030a |
|
@ -17,6 +17,7 @@ Search and install the following libaries:<br>
|
|||
<li>AXP202X_Library</li>
|
||||
<li>OneWire</li>
|
||||
<li>DallasTemperature</li>
|
||||
<li>XPowersLib<li>
|
||||
</ul>
|
||||
<br>
|
||||
<h3>2. Command Line Tool</h3>
|
||||
|
@ -30,6 +31,7 @@ platformio lib install "AXP202X_Library"<br>
|
|||
platformio lib install "Adafruit Unified Sensor"<br>
|
||||
platformio lib install "OneWire"<br>
|
||||
platformio lib install "DallasTemperature"<br>
|
||||
platformio lib install "XPowersLib'<br>
|
||||
<br>
|
||||
Check that the platformio.ini is available as it holds the board type for PlatformIO.<br>
|
||||
After pressing the check mark the code will be compiled, after pressing the arrow it will be compiled and uploaded to a connected TTGO.<br>
|
||||
|
|
|
@ -0,0 +1,16 @@
|
|||
{
|
||||
"folders": [
|
||||
{
|
||||
"path": "../LoRa aprs"
|
||||
},
|
||||
{
|
||||
"name": "TTGO-T-Beam-LoRa-APRS-master",
|
||||
"path": "."
|
||||
}
|
||||
],
|
||||
"settings": {
|
||||
"files.associations": {
|
||||
"*.tpp": "cpp"
|
||||
}
|
||||
}
|
||||
}
|
17
README.md
17
README.md
|
@ -9,12 +9,16 @@ After connection with APRX based DIGI it can be used as KISS-TNC
|
|||
## Contributors
|
||||
* Initial work: OE1ACM, OE3CJB
|
||||
* Redesigned: SQ9MDD
|
||||
* KISS TNC Over Seriall or Bluetooth: SQ5RWU
|
||||
* Lora32 board support DJ1AN
|
||||
* KISS TNC Over Serial or Bluetooth: SQ5RWU
|
||||
* Lora32 board support: DJ1AN
|
||||
* Self-telemetry improvement: KB1GIM
|
||||
* T-beam v1.2 board support: SP6NYA
|
||||
* New XPowersLib Library: SP6NYA
|
||||
|
||||
## Supported boards
|
||||
* TTGO T-beam v.0.7
|
||||
* TTGO T-beam v.1.0
|
||||
* LILYGO/TTGO T-beam v.1.0 - v.1.1
|
||||
* LILYGO/TTGO T-Beam v.1.2
|
||||
* Lora32 board
|
||||
|
||||
## User key functions:
|
||||
|
@ -43,6 +47,10 @@ After connection with APRX based DIGI it can be used as KISS-TNC
|
|||
* ((AUT TX)) - information about sending automatic positioning frame when GPS is turned off
|
||||
* ((KISSTX)) - information about sending the frame sent by KISS
|
||||
* ((WEB TX)) - sending frame as requested via HTTP
|
||||
* ((TEL TX)) - information about sending telemetry
|
||||
## LED'S information
|
||||
* (Blue) Slow blinking - battery voltage 3.5V-3.3V
|
||||
* (Blue) Fast blinking - battery voltage > 3.3V
|
||||
|
||||
## How to binary first flash readme... (thanx SP6VWX)
|
||||
* Download the appropriate binary file for your board from: https://github.com/SQ9MDD/TTGO-T-Beam-LoRa-APRS/releases
|
||||
|
@ -64,13 +72,14 @@ After connection with APRX based DIGI it can be used as KISS-TNC
|
|||
* In the left column click on the ANT-shaped icon, choose your board and click on "Upload". COM port should be detected automatically Wait for procedure to finish and keep reading
|
||||
|
||||
## Configuring parameters
|
||||
Wait for the board to reboot, connect to "N0CALL AP" WiFi network, password is: xxxxxxxxxx (10 times "x") and point your browser to "192.168.4.1"
|
||||
Wait for the board to reboot, connect to "N0CALL AP" WiFi network, password is: xxxxxxxxxx (10 times "x") and point your browser to "http://192.168.4.1" (http, not http*s*). Hover your mouse to textboxes to get useful hints.
|
||||
|
||||
### WiFi Settings
|
||||
you can scan for local SSID or manually type in name and password
|
||||
* Scan WiFi: scan for local WiFi networks
|
||||
* SSID: name of the AP to connect to
|
||||
* Password: password of WiFi AP
|
||||
* AUTO AP Password: if configured network is not reachable the AP mode will be enabled, SSID will be your callsign and this will be the password
|
||||
|
||||
### APRS Settings
|
||||
These are main APRS settings such as callsign, SSID and symbol (refer to: http://www.aprs.org/symbols.html). Please remember to turn ON GPS in order to use it as a tracker.
|
||||
|
|
|
@ -0,0 +1,16 @@
|
|||
{
|
||||
"folders": [
|
||||
{
|
||||
"path": "."
|
||||
},
|
||||
{
|
||||
"name": "LoRa aprs",
|
||||
"path": "../LoRa aprs"
|
||||
}
|
||||
],
|
||||
"settings": {
|
||||
"files.associations": {
|
||||
"*.tpp": "cpp"
|
||||
}
|
||||
}
|
||||
}
|
|
@ -26,15 +26,15 @@
|
|||
</div>
|
||||
<div>
|
||||
<label for="wifi_ssid">WiFi SSID</label>
|
||||
<input class="u-full-width" type="text" name="wifi_ssid" placeholder="Your Wifi SSID" id="wifi_ssid">
|
||||
<input class="u-full-width" type="text" name="wifi_ssid" placeholder="Your Wifi SSID" title="Your Wifi SSID" id="wifi_ssid">
|
||||
</div>
|
||||
<div>
|
||||
<label for="wifi_password">WiFi Password</label>
|
||||
<input class="u-full-width" type="password" name="wifi_password" id="wifi_password">
|
||||
<input class="u-full-width" type="password" name="wifi_password" id="wifi_password" placeholder="Your WiFi Password" title="Your WiFi Password">
|
||||
</div>
|
||||
<div>
|
||||
<label for="ap_password">AUTO AP Password</label>
|
||||
<input class="u-full-width" type="password" name="ap_password" id="ap_password" disabled>
|
||||
<input class="u-full-width" type="password" name="ap_password" id="ap_password" placeholder="AUTO AP Password" title="AUTO AP Password">
|
||||
</div>
|
||||
</div>
|
||||
<div class="grid-container full">
|
||||
|
@ -58,10 +58,14 @@
|
|||
<input name="lora_freq" id="lora_freq" type="number" min="433.000" max="928.000" step="0.001" title="LoRa center frequency between 433.001 and 928.000">
|
||||
</div>
|
||||
<div>
|
||||
<label for="lora_speed">Speed [baud]</label>
|
||||
<label for="lora_speed">Speed</label>
|
||||
<select id="lora_speed" name="lora_speed">
|
||||
<option value="300">300 baud</option>
|
||||
<option value="1200">1200 baud</option>
|
||||
<option value="300">BW 125khz CR 4:5 SF 12 (Slow Standard, 300bps)</option>
|
||||
<option value="240">BW 125khz CR 4:6 SF 12 (244bps)</option>
|
||||
<option value="210">BW 125khz CR 4:7 SF 12 (209bps)</option>
|
||||
<option value="180">BW 125khz CR 4:8 SF 12 (183bps)</option>
|
||||
<option value="610">BW 125khz CR 4:8 SF 10 (610bps)</option>
|
||||
<option value="1200">BW 125khz CR 4:7 SF 9 (Fast Standard, 1200bps)</option>
|
||||
</select>
|
||||
</div>
|
||||
</div>
|
||||
|
@ -101,6 +105,30 @@
|
|||
<label for="aprs_batt">Show Battery</label>
|
||||
<input name="aprs_batt" id="aprs_batt" type="checkbox" value="1" title=" show battery voltage after personal comment">
|
||||
</div>
|
||||
</div>
|
||||
<div class="grid-container full">
|
||||
<h5 class="u-full-width">Telemetry Settings</h5>
|
||||
</div>
|
||||
<div class="grid-container quarters">
|
||||
<div>
|
||||
<label for="tnc_tel">Enable Self Telemetry</label>
|
||||
<input name="tnc_tel" id="tnc_tel" type="checkbox" value="1" title="send self telemetry data">
|
||||
</div>
|
||||
<div>
|
||||
<label for="tnc_tel_int">Self Telemetry Interval [s]</label>
|
||||
<input name="tnc_tel_int" id="tnc_tel_int" type="number" min="10" title="time between sending telemetry if Enable Self Telemetry option is selected ">
|
||||
</div>
|
||||
<div>
|
||||
<label for="tnc_tel_mic">Self Telemetry Sequence</label>
|
||||
<select id="tnc_tel_mic" name="tnc_tel_mic" title="self telemetry sequence type (numeric supported by aprs.fi and aprsdirect.com)">
|
||||
<option value="0">Numeric</option>
|
||||
<option value="1">MIC</option>
|
||||
</select>
|
||||
</div>
|
||||
<div>
|
||||
<label for="tnc_tel_path">Self Telemetry Relay Path</label>
|
||||
<input class="u-full-width" type="text" minlength="0" name="tnc_tel_path" id="tnc_tel_path" title="APRS path for self telemetry, use the shortest as possible, ECHO or WIDE1-1">
|
||||
</div>
|
||||
</div>
|
||||
<div class="grid-container full">
|
||||
<h5 class="u-full-width">Fixed Beaconing Settings</h5>
|
||||
|
@ -279,7 +307,7 @@
|
|||
</section>
|
||||
</div>
|
||||
<footer>
|
||||
<center><b>Contributors in order of appearance:</b><br> OE1ACM, OE3CJB, SQ9MDD, SQ5RWU, DJ1AN, M0IGA, SQ5WPR, DO2JMG, SP6VWX, SQ2WB, IU2FRL, DO3BOX</center>
|
||||
<center><b>Contributors in order of appearance:</b><br> OE1ACM, OE3CJB, SQ9MDD, SQ5RWU, DJ1AN, M0IGA, SQ5WPR, DO2JMG, SP6VWX, SQ2WB, IU2FRL, DO3BOX, DL9SAU, SP6NYA</center>
|
||||
<center><b>Latest stable version:</b> <a href=https://github.com/SQ9MDD/TTGO-T-Beam-LoRa-APRS>https://github.com/SQ9MDD/TTGO-T-Beam-LoRa-APRS</a></center>
|
||||
<center><b>Licensed under:</b> CC BY-NC-SA</center>
|
||||
<center><!--VERSION--></center>
|
||||
|
|
Plik binarny nie jest wyświetlany.
Plik binarny nie jest wyświetlany.
Plik binarny nie jest wyświetlany.
|
@ -0,0 +1,45 @@
|
|||
#pragma once
|
||||
|
||||
#define SATELLITE_IMAGE_WIDTH 16
|
||||
#define SATELLITE_IMAGE_HEIGHT 15
|
||||
const uint8_t SATELLITE_IMAGE[] PROGMEM = {0x00, 0x08, 0x00, 0x1C, 0x00, 0x0E, 0x20, 0x07, 0x70, 0x02,
|
||||
0xF8, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC8, 0x01, 0x9C, 0x54,
|
||||
0x0E, 0x52, 0x07, 0x48, 0x02, 0x26, 0x00, 0x10, 0x00, 0x0E};
|
||||
|
||||
const uint8_t imgSatellite[] PROGMEM = { 0x70, 0x71, 0x22, 0xFA, 0xFA, 0x22, 0x71, 0x70 };
|
||||
const uint8_t imgUSB[] PROGMEM = { 0x60, 0x60, 0x30, 0x18, 0x18, 0x18, 0x24, 0x42, 0x42, 0x42, 0x42, 0x7E, 0x24, 0x24, 0x24, 0x3C };
|
||||
const uint8_t imgPower[] PROGMEM = { 0x40, 0x40, 0x40, 0x58, 0x48, 0x08, 0x08, 0x08, 0x1C, 0x22, 0x22, 0x41, 0x7F, 0x22, 0x22, 0x22 };
|
||||
const uint8_t imgUser[] PROGMEM = { 0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3C };
|
||||
const uint8_t imgPositionEmpty[] PROGMEM = { 0x20, 0x30, 0x28, 0x24, 0x42, 0xFF };
|
||||
const uint8_t imgPositionSolid[] PROGMEM = { 0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF };
|
||||
const uint8_t imgInfo[] PROGMEM = { 0xFF, 0x81, 0x81, 0xB5, 0xB5, 0x81, 0x81, 0xFF };
|
||||
|
||||
// We now programmatically draw our compass
|
||||
#if 0
|
||||
const
|
||||
#include "img/compass.xbm"
|
||||
#endif
|
||||
|
||||
#if 0
|
||||
const uint8_t activeSymbol[] PROGMEM = {
|
||||
B00000000,
|
||||
B00000000,
|
||||
B00011000,
|
||||
B00100100,
|
||||
B01000010,
|
||||
B01000010,
|
||||
B00100100,
|
||||
B00011000
|
||||
};
|
||||
|
||||
const uint8_t inactiveSymbol[] PROGMEM = {
|
||||
B00000000,
|
||||
B00000000,
|
||||
B00000000,
|
||||
B00000000,
|
||||
B00011000,
|
||||
B00011000,
|
||||
B00000000,
|
||||
B00000000
|
||||
};
|
||||
#endif
|
|
@ -6,9 +6,10 @@
|
|||
#define ENABLE_PREFERENCES
|
||||
extern Preferences preferences;
|
||||
|
||||
// MAX 15 chars for preferenece key!!!
|
||||
// MAX 15 chars for preference key!!!
|
||||
static const char *const PREF_WIFI_SSID = "wifi_ssid";
|
||||
static const char *const PREF_WIFI_PASSWORD = "wifi_password";
|
||||
static const char *const PREF_AP_PASSWORD = "ap_password";
|
||||
// LoRa settings
|
||||
static const char *const PREF_LORA_FREQ_PRESET_INIT = "lora_freq_i";
|
||||
static const char *const PREF_LORA_FREQ_PRESET = "lora_freq";
|
||||
|
@ -34,6 +35,16 @@ static const char *const PREF_APRS_FIXED_BEACON_PRESET = "aprs_fixed_beac";
|
|||
static const char *const PREF_APRS_FIXED_BEACON_PRESET_INIT = "aprs_fix_b_init";
|
||||
static const char *const PREF_APRS_FIXED_BEACON_INTERVAL_PRESET = "aprs_fb_interv";
|
||||
static const char *const PREF_APRS_FIXED_BEACON_INTERVAL_PRESET_INIT = "aprs_fb_in_init";
|
||||
static const char *const PREF_ENABLE_TNC_SELF_TELEMETRY = "tnc_tel";
|
||||
static const char *const PREF_ENABLE_TNC_SELF_TELEMETRY_INIT = "tnc_tel_i";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_INTERVAL = "tnc_tel_int";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_INTERVAL_INIT = "tnc_tel_int_i";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_SEQ = "tnc_tel_seq";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_SEQ_INIT = "tnc_tel_seq_i";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_MIC = "tnc_tel_mic";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_MIC_INIT = "tnc_tel_mic_i";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_PATH = "tnc_tel_path";
|
||||
static const char *const PREF_TNC_SELF_TELEMETRY_PATH_INIT = "tnc_tel_path_i";
|
||||
// SMART BEACONING
|
||||
static const char *const PREF_APRS_SB_MIN_INTERVAL_PRESET = "sb_min_interv";
|
||||
static const char *const PREF_APRS_SB_MIN_INTERVAL_PRESET_INIT = "sb_min_interv_i";
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
#include <ESPmDNS.h>
|
||||
#include <Update.h>
|
||||
#include <BG_RF95.h>
|
||||
#include <esp_wifi.h>
|
||||
|
||||
#ifndef TASK_WEBSERVER
|
||||
#define TASK_WEBSERVER
|
||||
|
@ -24,7 +25,6 @@ typedef struct {
|
|||
int SNR;
|
||||
} tReceivedPacketData;
|
||||
|
||||
|
||||
extern QueueHandle_t webListReceivedQueue;
|
||||
|
||||
[[noreturn]] void taskWebServer(void *parameter);
|
||||
|
|
|
@ -0,0 +1,10 @@
|
|||
|
||||
#ifndef BUILD_NUMBER
|
||||
#define BUILD_NUMBER "182"
|
||||
#endif
|
||||
#ifndef VERSION
|
||||
#define VERSION "v0.4.182- - 2023-09-09 23:52:50.292490"
|
||||
#endif
|
||||
#ifndef VERSION_SHORT
|
||||
#define VERSION_SHORT "v0.4.182-"
|
||||
#endif
|
|
@ -21,10 +21,13 @@ PROGMEM static const BG_RF95::ModemConfig MODEM_CONFIG_TABLE[] =
|
|||
{ 0x72, 0x74, 0x00}, // Bw125Cr45Sf128 (the chip default)
|
||||
{ 0x92, 0x74, 0x00}, // Bw500Cr45Sf128
|
||||
{ 0x48, 0x94, 0x00}, // Bw31_25Cr48Sf512
|
||||
{ 0x78, 0xc4, 0x00}, // Bw125Cr48Sf4096
|
||||
{ 0x72, 0xc7, 0x8}, // BG 125 cr45 sf12
|
||||
{ 0x78, 0xc7, 0x08}, // Bw125Cr48Sf4096
|
||||
{ 0x76, 0xc7, 0x08}, // Bw125Cr47Sf4096
|
||||
{ 0x74, 0xc7, 0x08}, // Bw125Cr46Sf4096
|
||||
{ 0x72, 0xc7, 0x08}, // Bw125Cr45Sf4096
|
||||
{ 0x72, 0xb4, 0x00}, // Bw125Cr45Sf2048 <= M0IGA messup speed
|
||||
{ 0x76, 0x94, 0x04}, // Bw125Cr47Sf512 <= corrected 1200baud
|
||||
{ 0x78, 0xa4, 0x00}, // Bw125Cr48Sf1024
|
||||
};
|
||||
|
||||
BG_RF95::BG_RF95(uint8_t slaveSelectPin, uint8_t interruptPin, RHGenericSPI& spi)
|
||||
|
|
|
@ -542,13 +542,16 @@ public:
|
|||
/// you may need to change the RHReliableDatagram timeout for reliable operations.
|
||||
typedef enum
|
||||
{
|
||||
Bw125Cr45Sf128 = 0, ///< Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on. Default medium range
|
||||
Bw500Cr45Sf128, ///< Bw = 500 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on. Fast+short range
|
||||
Bw31_25Cr48Sf512, ///< Bw = 31.25 kHz, Cr = 4/8, Sf = 512chips/symbol, CRC on. Slow+long range
|
||||
Bw125Cr48Sf4096, ///< Bw = 125 kHz, Cr = 4/8, Sf = 4096chips/symbol, CRC on. Slow+long range
|
||||
Bw125Cr45Sf4096, ///< APRS
|
||||
Bw125Cr45Sf2048, ///< M0IGA Messup speed / 698baud (not 1200)
|
||||
Bw125Cr47Sf512, ///< corrected 1200 baud
|
||||
Bw125Cr45Sf128 = 0, ///< Bw = 125 kHz, Cr = 4:5, Sf = 128chips/symbol, CRC on. Default medium range
|
||||
Bw500Cr45Sf128, ///< Bw = 500 kHz, Cr = 4:5, Sf = 128chips/symbol, CRC on. Fast+short range
|
||||
Bw31_25Cr48Sf512, ///< Bw = 31.25 kHz, Cr = 4:8, Sf = 512chips/symbol, CRC on. Slow+long range
|
||||
Bw125Cr48Sf4096, ///< Bw = 125 kHz, Cr = 4:8, Sf = 4096chips/symbol, CRC on. Slow+long range
|
||||
Bw125Cr47Sf4096, ///< Bw = 125 kHz, Cr = 4:7, Sf = 4096chips/symbol, CRC on. Slow+long range
|
||||
Bw125Cr46Sf4096, ///< Bw = 125 kHz, Cr = 4:6, Sf = 4096chips/symbol, CRC on. Slow+long range
|
||||
Bw125Cr45Sf4096, ///< APRS (BW 125 khz, Cr = 4:5, Sf = 4096chips/symbol, CRC on. Slow+long range
|
||||
Bw125Cr45Sf2048, ///< M0IGA Messup speed / 698baud (not 1200)
|
||||
Bw125Cr47Sf512, ///< corrected 1200 baud
|
||||
Bw125Cr48Sf1024, /// Bw 125, Cr = 4/8, Sf = 1024chips/symbol, CRC on
|
||||
} ModemConfigChoice;
|
||||
|
||||
/// Constructor. You can have multiple instances, but each instance must have its own
|
||||
|
|
343
platformio.ini
343
platformio.ini
|
@ -1,127 +1,216 @@
|
|||
; PlatformIO Project Configuration File
|
||||
;
|
||||
; Build options: build flags, source filter
|
||||
; Upload options: custom upload port, speed and extra flags
|
||||
; Library options: dependencies, extra library storages
|
||||
; Advanced options: extra scripting
|
||||
;
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
|
||||
[env]
|
||||
framework = arduino
|
||||
monitor_speed = 115200
|
||||
board_build.partitions = partitions.csv
|
||||
board_build.embed_files =
|
||||
data_embed/index.html.out
|
||||
data_embed/style.css.out
|
||||
data_embed/js.js.out
|
||||
extra_scripts =
|
||||
pre:tools/buildscript_versioning.py
|
||||
pre:tools/compress_assets.py
|
||||
lib_deps =
|
||||
RadioHead
|
||||
TinyGPSPlus
|
||||
Adafruit SSD1306
|
||||
Adafruit GFX Library
|
||||
Adafruit Unified Sensor
|
||||
https://github.com/SQ9MDD/AXP202X_Library.git
|
||||
SparkFun u-blox Arduino Library
|
||||
bblanchon/ArduinoJson
|
||||
build_flags =
|
||||
-Wl,--gc-sections,--relax
|
||||
-D 'KISS_PROTOCOL' ; leave enabled
|
||||
-D 'CALLSIGN="N0CALL-0"' ; can be set from www interfeace
|
||||
-D 'DIGI_PATH="WIDE1-1"' ; can be set from www interfeace
|
||||
-D 'FIXED_BEACON_EN' ; can be set from www interfeace
|
||||
-D 'LATIDUDE_PRESET="0000.00N"' ; can be set from www interfeace
|
||||
-D 'LONGITUDE_PRESET="00000.00E"' ; can be set from www interfeace
|
||||
-D 'APRS_SYMBOL_TABLE="/"' ; can be set from www interfeace
|
||||
-D 'APRS_SYMBOL="["' ; can be set from www interfeace
|
||||
-D 'MY_COMMENT="Lora Tracker"' ; can be set from www interfeace
|
||||
-D 'SHOW_ALT' ; can be set from www interfeace
|
||||
-D 'SHOW_BATT' ; can be set from www interfeace
|
||||
-D 'SHOW_RX_PACKET' ; can be set from www interfeace
|
||||
-D 'SHOW_RX_TIME=10000' ; can be set from www interfeace
|
||||
-D 'TXFREQ=433.775' ; set operating frequency
|
||||
-D 'SPEED_1200' ; comment out to set 300baud
|
||||
-D 'TXdbmW=23' ; set power
|
||||
-D 'ENABLE_OLED' ; can be set from www interfeace
|
||||
-D 'ENABLE_LED_SIGNALING' ; can be set from www interfeace
|
||||
-D 'NETWORK_TNC_PORT=8001' ; default KISS TCP port
|
||||
-D 'MAX_TIME_TO_NEXT_TX=120000L' ; can be set from www interfeace
|
||||
-D 'FIX_BEACON_INTERVAL=1800000L' ; can be set from www interfeace
|
||||
-D 'NETWORK_GPS_PORT=10110' ; GPS NMEA Port
|
||||
-D 'SHOW_OLED_TIME=15000' ; OLED Timeout
|
||||
|
||||
[env:ttgo-t-beam-v1.0]
|
||||
platform = espressif32 @ 3.0.0
|
||||
board = ttgo-t-beam
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D T_BEAM_V1_0
|
||||
-D ENABLE_WIFI
|
||||
-D ENABLE_BLUETOOTH
|
||||
|
||||
[env:ttgo-t-beam-v0.7]
|
||||
platform = espressif32 @ 3.0.0
|
||||
board = ttgo-t-beam
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D T_BEAM_V0_7
|
||||
|
||||
[env:ttgo-lora32-v2.1]
|
||||
platform = espressif32 @ 3.1.1
|
||||
board = ttgo-lora32-v21
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D LORA32_21
|
||||
|
||||
[env:ttgo-lora32-v2]
|
||||
platform = espressif32 @ 3.1.1
|
||||
board = ttgo-lora32-v2
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D LORA32_2
|
||||
|
||||
[env:ttgo-lora32-v1]
|
||||
platform = espressif32 @ 3.1.1
|
||||
board = ttgo-lora32-v1
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D LORA32_1
|
||||
|
||||
[env:Heltec-WiFi-v1]
|
||||
platform = espressif32 @ 3.1.1
|
||||
board = heltec_wifi_kit_32
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D HELTEC_V1
|
||||
|
||||
[env:Heltec-WiFi-v2]
|
||||
platform = espressif32 @ 3.1.1
|
||||
board = heltec_wifi_kit_32_v2
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D HELTEC_V2
|
||||
|
||||
[env:ttgo-t-beam-v1.0-development]
|
||||
platform = espressif32 @ 3.0.0
|
||||
board = ttgo-t-beam
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D T_BEAM_V1_0
|
||||
-D ENABLE_WIFI
|
||||
-D ENABLE_BLUETOOTH
|
||||
-D ENABLE_SYSLOG
|
||||
-D 'SYSLOG_IP="192.168.0.102"'
|
||||
-D DEVELOPMENT_DEBUG
|
||||
lib_deps =
|
||||
${env.lib_deps}
|
||||
arcao/Syslog
|
||||
; PlatformIO Project Configuration File
|
||||
;
|
||||
; Build options: build flags, source filter
|
||||
; Upload options: custom upload port, speed and extra flags
|
||||
; Library options: dependencies, extra library storages
|
||||
; Advanced options: extra scripting
|
||||
;
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
[env]
|
||||
framework = arduino
|
||||
monitor_speed = 115200
|
||||
board_build.partitions = partitions.csv
|
||||
board_build.embed_files =
|
||||
data_embed/index.html.out
|
||||
data_embed/style.css.out
|
||||
data_embed/js.js.out
|
||||
extra_scripts =
|
||||
pre:tools/buildscript_versioning.py
|
||||
pre:tools/compress_assets.py
|
||||
lib_deps =
|
||||
RadioHead
|
||||
TinyGPSPlus
|
||||
Adafruit SSD1306
|
||||
Adafruit GFX Library
|
||||
Adafruit Unified Sensor
|
||||
SparkFun u-blox Arduino Library
|
||||
bblanchon/ArduinoJson
|
||||
XPowersLib
|
||||
build_flags =
|
||||
-Wl,--gc-sections,--relax
|
||||
-D 'KISS_PROTOCOL'
|
||||
-D 'CALLSIGN="N0CALL-0"'
|
||||
-D 'DIGI_PATH="WIDE1-1"'
|
||||
-D 'FIXED_BEACON_EN'
|
||||
-D 'LATIDUDE_PRESET="0000.00N"'
|
||||
-D 'LONGITUDE_PRESET="00000.00E"'
|
||||
-D 'APRS_SYMBOL_TABLE="/"'
|
||||
-D 'APRS_SYMBOL="["'
|
||||
-D 'MY_COMMENT="Lora Tracker"'
|
||||
-D 'SHOW_ALT'
|
||||
-D 'SHOW_BATT'
|
||||
-D 'SHOW_RX_PACKET'
|
||||
-D 'SHOW_RX_TIME=10000'
|
||||
-D 'TXFREQ=433.775'
|
||||
-D 'SPEED_1200'
|
||||
-D 'TXdbmW=23'
|
||||
-D 'ENABLE_OLED'
|
||||
-D 'ENABLE_LED_SIGNALING'
|
||||
-D 'NETWORK_TNC_PORT=8001'
|
||||
-D 'MAX_TIME_TO_NEXT_TX=120000L'
|
||||
-D 'FIX_BEACON_INTERVAL=1800000L'
|
||||
-D 'NETWORK_GPS_PORT=10110'
|
||||
-D 'ENABLE_TNC_SELF_TELEMETRY'
|
||||
-D 'TNC_SELF_TELEMETRY_INTERVAL=3600L'
|
||||
-D 'SHOW_OLED_TIME=15000'
|
||||
|
||||
[env:ttgo-t-beam-v1_0]
|
||||
platform = espressif32 @ 3.0.0
|
||||
board = ttgo-t-beam
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D T_BEAM_V1_0
|
||||
-D ENABLE_WIFI
|
||||
-D ENABLE_BLUETOOTH
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:ttgo-t-beam-v1_2]
|
||||
platform = espressif32 @ 3.0.0
|
||||
board = ttgo-t-beam
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D T_BEAM_V1_2
|
||||
-D ENABLE_WIFI
|
||||
-D ENABLE_BLUETOOTH
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:ttgo-t-beam-v0_7]
|
||||
platform = espressif32 @ 3.0.0
|
||||
board = ttgo-t-beam
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D T_BEAM_V0_7
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:ttgo-lora32-v2_1]
|
||||
platform = espressif32 @ 3.2.0
|
||||
board = ttgo-lora32-v21
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D LORA32_21
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:ttgo-lora32-v2]
|
||||
platform = espressif32 @ 3.2.0
|
||||
board = ttgo-lora32-v2
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D LORA32_2
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:ttgo-lora32-v1]
|
||||
platform = espressif32 @ 3.2.0
|
||||
board = ttgo-lora32-v1
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D LORA32_1
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:Heltec-WiFi-v1]
|
||||
platform = espressif32 @ 3.2.0
|
||||
board = heltec_wifi_kit_32
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D HELTEC_V1
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:Heltec-WiFi-v2]
|
||||
platform = espressif32 @ 3.2.0
|
||||
board = heltec_wifi_kit_32_v2
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D ENABLE_WIFI
|
||||
-D HELTEC_V2
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
||||
[env:ttgo-t-beam-v1_0-development]
|
||||
platform = espressif32 @ 3.0.0
|
||||
board = ttgo-t-beam
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D T_BEAM_V1_0
|
||||
-D ENABLE_WIFI
|
||||
-D ENABLE_BLUETOOTH
|
||||
-D ENABLE_SYSLOG
|
||||
-D 'SYSLOG_IP="192.168.0.102"'
|
||||
-D DEVELOPMENT_DEBUG
|
||||
lib_deps =
|
||||
${env.lib_deps}
|
||||
arcao/Syslog
|
||||
lewisxhe/XPowersLib@^0.1.8
|
||||
mikem/RadioHead@^1.120
|
||||
mikalhart/TinyGPSPlus@^1.0.3
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
adafruit/Adafruit GFX Library@^1.11.7
|
||||
paulstoffregen/OneWire@^2.3.7
|
||||
sparkfun/SparkFun u-blox Arduino Library@^1.8.11
|
||||
bblanchon/ArduinoJson@^6.21.3
|
||||
|
|
|
@ -19,11 +19,11 @@
|
|||
#include <Adafruit_SPITFT.h>
|
||||
#include <Adafruit_SPITFT_Macros.h>
|
||||
#include <gfxfont.h>
|
||||
#include <axp20x.h>
|
||||
#include "taskGPS.h"
|
||||
#include "version.h"
|
||||
#include "preference_storage.h"
|
||||
#include "syslog_log.h"
|
||||
#include "XPowersLib.h"
|
||||
|
||||
#ifdef KISS_PROTOCOL
|
||||
#include "taskTNC.h"
|
||||
|
@ -42,7 +42,15 @@
|
|||
#define SPI_ss 18
|
||||
|
||||
// IO config
|
||||
#ifdef T_BEAM_V1_0
|
||||
#ifdef T_BEAM_V1_2
|
||||
#define XPOWERS_CHIP_AXP2101
|
||||
#define I2C_SDA 21
|
||||
#define I2C_SCL 22
|
||||
#define BUTTON 38 //pin number for Button on TTGO T-Beam
|
||||
#define BUZZER 15 // enter your buzzer pin gpio
|
||||
const byte TXLED = 4;
|
||||
#elif T_BEAM_V1_0
|
||||
#define XPOWERS_CHIP_AXP192
|
||||
#define I2C_SDA 21
|
||||
#define I2C_SCL 22
|
||||
#define BUTTON 38 //pin number for Button on TTGO T-Beam
|
||||
|
@ -54,12 +62,20 @@
|
|||
#define BUTTON 39 //pin number for Button on TTGO T-Beam
|
||||
#define BUZZER 15 // enter your buzzer pin gpio
|
||||
const byte TXLED = 4; //pin number for LED on TX Tracker
|
||||
/* Original LORA32 V2.1 Setup
|
||||
#elif LORA32_21
|
||||
#define I2C_SDA 4
|
||||
#define I2C_SCL 15
|
||||
#define BUTTON 2 //pin number for BUTTO
|
||||
#define BUZZER 13 // enter your buzzer pin gpio
|
||||
const byte TXLED = 4; //pin number for LED on TX Tracker
|
||||
*/
|
||||
#elif LORA32_21 // Modified as in #47
|
||||
#define I2C_SDA 21
|
||||
#define I2C_SCL 22
|
||||
#define BUTTON 2 //pin number for BUTTO
|
||||
#define BUZZER 13 // enter your buzzer pin gpio
|
||||
const byte TXLED = 4; //pin number for LED on TX Tracker
|
||||
#elif LORA32_2
|
||||
#define I2C_SDA 21
|
||||
#define I2C_SCL 22
|
||||
|
@ -103,6 +119,10 @@ boolean key_up = true;
|
|||
boolean t_lock = false;
|
||||
boolean fixed_beacon_enabled = false;
|
||||
boolean show_cmt = true;
|
||||
// Telemetry sequence, current value
|
||||
int tel_sequence;
|
||||
// Telemetry path
|
||||
String tel_path;
|
||||
|
||||
#ifdef SHOW_ALT
|
||||
boolean showAltitude = true;
|
||||
|
@ -114,6 +134,22 @@ boolean show_cmt = true;
|
|||
#else
|
||||
boolean showBattery = false;
|
||||
#endif
|
||||
#ifdef ENABLE_TNC_SELF_TELEMETRY
|
||||
boolean enable_tel = true;
|
||||
#else
|
||||
boolean enable_tel = false;
|
||||
#endif
|
||||
// Telemetry interval, seconds
|
||||
#ifdef TNC_SELF_TELEMETRY_INTERVAL
|
||||
int tel_interval = TNC_SELF_TELEMETRY_INTERVAL;
|
||||
#else
|
||||
int tel_interval = 3600;
|
||||
#endif
|
||||
#ifdef TNC_SELF_TELEMETRY_MIC
|
||||
int tel_mic = 1; // telemetry as "T#MIC"
|
||||
#else
|
||||
int tel_mic = 0; // telemetry as "T#001"
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
boolean enable_bluetooth = true;
|
||||
#else
|
||||
|
@ -153,6 +189,7 @@ byte lora_FDeviceError; //flag, set to 1 if RFM98 device error
|
|||
byte lora_TXPacketL; //length of packet to send, includes source, destination and packet type.
|
||||
|
||||
unsigned long lastTX = 0L;
|
||||
float ConvertToV;
|
||||
float BattVolts;
|
||||
float InpVolts;
|
||||
|
||||
|
@ -188,9 +225,17 @@ uint oled_timeout = SHOW_OLED_TIME; // OLED Timeout
|
|||
bool tempOled = true; // Turn ON OLED at first startup
|
||||
ulong oled_timer;
|
||||
|
||||
// Variable to manually send beacon from html page
|
||||
|
||||
|
||||
bool manBeacon = false;
|
||||
|
||||
// Variable to show AP settings on OLED
|
||||
bool apEnabled = false;
|
||||
bool apConnected = false;
|
||||
String infoApName = "";
|
||||
String infoApPass = "";
|
||||
String infoApAddr = "";
|
||||
|
||||
#define ANGLE_AVGS 3 // angle averaging - x times
|
||||
float average_course[ANGLE_AVGS];
|
||||
float avg_c_y, avg_c_x;
|
||||
|
@ -204,7 +249,21 @@ uint8_t txPower = TXdbmW;
|
|||
static const adc_atten_t atten = ADC_ATTEN_DB_6;
|
||||
static const adc_unit_t unit = ADC_UNIT_1;
|
||||
#ifdef T_BEAM_V1_0
|
||||
AXP20X_Class axp;
|
||||
bool pmu_flag = 0;
|
||||
XPowersAXP192 PMU;
|
||||
|
||||
void setFlag(void)
|
||||
{
|
||||
pmu_flag = true;
|
||||
}
|
||||
#elif T_BEAM_V1_2 //PMU TBEAM 1.2
|
||||
bool pmu_flag = 0;
|
||||
XPowersAXP2101 PMU;
|
||||
|
||||
void setFlag(void)
|
||||
{
|
||||
pmu_flag = true;
|
||||
}
|
||||
#endif
|
||||
|
||||
// checkRX
|
||||
|
@ -230,6 +289,43 @@ char *ax25_base91enc(char *s, uint8_t n, uint32_t v){
|
|||
return(s);
|
||||
}
|
||||
|
||||
#if defined(KISS_PROTOCOL)
|
||||
/**
|
||||
*
|
||||
* @param TNC2FormatedFrame
|
||||
*/
|
||||
void sendToTNC(const String& TNC2FormatedFrame) {
|
||||
if (tncToSendQueue){
|
||||
auto *buffer = new String();
|
||||
buffer->concat(TNC2FormatedFrame);
|
||||
if (xQueueSend(tncReceivedQueue, &buffer, (1000 / portTICK_PERIOD_MS)) != pdPASS){
|
||||
// remove buffer on error
|
||||
delete buffer;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
void enablepins(){
|
||||
#ifdef T_BEAM_V1_2
|
||||
PMU.enableBattDetection();
|
||||
PMU.enableVbusVoltageMeasure();
|
||||
PMU.enableBattVoltageMeasure();
|
||||
PMU.enableSystemVoltageMeasure();
|
||||
#elif T_BEAM_V1_0
|
||||
PMU.enableBattDetection();
|
||||
PMU.enableVbusVoltageMeasure();
|
||||
PMU.enableBattVoltageMeasure();
|
||||
PMU.enableSystemVoltageMeasure();
|
||||
#elif T_BEAM_V0_7 /*
|
||||
adcAttachPin(35);
|
||||
adcStart(35);
|
||||
analogReadResolution(10);
|
||||
analogSetAttenuation(ADC_6db); */
|
||||
pinMode(35, INPUT);
|
||||
//adc1_config_width(ADC_WIDTH_BIT_12);
|
||||
//adc1_config_channel_atten(ADC1_CHANNEL_7,ADC_ATTEN_DB_11);
|
||||
#endif
|
||||
}
|
||||
void prepareAPRSFrame(){
|
||||
String helper;
|
||||
String Altx;
|
||||
|
@ -252,9 +348,9 @@ void prepareAPRSFrame(){
|
|||
outString += Tcall;
|
||||
|
||||
if (relay_path.isEmpty()){
|
||||
outString += ">APLO01:!";
|
||||
outString += ">APLO02:!";
|
||||
}else{
|
||||
outString += ">APLO01," + relay_path + ":!";
|
||||
outString += ">APLO02," + relay_path + ":!";
|
||||
}
|
||||
|
||||
if(gps_state && gps.location.isValid()){
|
||||
|
@ -275,7 +371,7 @@ void prepareAPRSFrame(){
|
|||
outString += "H";
|
||||
|
||||
if (showAltitude){
|
||||
Talt = gps.altitude.meters() * 3.28d;
|
||||
Talt = gps.altitude.meters() * 3.28;
|
||||
Altx = Talt;
|
||||
outString += "/A=";
|
||||
for (i = 0; i < (6 - Altx.length()); ++i){
|
||||
|
@ -322,15 +418,6 @@ void buzzer(int* melody, int array_size){
|
|||
}
|
||||
#endif
|
||||
|
||||
void sendpacket(){
|
||||
#ifdef BUZZER
|
||||
int melody[] = {1000, 50, 800, 100};
|
||||
buzzer(melody, sizeof(melody)/sizeof(int));
|
||||
#endif
|
||||
batt_read();
|
||||
prepareAPRSFrame();
|
||||
loraSend(txPower, lora_freq, outString); //send the packet, data is in TXbuff from lora_TXStart to lora_TXEnd
|
||||
}
|
||||
|
||||
/**
|
||||
* Send message as APRS LoRa packet
|
||||
|
@ -349,7 +436,19 @@ void loraSend(byte lora_LTXPower, float lora_FREQ, const String &message) {
|
|||
if(lora_speed==1200){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr47Sf512);
|
||||
}
|
||||
else{
|
||||
else if(lora_speed==610){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr48Sf1024);
|
||||
}
|
||||
else if(lora_speed==180){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr48Sf4096);
|
||||
}
|
||||
else if(lora_speed==210){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr47Sf4096);
|
||||
}
|
||||
else if(lora_speed==240){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr46Sf4096);
|
||||
}
|
||||
else {
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr45Sf4096);
|
||||
}
|
||||
rf95.setFrequency(lora_FREQ);
|
||||
|
@ -362,23 +461,57 @@ void loraSend(byte lora_LTXPower, float lora_FREQ, const String &message) {
|
|||
}
|
||||
|
||||
void batt_read(){
|
||||
#ifdef T_BEAM_V1_0
|
||||
BattVolts = axp.getBattVoltage()/1000;
|
||||
InpVolts = axp.getVbusVoltage()/1000;
|
||||
ConvertToV = 1000;
|
||||
#ifdef T_BEAM_V1_2
|
||||
BattVolts = PMU.getBattVoltage()/ConvertToV;
|
||||
InpVolts = PMU.getVbusVoltage()/ConvertToV;
|
||||
#elif T_BEAM_V1_0
|
||||
BattVolts = PMU.getBattVoltage()/ConvertToV;
|
||||
InpVolts = PMU.getVbusVoltage()/ConvertToV;
|
||||
#elif T_BEAM_V0_7
|
||||
BattVolts = ((float)analogRead(35) / 8192.0) * 2.0 * 3.3 * (1100.0 / 1000.0); // fixed thanks to Luca IU2FRL
|
||||
BattVolts = (((float)analogRead(35) / 8192.0) * 2.0 * 3.3 * (1100.0 / 1000.0))+0.41; // fixed thanks to Luca IU2FRL
|
||||
//BattVolts = adc1_get_raw(ADC1_CHANNEL_7)/1000;
|
||||
#else
|
||||
BattVolts = analogRead(35)*7.221/4096; // fixed thanks to Luca IU2FRL
|
||||
BattVolts = analogRead(35)*7.221/4096;
|
||||
#endif
|
||||
Serial.print(BattVolts);
|
||||
}
|
||||
|
||||
void sendpacket(){
|
||||
#ifdef BUZZER
|
||||
int melody[] = {1000, 50, 800, 100};
|
||||
buzzer(melody, sizeof(melody)/sizeof(int));
|
||||
#endif
|
||||
batt_read();
|
||||
prepareAPRSFrame();
|
||||
loraSend(txPower, lora_freq, outString); //send the packet, data is in TXbuff from lora_TXStart to lora_TXEnd
|
||||
}
|
||||
|
||||
void writedisplaytext(String HeaderTxt, String Line1, String Line2, String Line3, String Line4, String Line5) {
|
||||
batt_read();
|
||||
if (BattVolts < 3.5 && BattVolts > 3.2){
|
||||
#ifdef T_BEAM_V1_0
|
||||
# ifdef ENABLE_LED_SIGNALING
|
||||
axp.setChgLEDMode(AXP20X_LED_BLINK_4HZ);
|
||||
if (BattVolts < 3.5 && BattVolts > 3.3){
|
||||
#ifdef T_BEAM_V1_2
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_BLINK_1HZ);
|
||||
#endif
|
||||
#elif T_BEAM_V1_0
|
||||
# ifdef ENABLE_LED_SIGNALING
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_BLINK_1HZ);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
else if(BattVolts <= 3.3){
|
||||
#ifdef T_BEAM_V1_2
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_BLINK_4HZ);
|
||||
#elif T_BEAM_V1_0
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_BLINK_4HZ);
|
||||
#endif
|
||||
}
|
||||
else if(BattVolts <=3.0){
|
||||
#ifdef T_BEAM_V1_2
|
||||
//PMU.shutdown();
|
||||
#elif T_BEAM_V1_0
|
||||
PMU.shutdown();
|
||||
#endif
|
||||
}
|
||||
display.clearDisplay();
|
||||
|
@ -397,11 +530,7 @@ void writedisplaytext(String HeaderTxt, String Line1, String Line2, String Line3
|
|||
display.println(Line4);
|
||||
display.setCursor(0,56);
|
||||
display.println(Line5);
|
||||
if (enabled_oled){
|
||||
//axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON); // enable oled
|
||||
//display.dim(false);
|
||||
}else{
|
||||
//axp.setPowerOutPut(AXP192_DCDC1, AXP202_OFF); // disable oled
|
||||
if (!enabled_oled){ // disable oled
|
||||
display.dim(true);
|
||||
}
|
||||
display.display();
|
||||
|
@ -412,13 +541,13 @@ String getSatAndBatInfo() {
|
|||
String line5;
|
||||
if(gps_state == true){
|
||||
if(InpVolts > 4){
|
||||
line5 = "SAT: " + String(gps.satellites.value()) + " BAT: " + String(BattVolts, 2) + "V *";
|
||||
line5 = "SAT: " + String(gps.satellites.value()) + " BAT: " + String(BattVolts, 1) + "V*";
|
||||
}else{
|
||||
line5 = "SAT: " + String(gps.satellites.value()) + " BAT: " + String(BattVolts, 2) + "V";
|
||||
}
|
||||
}else{
|
||||
if(InpVolts > 4){
|
||||
line5 = "SAT: X BAT: " + String(BattVolts, 2) + "V *";
|
||||
line5 = "SAT: X BAT: " + String(BattVolts, 1) + "V*";
|
||||
}else{
|
||||
line5 = "SAT: X BAT: " + String(BattVolts, 2) + "V";
|
||||
}
|
||||
|
@ -442,22 +571,6 @@ void displayInvalidGPS() {
|
|||
writedisplaytext(" " + Tcall, nextTxInfo, "LAT: not valid", "LON: not valid", "SPD: --- CRS: ---", getSatAndBatInfo());
|
||||
}
|
||||
|
||||
#if defined(KISS_PROTOCOL)
|
||||
/**
|
||||
*
|
||||
* @param TNC2FormatedFrame
|
||||
*/
|
||||
void sendToTNC(const String& TNC2FormatedFrame) {
|
||||
if (tncToSendQueue){
|
||||
auto *buffer = new String();
|
||||
buffer->concat(TNC2FormatedFrame);
|
||||
if (xQueueSend(tncReceivedQueue, &buffer, (1000 / portTICK_PERIOD_MS)) != pdPASS){
|
||||
// remove buffer on error
|
||||
delete buffer;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#if defined(ENABLE_WIFI)
|
||||
/**
|
||||
*
|
||||
|
@ -492,35 +605,136 @@ String prepareCallsign(const String& callsign){
|
|||
}
|
||||
|
||||
#if defined(ENABLE_TNC_SELF_TELEMETRY) && defined(KISS_PROTOCOL)
|
||||
void sendTelemetryFrame() {
|
||||
#ifdef T_BEAM_V1_0
|
||||
uint8_t b_volt = (axp.getBattVoltage() - 3000) / 5.1;
|
||||
uint8_t b_in_c = (axp.getBattChargeCurrent()) / 10;
|
||||
uint8_t b_out_c = (axp.getBattDischargeCurrent()) / 10;
|
||||
uint8_t ac_volt = (axp.getVbusVoltage() - 3000) / 28;
|
||||
uint8_t ac_c = (axp.getVbusCurrent()) / 10;
|
||||
void sendTelemetryFrame() {
|
||||
if(enable_tel == true){
|
||||
#ifdef T_BEAM_V1_2
|
||||
uint8_t b_volt = (PMU.getBattVoltage() - 3000) / 5.1;
|
||||
uint8_t ac_volt = (PMU.getVbusVoltage() - 3000) / 28;
|
||||
// Pad telemetry message address to 9 characters
|
||||
char Tcall_message_char[9];
|
||||
sprintf_P(Tcall_message_char, "%-9s", Tcall);
|
||||
String Tcall_message = String(Tcall_message_char);
|
||||
// Flash the light when telemetry is being sent
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
digitalWrite(TXLED, LOW);
|
||||
#endif
|
||||
|
||||
String telemetryParamsNames = String(":") + Tcall + ":PARM.B Volt,B In,B Out,AC V,AC C";
|
||||
String telemetryUnitNames = String(":") + Tcall + ":UNIT.mV,mA,mA,mV,mA";
|
||||
String telemetryEquations = String(":") + Tcall + ":EQNS.0,5.1,3000,0,10,0,0,10,0,0,28,3000,0,10,0";
|
||||
String telemetryData = String("T#MIC") + String(b_volt) + ","+ String(b_in_c) + ","+ String(b_out_c) + ","+ String(ac_volt) + ","+ String(ac_c) + ",00000000";
|
||||
String telemetryBase = "";
|
||||
telemetryBase += Tcall + ">APLO01" + ":";
|
||||
sendToTNC(telemetryBase + telemetryParamsNames);
|
||||
sendToTNC(telemetryBase + telemetryUnitNames);
|
||||
sendToTNC(telemetryBase + telemetryEquations);
|
||||
sendToTNC(telemetryBase + telemetryData);
|
||||
#endif
|
||||
}
|
||||
// Determine sequence number (or 'MIC')
|
||||
String tel_sequence_str;
|
||||
if(tel_mic == 1){
|
||||
tel_sequence_str = "MIC";
|
||||
}else{
|
||||
// Get the current saved telemetry sequence
|
||||
tel_sequence = preferences.getUInt(PREF_TNC_SELF_TELEMETRY_SEQ, 0);
|
||||
// Pad to 3 digits
|
||||
char tel_sequence_char[3];
|
||||
sprintf_P(tel_sequence_char, "%03u", tel_sequence);
|
||||
tel_sequence_str = String(tel_sequence_char);
|
||||
}
|
||||
// Format telemetry path
|
||||
String tel_path_str;
|
||||
if(tel_path == ""){
|
||||
tel_path_str = tel_path;
|
||||
}else{
|
||||
tel_path_str = "," + tel_path;
|
||||
}
|
||||
|
||||
String telemetryParamsNames = String(":") + Tcall_message + ":PARM.B Volt,AC V,";
|
||||
String telemetryUnitNames = String(":") + Tcall_message + ":UNIT.mV,mV,";
|
||||
String telemetryEquations = String(":") + Tcall_message + ":EQNS.0,5.1,3000,0,10,0,0,10,0,0,28,3000,0,10,0";
|
||||
String telemetryData = String("T#") + tel_sequence_str + "," + String(b_volt) + "," + String(ac_volt) + ",00000000";
|
||||
String telemetryBase = "";
|
||||
telemetryBase += Tcall + ">APLO02" + tel_path_str + ":";
|
||||
Serial.print(telemetryBase);
|
||||
sendToTNC(telemetryBase + telemetryParamsNames);
|
||||
sendToTNC(telemetryBase + telemetryUnitNames);
|
||||
sendToTNC(telemetryBase + telemetryEquations);
|
||||
sendToTNC(telemetryBase + telemetryData);
|
||||
|
||||
// Show when telemetry is being sent
|
||||
writedisplaytext("((TEL TX))","","","","","");
|
||||
|
||||
// Flash the light when telemetry is being sent
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
digitalWrite(TXLED, HIGH);
|
||||
#endif
|
||||
|
||||
// Update the telemetry sequence number
|
||||
if(tel_sequence >= 999){
|
||||
tel_sequence = 0;
|
||||
}else{
|
||||
tel_sequence = tel_sequence + 1;
|
||||
}
|
||||
preferences.putUInt(PREF_TNC_SELF_TELEMETRY_SEQ, tel_sequence);
|
||||
#elif T_BEAM_V1_0
|
||||
uint8_t b_volt = (PMU.getBattVoltage() - 3000) / 5.1;
|
||||
uint8_t b_in_c = (PMU.getBatteryChargeCurrent()) / 10;
|
||||
uint8_t b_out_c = (PMU.getBattDischargeCurrent()) / 10;
|
||||
uint8_t ac_volt = (PMU.getVbusVoltage() - 3000) / 28;
|
||||
uint8_t ac_c = (PMU.getVbusCurrent()) / 10;
|
||||
// Pad telemetry message address to 9 characters
|
||||
char Tcall_message_char[9];
|
||||
sprintf_P(Tcall_message_char, "%-9s", Tcall);
|
||||
String Tcall_message = String(Tcall_message_char);
|
||||
// Flash the light when telemetry is being sent
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
digitalWrite(TXLED, LOW);
|
||||
#endif
|
||||
|
||||
// Determine sequence number (or 'MIC')
|
||||
String tel_sequence_str;
|
||||
if(tel_mic == 1){
|
||||
tel_sequence_str = "MIC";
|
||||
}else{
|
||||
// Get the current saved telemetry sequence
|
||||
tel_sequence = preferences.getUInt(PREF_TNC_SELF_TELEMETRY_SEQ, 0);
|
||||
// Pad to 3 digits
|
||||
char tel_sequence_char[3];
|
||||
sprintf_P(tel_sequence_char, "%03u", tel_sequence);
|
||||
tel_sequence_str = String(tel_sequence_char);
|
||||
}
|
||||
// Format telemetry path
|
||||
String tel_path_str;
|
||||
if(tel_path == ""){
|
||||
tel_path_str = tel_path;
|
||||
}else{
|
||||
tel_path_str = "," + tel_path;
|
||||
}
|
||||
|
||||
String telemetryParamsNames = String(":") + Tcall_message + ":PARM.B Volt,B In,B Out,AC V,AC C";
|
||||
String telemetryUnitNames = String(":") + Tcall_message + ":UNIT.mV,mA,mA,mV,mA";
|
||||
String telemetryEquations = String(":") + Tcall_message + ":EQNS.0,5.1,3000,0,10,0,0,10,0,0,28,3000,0,10,0";
|
||||
String telemetryData = String("T#") + tel_sequence_str + "," + String(b_volt) + "," + String(b_in_c) + "," + String(b_out_c) + "," + String(ac_volt) + "," + String(ac_c) + ",00000000";
|
||||
String telemetryBase = "";
|
||||
telemetryBase += Tcall + ">APLO02" + tel_path_str + ":";
|
||||
Serial.print(telemetryBase);
|
||||
sendToTNC(telemetryBase + telemetryParamsNames);
|
||||
sendToTNC(telemetryBase + telemetryUnitNames);
|
||||
sendToTNC(telemetryBase + telemetryEquations);
|
||||
sendToTNC(telemetryBase + telemetryData);
|
||||
|
||||
// Show when telemetry is being sent
|
||||
writedisplaytext("((TEL TX))","","","","","");
|
||||
|
||||
// Flash the light when telemetry is being sent
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
digitalWrite(TXLED, HIGH);
|
||||
#endif
|
||||
|
||||
// Update the telemetry sequence number
|
||||
if(tel_sequence >= 999){
|
||||
tel_sequence = 0;
|
||||
}else{
|
||||
tel_sequence = tel_sequence + 1;
|
||||
}
|
||||
preferences.putUInt(PREF_TNC_SELF_TELEMETRY_SEQ, tel_sequence);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// + SETUP --------------------------------------------------------------+//
|
||||
void setup(){
|
||||
//#ifdef T_BEAM_V0_7
|
||||
// adcAttachPin(35);
|
||||
// adcStart(35);
|
||||
// analogReadResolution(10);
|
||||
//#endif
|
||||
|
||||
SPI.begin(SPI_sck,SPI_miso,SPI_mosi,SPI_ss); //DO2JMG Heltec Patch
|
||||
Serial.begin(115200);
|
||||
|
@ -541,6 +755,10 @@ void setup(){
|
|||
fixed_beacon_enabled = true;
|
||||
#endif
|
||||
|
||||
// This section loads values from saved preferences,
|
||||
// if available.
|
||||
// https://randomnerdtutorials.com/esp32-save-data-permanently-preferences/
|
||||
|
||||
#ifdef ENABLE_PREFERENCES
|
||||
int clear_preferences = 0;
|
||||
if(digitalRead(BUTTON)==LOW){
|
||||
|
@ -607,6 +825,36 @@ void setup(){
|
|||
}
|
||||
showBattery = preferences.getBool(PREF_APRS_SHOW_BATTERY);
|
||||
|
||||
if (!preferences.getBool(PREF_ENABLE_TNC_SELF_TELEMETRY_INIT)){
|
||||
preferences.putBool(PREF_ENABLE_TNC_SELF_TELEMETRY_INIT, true);
|
||||
preferences.putBool(PREF_ENABLE_TNC_SELF_TELEMETRY, enable_tel);
|
||||
}
|
||||
enable_tel = preferences.getBool(PREF_ENABLE_TNC_SELF_TELEMETRY);
|
||||
|
||||
if (!preferences.getBool(PREF_TNC_SELF_TELEMETRY_INTERVAL_INIT)){
|
||||
preferences.putBool(PREF_TNC_SELF_TELEMETRY_INTERVAL_INIT, true);
|
||||
preferences.putInt(PREF_TNC_SELF_TELEMETRY_INTERVAL, tel_interval);
|
||||
}
|
||||
tel_interval = preferences.getInt(PREF_TNC_SELF_TELEMETRY_INTERVAL);
|
||||
|
||||
if (!preferences.getBool(PREF_TNC_SELF_TELEMETRY_SEQ_INIT)){
|
||||
preferences.putBool(PREF_TNC_SELF_TELEMETRY_SEQ_INIT, true);
|
||||
preferences.putInt(PREF_TNC_SELF_TELEMETRY_SEQ, tel_sequence);
|
||||
}
|
||||
tel_sequence = preferences.getInt(PREF_TNC_SELF_TELEMETRY_SEQ);
|
||||
|
||||
if (!preferences.getBool(PREF_TNC_SELF_TELEMETRY_MIC_INIT)){
|
||||
preferences.putBool(PREF_TNC_SELF_TELEMETRY_MIC_INIT, true);
|
||||
preferences.putInt(PREF_TNC_SELF_TELEMETRY_MIC, tel_mic);
|
||||
}
|
||||
tel_mic = preferences.getInt(PREF_TNC_SELF_TELEMETRY_MIC);
|
||||
|
||||
if (!preferences.getBool(PREF_TNC_SELF_TELEMETRY_PATH_INIT)){
|
||||
preferences.putBool(PREF_TNC_SELF_TELEMETRY_PATH_INIT, true);
|
||||
preferences.putString(PREF_TNC_SELF_TELEMETRY_PATH, tel_path);
|
||||
}
|
||||
tel_path = preferences.getString(PREF_TNC_SELF_TELEMETRY_PATH);
|
||||
|
||||
if (!preferences.getBool(PREF_APRS_LATITUDE_PRESET_INIT)){
|
||||
preferences.putBool(PREF_APRS_LATITUDE_PRESET_INIT, true);
|
||||
preferences.putString(PREF_APRS_LATITUDE_PRESET, LATIDUDE_PRESET);
|
||||
|
@ -625,7 +873,6 @@ void setup(){
|
|||
}
|
||||
fixed_beacon_enabled = preferences.getBool(PREF_APRS_FIXED_BEACON_PRESET);
|
||||
|
||||
|
||||
if (!preferences.getBool(PREF_APRS_FIXED_BEACON_INTERVAL_PRESET_INIT)){
|
||||
preferences.putBool(PREF_APRS_FIXED_BEACON_INTERVAL_PRESET_INIT, true);
|
||||
preferences.putInt(PREF_APRS_FIXED_BEACON_INTERVAL_PRESET, fix_beacon_interval/1000);
|
||||
|
@ -722,8 +969,10 @@ void setup(){
|
|||
}
|
||||
|
||||
pinMode(TXLED, OUTPUT);
|
||||
#ifdef T_BEAM_V1_0
|
||||
#ifdef T_BEAM_V1_2
|
||||
pinMode(BUTTON, INPUT);
|
||||
#elif T_BEAM_V1_0
|
||||
pinMode(BUTTON, INPUT);
|
||||
#elif T_BEAM_V0_7
|
||||
pinMode(BUTTON, INPUT);
|
||||
#else
|
||||
|
@ -733,24 +982,44 @@ void setup(){
|
|||
|
||||
Wire.begin(I2C_SDA, I2C_SCL);
|
||||
|
||||
#ifdef T_BEAM_V1_0
|
||||
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) {
|
||||
#ifdef T_BEAM_V1_2
|
||||
if (! PMU.begin(Wire, AXP2101_SLAVE_ADDRESS, I2C_SDA, I2C_SCL)) {
|
||||
}
|
||||
axp.setLowTemp(0xFF); //SP6VWX Set low charging temperature
|
||||
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); // LoRa
|
||||
//axp.setLowTemp(0xFF); //SP6VWX Set low charging temperature need to convert
|
||||
PMU.setALDO2Voltage(3300);
|
||||
PMU.enableALDO2(); // LoRa
|
||||
if (gps_state){
|
||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // switch on GPS
|
||||
PMU.enableALDO3(); // switch on GPS
|
||||
} else {
|
||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF); // switch off GPS
|
||||
PMU.disableALDO3(); // switch off GPS
|
||||
}
|
||||
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
|
||||
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
|
||||
axp.setDCDC1Voltage(3300);
|
||||
PMU.enableDC2();
|
||||
//axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON); NC
|
||||
PMU.setDC1Voltage(3300);
|
||||
// Enable ADC to measure battery current, USB voltage etc.
|
||||
axp.adc1Enable(0xfe, true);
|
||||
axp.adc2Enable(0x80, true);
|
||||
axp.setChgLEDMode(AXP20X_LED_OFF);
|
||||
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON); // oled do not turn off
|
||||
//axp.adc1Enable(0xfe, true);
|
||||
//axp.adc2Enable(0x80, true);
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
PMU.enableDC1(); // oled do not turn off
|
||||
#elif T_BEAM_V1_0
|
||||
if (!PMU.begin(Wire, AXP192_SLAVE_ADDRESS, I2C_SDA, I2C_SCL)) {
|
||||
}
|
||||
//axp.setLowTemp(0xFF); //SP6VWX Set low charging temperature need to convert
|
||||
PMU.setLDO2Voltage(3300);
|
||||
PMU.enableLDO2(); // LoRa
|
||||
if (gps_state){
|
||||
PMU.enableLDO3(); // switch on GPS
|
||||
} else {
|
||||
PMU.disableLDO3(); // switch off GPS
|
||||
}
|
||||
PMU.enableDC2();
|
||||
//axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON); NC
|
||||
PMU.setDC1Voltage(3300);
|
||||
// Enable ADC to measure battery current, USB voltage etc.
|
||||
//axp.adc1Enable(0xfe, true);
|
||||
//axp.adc2Enable(0x80, true);
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
PMU.enableDC1(); // oled do not turn off
|
||||
#endif
|
||||
|
||||
if(!display.begin(SSD1306_SWITCHCAPVCC, SSD1306_ADDRESS)) {
|
||||
|
@ -806,10 +1075,24 @@ void setup(){
|
|||
batt_read();
|
||||
writedisplaytext("LoRa-APRS","","Init:","ADC OK!","BAT: "+String(BattVolts,2),"");
|
||||
|
||||
if(lora_speed==1200)
|
||||
if(lora_speed==1200){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr47Sf512);
|
||||
else
|
||||
}
|
||||
else if(lora_speed==610){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr48Sf1024);
|
||||
}
|
||||
else if(lora_speed==180){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr48Sf4096);
|
||||
}
|
||||
else if(lora_speed==210){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr47Sf4096);
|
||||
}
|
||||
else if(lora_speed==240){
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr46Sf4096);
|
||||
}
|
||||
else {
|
||||
rf95.setModemConfig(BG_RF95::Bw125Cr45Sf4096);
|
||||
}
|
||||
|
||||
Serial.printf("LoRa Speed:\t%d\n", lora_speed);
|
||||
|
||||
|
@ -882,6 +1165,17 @@ void loop() {
|
|||
}
|
||||
}
|
||||
|
||||
// Show informations on WiFi Status
|
||||
if (apConnected) {
|
||||
enableOled(); // turn ON OLED temporary
|
||||
writedisplaytext(" ((WiFi))","WiFi Client Mode","SSID: " + infoApName, "Pass: ********", "IP: " + infoApAddr, getSatAndBatInfo());
|
||||
apConnected=false;
|
||||
} else if (apEnabled) {
|
||||
enableOled(); // turn ON OLED temporary
|
||||
writedisplaytext(" ((WiFi))","WiFi AP Mode","SSID: " + infoApName, "Pass: " + infoApPass, "IP: " + infoApAddr, getSatAndBatInfo());
|
||||
apEnabled=false;
|
||||
}
|
||||
|
||||
if (manBeacon) {
|
||||
// Manually sending beacon from html page
|
||||
enableOled();
|
||||
|
@ -910,8 +1204,10 @@ void loop() {
|
|||
t_lock = true;
|
||||
if(gps_state){
|
||||
gps_state = false;
|
||||
#ifdef T_BEAM_V1_0
|
||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF); // GPS OFF
|
||||
#ifdef T_BEAM_V1_2
|
||||
PMU.disableALDO3(); //GPS OFF
|
||||
#elif T_BEAM_V1_0
|
||||
PMU.disableLDO3(); // GPS OFF
|
||||
#endif
|
||||
writedisplaytext("((GPSOFF))","","","","","");
|
||||
next_fixed_beacon = millis() + fix_beacon_interval;
|
||||
|
@ -920,8 +1216,10 @@ void loop() {
|
|||
#endif
|
||||
}else{
|
||||
gps_state = true;
|
||||
#ifdef T_BEAM_V1_0
|
||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON);
|
||||
#ifdef T_BEAM_v1_2
|
||||
PMU.enableALDO3(); // GPS ON
|
||||
#elif T_BEAM_V1_0
|
||||
PMU.enableLDO3();
|
||||
#endif
|
||||
writedisplaytext("((GPS ON))","","","","",""); // GPS ON
|
||||
#ifdef ENABLE_PREFERENCES
|
||||
|
@ -944,7 +1242,7 @@ void loop() {
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef T_BEAM_V1_0
|
||||
#ifdef T_BEAM_V1_2
|
||||
if(shutdown_active){
|
||||
if(InpVolts> 4){
|
||||
shutdown_usb_status_bef = true;
|
||||
|
@ -959,7 +1257,28 @@ void loop() {
|
|||
|
||||
if(shutdown_countdown_timer_enable){
|
||||
if(millis() >= shutdown_countdown_timer){
|
||||
axp.shutdown();
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
PMU.shutdown();
|
||||
}
|
||||
}
|
||||
}
|
||||
#elif T_BEAM_V1_0
|
||||
if(shutdown_active){
|
||||
if(InpVolts> 4){
|
||||
shutdown_usb_status_bef = true;
|
||||
shutdown_countdown_timer_enable = false;
|
||||
}
|
||||
|
||||
if(InpVolts < 4 && shutdown_usb_status_bef == true){
|
||||
shutdown_usb_status_bef = false;
|
||||
shutdown_countdown_timer_enable = true;
|
||||
shutdown_countdown_timer = millis() + shutdown_delay_time;
|
||||
}
|
||||
|
||||
if(shutdown_countdown_timer_enable){
|
||||
if(millis() >= shutdown_countdown_timer){
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
PMU.shutdown();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -979,9 +1298,13 @@ void loop() {
|
|||
#endif
|
||||
|
||||
if (rf95.waitAvailableTimeout(100)) {
|
||||
#ifdef T_BEAM_V1_0
|
||||
#ifdef T_BEAM_V1_2
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
axp.setChgLEDMode(AXP20X_LED_LOW_LEVEL);
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_ON);
|
||||
#endif
|
||||
#elif T_BEAM_V1_0
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_ON);
|
||||
#endif
|
||||
#endif
|
||||
#ifdef BUZZER
|
||||
|
@ -1008,9 +1331,13 @@ void loop() {
|
|||
syslog_log(LOG_INFO, String("Received LoRa: '") + loraReceivedFrameString + "', RSSI:" + rf95.lastRssi() + ", SNR: " + rf95.lastSNR());
|
||||
}
|
||||
#endif
|
||||
#ifdef T_BEAM_V1_0
|
||||
#ifdef T_BEAM_V1_2
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
axp.setChgLEDMode(AXP20X_LED_OFF);
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
#endif
|
||||
#elif T_BEAM_V1_0
|
||||
#ifdef ENABLE_LED_SIGNALING
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
@ -1081,7 +1408,8 @@ void loop() {
|
|||
}
|
||||
#if defined(ENABLE_TNC_SELF_TELEMETRY) && defined(KISS_PROTOCOL)
|
||||
if (nextTelemetryFrame < millis()){
|
||||
nextTelemetryFrame = millis() + TNC_SELF_TELEMETRY_INTERVAL;
|
||||
// Schedule the next telemetry frame
|
||||
nextTelemetryFrame = millis() + (tel_interval * 1000);
|
||||
sendTelemetryFrame();
|
||||
}
|
||||
#endif
|
||||
|
@ -1091,20 +1419,28 @@ void loop() {
|
|||
if (millis() - last_debug_send_time > 1000*5) {
|
||||
last_debug_send_time = millis();
|
||||
String debug_message = "";
|
||||
#ifdef T_BEAM_V1_0
|
||||
debug_message += "Bat V: " + String(axp.getBattVoltage());
|
||||
#ifdef T_BEAM_V1_2
|
||||
debug_message += "Bat V: " + String(PMU.getBattVoltage());
|
||||
debug_message += ", ";
|
||||
debug_message += "Bat IN A: " + String(axp.getBattChargeCurrent());
|
||||
debug_message += "USB Plugged: " + String(PMU.isVbusInsertOnSource());
|
||||
debug_message += ", ";
|
||||
debug_message += "Bat OUT A: " + String(axp.getBattDischargeCurrent());
|
||||
debug_message += "USB V: " + String(PMU.getVbusVoltage());
|
||||
debug_message += ", ";
|
||||
debug_message += "USB Plugged: " + String(axp.isVBUSPlug());
|
||||
debug_message += "Temp C: " + String(PMU.getTemperature());
|
||||
#elif T_BEAM_V1_0
|
||||
debug_message += "Bat V: " + String(PMU.getBattVoltage());
|
||||
debug_message += ", ";
|
||||
debug_message += "USB V: " + String(axp.getVbusVoltage());
|
||||
debug_message += "Bat IN A: " + String(PMU.getBatteryChargeCurrent());
|
||||
debug_message += ", ";
|
||||
debug_message += "USB A: " + String(axp.getVbusCurrent());
|
||||
debug_message += "Bat OUT A: " + String(PMU.getBattDischargeCurrent());
|
||||
debug_message += ", ";
|
||||
debug_message += "Temp C: " + String(axp.getTemp());
|
||||
debug_message += "USB Plugged: " + String(PMU.isVBUSin());
|
||||
debug_message += ", ";
|
||||
debug_message += "USB V: " + String(PMU.getVbusVoltage());
|
||||
debug_message += ", ";
|
||||
debug_message += "USB A: " + String(PMU.getVbusCurrent());
|
||||
debug_message += ", ";
|
||||
debug_message += "Temp C: " + String(PMU.getTemperature());
|
||||
#else
|
||||
debug_message += "Bat V: " + String(BattVolts);
|
||||
#endif
|
||||
|
|
|
@ -12,7 +12,9 @@ SFE_UBLOX_GPS myGPS;
|
|||
#endif
|
||||
|
||||
// Pins for GPS
|
||||
#ifdef T_BEAM_V1_0
|
||||
#ifdef T_BEAM_V1_2
|
||||
static const int RXPin = 12, TXPin = 34;
|
||||
#elif T_BEAM_V1_0
|
||||
static const int RXPin = 12, TXPin = 34;
|
||||
#else
|
||||
static const int RXPin = 15, TXPin = 12;
|
||||
|
@ -45,7 +47,9 @@ bool gpsInitialized = false;
|
|||
|
||||
String gpsDataBuffer = " ";
|
||||
for (;;) {
|
||||
#ifdef ENABLE_WIFI
|
||||
check_for_new_clients(&gpsServer, gps_clients, MAX_GPS_WIFI_CLIENTS);
|
||||
#endif
|
||||
while (gpsSerial.available() > 0) {
|
||||
char gpsChar = (char)gpsSerial.read();
|
||||
gps.encode(gpsChar);
|
||||
|
|
|
@ -19,12 +19,21 @@ extern const char web_js_js_end[] asm("_binary_data_embed_js_js_out_end");
|
|||
// Variable needed to send beacon from html page
|
||||
extern bool manBeacon;
|
||||
|
||||
// Variable to show AP status
|
||||
extern bool apEnabled;
|
||||
extern bool apConnected;
|
||||
extern String infoApName;
|
||||
extern String infoApPass;
|
||||
extern String infoApAddr;
|
||||
|
||||
QueueHandle_t webListReceivedQueue = nullptr;
|
||||
std::list <tReceivedPacketData*> receivedPackets;
|
||||
const int MAX_RECEIVED_LIST_SIZE = 50;
|
||||
|
||||
String apSSID = "";
|
||||
String apPassword = "xxxxxxxxxx";
|
||||
String apPassword;
|
||||
String defApPassword = "xxxxxxxxxx";
|
||||
|
||||
WebServer server(80);
|
||||
#ifdef KISS_PROTOCOL
|
||||
WiFiServer tncServer(NETWORK_TNC_PORT);
|
||||
|
@ -39,9 +48,12 @@ WiFiServer gpsServer(NETWORK_GPS_PORT);
|
|||
Syslog syslog(udpClient, SYSLOG_PROTO_IETF);
|
||||
#endif
|
||||
|
||||
#ifdef T_BEAM_V1_0
|
||||
#include <axp20x.h>
|
||||
extern AXP20X_Class axp;
|
||||
#ifdef T_BEAM_V1_2
|
||||
#include <XPowersLib.h>
|
||||
extern XPowersAXP2101 PMU;
|
||||
#elif T_BEAM_V1_0
|
||||
#include <XPowersLib.h>
|
||||
extern XPowersAXP192 PMU;
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -112,16 +124,38 @@ void handle_ScanWifi() {
|
|||
}
|
||||
|
||||
void handle_SaveWifiCfg() {
|
||||
if (!server.hasArg(PREF_WIFI_SSID) || !server.hasArg(PREF_WIFI_PASSWORD)){
|
||||
server.send(500, "text/plain", "Invalid request");
|
||||
if (!server.hasArg(PREF_WIFI_SSID) || !server.hasArg(PREF_WIFI_PASSWORD) || !server.hasArg(PREF_AP_PASSWORD)){
|
||||
server.send(500, "text/plain", "Invalid request, make sure all fields are set");
|
||||
}
|
||||
|
||||
if (!server.arg(PREF_WIFI_SSID).length()){
|
||||
server.send(403, "text/plain", "Empty SSID or Password");
|
||||
server.send(403, "text/plain", "Empty SSID");
|
||||
} else {
|
||||
// Update SSID
|
||||
preferences.putString(PREF_WIFI_SSID, server.arg(PREF_WIFI_SSID));
|
||||
Serial.println("Updated SSID: " + server.arg(PREF_WIFI_SSID));
|
||||
}
|
||||
|
||||
preferences.putString(PREF_WIFI_SSID, server.arg(PREF_WIFI_SSID));
|
||||
preferences.putString(PREF_WIFI_PASSWORD, server.arg(PREF_WIFI_PASSWORD));
|
||||
if (server.arg(PREF_WIFI_PASSWORD)!="*" && server.arg(PREF_WIFI_PASSWORD).length()>0 && server.arg(PREF_WIFI_PASSWORD).length()<8){
|
||||
server.send(403, "text/plain", "WiFi Password must be minimum 8 character");
|
||||
} else {
|
||||
if (server.arg(PREF_WIFI_PASSWORD)!="*") {
|
||||
// Update WiFi password
|
||||
preferences.putString(PREF_WIFI_PASSWORD, server.arg(PREF_WIFI_PASSWORD));
|
||||
Serial.println("Updated WiFi PASS: " + server.arg(PREF_WIFI_PASSWORD));
|
||||
}
|
||||
}
|
||||
|
||||
if (server.arg(PREF_AP_PASSWORD)!="*" && server.arg(PREF_AP_PASSWORD).length()<8){
|
||||
server.send(403, "text/plain", "AP Password must be minimum 8 character");
|
||||
} else {
|
||||
if (server.arg(PREF_AP_PASSWORD)!="*") {
|
||||
// Update AP password
|
||||
preferences.putString(PREF_AP_PASSWORD, server.arg(PREF_AP_PASSWORD));
|
||||
Serial.println("Updated AP PASS: " + server.arg(PREF_AP_PASSWORD));
|
||||
}
|
||||
}
|
||||
|
||||
server.sendHeader("Location", "/");
|
||||
server.send(302,"text/html", "");
|
||||
}
|
||||
|
@ -140,9 +174,14 @@ void handle_Beacon() {
|
|||
}
|
||||
|
||||
void handle_Shutdown() {
|
||||
#ifdef T_BEAM_V1_0
|
||||
#ifdef T_BEAM_V1_2
|
||||
server.send(200,"text/html", "Shutdown");
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
PMU.shutdown();
|
||||
#elif T_BEAM_V1_0
|
||||
server.send(200,"text/html", "Shutdown");
|
||||
axp.shutdown();
|
||||
PMU.setChargingLedMode(XPOWERS_CHG_LED_OFF);
|
||||
PMU.shutdown();
|
||||
#else
|
||||
server.send(404,"text/html", "Not supported");
|
||||
#endif
|
||||
|
@ -159,6 +198,7 @@ void handle_Restore() {
|
|||
void handle_Cfg() {
|
||||
String jsonData = "{";
|
||||
jsonData += String("\"") + PREF_WIFI_PASSWORD + "\": \"" + jsonEscape((preferences.getString(PREF_WIFI_PASSWORD).isEmpty() ? String("") : "*")) + R"(",)";
|
||||
jsonData += String("\"") + PREF_AP_PASSWORD + "\": \"" + jsonEscape((preferences.getString(PREF_AP_PASSWORD).isEmpty() ? String("") : "*")) + R"(",)";
|
||||
jsonData += jsonLineFromPreferenceString(PREF_WIFI_SSID);
|
||||
jsonData += jsonLineFromPreferenceDouble(PREF_LORA_FREQ_PRESET);
|
||||
jsonData += jsonLineFromPreferenceInt(PREF_LORA_SPEED_PRESET);
|
||||
|
@ -179,6 +219,10 @@ void handle_Cfg() {
|
|||
jsonData += jsonLineFromPreferenceBool(PREF_APRS_FIXED_BEACON_PRESET);
|
||||
jsonData += jsonLineFromPreferenceBool(PREF_APRS_SHOW_ALTITUDE);
|
||||
jsonData += jsonLineFromPreferenceBool(PREF_APRS_GPS_EN);
|
||||
jsonData += jsonLineFromPreferenceBool(PREF_ENABLE_TNC_SELF_TELEMETRY);
|
||||
jsonData += jsonLineFromPreferenceInt(PREF_TNC_SELF_TELEMETRY_INTERVAL);
|
||||
jsonData += jsonLineFromPreferenceInt(PREF_TNC_SELF_TELEMETRY_MIC);
|
||||
jsonData += jsonLineFromPreferenceString(PREF_TNC_SELF_TELEMETRY_PATH);
|
||||
jsonData += jsonLineFromPreferenceBool(PREF_DEV_OL_EN);
|
||||
jsonData += jsonLineFromPreferenceBool(PREF_APRS_SHOW_CMT);
|
||||
jsonData += jsonLineFromPreferenceBool(PREF_DEV_BT_EN);
|
||||
|
@ -198,6 +242,7 @@ void handle_Cfg() {
|
|||
|
||||
void handle_ReceivedList() {
|
||||
PSRAMJsonDocument doc(MAX_RECEIVED_LIST_SIZE * 1000);
|
||||
//DynamicJsonDocument doc(MAX_RECEIVED_LIST_SIZE * 500);
|
||||
JsonObject root = doc.to<JsonObject>();
|
||||
auto received = root.createNestedArray("received");
|
||||
for (auto element: receivedPackets){
|
||||
|
@ -244,6 +289,15 @@ void handle_SaveAPRSCfg() {
|
|||
if (server.hasArg(PREF_APRS_LONGITUDE_PRESET)){
|
||||
preferences.putString(PREF_APRS_LONGITUDE_PRESET, server.arg(PREF_APRS_LONGITUDE_PRESET));
|
||||
}
|
||||
if (server.hasArg(PREF_TNC_SELF_TELEMETRY_INTERVAL)){
|
||||
preferences.putInt(PREF_TNC_SELF_TELEMETRY_INTERVAL, server.arg(PREF_TNC_SELF_TELEMETRY_INTERVAL).toInt());
|
||||
}
|
||||
if (server.hasArg(PREF_TNC_SELF_TELEMETRY_MIC)){
|
||||
preferences.putInt(PREF_TNC_SELF_TELEMETRY_MIC, server.arg(PREF_TNC_SELF_TELEMETRY_MIC).toInt());
|
||||
}
|
||||
if (server.hasArg(PREF_TNC_SELF_TELEMETRY_PATH)){
|
||||
preferences.putString(PREF_TNC_SELF_TELEMETRY_PATH, server.arg(PREF_TNC_SELF_TELEMETRY_PATH));
|
||||
}
|
||||
|
||||
// Smart Beaconing settings
|
||||
if (server.hasArg(PREF_APRS_FIXED_BEACON_INTERVAL_PRESET)){
|
||||
|
@ -264,8 +318,10 @@ void handle_SaveAPRSCfg() {
|
|||
if (server.hasArg(PREF_APRS_SB_ANGLE_PRESET)){
|
||||
preferences.putDouble(PREF_APRS_SB_ANGLE_PRESET, server.arg(PREF_APRS_SB_ANGLE_PRESET).toDouble());
|
||||
}
|
||||
|
||||
|
||||
preferences.putBool(PREF_APRS_SHOW_BATTERY, server.hasArg(PREF_APRS_SHOW_BATTERY));
|
||||
preferences.putBool(PREF_ENABLE_TNC_SELF_TELEMETRY, server.hasArg(PREF_ENABLE_TNC_SELF_TELEMETRY));
|
||||
preferences.putBool(PREF_APRS_SHOW_ALTITUDE, server.hasArg(PREF_APRS_SHOW_ALTITUDE));
|
||||
preferences.putBool(PREF_APRS_FIXED_BEACON_PRESET, server.hasArg(PREF_APRS_FIXED_BEACON_PRESET));
|
||||
preferences.putBool(PREF_APRS_GPS_EN, server.hasArg(PREF_APRS_GPS_EN));
|
||||
|
@ -346,12 +402,21 @@ void handle_saveDeviceCfg(){
|
|||
|
||||
String wifi_password = preferences.getString(PREF_WIFI_PASSWORD);
|
||||
String wifi_ssid = preferences.getString(PREF_WIFI_SSID);
|
||||
if (preferences.getString(PREF_AP_PASSWORD).length() > 8) {
|
||||
// 8 characters is requirements for WPA2
|
||||
apPassword = preferences.getString(PREF_AP_PASSWORD);
|
||||
} else {
|
||||
apPassword = defApPassword;
|
||||
}
|
||||
if (!wifi_ssid.length()){
|
||||
WiFi.softAP(apSSID.c_str(), apPassword.c_str());
|
||||
} else {
|
||||
int retryWifi = 0;
|
||||
WiFi.begin(wifi_ssid.c_str(), wifi_password.length() ? wifi_password.c_str() : nullptr);
|
||||
Serial.println("Connecting to " + wifi_ssid);
|
||||
// Set power to minimum (max 20)
|
||||
// https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/network/esp_wifi.html
|
||||
esp_wifi_set_max_tx_power(8);
|
||||
while (WiFi.status() != WL_CONNECTED) {
|
||||
Serial.print("Not connected: ");
|
||||
Serial.println((int)WiFi.status());
|
||||
|
@ -361,15 +426,37 @@ void handle_saveDeviceCfg(){
|
|||
retryWifi += 1;
|
||||
if (retryWifi > 60) {
|
||||
WiFi.softAP(apSSID.c_str(), apPassword.c_str());
|
||||
//WiFi.softAP(apSSID.c_str(), "password");
|
||||
Serial.println("Unable to connect to to wifi. Starting AP");
|
||||
Serial.print("SSID: ");
|
||||
Serial.print(apSSID.c_str());
|
||||
Serial.print(" Password: ");
|
||||
Serial.println(apPassword.c_str());
|
||||
// Set power to minimum (max 20)
|
||||
esp_wifi_set_max_tx_power(8);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (WiFi.getMode() == wifi_mode_t::WIFI_MODE_AP){
|
||||
//Serial.print("WiFi Mode: ");
|
||||
//Serial.println(WiFi.getMode());
|
||||
if (WiFi.getMode() == 3){
|
||||
Serial.println("Running AP. IP: " + WiFi.softAPIP().toString());
|
||||
} else {
|
||||
apEnabled=true;
|
||||
infoApName = apSSID.c_str();
|
||||
infoApPass = apSSID.c_str();
|
||||
infoApAddr = WiFi.softAPIP().toString();
|
||||
} else if (WiFi.getMode() == 1) {
|
||||
// Save some battery
|
||||
//WiFi.setSleep(true);
|
||||
esp_wifi_set_ps(WIFI_PS_MAX_MODEM);
|
||||
Serial.println("Connected. IP: " + WiFi.localIP().toString());
|
||||
apConnected=true;
|
||||
infoApName = wifi_ssid.c_str();
|
||||
infoApPass = wifi_password.c_str();
|
||||
infoApAddr = WiFi.localIP().toString();
|
||||
} else {
|
||||
Serial.println("WiFi Mode: " + WiFi.getMode());
|
||||
}
|
||||
|
||||
#ifdef ENABLE_SYSLOG
|
||||
|
@ -432,4 +519,4 @@ void handle_saveDeviceCfg(){
|
|||
|
||||
vTaskDelay(5/portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
FILENAME_BUILDNO = '.pio/versioning'
|
||||
FILENAME_VERSION_H = 'include/version.h'
|
||||
version = 'v0.3.'
|
||||
version = 'v0.4.'
|
||||
|
||||
import datetime
|
||||
from subprocess import *
|
||||
|
|
Ładowanie…
Reference in New Issue