Porównaj commity

...

6 Commity

Autor SHA1 Wiadomość Data
Thomas Osterried d25692b209 Fixes and improvements: preamble, gps powersaving mode, LH, ..
- web:
  - preamble: A bit more detailed description, with suggestion to try
    value 12 (default is 8)
    Assurance in taskWebserver that value is >= 8.
  - sb_angle: min is 5 but text said Range 0 to 360.
  - GPS: new "GPS powersaving mode".
    Still testing. "Made GPS may sleep when running on battery" default.

- GPS powersaving mode:
  If you have problems, set it to "Ignore this feature".
  While looking at the power consumption, GPS has a quite high power
  consumption.
  If we have no fix for 10min, we go to sleep mode. Interval
  Sleep  1min, 2min, 4min, 8min, 1min, 2min, ..
  Awake  120, next: 60s, next: 40, next: 30s
  After 4 rounds, we run GPS 10min again (better chance to refresh the
  almanach).
  During sleep, taskGPS is suspended and gps chip is powered off.
  -> This algorithm saves reduces the power consumption of the GPS chip to
     ~30%.
  If it behaves good, more fine-tuning can be done (i.E. switching it earlier
  off if you don't move. Reduce the initial fix-loss-time of 10min, ..)
  LCD shows "GPS: sleep" when GPS is in power saving mode. If it awakes
  and has no fix, it shows (as usual) GPS: age nnn".

- preamble changes:
  - TX setting:
    Now only affects main qrg. Perhaps it's wiser to be able to set it
    in more detail: Main, Secondary, Both. Or with different values
    for the different frequencies.
  - RX setting:
    moved to loraSend(), where default rx values are reset after TX

- LCD:
  - "GPS: sleep" as described above
  - Tried to improve the readibility of the LastHeard lines. Need to verify

Signed-off-by: Thomas Osterried <dl9sau@darc.de>
2024-04-24 13:36:39 +02:00
Thomas Osterried 769896ae3f
Merge pull request #12 from piotr022/master
Preamble length settings, added ability to rx packets with longer preambles

Signed-off-by: Thomas Osterried dl9sau@darc.de
2024-04-23 14:56:29 +02:00
Piotr Lewandowski 3c645ca232 added preamble conf placeholder with def val, changed def to 8 symbols 2024-04-21 13:25:52 +02:00
Piotr Lewandowski bfa18ff5eb updated-description 2024-04-20 14:17:51 +02:00
Piotr Lewandowski 307aeb0c80 preambleLen added in preferences.cfg 2024-04-20 14:13:32 +02:00
Piotr Lewandowski 88c7994e47 tx preamle len settings, extended rx timeout 2024-04-20 13:15:02 +02:00
6 zmienionych plików z 237 dodań i 93 usunięć

Wyświetl plik

@ -14,6 +14,7 @@
"lora_rx_en": true,
"lora_tx_en": true,
"txPower": 23,
"preambleLen": 8,
"lora_cradapt": false,
"lora_rssi2p": 34,
"snraprsis": true,

Wyświetl plik

@ -154,6 +154,10 @@ You like to enable, if you use your tracker portable and it should automatically
<label for="txPower">TX power [dBm]</label>
<input name="txPower" id="txPower" type="number" min="0" max="23" title="LoRa TX Power. Range 0 to 23dBm">
</div>
<div>
<label for="preambleLen">TX preamble length [symbols]</label>
<input name="preambleLen" id="preambleLen" type="number" min="8" max="4096" title="A larger preamble size improves packet detection but increases transmission time. Range 8 to 4096 symbols. 8 is default. Please experiment with 12. This setting only affects transmission on Main frequency." placeholder="8">
</div>
<div>
<label for="lora_cradapt">Automatic CodeRate adaption on TX</label>
<input name="lora_cradapt" id="lora_cradapt" type="checkbox" value="1" title="Enable automatic CR adaption. Has only influence on TX (RX can decode every CR). Use this only if you are not a WIDE1 or WIDE2 digi (here you like to send always with higher speed). Still testing, if it behaves good to our network. Currently works only for SF12 modes, because for SF 10 and lower the code for programming CR+SF+BW-combination has not been written yet">
@ -372,7 +376,7 @@ III: Values above are referring to latitude; distance between two latitudes is a
<div class="grid-container thirds">
<div>
<label for="sb_angle">Course change [degrees]</label>
<input name="sb_angle" id="sb_angle" type="number" min="5" max="360" title="Angle of course change to speed up beacon transmission. Recommended value: 28. Range 0 to 360.">
<input name="sb_angle" id="sb_angle" type="number" min="5" max="360" title="Angle of course change to speed up beacon transmission. Recommended value: 28. Range 5 to 360.">
</div>
<div>
<label for="sb_turn_slope">Turn Slope [degrees]</label>
@ -388,6 +392,14 @@ III: Values above are referring to latitude; distance between two latitudes is a
<label for="gps_enabled">GPS enabled *</label>
<input name="gps_enabled" id="gps_enabled" type="checkbox" value="1" title="enable or disable GPS">
</div>
<div>
<label for="gps_pwrsve">GPS powersaving mode</label>
<select id="gps_pwrsve" name="gps_pwrsve" title="If there's no GPS fix, allow GPS to go to sleep (chip powered off; taskGPS will suspend). Chip awakes for 1 minute, looking for a fix; if no ifx, sleeps again. Sleep interval is: 1min, 2min, 4min, 8min, 1min, ... You can decide if it may always sleep, or only when you run on battery (default), or if GPS should always be on (according to GPS enabled setting).">
<option value="1">GPS may sleep when running on battery (default)</option>
<option value="2">GPS always may sleep</option>
<option value="0">Ignore this feature</option>
</select>
</div>
<div>
<label for="kiss_myloc_ok">Accept own positions via KISS</label>
<input name="kiss_myloc_ok" id="kiss_myloc_ok" type="checkbox" value="1" title="If set to true, we'll stop sending own position beacons if we heard a position from our call via kiss. Uncheck this, if you like to filter out those positions and keep sending it by this device.">

Wyświetl plik

@ -37,6 +37,8 @@ static const char *const PREF_LORA_TX_ENABLE_INIT = "lora_tx_en_i";
static const char *const PREF_LORA_TX_ENABLE = "lora_tx_en";
static const char *const PREF_LORA_TX_POWER_INIT = "txPower_i";
static const char *const PREF_LORA_TX_POWER = "txPower";
static const char *const PREF_LORA_TX_PREAMBLE_LEN_INIT = "preambleLen_i";
static const char *const PREF_LORA_TX_PREAMBLE_LEN = "preambleLen";
static const char *const PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET_INIT = "lora_rssi2p_i";
static const char *const PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET = "lora_rssi2p";
static const char *const PREF_LORA_ADD_SNR_RSSI_TO_PATH_END_AT_KISS_PRESET_INIT = "snraprsis_i";
@ -134,6 +136,8 @@ static const char *const PREF_APRS_SB_TURN_TIME_PRESET_INIT = "sb_turn_time_i";
// Device settings
static const char *const PREF_APRS_GPS_EN = "gps_enabled";
static const char *const PREF_APRS_GPS_EN_INIT = "gps_state_init";
static const char *const PREF_GPS_POWERSAVE = "gps_pwrsve";
static const char *const PREF_GPS_POWERSAVE_INIT = "gps_pwrsve_i";
static const char *const PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS = "kiss_myloc_ok";
static const char *const PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS_INIT = "kiss_myloc_ok_i";
static const char *const PREF_GPS_ALLOW_SLEEP_WHILE_KISS = "gps_sleep_ok";

Wyświetl plik

@ -204,6 +204,12 @@ String aprsPresetShown = "P";
#else
boolean gps_state = false;
#endif
TaskHandle_t xHandle_GPS; // needed for being able to suspend/resume task when GPS sleeps
volatile boolean gps_task_enabled = false;
uint8_t gps_may_sleep = 1; // gps may go to sleep: 1 only if we are battery powered. 2 always
uint32_t t_gps_powersave_operation_until_fix = 0L;
uint32_t t_gps_fix_lost = 1L;
// as we now collect the gps_data at the beginning of loop(), also the speed ist from there, we should not query gps.speed.kmph() directly later on
// the same show be done with course and alti (later)
// after successful data retrieval, gps_isValid becomes true (or turn false, if retrieval fails)
@ -449,6 +455,10 @@ boolean lora_tx_enabled = true;
#endif
#endif
uint16_t preambleLen = 8; // default tx preamble len
constexpr uint16_t preambleLen_default = 8; // default tx preamble len
constexpr uint16_t rxTimeoutSymbols = 1024; // extended rx timout to avoid rejecting packets with long preamble
#define UNITS_SPEED_KMH 1
#define UNITS_SPEED_MS 2
#define UNITS_SPEED_MPH 4
@ -1208,6 +1218,7 @@ void loraSend(byte lora_LTXPower, float lora_FREQ, ulong lora_SPEED, uint8_t fla
lora_set_speed(lora_SPEED);
rf95.setFrequency(lora_FREQ);
rf95.setTxPower(lora_LTXPower);
rf95.setPreambleLength(lora_FREQ == lora_freq ? preambleLen : preambleLen_default);
#ifdef ENABLE_LED_SIGNALING
digitalWrite(TXLED, LOW);
@ -1229,6 +1240,8 @@ void loraSend(byte lora_LTXPower, float lora_FREQ, ulong lora_SPEED, uint8_t fla
// With no buffer / length called, recvAPRS directly calls clearRxBuf()
rf95.recvAPRS(0, 0);
}
// setting rx TO, default to allow rx of long preamble packets
rf95.setPreambleLength(rxTimeoutSymbols);
#ifdef ENABLE_LED_SIGNALING
digitalWrite(TXLED, HIGH);
@ -1925,7 +1938,9 @@ void displayInvalidGPS() {
if (gps_state) {
//show GPS age (only if last retrieval was invalid)
gpsage = gps.location.age()/1000;
if (gpsage > 49700) {
if (!gps_task_enabled) {
gpsage_p = " GPS: sleep";
} else if (gpsage > 49700) {
gpsage_p = " GPS: no fix";
} else {
gpsage_p = " GPS age:" + compute_time_since_received(gpsage);
@ -3027,6 +3042,7 @@ void load_preferences_cfg_file()
lora_rx_enabled = jsonElementFromPreferenceCFGBool(PREF_LORA_RX_ENABLE,PREF_LORA_RX_ENABLE_INIT);
lora_tx_enabled = jsonElementFromPreferenceCFGBool(PREF_LORA_TX_ENABLE,PREF_LORA_TX_ENABLE_INIT);
txPower = jsonElementFromPreferenceCFGInt(PREF_LORA_TX_POWER,PREF_LORA_TX_POWER_INIT);
preambleLen = jsonElementFromPreferenceCFGInt(PREF_LORA_TX_PREAMBLE_LEN,PREF_LORA_TX_PREAMBLE_LEN_INIT);
lora_automatic_cr_adaption = jsonElementFromPreferenceCFGBool(PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET,PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET_INIT);
lora_add_snr_rssi_to_path = jsonElementFromPreferenceCFGInt(PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET,PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET_INIT);
kiss_add_snr_rssi_to_path_at_position_without_digippeated_flag = jsonElementFromPreferenceCFGBool(PREF_LORA_ADD_SNR_RSSI_TO_PATH_END_AT_KISS_PRESET,PREF_LORA_ADD_SNR_RSSI_TO_PATH_END_AT_KISS_PRESET_INIT);
@ -3050,6 +3066,7 @@ void load_preferences_cfg_file()
altitude_ratio = jsonElementFromPreferenceCFGInt(PREF_APRS_ALTITUDE_RATIO,PREF_APRS_ALTITUDE_RATIO);
always_send_cseSpd_AND_altitude = jsonElementFromPreferenceCFGBool(PREF_APRS_ALWAYS_SEND_CSE_SPEED_AND_ALTITUDE,PREF_APRS_ALWAYS_SEND_CSE_SPEED_AND_ALTITUDE_INIT);
gps_state = jsonElementFromPreferenceCFGBool(PREF_APRS_GPS_EN,PREF_APRS_GPS_EN_INIT);
gps_may_sleep = jsonElementFromPreferenceCFGBool(PREF_GPS_POWERSAVE,PREF_GPS_POWERSAVE_INIT);
acceptOwnPositionReportsViaKiss = jsonElementFromPreferenceCFGBool(PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS,PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS_INIT);
gps_allow_sleep_while_kiss = jsonElementFromPreferenceCFGBool(PREF_GPS_ALLOW_SLEEP_WHILE_KISS,PREF_GPS_ALLOW_SLEEP_WHILE_KISS_INIT);
showBattery = jsonElementFromPreferenceCFGBool(PREF_APRS_SHOW_BATTERY,PREF_APRS_SHOW_BATTERY_INIT);
@ -3196,6 +3213,12 @@ void load_preferences_from_flash()
}
txPower = lora_tx_enabled ? preferences.getInt(PREF_LORA_TX_POWER) : 0;
if (!preferences.getBool(PREF_LORA_TX_PREAMBLE_LEN_INIT)){
preferences.putBool(PREF_LORA_TX_PREAMBLE_LEN_INIT, true);
preferences.putInt(PREF_LORA_TX_PREAMBLE_LEN, preambleLen);
}
preambleLen = preferences.getInt(PREF_LORA_TX_PREAMBLE_LEN);
if (!preferences.getBool(PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET_INIT)){
preferences.putBool(PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET_INIT, true);
preferences.putBool(PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET, lora_automatic_cr_adaption);
@ -3331,6 +3354,12 @@ void load_preferences_from_flash()
}
gps_state = preferences.getBool(PREF_APRS_GPS_EN);
if (!preferences.getBool(PREF_GPS_POWERSAVE_INIT)){
preferences.putBool(PREF_GPS_POWERSAVE_INIT, true);
preferences.putInt(PREF_GPS_POWERSAVE, gps_may_sleep);
}
gps_may_sleep = preferences.getInt(PREF_GPS_POWERSAVE);
if (!preferences.getBool(PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS_INIT)){
preferences.putBool(PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS_INIT, true);
preferences.putBool(PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS, acceptOwnPositionReportsViaKiss);
@ -3693,16 +3722,27 @@ void setup_phase2_soft_reconfiguration(boolean runtime_reconfiguration) {
}
#endif
if (gps_state){
#ifdef T_BEAM_V1_0
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // switch on GPS
#elif T_BEAM_V1_2
axp.setButtonBatteryChargeVoltage(3300); // enable charge of the gps battery
axp.enableButtonBatteryCharge();
axp.setALDO3Voltage(3300);
axp.enableALDO3(); // switch on GPS
#endif
if (gps_state) {
if (xHandle_GPS) {
if (!gps_task_enabled) {
#ifdef T_BEAM_V1_0
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // switch on GPS
#elif T_BEAM_V1_2
axp.setButtonBatteryChargeVoltage(3300); // enable charge of the gps battery
axp.enableButtonBatteryCharge();
axp.setALDO3Voltage(3300);
axp.enableALDO3(); // switch on GPS
#endif
gps_task_enabled = true;
vTaskResume(xHandle_GPS);
}
t_gps_powersave_operation_until_fix = 0L;
}
} else {
gps_task_enabled = false;
t_gps_powersave_operation_until_fix = millis();
t_gps_fix_lost = millis();
gps_isValid = false;
#ifdef T_BEAM_V1_0
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF); // switch off GPS
#elif T_BEAM_V1_2
@ -3741,6 +3781,9 @@ void setup_phase2_soft_reconfiguration(boolean runtime_reconfiguration) {
// we tx on main and/or secondary frequency. For tx, loraSend is called (and always has desired txpower as argument)
rf95.setTxPower((lora_digipeating_mode < 2 || lora_cross_digipeating_mode < 1) ? txPower : txPower_cross_digi);
// setting rx TO, default to allow rx of long preamble packets
rf95.setPreambleLength(rxTimeoutSymbols);
Serial.printf("LoRa PWR: %d, LoRa PWR XDigi: %d, RX Enable: %d, TX Enable: %d\r\n", txPower, txPower_cross_digi, lora_rx_enabled, lora_tx_enabled);
// APRS fixed location and icon settings
@ -4063,7 +4106,7 @@ void setup()
// new process: GPS
if (gps_state) {
writedisplaytext(Tcall,"","Init:","Waiting for GPS","","");
xTaskCreate(taskGPS, "taskGPS", 5000, nullptr, 1, nullptr);
xTaskCreate(taskGPS, "taskGPS", 5000, nullptr, 1, &xHandle_GPS);
writedisplaytext(Tcall,"","Init:","GPS Task Created!","","");
}
@ -5636,8 +5679,9 @@ void fill_lh(const String &rxcall, const char *digipeatedflag, const char *p) {
}
void write_last_heard_calls_with_distance_and_course_to_display() {
String line[5];
char dist_and_course[9];
String lines[5];
//char dist_and_course[9];
char line[22]; // Display length 21 + \0
char course[3];
double courseTo;
double distTo;
@ -5669,21 +5713,26 @@ void write_last_heard_calls_with_distance_and_course_to_display() {
// space on display
// 012345678901234567890
// DB0ABC-10*10m 0001 SE
if (distTo < 1.0) {
sprintf(dist_and_course, " %4.2f %s", distTo, course);
} else if (distTo < 10.0) {
sprintf(dist_and_course, " %4.1f %s", distTo, course);
if (distTo < 10.0) {
//sprintf(dist_and_course, " %4.2f %-2s", distTo, course);
sprintf(line, "%-9s%c%3s %4.2f%2s", LH[i].callsign.c_str(), LH[i].direct ? ':' : '*', compute_time_since_received(millis()/1000.0L - LH[i].time_received).c_str(), distTo, course);
} else if (distTo < 100.0) {
//sprintf(dist_and_course, " %4.1f %-2s", distTo, course);
sprintf(line, "%-9s%c%3s %4.1f %2s", LH[i].callsign.c_str(), LH[i].direct ? ':' : '*', compute_time_since_received(millis()/1000.0L - LH[i].time_received).c_str(), distTo, course);
} else if (distTo < 999.49) {
sprintf(dist_and_course, " %03.0f %s", distTo, course);
//sprintf(dist_and_course, " %03.0f %-2s", distTo, course);
sprintf(line, "%-9s%c%3s %03.0f %2s", LH[i].callsign.c_str(), LH[i].direct ? ':' : '*', compute_time_since_received(millis()/1000.0L - LH[i].time_received).c_str(), distTo, course);
} else {
sprintf(dist_and_course, " >999 %s", course);
//sprintf(dist_and_course, " >999 %-2s", course);
sprintf(line, "%-9s%c%3s >999 %2s", LH[i].callsign.c_str(), LH[i].direct ? ':' : '*', compute_time_since_received(millis()/1000.0L - LH[i].time_received).c_str(), course);
}
line[i] = LH[i].callsign + (LH[i].direct ? ":" : "*") + compute_time_since_received(millis()/1000.0L - LH[i].time_received) + dist_and_course;
//lines[i] = LH[i].callsign + (LH[i].direct ? ":" : "*") + compute_time_since_received(millis()/1000.0L - LH[i].time_received) + dist_and_course;
lines[i] = String(line);
} else {
line[i] = "";
lines[i] = "";
}
}
writedisplaytext("((LH))",line[0],line[1],line[2],line[3],line[4]);
writedisplaytext("((LH))",lines[0],lines[1],lines[2],lines[3],lines[4]);
}
@ -5835,6 +5884,74 @@ void loop()
}
}
// time to wake up a sleeping GPS?
if (gps_state && gps_may_sleep && (gps_may_sleep > 1 ||
#ifdef T_BEAM_V1_0
!axp.isVBUSPlug()
#elif T_BEAM_V1_2
!axp.isVbusInsertOnSource()
#else
1
#endif
)) {
static uint32_t t_gps_powersave_operation_until_fix__next_action = 0L;
static uint8_t gps_wakeups = 0;
boolean do_suspend_gps = false;
boolean do_resume_gps = false;
if (t_gps_fix_lost > 0L) {
if (t_gps_powersave_operation_until_fix == 0L) {
if (millis() - t_gps_fix_lost > 10*60*1000L) {
t_gps_powersave_operation_until_fix = millis();
gps_wakeups = 0;
if (gps_task_enabled)
do_suspend_gps = true;
}
} else if (t_gps_powersave_operation_until_fix__next_action > 0L && millis() > t_gps_powersave_operation_until_fix__next_action) {
if (gps_task_enabled)
do_suspend_gps = true;
else
do_resume_gps = true;
}
if (do_suspend_gps && gps_task_enabled) {
gps_task_enabled = false; // vTaskSuspend() is done by taskGPS itself (he needs to delete the wdt timer)
#ifdef T_BEAM_V1_0
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF); // switch off GPS
#elif T_BEAM_V1_2
axp.disableALDO3(); // switch off GPS
#endif
gps_isValid = false;
// Sleep intervals 1min, 2min, 4min, 8min, 1min, 2min, ..
t_gps_powersave_operation_until_fix__next_action = millis() + (1 << (gps_wakeups % 4)) * 60*1000L;
} else if (do_resume_gps && !gps_task_enabled) {
if (xHandle_GPS) {
#ifdef T_BEAM_V1_0
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // switch on GPS
#elif T_BEAM_V1_2
axp.setALDO3Voltage(3300);
axp.enableALDO3(); // switch on GPS
#endif
gps_task_enabled = true;
vTaskResume(xHandle_GPS);
// Keep running first try: 120, next: 60s, next: 40, next: 30s
// No gps fix since 3 rounds? -> Give once (every 4 rounds) a higher grace time for getting a fix
gps_wakeups++;
t_gps_powersave_operation_until_fix__next_action = millis() + ((gps_wakeups % 12) ? (2*60*1000L / ((gps_wakeups % 4) + 1)) : 10*60*1000L);
}
}
} else {
if (t_gps_powersave_operation_until_fix > 0L) {
t_gps_powersave_operation_until_fix = 0L;
t_gps_powersave_operation_until_fix__next_action = 0L;
}
}
}
// Time to adjust time?
int8_t t_hour_adjust_next = -1;
if (gps_state && gps.time.isValid() && gps.time.isUpdated() &&
@ -5880,84 +5997,65 @@ void loop()
gps_isValid = true;
}
if (gps_isValid && gps.location.isUpdated()) {
if (gps_isValid && gps.location.isUpdated()) {
if (curr_hdop < bestHdop || millis() > t_interval_start + 5*60*1000L) {
// remember location with best hdop in this time range
bestRawLat = gps.location.rawLat();
bestRawLng = gps.location.rawLng();
bestDoubleLat = gps.location.lat();
bestDoubleLng = gps.location.lng();
bestHdop = curr_hdop;
}
uint32_t t_elapsed = millis() - t_interval_start;
//if (t_elapsed > 15000L && ((curr_hdop < 1.5 && curr_sats >= 5) || gps_isValid != gps_isValid_oldState || no_gps_position_since_boot)) {
if (t_elapsed > 15000L && ((curr_hdop < 1.5 && curr_sats >= 4) || gps_isValid != gps_isValid_oldState || no_gps_position_since_boot)) {
// Approach to avoid gps inaccuracy (we observed bad gps positions in a range of 30m, or more):
// Resolution of GPS is +/- 3 to 5m. In 1s at 10m/s (= 36 km/h) we are in 'best' case still
// in behalf the resolution of GPS.
do_update = 1;
} else if (t_elapsed > 400L && gps.speed.isValid() &&
( (curr_knots > 20.0 && curr_sats >= 4) ||
(curr_hdop < 1.5 && curr_sats >= 5 && curr_kmph > 1.8 && curr_kmph <= 16.0) ) ) {
// aprs resolution is 1sm/100 = 1852m/100 = 18.52m
// Updating this every 200ms would be enough for getting this resolution at speed of 18.52*3.6*5 = 333.36km/h.
do_update = 1;
} else if (millis() >= next_fixed_beacon && curr_sats >= 5 &&
TinyGPSPlus::distanceBetween(bestDoubleLat, bestDoubleLng, gps.location.lat(), gps.location.lng()) > 185.2) {
// This hack tries to avoid position jumps due to inaccurate gps measurement, but it updates if we moved 185.2m in 10min
do_update = 1;
}
if (do_update) {
if (!no_gps_position_since_boot || (latlon_precision > 0 && bestHdop < 1.0 && gps.speed.age() < 2000 && curr_knots < 18.0)) {
// DAO: heigher precision 1/1000 arc-minute, if not > 36 knots (valid gps measurered speed). Idea behind:
// 18.52 m/s are 36kn. We need abt 1s-2s time for understanding the whole displayed line -> resolution of > 2 decimal points is not needed
// If we consider gps age of < 2s, we use 18kt as limit
storeLatLonPreset(create_lat_aprs("-", bestRawLat, (latlon_precision == 2 ? 4 : 3)),
create_long_aprs("-", bestRawLng, (latlon_precision == 2 ? 4 : 3)),
latlon_precision);
} else {
storeLatLonPreset(create_lat_aprs("-", bestRawLat, 2), create_long_aprs("-", bestRawLng, 2), 0);
if (curr_hdop < bestHdop || millis() > t_interval_start + 5*60*1000L) {
// remember location with best hdop in this time range
bestRawLat = gps.location.rawLat();
bestRawLng = gps.location.rawLng();
bestDoubleLat = gps.location.lat();
bestDoubleLng = gps.location.lng();
bestHdop = curr_hdop;
}
// aprs compressed position has always a high precision (29.17 cm in latitude, 58.34 cm (or less) in longitude)
store_compressed_position(bestDoubleLat, bestDoubleLng);
aprsPresetShown = "";
uint32_t t_elapsed = millis() - t_interval_start;
bestHdop = 99.9;
t_interval_start = millis();
no_gps_position_since_boot = false;
}
}
//if (t_elapsed > 15000L && ((curr_hdop < 1.5 && curr_sats >= 5) || gps_isValid != gps_isValid_oldState || no_gps_position_since_boot)) {
if (t_elapsed > 15000L && ((curr_hdop < 1.5 && curr_sats >= 4) || gps_isValid != gps_isValid_oldState || no_gps_position_since_boot)) {
// Approach to avoid gps inaccuracy (we observed bad gps positions in a range of 30m, or more):
// Resolution of GPS is +/- 3 to 5m. In 1s at 10m/s (= 36 km/h) we are in 'best' case still
// in behalf the resolution of GPS.
do_update = 1;
} else if (t_elapsed > 400L && gps.speed.isValid() &&
( (curr_knots > 20.0 && curr_sats >= 4) ||
(curr_hdop < 1.5 && curr_sats >= 5 && curr_kmph > 1.8 && curr_kmph <= 16.0) ) ) {
// aprs resolution is 1sm/100 = 1852m/100 = 18.52m
// Updating this every 200ms would be enough for getting this resolution at speed of 18.52*3.6*5 = 333.36km/h.
do_update = 1;
} else if (millis() >= next_fixed_beacon && curr_sats >= 5 &&
TinyGPSPlus::distanceBetween(bestDoubleLat, bestDoubleLng, gps.location.lat(), gps.location.lng()) > 185.2) {
// This hack tries to avoid position jumps due to inaccurate gps measurement, but it updates if we moved 185.2m in 10min
do_update = 1;
}
#ifdef notdef
static uint32_t lastTxdistance_millis = 0;
// code has no function, as currently gps_speed_kmph_oled is not used in getSpeedCourseAlti
if ((millis()-lastTxdistance_millis) > 1000) {
static double lastTxLat = 0.0;
static double lastTxLng = 0.0;
double currLat = gps.location.lat();
double currLng = gps.location.lng();
double dist = TinyGPSPlus::distanceBetween(currLat, currLng, lastTxLat, lastTxLng);
// test code to smoothen km/h in oled, does not work, because of weird data from gps. Has to be looked at
// get GPS Data, if valid and mark accordingly
if (dist > 15 || (millis()-lastTxdistance_millis) > 3*60*10000) {
lastTxLat = currLat;
lastTxLng = currLng;
gps_speed_kmph_oled = gps_speed;
lastTxdistance_millis = millis();
} else {
gps_speed_kmph_oled = 0;
if (do_update) {
t_gps_fix_lost = 0L;
if (!no_gps_position_since_boot || (latlon_precision > 0 && bestHdop < 1.0 && gps.speed.age() < 2000 && curr_knots < 18.0)) {
// DAO: heigher precision 1/1000 arc-minute, if not > 36 knots (valid gps measurered speed). Idea behind:
// 18.52 m/s are 36kn. We need abt 1s-2s time for understanding the whole displayed line -> resolution of > 2 decimal points is not needed
// If we consider gps age of < 2s, we use 18kt as limit
storeLatLonPreset(create_lat_aprs("-", bestRawLat, (latlon_precision == 2 ? 4 : 3)),
create_long_aprs("-", bestRawLng, (latlon_precision == 2 ? 4 : 3)),
latlon_precision);
} else {
storeLatLonPreset(create_lat_aprs("-", bestRawLat, 2), create_long_aprs("-", bestRawLng, 2), 0);
}
// aprs compressed position has always a high precision (29.17 cm in latitude, 58.34 cm (or less) in longitude)
store_compressed_position(bestDoubleLat, bestDoubleLng);
aprsPresetShown = "";
bestHdop = 99.9;
t_interval_start = millis();
no_gps_position_since_boot = false;
}
}
#endif
}
if (gps_isValid != gps_isValid_oldState) {
// String functions are cpu consuming. We adust string aprsPresetShown only if we changed status.
if (!gps_isValid) {
t_gps_fix_lost = millis();
// update to the old values
update_speed_from_gps();
if (gps_state && gps.speed.age() < 2000 && curr_knots > 4.0 && curr_hdop < 1.5) {
@ -6117,9 +6215,15 @@ if (t_elapsed > 15000L && ((curr_hdop < 1.5 && curr_sats >= 4) || gps_isValid !=
axp.setALDO3Voltage(3300);
axp.enableALDO3();
#endif
if (xHandle_GPS) {
gps_task_enabled = true;
vTaskResume(xHandle_GPS);
t_gps_powersave_operation_until_fix = 0L;
}
}
#endif
gps_state = gps_state_before_autochange;
if (gps_state_before_autochange)
dont_send_own_position_packets = false;
time_last_own_position_via_kiss_received = 0L;
time_last_frame_via_kiss_received = 0L;
@ -6258,6 +6362,8 @@ if (t_elapsed > 15000L && ((curr_hdop < 1.5 && curr_sats >= 4) || gps_isValid !=
if (gps_allow_sleep_while_kiss) {
#if defined(T_BEAM_V1_0) || defined(T_BEAM_V1_2)
if (gps_state) {
gps_isValid = false;
gps_task_enabled = false; // vTaskSuspend() is done by taskGPS itself (he needs to delete the wdt timer)
#ifdef T_BEAM_V1_0
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF); // switch off GPS
#elif T_BEAM_V1_2
@ -6266,6 +6372,8 @@ if (t_elapsed > 15000L && ((curr_hdop < 1.5 && curr_sats >= 4) || gps_isValid !=
}
#endif
gps_state = false;
t_gps_powersave_operation_until_fix = millis();
t_gps_fix_lost = millis();
}
dont_send_own_position_packets = true;
// TODO: there are also tcp kiss devices. Instead of 'kiss_client_came_via_bluetooth', we should mark it in a session struct where we can iterate through

Wyświetl plik

@ -7,6 +7,7 @@
SFE_UBLOX_GPS myGPS;
extern uint8_t usb_serial_data_type;
extern volatile boolean gps_task_enabled;
#ifdef ENABLE_WIFI
#include "wifi_clients.h"
@ -30,7 +31,10 @@ TinyGPSPlus gps; // The TinyGPS++ object
bool gpsInitialized = false;
[[noreturn]] void taskGPS(void *parameter) {
reinitialize:
if (!gpsInitialized){
gpsSerial.begin(GPSBaud, SERIAL_8N1, TXPin, RXPin); //Startup HW serial for GPS
// set GPS parameters on restart
@ -49,13 +53,20 @@ bool gpsInitialized = false;
delay(1000);
}
}
gps_task_enabled = true;
// esp_task_wdt_init() has already been done in main task during setup()
esp_task_wdt_add(NULL); //add current thread to WDT watch
String gpsDataBuffer = " ";
for (;;) {
if (!gps_task_enabled) {
//gpsSerial.end(); // No, raises exception
esp_task_wdt_delete(NULL);
gpsInitialized = false;
vTaskSuspend(NULL);
goto reinitialize;
}
esp_task_wdt_reset();
#ifdef ENABLE_WIFI
check_for_new_clients(&gpsServer, gps_clients, MAX_GPS_WIFI_CLIENTS);
@ -69,8 +80,8 @@ bool gpsInitialized = false;
gpsDataBuffer += String(gpsChar);
if (gpsChar == '\n') {
if ((usb_serial_data_type & 4))
Serial.println(gpsDataBuffer);
if ((usb_serial_data_type & 4))
Serial.println(gpsDataBuffer);
#ifdef ENABLE_WIFI
iterateWifiClients([](WiFiClient *client, int clientIdx, const String *data){
if (client->connected()){

Wyświetl plik

@ -485,6 +485,7 @@ void refill_preferences_as_jsonData()
s = s + "\n " + jsonLineFromPreferenceBool(PREF_LORA_RX_ENABLE);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_LORA_TX_ENABLE);
s = s + "\n " + jsonLineFromPreferenceInt(PREF_LORA_TX_POWER);
s = s + "\n " + jsonLineFromPreferenceInt(PREF_LORA_TX_PREAMBLE_LEN);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET);
s = s + "\n " + jsonLineFromPreferenceInt(PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_LORA_ADD_SNR_RSSI_TO_PATH_END_AT_KISS_PRESET);
@ -524,6 +525,7 @@ void refill_preferences_as_jsonData()
s = s + "\n " + jsonLineFromPreferenceInt(PREF_APRS_ALTITUDE_RATIO);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_APRS_ALWAYS_SEND_CSE_SPEED_AND_ALTITUDE);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_APRS_GPS_EN);
s = s + "\n " + jsonLineFromPreferenceInt(PREF_GPS_POWERSAVE);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_GPS_ALLOW_SLEEP_WHILE_KISS);
s = s + "\n " + jsonLineFromPreferenceBool(PREF_ENABLE_TNC_SELF_TELEMETRY);
@ -961,6 +963,11 @@ void handle_SaveAPRSCfg() {
if (server.hasArg(PREF_LORA_TX_POWER)) {
preferences.putInt(PREF_LORA_TX_POWER, server.arg(PREF_LORA_TX_POWER).toInt());
}
if (server.hasArg(PREF_LORA_TX_PREAMBLE_LEN)) {
int i = server.arg(PREF_LORA_TX_PREAMBLE_LEN).toInt();
if (i < 8) i = 8; else if (i > 4096) i = 4096;
preferences.putInt(PREF_LORA_TX_PREAMBLE_LEN, i);
}
preferences.putBool(PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET, server.hasArg(PREF_LORA_AUTOMATIC_CR_ADAPTION_PRESET));
if (server.hasArg(PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET)){
preferences.putInt(PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET, server.arg(PREF_LORA_ADD_SNR_RSSI_TO_PATH_PRESET).toInt());
@ -1244,6 +1251,7 @@ void handle_SaveAPRSCfg() {
preferences.putBool(PREF_APRS_ALWAYS_SEND_CSE_SPEED_AND_ALTITUDE, server.hasArg(PREF_APRS_ALWAYS_SEND_CSE_SPEED_AND_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));
preferences.putInt(PREF_GPS_POWERSAVE, server.arg(PREF_GPS_POWERSAVE).toInt());
preferences.putBool(PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS, server.hasArg(PREF_ACCEPT_OWN_POSITION_REPORTS_VIA_KISS));
preferences.putBool(PREF_GPS_ALLOW_SLEEP_WHILE_KISS, server.hasArg(PREF_GPS_ALLOW_SLEEP_WHILE_KISS));
preferences.putBool(PREF_APRS_SHOW_CMT, server.hasArg(PREF_APRS_SHOW_CMT));