mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
M10 ValSet support, unit connection and reconnect stability (#12799)
* 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 42fc8c04fdbc436c9ef196b88f0764ffcbb9239f. 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>
This commit is contained in:
parent
807a7229c9
commit
083b595617
17 changed files with 1650 additions and 803 deletions
|
@ -109,8 +109,13 @@ cli_unittest_SRC := \
|
|||
$(USER_DIR)/common/crc.c \
|
||||
$(USER_DIR)/common/printf.c \
|
||||
$(USER_DIR)/common/streambuf.c \
|
||||
$(USER_DIR)/common/maths.c \
|
||||
$(USER_DIR)/common/gps_conversion.c \
|
||||
$(USER_DIR)/config/feature.c \
|
||||
$(USER_DIR)/io/gps.c \
|
||||
$(USER_DIR)/pg/pg.c \
|
||||
$(USER_DIR)/fc/runtime_config.c \
|
||||
$(USER_DIR)/drivers/serial.c \
|
||||
$(USER_DIR)/common/typeconversion.c
|
||||
|
||||
cli_unittest_DEFINES := \
|
||||
|
|
|
@ -26,9 +26,12 @@ extern "C" {
|
|||
#include "platform.h"
|
||||
#include "target.h"
|
||||
#include "build/version.h"
|
||||
#include "io/gps.h"
|
||||
#include "cli/cli.h"
|
||||
#include "cli/settings.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/gps_conversion.h"
|
||||
#include "config/feature.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
@ -39,7 +42,6 @@ extern "C" {
|
|||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/vtx.h"
|
||||
|
@ -47,6 +49,7 @@ extern "C" {
|
|||
#include "msp/msp_box.h"
|
||||
#include "osd/osd.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/gps_rescue.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/beeper.h"
|
||||
#include "pg/gps.h"
|
||||
|
@ -92,6 +95,7 @@ extern "C" {
|
|||
PG_REGISTER(pidConfig_t, pidConfig, PG_PID_CONFIG, 0);
|
||||
PG_REGISTER(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 0);
|
||||
PG_REGISTER(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 0);
|
||||
PG_REGISTER(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 0);
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(int8_t, unitTestData, PG_RESERVED_FOR_TESTING_1, 0);
|
||||
}
|
||||
|
@ -201,6 +205,7 @@ TEST(CLIUnittest, TestCliSetStringWriteOnce)
|
|||
// STUBS
|
||||
extern "C" {
|
||||
|
||||
int16_t debug[8];
|
||||
float motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
uint16_t batteryWarningVoltage;
|
||||
|
@ -280,9 +285,13 @@ bool parseColor(int, const char *) {return false; }
|
|||
bool resetEEPROM(void) { return true; }
|
||||
void bufWriterFlush(bufWriter_t *) {}
|
||||
void mixerResetDisarmedMotors(void) {}
|
||||
void gpsEnablePassthrough(struct serialPort_s *) {}
|
||||
bool gpsIsHealthy(void) { return true; }
|
||||
baudRate_e getGpsPortActualBaudRateIndex(void) { return BAUD_AUTO; }
|
||||
|
||||
typedef enum {
|
||||
DUMMY
|
||||
} pageId_e;
|
||||
|
||||
void dashboardShowFixedPage(pageId_e){}
|
||||
void dashboardUpdate(timeUs_t) {}
|
||||
|
||||
bool parseLedStripConfig(int, const char *){return false; }
|
||||
const char rcChannelLetters[] = "AERT12345678abcdefgh";
|
||||
|
@ -302,8 +311,6 @@ baudRate_e lookupBaudRateIndex(uint32_t){return BAUD_9600; }
|
|||
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e){ return NULL; }
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; }
|
||||
const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) { return NULL; }
|
||||
void serialSetBaudRate(serialPort_t *, uint32_t) {}
|
||||
void serialSetMode(serialPort_t *, portMode_e) {}
|
||||
void serialPassthrough(serialPort_t *, serialPort_t *, serialConsumer *, serialConsumer *) {}
|
||||
uint32_t millis(void) { return 0; }
|
||||
uint8_t getBatteryCellCount(void) { return 1; }
|
||||
|
@ -320,11 +327,10 @@ uint16_t averageSystemLoadPercent = 0;
|
|||
|
||||
timeDelta_t getTaskDeltaTimeUs(taskId_e){ return 0; }
|
||||
uint16_t currentRxIntervalUs = 9000;
|
||||
armingDisableFlags_e getArmingDisableFlags(void) { return ARMING_DISABLED_NO_GYRO; }
|
||||
|
||||
const char *armingDisableFlagNames[]= {
|
||||
/*const char *armingDisableFlagNames[]= {
|
||||
"DUMMYDISABLEFLAGNAME"
|
||||
};
|
||||
};*/
|
||||
|
||||
void getTaskInfo(taskId_e, taskInfo_t *) {}
|
||||
void getCheckFuncInfo(cfCheckFuncInfo_t *) {}
|
||||
|
@ -336,13 +342,13 @@ const char* const buildDate = "Jan 01 2017";
|
|||
const char * const buildTime = "00:00:00";
|
||||
const char * const shortGitRevision = "MASTER";
|
||||
|
||||
uint32_t serialRxBytesWaiting(const serialPort_t *) {return 0;}
|
||||
uint8_t serialRead(serialPort_t *){return 0;}
|
||||
//uint32_t serialRxBytesWaiting(const serialPort_t *) {return 0;}
|
||||
//uint8_t serialRead(serialPort_t *){return 0;}
|
||||
|
||||
void bufWriterAppend(bufWriter_t *, uint8_t ch){ printf("%c", ch); }
|
||||
void serialWriteBufShim(void *, const uint8_t *, int) {}
|
||||
//void serialWriteBufShim(void *, const uint8_t *, int) {}
|
||||
void bufWriterInit(bufWriter_t *, uint8_t *, int, bufWrite_t, void *) { }
|
||||
void setArmingDisabled(armingDisableFlags_e) {}
|
||||
//void setArmingDisabled(armingDisableFlags_e) {}
|
||||
|
||||
void waitForSerialPortToFinishTransmitting(serialPort_t *) {}
|
||||
void systemResetToBootloader(void) {}
|
||||
|
@ -353,15 +359,16 @@ void writeUnmodifiedConfigToEEPROM(void) {}
|
|||
void changePidProfile(uint8_t) {}
|
||||
bool serialIsPortAvailable(serialPortIdentifier_e) { return false; }
|
||||
void generateLedConfig(ledConfig_t *, char *, size_t) {}
|
||||
bool isSerialTransmitBufferEmpty(const serialPort_t *) {return true; }
|
||||
void serialWrite(serialPort_t *, uint8_t ch) { printf("%c", ch);}
|
||||
//bool isSerialTransmitBufferEmpty(const serialPort_t *) {return true; }
|
||||
//void serialWrite(serialPort_t *, uint8_t ch) { printf("%c", ch);}
|
||||
|
||||
void serialSetCtrlLineStateCb(serialPort_t *, void (*)(void *, uint16_t ), void *) {}
|
||||
//void serialSetCtrlLineStateCb(serialPort_t *, void (*)(void *, uint16_t ), void *) {}
|
||||
void serialSetCtrlLineStateDtrPin(serialPort_t *, ioTag_t ) {}
|
||||
void serialSetCtrlLineState(serialPort_t *, uint16_t ) {}
|
||||
|
||||
void serialSetBaudRateCb(serialPort_t *, void (*)(serialPort_t *context, uint32_t baud), serialPort_t *) {}
|
||||
|
||||
//void serialSetBaudRateCb(serialPort_t *, void (*)(serialPort_t *context, uint32_t baud), serialPort_t *) {}
|
||||
void rescheduleTask(taskId_e, timeDelta_t){}
|
||||
void schedulerSetNextStateTime(timeDelta_t ){}
|
||||
char *getBoardName(void) { return NULL; }
|
||||
char *getManufacturerId(void) { return NULL; }
|
||||
bool boardInformationIsSet(void) { return true; }
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
#define USE_MAG
|
||||
#define USE_BARO
|
||||
#define USE_GPS
|
||||
#define USE_GPS_NMEA
|
||||
#define USE_GPS_UBLOX
|
||||
#define USE_DASHBOARD
|
||||
#define USE_SERIALRX
|
||||
#define USE_RX_MSP
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue