Skip to content

Commit

Permalink
M10 ValSet support, unit connection and reconnect stability (#12799)
Browse files Browse the repository at this point in the history
* WIP

* start of implement m10 code

* Fetch MON-VER from unit to check for unit version

* test nav5 m10 command

* missing empty lines

* offload detect to config file

* copy from hasli and organization

* fix platform.h include

* fix cli_unittest gps include

* fix cli_unittest for gps calls

* guard ublox version in gpsData

* print human readable hw version

* add utc_standard param and transfer with nav5 set
add nav5x message for autonomous mode for m10

* fix typo

* revert order structure, remove functions and reduce flash size

* revert order structure, remove functions and reduce flash size

* fix gps init and navx5 message

* generalized nav5 message

* remove unguarded debug

* change ubx version detection, baud rate negotiation fix and save found baud

* revert indentation

* revert indentation and refactorings

* the new code works with faster baud rate changes

* remove unguarded debug statement

* fix cli commands, major space reduce finished, removed extensions for now

* ubx version checks, add valset for M10

* beta of valset, change suggestions from ledvinap and macgivergim

* valset helper function and combine set nav rate valsets

* more valset refactoring

* remove big array and replace with macro

* remove assert, as it can stop bf completely

* refactoring to offsetof

* making reconnect more resilient, reorganize rate setup, so it doesnt get missed on init

* improved lost communcation detection, dont rely on ACK/NACK anymore

* paket rate debug

* adding debug mode, fixing major flight mode bug

* revert fake flight "isConfiguratorConnected"

* fixed proto detection, fixed reconfigure on too low updaterate

* valset doesnt always send ACK, so we dont wait for it

* size optimization, debug mode rename, minor fixes

* implemented some requested changes

* changed wait delay millisecond based

* fixes from ctzsnooze and zzXyz

* timer fixes

* CamelCase new settings names

* indent

* Fix failure to enter flight model on GPS Fix

* remove old commented out debugs

* simplify timeouts

* Clarify skip_acc and remove development valset code

* accept PL's advice to remove  >> (8 * 0

* Simplify package counter, remove reconfiguration based on packet count

* fix error in package count introduced in previous commit

* Fix delay detecting Configurator, ANA disable (for another PR)

* address payload comments and fix logical error

* indentation edits

* delete old enum

* log gps and firmware nav interval times

* fix payload size, inc Rx buffer to 256, ifDef for sw_proto

* remove token parsing (Petr suggestions)

* fixes from reviews

* Basic NMEA improvements

* Address comments from karate

* only check platform version - thanks zzyzx

* Fix for too many sats problem - thanks zzyzx

* tidy up comments, ifdef some ublox definitions

* Use Nav packet intervals, NMEA and UBX, for time delta

* Resolve comments and flatten conditionals

* editorial change

* single function for gpsSol.navIntervalMs

* adam-ah suggestion for payload optimisation

* ACK/NAK & polled message timer fixes

* Revert timer fixes - unexpected side effects

* Revert adam-ah suggestion for payload optimisation"

This reverts commit 42fc8c0.
Broke the display of sat info when more than 32 sats in view

* implement a number of comments

* Fast task rate on new data, don't spam at the start

thanks adam-ah

* include PDOP for M10 via NAV-PVT

* Address some of PL's recent comments

* don't recalculate millis so many times

* tidy up baudrate connect code

* Split receiving of GPS bytes from processing by adding GPS_STATE_PROCESS_DATA

* Split receiving of GPS bytes from processing by adding GPS_STATE_PROCESS_DATA

* Preserve state whilst processing packets

* Set gpsData.state directly as gpsSetState() clobbers gpsData.state_position

* Restore original read time check

* Schedule gpsUpdate() to run immediately again when a packet is received for processing

* add debugs to display scheduler valuesl

* simpler scheduler solution

* minor debug change

* FIxes: M10 connection, pDop, NMEA disable; thanks zzyxz

NB: Breaks unit's neat reconnection methods
M8 need a lot of settling time before using the serial port

* ubx parse length sanity + cleanup + dashboard conditional compiles

* Address recent comments from PL

---------

Co-authored-by: ctzsnooze <chris.thompson@sydney.edu.au>
Co-authored-by: ZzyzxTek <zzyzx@zzyzxtek.com>
Co-authored-by: Steve Evans <Steve@SCEvans.com>
  • Loading branch information
4 people committed Aug 12, 2023
1 parent 807a722 commit 083b595
Show file tree
Hide file tree
Showing 17 changed files with 1,614 additions and 767 deletions.
1 change: 1 addition & 0 deletions src/main/build/debug.c
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ const char * const debugModeNames[DEBUG_COUNT] = {
"GPS_RESCUE_VELOCITY",
"GPS_RESCUE_HEADING",
"GPS_RESCUE_TRACKING",
"GPS_CONNECTION",
"ATTITUDE",
"VTX_MSP",
"GPS_DOP",
Expand Down
1 change: 1 addition & 0 deletions src/main/build/debug.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ typedef enum {
DEBUG_GPS_RESCUE_VELOCITY,
DEBUG_GPS_RESCUE_HEADING,
DEBUG_GPS_RESCUE_TRACKING,
DEBUG_GPS_CONNECTION,
DEBUG_ATTITUDE,
DEBUG_VTX_MSP,
DEBUG_GPS_DOP,
Expand Down
24 changes: 15 additions & 9 deletions src/main/cli/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -4787,7 +4787,7 @@ if (buildKey) {
#ifdef USE_GPS
cliPrint("GPS: ");
if (featureIsEnabled(FEATURE_GPS)) {
if (gpsIsHealthy()) {
if (gpsData.state >= GPS_STATE_CONFIGURE) {
cliPrint("connected, ");
} else {
cliPrint("NOT CONNECTED, ");
Expand All @@ -4808,7 +4808,7 @@ if (buildKey) {
cliPrint("), ");
}
}
if (!gpsIsHealthy()) {
if (gpsData.state <= GPS_STATE_CONFIGURE) {
cliPrint("NOT CONFIGURED");
} else {
if (gpsConfig()->autoConfig == GPS_AUTOCONFIG_OFF) {
Expand All @@ -4817,6 +4817,12 @@ if (buildKey) {
cliPrint("configured");
}
}
if (gpsData.platformVersion != UBX_VERSION_UNDEF) {
cliPrint(", version = ");
cliPrintf("%s", ubloxVersionMap[gpsData.platformVersion].str);
} else {
cliPrint("unknown");
}
} else {
cliPrint("NOT ENABLED");
}
Expand Down Expand Up @@ -4864,15 +4870,15 @@ static void cliTasks(const char *cmdName, char *cmdline)
if (systemConfig()->task_statistics) {
#if defined(USE_LATE_TASK_STATISTICS)
cliPrintLinef("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d %6d %6d %7d",
taskFrequency, taskInfo.maxExecutionTimeUs, taskInfo.averageExecutionTime10thUs / 10,
maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10,
taskInfo.totalExecutionTimeUs / 1000,
taskInfo.lateCount, taskInfo.runCount, taskInfo.execTime);
taskFrequency, taskInfo.maxExecutionTimeUs, taskInfo.averageExecutionTime10thUs / 10,
maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10,
taskInfo.totalExecutionTimeUs / 1000,
taskInfo.lateCount, taskInfo.runCount, taskInfo.execTime);
#else
cliPrintLinef("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d",
taskFrequency, taskInfo.maxExecutionTimeUs, taskInfo.averageExecutionTime10thUs / 10,
maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10,
taskInfo.totalExecutionTimeUs / 1000);
taskFrequency, taskInfo.maxExecutionTimeUs, taskInfo.averageExecutionTime10thUs / 10,
maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10,
taskInfo.totalExecutionTimeUs / 1000);
#endif
} else {
cliPrintLinef("%6d", taskFrequency);
Expand Down
21 changes: 13 additions & 8 deletions src/main/cli/settings.c
Original file line number Diff line number Diff line change
Expand Up @@ -198,17 +198,21 @@ static const char * const lookupTableGyro[] = {
#endif

#ifdef USE_GPS
static const char * const lookupTableGPSProvider[] = {
static const char * const lookupTableGpsProvider[] = {
"NMEA", "UBLOX", "MSP"
};

static const char * const lookupTableGPSSBASMode[] = {
static const char * const lookupTableGpsSbasMode[] = {
"AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"
};

static const char * const lookupTableGPSUBLOXModels[] = {
static const char * const lookupTableGpsUbloxModels[] = {
"PORTABLE", "STATIONARY", "PEDESTRIAN", "AUTOMOTIVE", "AT_SEA", "AIRBORNE_1G", "AIRBORNE_2G", "AIRBORNE_4G"
};

static const char * const lookupTableGpsUbloxUtcStandard[] = {
"AUTO", "USNO", "EU", "SU", "NTSC"
};
#endif

#ifdef USE_SERVOS
Expand Down Expand Up @@ -533,9 +537,10 @@ const lookupTableEntry_t lookupTables[] = {
LOOKUP_TABLE_ENTRY(lookupTableUnit),
LOOKUP_TABLE_ENTRY(lookupTableAlignment),
#ifdef USE_GPS
LOOKUP_TABLE_ENTRY(lookupTableGPSProvider),
LOOKUP_TABLE_ENTRY(lookupTableGPSSBASMode),
LOOKUP_TABLE_ENTRY(lookupTableGPSUBLOXModels),
LOOKUP_TABLE_ENTRY(lookupTableGpsProvider),
LOOKUP_TABLE_ENTRY(lookupTableGpsSbasMode),
LOOKUP_TABLE_ENTRY(lookupTableGpsUbloxModels),
LOOKUP_TABLE_ENTRY(lookupTableGpsUbloxUtcStandard),
#ifdef USE_GPS_RESCUE
LOOKUP_TABLE_ENTRY(lookupTableRescueSanityType),
LOOKUP_TABLE_ENTRY(lookupTableRescueAltitudeMode),
Expand Down Expand Up @@ -1017,9 +1022,9 @@ const clivalue_t valueTable[] = {
{ PARAM_NAME_GPS_AUTO_BAUD, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoBaud) },
{ PARAM_NAME_GPS_UBLOX_ACQUIRE_MODEL, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_UBLOX_MODELS }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_ublox_acquire_model) },
{ PARAM_NAME_GPS_UBLOX_FLIGHT_MODEL, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_UBLOX_MODELS }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_ublox_flight_model) },
{ PARAM_NAME_GPS_UPDATE_RATE_HZ, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = {1, 19}, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_update_rate_hz) },
{ PARAM_NAME_GPS_UPDATE_RATE_HZ, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = {1, 20}, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_update_rate_hz) },
{ PARAM_NAME_GPS_UBLOX_UTC_STANDARD, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_UBLOX_UTC_STANDARD }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_ublox_utc_standard) },
{ PARAM_NAME_GPS_UBLOX_USE_GALILEO, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_ublox_use_galileo) },
{ PARAM_NAME_GPS_UBLOX_FULL_POWER, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_ublox_full_power) },
{ PARAM_NAME_GPS_SET_HOME_POINT_ONCE, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_set_home_point_once) },
{ PARAM_NAME_GPS_USE_3D_SPEED, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_use_3d_speed) },
{ PARAM_NAME_GPS_SBAS_INTEGRITY, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbas_integrity) },
Expand Down
1 change: 1 addition & 0 deletions src/main/cli/settings.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ typedef enum {
TABLE_GPS_PROVIDER,
TABLE_GPS_SBAS_MODE,
TABLE_GPS_UBLOX_MODELS,
TABLE_GPS_UBLOX_UTC_STANDARD,
#endif
#ifdef USE_GPS_RESCUE
TABLE_GPS_RESCUE_SANITY_CHECK,
Expand Down
10 changes: 5 additions & 5 deletions src/main/drivers/serial_uart_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#define UARTDEV_COUNT_MAX 6
#define UARTHARDWARE_MAX_PINS 4
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 128
#define UART_RX_BUFFER_SIZE 256
#endif
#ifndef UART_TX_BUFFER_SIZE
#ifdef USE_MSP_DISPLAYPORT
Expand All @@ -39,7 +39,7 @@
#define UARTDEV_COUNT_MAX 8
#define UARTHARDWARE_MAX_PINS 4
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 128
#define UART_RX_BUFFER_SIZE 256
#endif
#ifndef UART_TX_BUFFER_SIZE
#ifdef USE_MSP_DISPLAYPORT
Expand All @@ -52,7 +52,7 @@
#define UARTDEV_COUNT_MAX 11 // UARTs 1 to 10 + LPUART1
#define UARTHARDWARE_MAX_PINS 5
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 128
#define UART_RX_BUFFER_SIZE 256
#endif
#ifndef UART_TX_BUFFER_SIZE
#ifdef USE_MSP_DISPLAYPORT
Expand All @@ -65,7 +65,7 @@
#define UARTDEV_COUNT_MAX 11 // UARTs 1 to 5 + LPUART1 (index 10)
#define UARTHARDWARE_MAX_PINS 3
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 128
#define UART_RX_BUFFER_SIZE 256
#endif
#ifndef UART_TX_BUFFER_SIZE
#ifdef USE_MSP_DISPLAYPORT
Expand All @@ -78,7 +78,7 @@
#define UARTDEV_COUNT_MAX 8 // UARTs 1 to 5 + LPUART1 (index 9)
#define UARTHARDWARE_MAX_PINS 5
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 128
#define UART_RX_BUFFER_SIZE 256
#endif
#ifndef UART_TX_BUFFER_SIZE
#ifdef USE_MSP_DISPLAYPORT
Expand Down
2 changes: 1 addition & 1 deletion src/main/fc/parameter_names.h
Original file line number Diff line number Diff line change
Expand Up @@ -143,9 +143,9 @@
#define PARAM_NAME_GPS_AUTO_CONFIG "gps_auto_config"
#define PARAM_NAME_GPS_AUTO_BAUD "gps_auto_baud"
#define PARAM_NAME_GPS_UBLOX_USE_GALILEO "gps_ublox_use_galileo"
#define PARAM_NAME_GPS_UBLOX_FULL_POWER "gps_ublox_full_power"
#define PARAM_NAME_GPS_UBLOX_ACQUIRE_MODEL "gps_ublox_acquire_model"
#define PARAM_NAME_GPS_UBLOX_FLIGHT_MODEL "gps_ublox_flight_model"
#define PARAM_NAME_GPS_UBLOX_UTC_STANDARD "gps_ublox_utc_standard"
#define PARAM_NAME_GPS_SET_HOME_POINT_ONCE "gps_set_home_point_once"
#define PARAM_NAME_GPS_USE_3D_SPEED "gps_use_3d_speed"
#define PARAM_NAME_GPS_NMEA_CUSTOM_COMMANDS "gps_nmea_custom_commands"
Expand Down
2 changes: 0 additions & 2 deletions src/main/fc/tasks.c
Original file line number Diff line number Diff line change
Expand Up @@ -251,8 +251,6 @@ static void taskGpsRescue(timeUs_t currentTimeUs)

if (gpsRescueIsConfigured()) {
gpsRescueUpdate();
} else {
schedulerIgnoreTaskStateTime();
}
}
#endif
Expand Down
10 changes: 5 additions & 5 deletions src/main/io/dashboard.c
Original file line number Diff line number Diff line change
Expand Up @@ -379,8 +379,8 @@ static void showGpsPage(void)

static uint8_t gpsTicker = 0;
static uint32_t lastGPSSvInfoReceivedCount = 0;
if (GPS_svInfoReceivedCount != lastGPSSvInfoReceivedCount) {
lastGPSSvInfoReceivedCount = GPS_svInfoReceivedCount;
if (dashboardGpsNavSvInfoRcvCount != lastGPSSvInfoReceivedCount) {
lastGPSSvInfoReceivedCount = dashboardGpsNavSvInfoRcvCount;
gpsTicker++;
gpsTicker = gpsTicker % TICKER_CHARACTER_COUNT;
}
Expand Down Expand Up @@ -419,7 +419,7 @@ static void showGpsPage(void)
i2c_OLED_set_xy(dev, HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++);
i2c_OLED_send_string(dev, lineBuffer);

tfp_sprintf(lineBuffer, "RX: %d", GPS_packetCount);
tfp_sprintf(lineBuffer, "RX: %d", dashboardGpsPacketCount);
padHalfLineBuffer();
i2c_OLED_set_line(dev, rowIndex);
i2c_OLED_send_string(dev, lineBuffer);
Expand All @@ -429,7 +429,7 @@ static void showGpsPage(void)
i2c_OLED_set_xy(dev, HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++);
i2c_OLED_send_string(dev, lineBuffer);

tfp_sprintf(lineBuffer, "Dt: %d", gpsData.lastMessage - gpsData.lastLastMessage);
tfp_sprintf(lineBuffer, "Dt: %d", gpsSol.navIntervalMs);
padHalfLineBuffer();
i2c_OLED_set_line(dev, rowIndex);
i2c_OLED_send_string(dev, lineBuffer);
Expand All @@ -439,7 +439,7 @@ static void showGpsPage(void)
i2c_OLED_set_xy(dev, HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++);
i2c_OLED_send_string(dev, lineBuffer);

strncpy(lineBuffer, gpsPacketLog, GPS_PACKET_LOG_ENTRY_COUNT);
strncpy(lineBuffer, dashboardGpsPacketLog, GPS_PACKET_LOG_ENTRY_COUNT);
padHalfLineBuffer();
i2c_OLED_set_line(dev, rowIndex++);
i2c_OLED_send_string(dev, lineBuffer);
Expand Down

0 comments on commit 083b595

Please sign in to comment.