1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Merge branch 'master' into km-stats-postflight

This commit is contained in:
krzysztofmatula 2019-04-21 22:44:44 +02:00 committed by GitHub
commit 14bb0fca72
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
24 changed files with 1048 additions and 202 deletions

View file

@ -123,6 +123,7 @@ COMMON_SRC = \
cms/cms_menu_blackbox.c \ cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \ cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \ cms/cms_menu_failsafe.c \
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \ cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \ cms/cms_menu_ledstrip.c \
cms/cms_menu_misc.c \ cms/cms_menu_misc.c \
@ -302,6 +303,7 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
cms/cms_menu_blackbox.c \ cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \ cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \ cms/cms_menu_failsafe.c \
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \ cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \ cms/cms_menu_ledstrip.c \
cms/cms_menu_misc.c \ cms/cms_menu_misc.c \

View file

@ -86,4 +86,5 @@ const char * const debugModeNames[DEBUG_COUNT] = {
"AC_CORRECTION", "AC_CORRECTION",
"AC_ERROR", "AC_ERROR",
"DUAL_GYRO_SCALED", "DUAL_GYRO_SCALED",
"DSHOT_RPM_ERRORS",
}; };

View file

@ -102,6 +102,7 @@ typedef enum {
DEBUG_AC_CORRECTION, DEBUG_AC_CORRECTION,
DEBUG_AC_ERROR, DEBUG_AC_ERROR,
DEBUG_DUAL_GYRO_SCALED, DEBUG_DUAL_GYRO_SCALED,
DEBUG_DSHOT_RPM_ERRORS,
DEBUG_COUNT DEBUG_COUNT
} debugType_e; } debugType_e;

View file

@ -75,6 +75,7 @@ extern uint8_t __config_end;
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/io_impl.h" #include "drivers/io_impl.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"
#include "drivers/pwm_output.h"
#include "drivers/rangefinder/rangefinder_hcsr04.h" #include "drivers/rangefinder/rangefinder_hcsr04.h"
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -538,6 +539,10 @@ static void printValuePointer(const clivalue_t *var, const void *valuePointer, b
} else { } else {
cliPrintf("OFF"); cliPrintf("OFF");
} }
break;
case MODE_STRING:
cliPrintf("%s", (char *)valuePointer);
break;
} }
if (valueIsCorrupted) { if (valueIsCorrupted) {
@ -756,7 +761,6 @@ static void cliSetVar(const clivalue_t *var, const uint32_t value)
} }
*(uint32_t *)ptr = workValue; *(uint32_t *)ptr = workValue;
break; break;
} }
} else { } else {
switch (var->type & VALUE_TYPE_MASK) { switch (var->type & VALUE_TYPE_MASK) {
@ -3954,6 +3958,19 @@ static uint8_t getWordLength(char *bufBegin, char *bufEnd)
return bufEnd - bufBegin; return bufEnd - bufBegin;
} }
uint16_t cliGetSettingIndex(char *name, uint8_t length)
{
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
const char *settingName = valueTable[i].name;
// ensure exact match when setting to prevent setting variables with shorter names
if (strncasecmp(name, settingName, strlen(settingName)) == 0 && length == strlen(settingName)) {
return i;
}
}
return valueTableEntryCount;
}
STATIC_UNIT_TESTED void cliSet(char *cmdline) STATIC_UNIT_TESTED void cliSet(char *cmdline)
{ {
const uint32_t len = strlen(cmdline); const uint32_t len = strlen(cmdline);
@ -3977,11 +3994,12 @@ STATIC_UNIT_TESTED void cliSet(char *cmdline)
eqptr++; eqptr++;
eqptr = skipSpace(eqptr); eqptr = skipSpace(eqptr);
for (uint32_t i = 0; i < valueTableEntryCount; i++) { const uint16_t index = cliGetSettingIndex(cmdline, variableNameLength);
const clivalue_t *val = &valueTable[i]; if (index >= valueTableEntryCount) {
cliPrintErrorLinef("INVALID NAME");
// ensure exact match when setting to prevent setting variables with shorter names return;
if (strncasecmp(cmdline, val->name, strlen(val->name)) == 0 && variableNameLength == strlen(val->name)) { }
const clivalue_t *val = &valueTable[index];
bool valueChanged = false; bool valueChanged = false;
int16_t value = 0; int16_t value = 0;
@ -4096,7 +4114,26 @@ STATIC_UNIT_TESTED void cliSet(char *cmdline)
valueChanged = true; valueChanged = true;
break; break;
case MODE_STRING: {
char *valPtr = eqptr;
valPtr = skipSpace(valPtr);
const unsigned int len = strlen(valPtr);
const uint8_t min = val->config.string.minlength;
const uint8_t max = val->config.string.maxlength;
const bool updatable = ((val->config.string.flags & STRING_FLAGS_WRITEONCE) == 0 ||
strlen((char *)cliGetValuePointer(val)) == 0 ||
strncmp(valPtr, (char *)cliGetValuePointer(val), len) == 0);
if (updatable && len > 0 && len <= max) {
memset((char *)cliGetValuePointer(val), 0, max);
if (len >= min && strncmp(valPtr, emptyName, len)) {
strncpy((char *)cliGetValuePointer(val), valPtr, len);
}
valueChanged = true;
}
}
break;
} }
if (valueChanged) { if (valueChanged) {
@ -4108,9 +4145,6 @@ STATIC_UNIT_TESTED void cliSet(char *cmdline)
} }
return; return;
}
}
cliPrintErrorLinef("INVALID NAME");
} else { } else {
// no equals, check for matching variables. // no equals, check for matching variables.
cliGet(cmdline); cliGet(cmdline);
@ -4237,28 +4271,6 @@ static void cliStatus(char *cmdline)
cliPrintf(" %s", armingDisableFlagNames[bitpos]); cliPrintf(" %s", armingDisableFlagNames[bitpos]);
} }
cliPrintLinefeed(); cliPrintLinefeed();
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
if (useDshotTelemetry) {
cliPrintLinef("Dshot reads: %u", readDoneCount);
cliPrintLinef("Dshot invalid pkts: %u", dshotInvalidPacketCount);
extern uint32_t setDirectionMicros;
cliPrintLinef("Dshot irq micros: %u", setDirectionMicros);
for (int i = 0; i<getMotorCount(); i++) {
cliPrintLinef( "Dshot RPM Motor %u: %u", i, (int)getDshotTelemetry(i));
}
bool proshot = (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000);
int modulo = proshot ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
int len = proshot ? 8 : DSHOT_TELEMETRY_INPUT_LEN;
for (int i=0; i<len; i++) {
cliPrintf("%u ", (int)inputBuffer[i]);
}
cliPrintLinefeed();
for (int i=1; i<len; i+=2) {
cliPrintf("%u ", (int)(inputBuffer[i] + modulo - inputBuffer[i-1]) % modulo);
}
cliPrintLinefeed();
}
#endif
} }
#if defined(USE_TASK_STATISTICS) #if defined(USE_TASK_STATISTICS)
@ -5312,6 +5324,57 @@ static void cliTimer(char *cmdline)
} }
#endif #endif
#ifdef USE_DSHOT_TELEMETRY
static void cliDshotTelemetryInfo(char *cmdline)
{
UNUSED(cmdline);
if (useDshotTelemetry) {
cliPrintLinef("Dshot reads: %u", readDoneCount);
cliPrintLinef("Dshot invalid pkts: %u", dshotInvalidPacketCount);
extern uint32_t setDirectionMicros;
cliPrintLinef("Dshot irq micros: %u", setDirectionMicros);
cliPrintLinefeed();
#ifdef USE_DSHOT_TELEMETRY_STATS
cliPrintLine("Motor RPM Invalid");
cliPrintLine("===== ===== =======");
#else
cliPrintLine("Motor RPM");
cliPrintLine("===== =====");
#endif
for (uint8_t i = 0; i < getMotorCount(); i++) {
cliPrintf("%5d %5d ", i, (int)getDshotTelemetry(i));
#ifdef USE_DSHOT_TELEMETRY_STATS
if (isDshotMotorTelemetryActive(i)) {
const int calcPercent = getDshotTelemetryMotorInvalidPercent(i);
cliPrintLinef("%3d.%02d%%", calcPercent / 100, calcPercent % 100);
} else {
cliPrintLine("NO DATA");
}
#else
cliPrintLinefeed();
#endif
}
cliPrintLinefeed();
const bool proshot = (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000);
const int modulo = proshot ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
const int len = proshot ? 8 : DSHOT_TELEMETRY_INPUT_LEN;
for (int i = 0; i < len; i++) {
cliPrintf("%u ", (int)inputBuffer[i]);
}
cliPrintLinefeed();
for (int i = 1; i < len; i+=2) {
cliPrintf("%u ", (int)(inputBuffer[i] + modulo - inputBuffer[i-1]) % modulo);
}
cliPrintLinefeed();
} else {
cliPrintLine("Dshot telemetry not enabled");
}
}
#endif
static void printConfig(char *cmdline, bool doDiff) static void printConfig(char *cmdline, bool doDiff)
{ {
dumpFlags_t dumpMask = DUMP_MASTER; dumpFlags_t dumpMask = DUMP_MASTER;
@ -5642,6 +5705,9 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("dma", "show DMA assignments", "show", cliDma), CLI_COMMAND_DEF("dma", "show DMA assignments", "show", cliDma),
#endif #endif
#endif #endif
#ifdef USE_DSHOT_TELEMETRY
CLI_COMMAND_DEF("dshot_telemetry_info", "disply dshot telemetry info and stats", NULL, cliDshotTelemetryInfo),
#endif
#ifdef USE_DSHOT #ifdef USE_DSHOT
CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg), CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg),
#endif #endif
@ -5653,7 +5719,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("exit", NULL, NULL, cliExit), CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
CLI_COMMAND_DEF("feature", "configure features", CLI_COMMAND_DEF("feature", "configure features",
"list\r\n" "list\r\n"
"\t<+|->[name]", cliFeature), "\t<->[name]", cliFeature),
#ifdef USE_FLASHFS #ifdef USE_FLASHFS
CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase), CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo), CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),

View file

@ -88,6 +88,7 @@
#include "pg/sdio.h" #include "pg/sdio.h"
#include "pg/rcdevice.h" #include "pg/rcdevice.h"
#include "pg/stats.h" #include "pg/stats.h"
#include "pg/board.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/cc2500_frsky_common.h" #include "rx/cc2500_frsky_common.h"
@ -1123,8 +1124,15 @@ const clivalue_t valueTable[] = {
#endif #endif
{ "osd_warn_no_gps_rescue", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_GPS_RESCUE_UNAVAILABLE, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)}, { "osd_warn_no_gps_rescue", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_GPS_RESCUE_UNAVAILABLE, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
{ "osd_warn_gps_rescue_disabled", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_GPS_RESCUE_DISABLED, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)}, { "osd_warn_gps_rescue_disabled", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_GPS_RESCUE_DISABLED, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
{ "osd_warn_rssi", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_RSSI, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
#ifdef USE_RX_LINK_QUALITY_INFO
{ "osd_warn_link_quality", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_WARNING_LINK_QUALITY, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings)},
#endif
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) }, { "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
#ifdef USE_RX_LINK_QUALITY_INFO
{ "osd_link_quality_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, link_quality_alarm) },
#endif
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) }, { "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) }, { "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
{ "osd_esc_temp_alarm", VAR_INT8 | MASTER_VALUE, .config.minmax = { INT8_MIN, INT8_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, esc_temp_alarm) }, { "osd_esc_temp_alarm", VAR_INT8 | MASTER_VALUE, .config.minmax = { INT8_MIN, INT8_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, esc_temp_alarm) },
@ -1424,8 +1432,13 @@ const clivalue_t valueTable[] = {
#ifdef USE_PERSISTENT_STATS #ifdef USE_PERSISTENT_STATS
{ "stats", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_enabled) }, { "stats", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_enabled) },
{ "stats_total_flights", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_flights) }, { "stats_total_flights", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_flights) },
{ "stats_total_time_s", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_time_s) }, { "stats_total_time_s", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_time_s) },
{ "stats_total_dist_m", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_dist_m) }, { "stats_total_dist_m", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_STATS_CONFIG, offsetof(statsConfig_t, stats_total_dist_m) },
#endif
{ "name", VAR_UINT8 | MASTER_VALUE | MODE_STRING, .config.string = { 1, MAX_NAME_LENGTH, STRING_FLAGS_NONE }, PG_PILOT_CONFIG, offsetof(pilotConfig_t, name) },
#ifdef USE_OSD
{ "display_name", VAR_UINT8 | MASTER_VALUE | MODE_STRING, .config.string = { 1, MAX_NAME_LENGTH, STRING_FLAGS_NONE }, PG_PILOT_CONFIG, offsetof(pilotConfig_t, displayName) },
#endif #endif
}; };

View file

@ -160,17 +160,18 @@ typedef enum {
PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET), PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
HARDWARE_VALUE = (3 << VALUE_SECTION_OFFSET), // Part of the master section, but used for the hardware definition HARDWARE_VALUE = (3 << VALUE_SECTION_OFFSET), // Part of the master section, but used for the hardware definition
// value mode, bits 5-6 // value mode, bits 5-7
MODE_DIRECT = (0 << VALUE_MODE_OFFSET), MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
MODE_LOOKUP = (1 << VALUE_MODE_OFFSET), MODE_LOOKUP = (1 << VALUE_MODE_OFFSET),
MODE_ARRAY = (2 << VALUE_MODE_OFFSET), MODE_ARRAY = (2 << VALUE_MODE_OFFSET),
MODE_BITSET = (3 << VALUE_MODE_OFFSET) MODE_BITSET = (3 << VALUE_MODE_OFFSET),
MODE_STRING = (4 << VALUE_MODE_OFFSET),
} cliValueFlag_e; } cliValueFlag_e;
#define VALUE_TYPE_MASK (0x07) #define VALUE_TYPE_MASK (0x07)
#define VALUE_SECTION_MASK (0x18) #define VALUE_SECTION_MASK (0x18)
#define VALUE_MODE_MASK (0x60) #define VALUE_MODE_MASK (0xE0)
typedef struct cliMinMaxConfig_s { typedef struct cliMinMaxConfig_s {
const int16_t min; const int16_t min;
@ -190,11 +191,21 @@ typedef struct cliArrayLengthConfig_s {
const uint8_t length; const uint8_t length;
} cliArrayLengthConfig_t; } cliArrayLengthConfig_t;
typedef struct cliStringLengthConfig_s {
const uint8_t minlength;
const uint8_t maxlength;
const uint8_t flags;
} cliStringLengthConfig_t;
#define STRING_FLAGS_NONE (0)
#define STRING_FLAGS_WRITEONCE (1 << 0)
typedef union { typedef union {
cliLookupTableConfig_t lookup; // used for MODE_LOOKUP excl. VAR_UINT32 cliLookupTableConfig_t lookup; // used for MODE_LOOKUP excl. VAR_UINT32
cliMinMaxConfig_t minmax; // used for MODE_DIRECT with signed parameters cliMinMaxConfig_t minmax; // used for MODE_DIRECT with signed parameters
cliMinMaxUnsignedConfig_t minmaxUnsigned; // used for MODE_DIRECT with unsigned parameters cliMinMaxUnsignedConfig_t minmaxUnsigned; // used for MODE_DIRECT with unsigned parameters
cliArrayLengthConfig_t array; // used for MODE_ARRAY cliArrayLengthConfig_t array; // used for MODE_ARRAY
cliStringLengthConfig_t string; // used for MODE_STRING
uint8_t bitpos; // used for MODE_BITSET uint8_t bitpos; // used for MODE_BITSET
uint32_t u32Max; // used for MODE_DIRECT with VAR_UINT32 uint32_t u32Max; // used for MODE_DIRECT with VAR_UINT32
} cliValueConfig_t; } cliValueConfig_t;

View file

@ -31,6 +31,10 @@
#include "cms/cms_types.h" #include "cms/cms_types.h"
#include "cms/cms_menu_failsafe.h" #include "cms/cms_menu_failsafe.h"
#ifdef USE_CMS_GPS_RESCUE_MENU
#include "cms/cms_menu_gps_rescue.h"
#endif
#include "config/feature.h" #include "config/feature.h"
#include "fc/config.h" #include "fc/config.h"
@ -73,6 +77,9 @@ static const OSD_Entry cmsx_menuFailsafeEntries[] =
{ "GUARD TIME", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_delay, 0, 200, 1, 100 }, 0 }, { "GUARD TIME", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_delay, 0, 200, 1, 100 }, 0 },
{ "STAGE 2 DELAY", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_off_delay, 0, 200, 1, 100 }, 0 }, { "STAGE 2 DELAY", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &failsafeConfig_failsafe_off_delay, 0, 200, 1, 100 }, 0 },
{ "STAGE 2 THROTTLE", OME_UINT16, NULL, &(OSD_UINT16_t) { &failsafeConfig_failsafe_throttle, PWM_PULSE_MIN, PWM_PULSE_MAX, 1 }, 0 }, { "STAGE 2 THROTTLE", OME_UINT16, NULL, &(OSD_UINT16_t) { &failsafeConfig_failsafe_throttle, PWM_PULSE_MIN, PWM_PULSE_MAX, 1 }, 0 },
#ifdef USE_CMS_GPS_RESCUE_MENU
{ "GPS RESCUE", OME_Submenu, cmsMenuChange, &cmsx_menuGpsRescue, 0},
#endif
{ "BACK", OME_Back, NULL, NULL, 0 }, { "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 } { NULL, OME_END, NULL, NULL, 0 }
}; };

View file

@ -0,0 +1,183 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef USE_CMS_GPS_RESCUE_MENU
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_gps_rescue.h"
#include "config/feature.h"
#include "fc/config.h"
#include "flight/gps_rescue.h"
static uint16_t gpsRescueConfig_angle; //degrees
static uint16_t gpsRescueConfig_initialAltitudeM; //meters
static uint16_t gpsRescueConfig_descentDistanceM; //meters
static uint16_t gpsRescueConfig_rescueGroundspeed; // centimeters per second
static uint16_t gpsRescueConfig_throttleMin;
static uint16_t gpsRescueConfig_throttleMax;
static uint16_t gpsRescueConfig_throttleHover;
static uint8_t gpsRescueConfig_minSats;
static uint16_t gpsRescueConfig_minRescueDth; //meters
static uint8_t gpsRescueConfig_allowArmingWithoutFix;
static uint16_t gpsRescueConfig_throttleP, gpsRescueConfig_throttleI, gpsRescueConfig_throttleD;
static uint16_t gpsRescueConfig_velP, gpsRescueConfig_velI, gpsRescueConfig_velD;
static uint16_t gpsRescueConfig_yawP;
static long cms_menuGpsRescuePidOnEnter(void)
{
gpsRescueConfig_throttleP = gpsRescueConfig()->throttleP;
gpsRescueConfig_throttleI = gpsRescueConfig()->throttleI;
gpsRescueConfig_throttleD = gpsRescueConfig()->throttleD;
gpsRescueConfig_yawP = gpsRescueConfig()->yawP;
gpsRescueConfig_velP = gpsRescueConfig()->velP;
gpsRescueConfig_velI = gpsRescueConfig()->velI;
gpsRescueConfig_velD = gpsRescueConfig()->velD;
return 0;
}
static long cms_menuGpsRescuePidOnExit(const OSD_Entry *self)
{
UNUSED(self);
gpsRescueConfigMutable()->throttleP = gpsRescueConfig_throttleP;
gpsRescueConfigMutable()->throttleI = gpsRescueConfig_throttleI;
gpsRescueConfigMutable()->throttleD = gpsRescueConfig_throttleD;
gpsRescueConfigMutable()->yawP = gpsRescueConfig_yawP;
gpsRescueConfigMutable()->velP = gpsRescueConfig_velP;
gpsRescueConfigMutable()->velI = gpsRescueConfig_velI;
gpsRescueConfigMutable()->velD = gpsRescueConfig_velD;
return 0;
}
const OSD_Entry cms_menuGpsRescuePidEntries[] =
{
{"--- GPS RESCUE PID---", OME_Label, NULL, NULL, 0},
{ "THROTTLE P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleP, 0, 500, 1 }, 0 },
{ "THROTTLE I", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleI, 0, 500, 1 }, 0 },
{ "THROTTLE D", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleD, 0, 500, 1 }, 0 },
{ "YAW P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_yawP, 0, 500, 1 }, 0 },
{ "VELOCITY P", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velP, 0, 500, 1 }, 0 },
{ "VELOCITY I", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velI, 0, 500, 1 }, 0 },
{ "VELOCITY D", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_velD, 0, 500, 1 }, 0 },
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cms_menuGpsRescuePid = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUGPSRPID",
.GUARD_type = OME_MENU,
#endif
.onEnter = cms_menuGpsRescuePidOnEnter,
.onExit = cms_menuGpsRescuePidOnExit,
.entries = cms_menuGpsRescuePidEntries,
};
static long cmsx_menuGpsRescueOnEnter(void)
{
gpsRescueConfig_angle = gpsRescueConfig()->angle;
gpsRescueConfig_initialAltitudeM = gpsRescueConfig()->initialAltitudeM;
gpsRescueConfig_descentDistanceM = gpsRescueConfig()->descentDistanceM;
gpsRescueConfig_rescueGroundspeed = gpsRescueConfig()->rescueGroundspeed;
gpsRescueConfig_throttleMin = gpsRescueConfig()->throttleMin ;
gpsRescueConfig_throttleMax = gpsRescueConfig()->throttleMax;
gpsRescueConfig_throttleHover = gpsRescueConfig()->throttleHover;
gpsRescueConfig_minSats = gpsRescueConfig()->minSats;
gpsRescueConfig_minRescueDth = gpsRescueConfig()->minRescueDth;
gpsRescueConfig_allowArmingWithoutFix = gpsRescueConfig()->allowArmingWithoutFix;
return 0;
}
static long cmsx_menuGpsRescueOnExit(const OSD_Entry *self)
{
UNUSED(self);
gpsRescueConfigMutable()->angle = gpsRescueConfig_angle;
gpsRescueConfigMutable()->initialAltitudeM = gpsRescueConfig_initialAltitudeM;
gpsRescueConfigMutable()->descentDistanceM = gpsRescueConfig_descentDistanceM;
gpsRescueConfigMutable()->rescueGroundspeed = gpsRescueConfig_rescueGroundspeed;
gpsRescueConfigMutable()->throttleMin = gpsRescueConfig_throttleMin;
gpsRescueConfigMutable()->throttleMax = gpsRescueConfig_throttleMax;
gpsRescueConfigMutable()->throttleHover = gpsRescueConfig_throttleHover;
gpsRescueConfigMutable()->minSats = gpsRescueConfig_minSats;
gpsRescueConfigMutable()->minRescueDth = gpsRescueConfig_minRescueDth;
gpsRescueConfigMutable()->allowArmingWithoutFix = gpsRescueConfig_allowArmingWithoutFix;
return 0;
}
const OSD_Entry cmsx_menuGpsRescueEntries[] =
{
{"--- GPS RESCUE ---", OME_Label, NULL, NULL, 0},
{ "ANGLE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_angle, 0, 200 ,1 }, 0 },
{ "MIN DIST HOME M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_minRescueDth, 50, 1000 ,1 }, 0 },
{ "INITAL ALT M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_initialAltitudeM, 20, 100, 1 }, 0 },
{ "DESCENT DIST M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descentDistanceM, 30, 500, 1 }, 0 },
{ "GROUND SPEED C/M", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_rescueGroundspeed, 30, 3000, 1 }, 0 },
{ "THROTTLE MIN", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMin, 1000, 2000, 1 }, 0 },
{ "THROTTLE MAX", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMax, 1000, 2000, 1 }, 0 },
{ "THROTTLE HOV", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleHover, 1000, 2000, 1 }, 0 },
{ "ARM WITHOUT FIX", OME_Bool, NULL, &gpsRescueConfig_allowArmingWithoutFix, 0 },
{ "MIN SATELITES", OME_UINT8, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_minSats, 5, 50, 1 }, 0 },
{ "GPS RESCUE PID", OME_Submenu, cmsMenuChange, &cms_menuGpsRescuePid, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu cmsx_menuGpsRescue = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUGPSRES",
.GUARD_type = OME_MENU,
#endif
.onEnter = cmsx_menuGpsRescueOnEnter,
.onExit = cmsx_menuGpsRescueOnExit,
.entries = cmsx_menuGpsRescueEntries,
};
#endif

View file

@ -0,0 +1,23 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
extern CMS_Menu cmsx_menuGpsRescue;

View file

@ -122,6 +122,22 @@ typedef enum {
#define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */ #define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
#define PROSHOT_DMA_BUFFER_SIZE 6 /* resolution + frame reset (2us) */ #define PROSHOT_DMA_BUFFER_SIZE 6 /* resolution + frame reset (2us) */
#ifdef USE_DSHOT_TELEMETRY
#ifdef USE_DSHOT_TELEMETRY_STATS
#define DSHOT_TELEMETRY_QUALITY_WINDOW 1 // capture a rolling 1 second of packet stats
#define DSHOT_TELEMETRY_QUALITY_BUCKET_MS 100 // determines the granularity of the stats and the overall number of rolling buckets
#define DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT (DSHOT_TELEMETRY_QUALITY_WINDOW * 1000 / DSHOT_TELEMETRY_QUALITY_BUCKET_MS)
typedef struct dshotTelemetryQuality_s {
uint32_t packetCountSum;
uint32_t invalidCountSum;
uint32_t packetCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
uint32_t invalidCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
uint8_t lastBucketIndex;
} dshotTelemetryQuality_t;
#endif // USE_DSHOT_TELEMETRY_STATS
#endif // USE_DSHOT_TELEMETRY
typedef struct { typedef struct {
TIM_TypeDef *timer; TIM_TypeDef *timer;
#if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR) #if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR)
@ -153,6 +169,9 @@ typedef struct {
uint16_t dshotTelemetryValue; uint16_t dshotTelemetryValue;
timeDelta_t dshotTelemetryDeadtimeUs; timeDelta_t dshotTelemetryDeadtimeUs;
bool dshotTelemetryActive; bool dshotTelemetryActive;
#ifdef USE_DSHOT_TELEMETRY_STATS
dshotTelemetryQuality_t dshotTelemetryQuality;
#endif
#ifdef USE_HAL_DRIVER #ifdef USE_HAL_DRIVER
LL_TIM_OC_InitTypeDef ocInitStruct; LL_TIM_OC_InitTypeDef ocInitStruct;
LL_TIM_IC_InitTypeDef icInitStruct; LL_TIM_IC_InitTypeDef icInitStruct;
@ -261,6 +280,10 @@ bool pwmDshotCommandOutputIsEnabled(uint8_t motorCount);
uint16_t getDshotTelemetry(uint8_t index); uint16_t getDshotTelemetry(uint8_t index);
bool isDshotMotorTelemetryActive(uint8_t motorIndex); bool isDshotMotorTelemetryActive(uint8_t motorIndex);
void setDshotPidLoopTime(uint32_t pidLoopTime); void setDshotPidLoopTime(uint32_t pidLoopTime);
#ifdef USE_DSHOT_TELEMETRY_STATS
int16_t getDshotTelemetryMotorInvalidPercent(uint8_t motorIndex);
#endif
#endif #endif
#ifdef USE_BEEPER #ifdef USE_BEEPER

View file

@ -202,12 +202,34 @@ FAST_CODE void pwmDshotSetDirectionOutput(
); );
#ifdef USE_DSHOT_TELEMETRY #ifdef USE_DSHOT_TELEMETRY
#ifdef USE_DSHOT_TELEMETRY_STATS
void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool packetValid, timeMs_t currentTimeMs)
{
uint8_t statsBucketIndex = (currentTimeMs / DSHOT_TELEMETRY_QUALITY_BUCKET_MS) % DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT;
if (statsBucketIndex != qualityStats->lastBucketIndex) {
qualityStats->packetCountSum -= qualityStats->packetCountArray[statsBucketIndex];
qualityStats->invalidCountSum -= qualityStats->invalidCountArray[statsBucketIndex];
qualityStats->packetCountArray[statsBucketIndex] = 0;
qualityStats->invalidCountArray[statsBucketIndex] = 0;
qualityStats->lastBucketIndex = statsBucketIndex;
}
qualityStats->packetCountSum++;
qualityStats->packetCountArray[statsBucketIndex]++;
if (!packetValid) {
qualityStats->invalidCountSum++;
qualityStats->invalidCountArray[statsBucketIndex]++;
}
}
#endif // USE_DSHOT_TELEMETRY_STATS
bool pwmStartDshotMotorUpdate(uint8_t motorCount) bool pwmStartDshotMotorUpdate(uint8_t motorCount)
{ {
if (!useDshotTelemetry) { if (!useDshotTelemetry) {
return true; return true;
} }
#ifdef USE_DSHOT_TELEMETRY_STATS
const timeMs_t currentTimeMs = millis();
#endif
for (int i = 0; i < motorCount; i++) { for (int i = 0; i < motorCount; i++) {
if (dmaMotors[i].hasTelemetry) { if (dmaMotors[i].hasTelemetry) {
#ifdef STM32F7 #ifdef STM32F7
@ -223,12 +245,18 @@ bool pwmStartDshotMotorUpdate(uint8_t motorCount)
value = decodeDshotPacket(dmaMotors[i].dmaBuffer); value = decodeDshotPacket(dmaMotors[i].dmaBuffer);
} }
} }
#ifdef USE_DSHOT_TELEMETRY_STATS
bool validTelemetryPacket = false;
#endif
if (value != 0xffff) { if (value != 0xffff) {
dmaMotors[i].dshotTelemetryValue = value; dmaMotors[i].dshotTelemetryValue = value;
dmaMotors[i].dshotTelemetryActive = true; dmaMotors[i].dshotTelemetryActive = true;
if (i < 4) { if (i < 4) {
DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, i, value); DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, i, value);
} }
#ifdef USE_DSHOT_TELEMETRY_STATS
validTelemetryPacket = true;
#endif
} else { } else {
dshotInvalidPacketCount++; dshotInvalidPacketCount++;
if (i == 0) { if (i == 0) {
@ -236,6 +264,9 @@ bool pwmStartDshotMotorUpdate(uint8_t motorCount)
} }
} }
dmaMotors[i].hasTelemetry = false; dmaMotors[i].hasTelemetry = false;
#ifdef USE_DSHOT_TELEMETRY_STATS
updateDshotTelemetryQuality(&dmaMotors[i].dshotTelemetryQuality, validTelemetryPacket, currentTimeMs);
#endif
} else { } else {
timeDelta_t usSinceInput = cmpTimeUs(micros(), dmaMotors[i].timer->inputDirectionStampUs); timeDelta_t usSinceInput = cmpTimeUs(micros(), dmaMotors[i].timer->inputDirectionStampUs);
if (usSinceInput >= 0 && usSinceInput < dmaMotors[i].dshotTelemetryDeadtimeUs) { if (usSinceInput >= 0 && usSinceInput < dmaMotors[i].dshotTelemetryDeadtimeUs) {
@ -258,5 +289,22 @@ bool isDshotMotorTelemetryActive(uint8_t motorIndex)
return dmaMotors[motorIndex].dshotTelemetryActive; return dmaMotors[motorIndex].dshotTelemetryActive;
} }
#endif #ifdef USE_DSHOT_TELEMETRY_STATS
#endif int16_t getDshotTelemetryMotorInvalidPercent(uint8_t motorIndex)
{
int16_t invalidPercent = 0;
if (dmaMotors[motorIndex].dshotTelemetryActive) {
const uint32_t totalCount = dmaMotors[motorIndex].dshotTelemetryQuality.packetCountSum;
const uint32_t invalidCount = dmaMotors[motorIndex].dshotTelemetryQuality.invalidCountSum;
if (totalCount > 0) {
invalidPercent = lrintf(invalidCount * 10000.0f / totalCount);
}
} else {
invalidPercent = 10000; // 100.00%
}
return invalidPercent;
}
#endif // USE_DSHOT_TELEMETRY_STATS
#endif // USE_DSHOT_TELEMETRY
#endif // USE_DSHOT

View file

@ -52,6 +52,8 @@
#include "io/serial.h" #include "io/serial.h"
#include "io/gps.h" #include "io/gps.h"
#include "osd/osd.h"
#include "pg/beeper.h" #include "pg/beeper.h"
#include "pg/beeper_dev.h" #include "pg/beeper_dev.h"
#include "pg/rx.h" #include "pg/rx.h"
@ -463,6 +465,16 @@ static void validateAndFixConfig(void)
} }
#endif #endif
#if defined(USE_OSD)
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
const uint16_t t = osdConfig()->timers[i];
if (OSD_TIMER_SRC(t) >= OSD_TIMER_SRC_COUNT ||
OSD_TIMER_PRECISION(t) >= OSD_TIMER_PREC_COUNT) {
osdConfigMutable()->timers[i] = osdTimerDefault[i];
}
}
#endif
#if defined(TARGET_VALIDATECONFIG) #if defined(TARGET_VALIDATECONFIG)
targetValidateConfiguration(); targetValidateConfiguration();
#endif #endif

View file

@ -1104,6 +1104,15 @@ static FAST_CODE void subTaskMotorUpdate(timeUs_t currentTimeUs)
writeMotors(); writeMotors();
#ifdef USE_DSHOT_TELEMETRY_STATS
if (debugMode == DEBUG_DSHOT_RPM_ERRORS && useDshotTelemetry) {
const uint8_t motorCount = MIN(getMotorCount(), 4);
for (uint8_t i = 0; i < motorCount; i++) {
debug[i] = getDshotTelemetryMotorInvalidPercent(i);
}
}
#endif
DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime); DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime);
} }

View file

@ -94,7 +94,8 @@
const char * const osdTimerSourceNames[] = { const char * const osdTimerSourceNames[] = {
"ON TIME ", "ON TIME ",
"TOTAL ARM", "TOTAL ARM",
"LAST ARM " "LAST ARM ",
"ON/ARM "
}; };
// Things in both OSD and CMS // Things in both OSD and CMS
@ -121,6 +122,7 @@ static uint8_t osdProfile = 1;
static displayPort_t *osdDisplayPort; static displayPort_t *osdDisplayPort;
static bool suppressStatsDisplay = false; static bool suppressStatsDisplay = false;
static uint8_t osdStatsRowCount = 0;
#ifdef USE_ESC_SENSOR #ifdef USE_ESC_SENSOR
escSensorData_t *osdEscDataCombined; escSensorData_t *osdEscDataCombined;
@ -198,6 +200,11 @@ static void osdDrawElements(timeUs_t currentTimeUs)
osdDrawActiveElements(osdDisplayPort, currentTimeUs); osdDrawActiveElements(osdDisplayPort, currentTimeUs);
} }
const uint16_t osdTimerDefault[OSD_TIMER_COUNT] = {
OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10),
OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_SECOND, 10)
};
void pgResetFn_osdConfig(osdConfig_t *osdConfig) void pgResetFn_osdConfig(osdConfig_t *osdConfig)
{ {
// Position elements near centre of screen and disabled by default // Position elements near centre of screen and disabled by default
@ -234,13 +241,17 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
for (int i=0; i < OSD_WARNING_COUNT; i++) { for (int i=0; i < OSD_WARNING_COUNT; i++) {
osdWarnSetState(i, true); osdWarnSetState(i, true);
} }
// turn off RSSI & Link Quality warnings by default
osdWarnSetState(OSD_WARNING_RSSI, false);
osdWarnSetState(OSD_WARNING_LINK_QUALITY, false);
osdConfig->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10); osdConfig->timers[OSD_TIMER_1] = osdTimerDefault[OSD_TIMER_1];
osdConfig->timers[OSD_TIMER_2] = OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_SECOND, 10); osdConfig->timers[OSD_TIMER_2] = osdTimerDefault[OSD_TIMER_2];
osdConfig->overlay_radio_mode = 2; osdConfig->overlay_radio_mode = 2;
osdConfig->rssi_alarm = 20; osdConfig->rssi_alarm = 20;
osdConfig->link_quality_alarm = 80;
osdConfig->cap_alarm = 2200; osdConfig->cap_alarm = 2200;
osdConfig->alt_alarm = 100; // meters or feet depend on configuration osdConfig->alt_alarm = 100; // meters or feet depend on configuration
osdConfig->esc_temp_alarm = ESC_TEMP_ALARM_OFF; // off by default osdConfig->esc_temp_alarm = ESC_TEMP_ALARM_OFF; // off by default
@ -463,13 +474,26 @@ static bool isSomeStatEnabled(void)
// on the stats screen will have to be more beneficial than the hassle of not matching exactly to the // on the stats screen will have to be more beneficial than the hassle of not matching exactly to the
// configurator list. // configurator list.
static void osdShowStats(uint16_t endBatteryVoltage) static uint8_t osdShowStats(uint16_t endBatteryVoltage, int statsRowCount)
{ {
uint8_t top = 2; uint8_t top = 0;
char buff[OSD_ELEMENT_BUFFER_LENGTH]; char buff[OSD_ELEMENT_BUFFER_LENGTH];
bool displayLabel = false;
displayClearScreen(osdDisplayPort); // if statsRowCount is 0 then we're running an initial analysis of the active stats items
if (statsRowCount > 0) {
const int availableRows = osdDisplayPort->rows;
int displayRows = MIN(statsRowCount, availableRows);
if (statsRowCount < availableRows) {
displayLabel = true;
displayRows++;
}
top = (availableRows - displayRows) / 2; // center the stats vertically
}
if (displayLabel) {
displayWrite(osdDisplayPort, 2, top++, " --- STATS ---"); displayWrite(osdDisplayPort, 2, top++, " --- STATS ---");
}
if (osdStatGetState(OSD_STAT_RTC_DATE_TIME)) { if (osdStatGetState(OSD_STAT_RTC_DATE_TIME)) {
bool success = false; bool success = false;
@ -542,8 +566,7 @@ static void osdShowStats(uint16_t endBatteryVoltage)
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) { if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
if (osdStatGetState(OSD_STAT_MAX_CURRENT)) { if (osdStatGetState(OSD_STAT_MAX_CURRENT)) {
itoa(stats.max_current, buff, 10); tfp_sprintf(buff, "%d%c", stats.max_current, SYM_AMP);
strcat(buff, "A");
osdDisplayStatisticLabel(top++, "MAX CURRENT", buff); osdDisplayStatisticLabel(top++, "MAX CURRENT", buff);
} }
@ -626,6 +649,21 @@ static void osdShowStats(uint16_t endBatteryVoltage)
osdDisplayStatisticLabel(top++, "TOTAL DISTANCE", buff); osdDisplayStatisticLabel(top++, "TOTAL DISTANCE", buff);
} }
#endif #endif
return top;
}
static void osdRefreshStats(uint16_t endBatteryVoltage)
{
displayClearScreen(osdDisplayPort);
if (osdStatsRowCount == 0) {
// No stats row count has been set yet.
// Go through the logic one time to determine how many stats are actually displayed.
osdStatsRowCount = osdShowStats(endBatteryVoltage, 0);
// Then clear the screen and commence with normal stats display which will
// determine if the heading should be displayed and also center the content vertically.
displayClearScreen(osdDisplayPort);
}
osdShowStats(endBatteryVoltage, osdStatsRowCount);
} }
static void osdShowArmed(void) static void osdShowArmed(void)
@ -657,6 +695,7 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
osdStatsEnabled = true; osdStatsEnabled = true;
resumeRefreshAt = currentTimeUs + (60 * REFRESH_1S); resumeRefreshAt = currentTimeUs + (60 * REFRESH_1S);
endBatteryVoltage = getBatteryVoltage(); endBatteryVoltage = getBatteryVoltage();
osdStatsRowCount = 0; // reset to 0 so it will be recalculated on the next stats refresh
} }
armState = ARMING_FLAG(ARMED); armState = ARMING_FLAG(ARMED);
@ -684,7 +723,7 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
} }
if (currentTimeUs >= osdStatsRefreshTimeUs) { if (currentTimeUs >= osdStatsRefreshTimeUs) {
osdStatsRefreshTimeUs = currentTimeUs + REFRESH_1S; osdStatsRefreshTimeUs = currentTimeUs + REFRESH_1S;
osdShowStats(endBatteryVoltage); osdRefreshStats(endBatteryVoltage);
} }
} }
} }

View file

@ -26,7 +26,7 @@
#include "sensors/esc_sensor.h" #include "sensors/esc_sensor.h"
#define OSD_NUM_TIMER_TYPES 3 #define OSD_NUM_TIMER_TYPES 4
extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES]; extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
#define OSD_ELEMENT_BUFFER_LENGTH 32 #define OSD_ELEMENT_BUFFER_LENGTH 32
@ -183,6 +183,7 @@ typedef enum {
OSD_TIMER_SRC_ON, OSD_TIMER_SRC_ON,
OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_SRC_TOTAL_ARMED,
OSD_TIMER_SRC_LAST_ARMED, OSD_TIMER_SRC_LAST_ARMED,
OSD_TIMER_SRC_ON_OR_ARMED,
OSD_TIMER_SRC_COUNT OSD_TIMER_SRC_COUNT
} osd_timer_source_e; } osd_timer_source_e;
@ -206,6 +207,8 @@ typedef enum {
OSD_WARNING_LAUNCH_CONTROL, OSD_WARNING_LAUNCH_CONTROL,
OSD_WARNING_GPS_RESCUE_UNAVAILABLE, OSD_WARNING_GPS_RESCUE_UNAVAILABLE,
OSD_WARNING_GPS_RESCUE_DISABLED, OSD_WARNING_GPS_RESCUE_DISABLED,
OSD_WARNING_RSSI,
OSD_WARNING_LINK_QUALITY,
OSD_WARNING_COUNT // MUST BE LAST OSD_WARNING_COUNT // MUST BE LAST
} osdWarningsFlags_e; } osdWarningsFlags_e;
@ -218,6 +221,8 @@ STATIC_ASSERT(OSD_WARNING_COUNT <= 32, osdwarnings_overflow);
#define OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US 3000000 // 3 seconds #define OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US 3000000 // 3 seconds
extern const uint16_t osdTimerDefault[OSD_TIMER_COUNT];
typedef struct osdConfig_s { typedef struct osdConfig_s {
uint16_t item_pos[OSD_ITEM_COUNT]; uint16_t item_pos[OSD_ITEM_COUNT];
@ -241,6 +246,7 @@ typedef struct osdConfig_s {
uint8_t ahInvert; // invert the artificial horizon uint8_t ahInvert; // invert the artificial horizon
uint8_t osdProfileIndex; uint8_t osdProfileIndex;
uint8_t overlay_radio_mode; uint8_t overlay_radio_mode;
uint8_t link_quality_alarm;
} osdConfig_t; } osdConfig_t;
PG_DECLARE(osdConfig_t, osdConfig); PG_DECLARE(osdConfig_t, osdConfig);

View file

@ -296,6 +296,8 @@ static char osdGetTimerSymbol(osd_timer_source_e src)
case OSD_TIMER_SRC_TOTAL_ARMED: case OSD_TIMER_SRC_TOTAL_ARMED:
case OSD_TIMER_SRC_LAST_ARMED: case OSD_TIMER_SRC_LAST_ARMED:
return SYM_FLY_M; return SYM_FLY_M;
case OSD_TIMER_SRC_ON_OR_ARMED:
return ARMING_FLAG(ARMED) ? SYM_FLY_M : SYM_ON_M;
default: default:
return ' '; return ' ';
} }
@ -312,6 +314,8 @@ static timeUs_t osdGetTimerValue(osd_timer_source_e src)
statistic_t *stats = osdGetStats(); statistic_t *stats = osdGetStats();
return stats->armed_time; return stats->armed_time;
} }
case OSD_TIMER_SRC_ON_OR_ARMED:
return ARMING_FLAG(ARMED) ? osdFlyTime : micros();
default: default:
return 0; return 0;
} }
@ -674,7 +678,7 @@ static void osdElementFlymode(osdElementParms_t *element)
// 5. ACRO // 5. ACRO
if (FLIGHT_MODE(FAILSAFE_MODE)) { if (FLIGHT_MODE(FAILSAFE_MODE)) {
strcpy(element->buff, "!FS!"); strcpy(element->buff, "*FS*");
} else if (FLIGHT_MODE(GPS_RESCUE_MODE)) { } else if (FLIGHT_MODE(GPS_RESCUE_MODE)) {
strcpy(element->buff, "RESC"); strcpy(element->buff, "RESC");
} else if (FLIGHT_MODE(HEADFREE_MODE)) { } else if (FLIGHT_MODE(HEADFREE_MODE)) {
@ -846,8 +850,14 @@ static void osdElementMainBatteryUsage(osdElementParms_t *element)
static void osdElementMainBatteryVoltage(osdElementParms_t *element) static void osdElementMainBatteryVoltage(osdElementParms_t *element)
{ {
const int batteryVoltage = (getBatteryVoltage() + 5) / 10;
element->buff[0] = osdGetBatterySymbol(getBatteryAverageCellVoltage()); element->buff[0] = osdGetBatterySymbol(getBatteryAverageCellVoltage());
tfp_sprintf(element->buff + 1, "%2d.%02d%c", getBatteryVoltage() / 100, getBatteryVoltage() % 100, SYM_VOLT); if (batteryVoltage >= 100) {
tfp_sprintf(element->buff + 1, "%d.%d%c", batteryVoltage / 10, batteryVoltage % 10, SYM_VOLT);
} else {
tfp_sprintf(element->buff + 1, "%d.%d0%c", batteryVoltage / 10, batteryVoltage % 10, SYM_VOLT);
}
} }
static void osdElementMotorDiagnostics(osdElementParms_t *element) static void osdElementMotorDiagnostics(osdElementParms_t *element)
@ -1020,7 +1030,7 @@ static void osdElementVtxChannel(osdElementParms_t *element)
static void osdElementWarnings(osdElementParms_t *element) static void osdElementWarnings(osdElementParms_t *element)
{ {
#define OSD_WARNINGS_MAX_SIZE 11 #define OSD_WARNINGS_MAX_SIZE 12
#define OSD_FORMAT_MESSAGE_BUFFER_SIZE (OSD_WARNINGS_MAX_SIZE + 1) #define OSD_FORMAT_MESSAGE_BUFFER_SIZE (OSD_WARNINGS_MAX_SIZE + 1)
STATIC_ASSERT(OSD_FORMAT_MESSAGE_BUFFER_SIZE <= OSD_ELEMENT_BUFFER_LENGTH, osd_warnings_size_exceeds_buffer_size); STATIC_ASSERT(OSD_FORMAT_MESSAGE_BUFFER_SIZE <= OSD_ELEMENT_BUFFER_LENGTH, osd_warnings_size_exceeds_buffer_size);
@ -1112,6 +1122,22 @@ static void osdElementWarnings(osdElementParms_t *element)
} }
#endif // USE_LAUNCH_CONTROL #endif // USE_LAUNCH_CONTROL
// RSSI
if (osdWarnGetState(OSD_WARNING_RSSI) && (getRssiPercent() < osdConfig()->rssi_alarm)) {
osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "RSSI LOW");
SET_BLINK(OSD_WARNINGS);
return;
}
#ifdef USE_RX_LINK_QUALITY_INFO
// Link Quality
if (osdWarnGetState(OSD_WARNING_LINK_QUALITY) && (rxGetLinkQualityPercent() < osdConfig()->link_quality_alarm)) {
osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "LINK QUALITY");
SET_BLINK(OSD_WARNINGS);
return;
}
#endif // USE_RX_LINK_QUALITY_INFO
if (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL) && batteryState == BATTERY_CRITICAL) { if (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL) && batteryState == BATTERY_CRITICAL) {
osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " LAND NOW"); osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " LAND NOW");
SET_BLINK(OSD_WARNINGS); SET_BLINK(OSD_WARNINGS);
@ -1520,6 +1546,14 @@ void osdUpdateAlarms(void)
CLR_BLINK(OSD_RSSI_VALUE); CLR_BLINK(OSD_RSSI_VALUE);
} }
#ifdef USE_RX_LINK_QUALITY_INFO
if (rxGetLinkQualityPercent() < osdConfig()->link_quality_alarm) {
SET_BLINK(OSD_LINK_QUALITY);
} else {
CLR_BLINK(OSD_LINK_QUALITY);
}
#endif // USE_RX_LINK_QUALITY_INFO
if (getBatteryState() == BATTERY_OK) { if (getBatteryState() == BATTERY_OK) {
CLR_BLINK(OSD_MAIN_BATT_VOLTAGE); CLR_BLINK(OSD_MAIN_BATT_VOLTAGE);
CLR_BLINK(OSD_AVG_CELL_VOLTAGE); CLR_BLINK(OSD_AVG_CELL_VOLTAGE);

View file

@ -539,7 +539,7 @@ bool gyroInit(void)
} }
#if defined(USE_MULTI_GYRO) #if defined(USE_MULTI_GYRO)
if ((gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH && !(gyroDetectionFlags & DETECTED_BOTH_GYROS)) if ((gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH && !((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS))
|| (gyroToUse == GYRO_CONFIG_USE_GYRO_1 && !(gyroDetectionFlags & DETECTED_GYRO_1)) || (gyroToUse == GYRO_CONFIG_USE_GYRO_1 && !(gyroDetectionFlags & DETECTED_GYRO_1))
|| (gyroToUse == GYRO_CONFIG_USE_GYRO_2 && !(gyroDetectionFlags & DETECTED_GYRO_2))) { || (gyroToUse == GYRO_CONFIG_USE_GYRO_2 && !(gyroDetectionFlags & DETECTED_GYRO_2))) {
if (gyroDetectionFlags & DETECTED_GYRO_1) { if (gyroDetectionFlags & DETECTED_GYRO_1) {
@ -552,7 +552,7 @@ bool gyroInit(void)
} }
// Only allow using both gyros simultaneously if they are the same hardware type. // Only allow using both gyros simultaneously if they are the same hardware type.
if ((gyroDetectionFlags & DETECTED_BOTH_GYROS) && gyroSensor1.gyroDev.gyroHardware == gyroSensor2.gyroDev.gyroHardware) { if (((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS) && gyroSensor1.gyroDev.gyroHardware == gyroSensor2.gyroDev.gyroHardware) {
gyroDetectionFlags |= DETECTED_DUAL_GYROS; gyroDetectionFlags |= DETECTED_DUAL_GYROS;
} else if (gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) { } else if (gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
// If the user selected "BOTH" and they are not the same type, then reset to using only the first gyro. // If the user selected "BOTH" and they are not the same type, then reset to using only the first gyro.

View file

@ -258,17 +258,17 @@
#undef USE_GYRO_DATA_ANALYSE #undef USE_GYRO_DATA_ANALYSE
#endif #endif
#ifndef USE_DSHOT
#undef USE_DSHOT_TELEMETRY
#undef USE_RPM_FILTER
#endif
#ifndef USE_CMS #ifndef USE_CMS
#undef USE_CMS_FAILSAFE_MENU #undef USE_CMS_FAILSAFE_MENU
#endif #endif
#ifndef USE_DSHOT
#undef USE_DSHOT_TELEMETRY
#endif
#ifndef USE_DSHOT_TELEMETRY #ifndef USE_DSHOT_TELEMETRY
#undef USE_RPM_FILTER #undef USE_RPM_FILTER
#undef USE_DSHOT_TELEMETRY_STATS
#endif #endif
#if !defined(USE_BOARD_INFO) #if !defined(USE_BOARD_INFO)
@ -280,6 +280,10 @@
#undef USE_ACRO_TRAINER #undef USE_ACRO_TRAINER
#endif #endif
#if (!defined(USE_GPS_RESCUE) || !defined(USE_CMS_FAILSAFE_MENU))
#undef USE_CMS_GPS_RESCUE_MENU
#endif
#ifndef USE_BEEPER #ifndef USE_BEEPER
#undef BEEPER_PIN #undef BEEPER_PIN
#undef BEEPER_PWM_HZ #undef BEEPER_PWM_HZ

View file

@ -54,6 +54,7 @@
#endif #endif
#define USE_DSHOT #define USE_DSHOT
#define USE_DSHOT_TELEMETRY #define USE_DSHOT_TELEMETRY
#define USE_DSHOT_TELEMETRY_STATS
#define USE_RPM_FILTER #define USE_RPM_FILTER
#define I2C3_OVERCLOCK true #define I2C3_OVERCLOCK true
#define USE_GYRO_DATA_ANALYSE #define USE_GYRO_DATA_ANALYSE
@ -80,6 +81,7 @@
#define USE_FAST_RAM #define USE_FAST_RAM
#define USE_DSHOT #define USE_DSHOT
#define USE_DSHOT_TELEMETRY #define USE_DSHOT_TELEMETRY
#define USE_DSHOT_TELEMETRY_STATS
#define USE_RPM_FILTER #define USE_RPM_FILTER
#define I2C3_OVERCLOCK true #define I2C3_OVERCLOCK true
#define I2C4_OVERCLOCK true #define I2C4_OVERCLOCK true
@ -296,6 +298,8 @@
#define USE_ESCSERIAL_SIMONK #define USE_ESCSERIAL_SIMONK
#define USE_SERIAL_4WAY_SK_BOOTLOADER #define USE_SERIAL_4WAY_SK_BOOTLOADER
#define USE_CMS_FAILSAFE_MENU #define USE_CMS_FAILSAFE_MENU
#define USE_CMS_GPS_RESCUE_MENU
#define USE_SMART_FEEDFORWARD
#define USE_TELEMETRY_SENSORS_DISABLED_DETAILS #define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
// Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY // Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY
//#define USE_VTX_TABLE //#define USE_VTX_TABLE

View file

@ -20,6 +20,8 @@ TARGET_DIR = $(USER_DIR)/target
include $(ROOT)/make/system-id.mk include $(ROOT)/make/system-id.mk
include $(ROOT)/make/targets_list.mk include $(ROOT)/make/targets_list.mk
VPATH := $(VPATH):$(USER_DIR):$(TEST_DIR)
# specify which files that are included in the test in addition to the unittest file. # specify which files that are included in the test in addition to the unittest file.
# variables available: # variables available:
# <test_name>_SRC # <test_name>_SRC
@ -658,4 +660,3 @@ target_list:
@echo $(foreach target,$(ALT_TARGETS),$(target)\>$(call get_base_target,$(target))) @echo $(foreach target,$(ALT_TARGETS),$(target)\>$(call get_base_target,$(target)))
@echo ========== ALT/BASE FULL MAPPING ========== @echo ========== ALT/BASE FULL MAPPING ==========
@echo $(foreach target,$(VALID_TARGETS),$(target)\>$(call get_base_target,$(target))) @echo $(foreach target,$(VALID_TARGETS),$(target)\>$(call get_base_target,$(target)))

View file

@ -17,7 +17,6 @@
#include <stdint.h> #include <stdint.h>
#include <stdbool.h> #include <stdbool.h>
#include <stdio.h>
#include <limits.h> #include <limits.h>
@ -55,9 +54,12 @@ extern "C" {
void cliSet(char *cmdline); void cliSet(char *cmdline);
void cliGet(char *cmdline); void cliGet(char *cmdline);
int cliGetSettingIndex(char *name, uint8_t length);
const clivalue_t valueTable[] = { const clivalue_t valueTable[] = {
{ "array_unit_test", VAR_INT8 | MODE_ARRAY | MASTER_VALUE, .config.array.length = 3, PG_RESERVED_FOR_TESTING_1, 0 } { "array_unit_test", VAR_INT8 | MODE_ARRAY | MASTER_VALUE, .config.array.length = 3, PG_RESERVED_FOR_TESTING_1, 0 },
{ "str_unit_test", VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config.string = { 0, 16, 0 }, PG_RESERVED_FOR_TESTING_1, 0 },
{ "wos_unit_test", VAR_UINT8 | MODE_STRING | MASTER_VALUE, .config.string = { 0, 16, STRING_FLAGS_WRITEONCE }, PG_RESERVED_FOR_TESTING_1, 0 },
}; };
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable); const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
const lookupTableEntry_t lookupTables[] = {}; const lookupTableEntry_t lookupTables[] = {};
@ -87,21 +89,20 @@ extern "C" {
#include "unittest_macros.h" #include "unittest_macros.h"
#include "gtest/gtest.h" #include "gtest/gtest.h"
TEST(CLIUnittest, TestCliSet)
TEST(CLIUnittest, TestCliSetArray)
{ {
char *str = (char *)"array_unit_test = 123, -3 , 1";
cliSet(str);
cliSet((char *)"array_unit_test = 123, -3 , 1"); const uint16_t index = cliGetSettingIndex(str, 15);
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t cval = { const clivalue_t val = valueTable[index];
.name = "array_unit_test",
.type = MODE_ARRAY | MASTER_VALUE | VAR_INT8,
.pgn = PG_RESERVED_FOR_TESTING_1,
.offset = 0
};
printf("\n===============================\n"); printf("\n===============================\n");
int8_t *data = (int8_t *)cliGetValuePointer(&cval); int8_t *data = (int8_t *)cliGetValuePointer(&val);
for(int i=0; i<3; i++){ for(int i=0; i < val.config.array.length; i++){
printf("data[%d] = %d\n", i, data[i]); printf("data[%d] = %d\n", i, data[i]);
} }
printf("\n===============================\n"); printf("\n===============================\n");
@ -116,6 +117,82 @@ TEST(CLIUnittest, TestCliSet)
//EXPECT_EQ(false, false); //EXPECT_EQ(false, false);
} }
TEST(CLIUnittest, TestCliSetStringNoFlags)
{
char *str = (char *)"str_unit_test = SAMPLE";
cliSet(str);
const uint16_t index = cliGetSettingIndex(str, 13);
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
uint8_t *data = (uint8_t *)cliGetValuePointer(&val);
for(int i = 0; i < val.config.string.maxlength && data[i] != 0; i++){
printf("data[%d] = %d (%c)\n", i, data[i], data[i]);
}
printf("\n===============================\n");
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
}
TEST(CLIUnittest, TestCliSetStringWriteOnce)
{
char *str1 = (char *)"wos_unit_test = SAMPLE";
char *str2 = (char *)"wos_unit_test = ELPMAS";
cliSet(str1);
const uint16_t index = cliGetSettingIndex(str1, 13);
EXPECT_LT(index, valueTableEntryCount);
const clivalue_t val = valueTable[index];
printf("\n===============================\n");
uint8_t *data = (uint8_t *)cliGetValuePointer(&val);
for(int i = 0; i < val.config.string.maxlength && data[i] != 0; i++){
printf("data[%d] = %d (%c)\n", i, data[i], data[i]);
}
printf("\n===============================\n");
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
cliSet(str2);
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
cliSet(str1);
EXPECT_EQ('S', data[0]);
EXPECT_EQ('A', data[1]);
EXPECT_EQ('M', data[2]);
EXPECT_EQ('P', data[3]);
EXPECT_EQ('L', data[4]);
EXPECT_EQ('E', data[5]);
EXPECT_EQ(0, data[6]);
printf("\n");
}
// STUBS // STUBS
extern "C" { extern "C" {

View file

@ -517,7 +517,7 @@ TEST(OsdTest, TestAlarms)
printf("%d\n", i); printf("%d\n", i);
#endif #endif
displayPortTestBufferSubstring(8, 1, "%c99", SYM_RSSI); displayPortTestBufferSubstring(8, 1, "%c99", SYM_RSSI);
displayPortTestBufferSubstring(12, 1, "%c16.80%c", SYM_BATT_FULL, SYM_VOLT); displayPortTestBufferSubstring(12, 1, "%c16.8%c", SYM_BATT_FULL, SYM_VOLT);
displayPortTestBufferSubstring(1, 1, "%c00:", SYM_FLY_M); // only test the minute part of the timer displayPortTestBufferSubstring(1, 1, "%c00:", SYM_FLY_M); // only test the minute part of the timer
displayPortTestBufferSubstring(20, 1, "%c01:", SYM_ON_M); // only test the minute part of the timer displayPortTestBufferSubstring(20, 1, "%c01:", SYM_ON_M); // only test the minute part of the timer
displayPortTestBufferSubstring(23, 7, " .0%c", SYM_M); displayPortTestBufferSubstring(23, 7, " .0%c", SYM_M);
@ -546,7 +546,7 @@ TEST(OsdTest, TestAlarms)
#endif #endif
if (i % 2 == 0) { if (i % 2 == 0) {
displayPortTestBufferSubstring(8, 1, "%c12", SYM_RSSI); displayPortTestBufferSubstring(8, 1, "%c12", SYM_RSSI);
displayPortTestBufferSubstring(12, 1, "%c13.50%c", SYM_MAIN_BATT, SYM_VOLT); displayPortTestBufferSubstring(12, 1, "%c13.5%c", SYM_MAIN_BATT, SYM_VOLT);
displayPortTestBufferSubstring(1, 1, "%c01:", SYM_FLY_M); // only test the minute part of the timer displayPortTestBufferSubstring(1, 1, "%c01:", SYM_FLY_M); // only test the minute part of the timer
displayPortTestBufferSubstring(20, 1, "%c02:", SYM_ON_M); // only test the minute part of the timer displayPortTestBufferSubstring(20, 1, "%c02:", SYM_ON_M); // only test the minute part of the timer
displayPortTestBufferSubstring(23, 7, " 120.0%c", SYM_M); displayPortTestBufferSubstring(23, 7, " 120.0%c", SYM_M);

View file

@ -0,0 +1,140 @@
# Betaflight / STM32F405 (S405) 4.0.0 Apr 3 2019 / 14:30:44 (22b9f3453) MSP API: 1.41
board_name HGLRCF405
manufacturer_id HGLR
# resources
resource BEEPER 1 B04
resource MOTOR 1 B00
resource MOTOR 2 B01
resource MOTOR 3 A03
resource MOTOR 4 B05
resource PPM 1 B08
resource LED_STRIP 1 B06
resource SERIAL_TX 1 A09
resource SERIAL_TX 2 A02
resource SERIAL_TX 3 B10
resource SERIAL_TX 6 C06
resource SERIAL_RX 1 A10
resource SERIAL_RX 3 B11
resource SERIAL_RX 4 A01
resource SERIAL_RX 6 C07
resource I2C_SCL 1 B08
resource I2C_SDA 1 B09
resource LED 1 A08
resource SPI_SCK 1 A05
resource SPI_SCK 2 B13
resource SPI_SCK 3 C10
resource SPI_MISO 1 A06
resource SPI_MISO 2 B14
resource SPI_MISO 3 C11
resource SPI_MOSI 1 A07
resource SPI_MOSI 2 B15
resource SPI_MOSI 3 C12
resource ESCSERIAL 1 B08
resource CAMERA_CONTROL 1 B07
resource ADC_BATT 1 C02
resource ADC_RSSI 1 A00
resource ADC_CURR 1 C01
resource BARO_CS 1 B03
resource FLASH_CS 1 B12
resource OSD_CS 1 A15
resource GYRO_EXTI 1 C04
resource GYRO_CS 1 A04
resource GYRO_CS 2 C14
# timer
timer B00 1
timer B01 1
timer A03 0
timer B05 0
timer C08 1
timer C09 1
timer B06 0
timer B08 1
timer C06 1
timer C07 1
timer A09 0
timer A10 0
timer A01 1
timer A02 2
# dma
dma ADC 2 1
# ADC 2: DMA2 Stream 3 Channel 1
dma pin B00 0
# pin B00: DMA1 Stream 7 Channel 5
dma pin B01 0
# pin B01: DMA1 Stream 2 Channel 5
dma pin A03 1
# pin A03: DMA1 Stream 6 Channel 3
dma pin B05 0
# pin B05: DMA1 Stream 5 Channel 5
dma pin C08 0
# pin C08: DMA2 Stream 2 Channel 0
dma pin C09 0
# pin C09: DMA2 Stream 7 Channel 7
dma pin B06 0
# pin B06: DMA1 Stream 0 Channel 2
dma pin C06 0
# pin C06: DMA2 Stream 2 Channel 0
dma pin C07 0
# pin C07: DMA2 Stream 2 Channel 0
dma pin A09 0
# pin A09: DMA2 Stream 6 Channel 0
dma pin A10 0
# pin A10: DMA2 Stream 6 Channel 0
dma pin A01 0
# pin A01: DMA1 Stream 4 Channel 6
# master
set gyro_to_use = FIRST
set align_mag = DEFAULT
set mag_bustype = I2C
set mag_i2c_device = 1
set mag_i2c_address = 0
set mag_spi_device = 0
set baro_bustype = SPI
set baro_spi_device = 3
set baro_i2c_device = 0
set baro_i2c_address = 0
set rx_spi_bus = 0
set rx_spi_led_inversion = OFF
set adc_device = 2
set blackbox_device = SPIFLASH
set dshot_burst = OFF
set current_meter = ADC
set battery_meter = ADC
set ibata_scale = 400
set beeper_inversion = ON
set beeper_od = OFF
set beeper_frequency = 0
set sdcard_detect_inverted = OFF
set sdcard_mode = OFF
set sdcard_spi_bus = 0
set system_hse_mhz = 8
set max7456_clock = DEFAULT
set max7456_spi_bus = 3
set max7456_preinit_opu = OFF
set cc2500_spi_chip_detect = ON
set led_inversion = 0
set dashboard_i2c_bus = 1
set dashboard_i2c_addr = 60
set usb_msc_pin_pullup = ON
set flash_spi_bus = 2
set gyro_1_bustype = SPI
set gyro_1_spibus = 1
set gyro_1_i2cBus = 0
set gyro_1_i2c_address = 0
set gyro_1_sensor_align = CW180
set gyro_2_bustype = SPI
set gyro_2_spibus = 1
set gyro_2_i2cBus = 0
set gyro_2_i2c_address = 0
set gyro_2_sensor_align = CW0
set i2c1_pullup = OFF
set i2c1_overclock = ON
set i2c2_pullup = OFF
set i2c2_overclock = ON
set i2c3_pullup = OFF
set i2c3_overclock = ON

View file

@ -0,0 +1,142 @@
# Betaflight / STM32F745 (S745) 4.0.0 Apr 3 2019 / 14:32:23 (22b9f3453) MSP API: 1.41
board_name HGLRCF745
manufacturer_id HGLR
# resources
resource BEEPER 1 D15
resource MOTOR 1 B00
resource MOTOR 2 B01
resource MOTOR 3 E09
resource MOTOR 4 E11
resource PPM 1 A03
resource SONAR_TRIGGER 1 B10
resource SONAR_ECHO 1 B11
resource LED_STRIP 1 D12
resource SERIAL_TX 1 A09
resource SERIAL_TX 3 B10
resource SERIAL_TX 6 C06
resource SERIAL_RX 1 A10
resource SERIAL_RX 2 A03
resource SERIAL_RX 3 B11
resource SERIAL_RX 6 C07
resource SERIAL_RX 7 E07
resource LED 1 E00
resource SPI_SCK 1 A05
resource SPI_SCK 2 B13
resource SPI_SCK 3 C10
resource SPI_SCK 4 E02
resource SPI_MISO 1 A06
resource SPI_MISO 2 B14
resource SPI_MISO 3 C11
resource SPI_MISO 4 E05
resource SPI_MOSI 1 A07
resource SPI_MOSI 2 B15
resource SPI_MOSI 3 C12
resource SPI_MOSI 4 E06
resource ADC_BATT 1 C03
resource ADC_RSSI 1 C05
resource ADC_CURR 1 C02
resource BARO_CS 1 A01
resource SDCARD_CS 1 E04
resource SDCARD_DETECT 1 E03
resource OSD_CS 1 B12
resource GYRO_EXTI 1 D00
resource GYRO_EXTI 2 E08
resource GYRO_CS 1 A15
resource GYRO_CS 2 A04
resource USB_DETECT 1 C04
# timer
timer E13 0
timer B00 1
timer B01 1
timer E09 0
timer E11 0
timer D12 0
timer B10 0
timer B11 0
timer C06 1
timer C07 1
timer A03 0
timer A02 2
# dma
dma SPI_TX 4 0
# SPI_TX 4: DMA2 Stream 1 Channel 4
dma ADC 1 1
# ADC 1: DMA2 Stream 4 Channel 0
dma pin E13 1
# pin E13: DMA2 Stream 6 Channel 6
dma pin B00 0
# pin B00: DMA1 Stream 7 Channel 5
dma pin B01 0
# pin B01: DMA1 Stream 2 Channel 5
dma pin E09 2
# pin E09: DMA2 Stream 3 Channel 6
dma pin E11 1
# pin E11: DMA2 Stream 2 Channel 6
dma pin D12 0
# pin D12: DMA1 Stream 0 Channel 2
dma pin B10 0
# pin B10: DMA1 Stream 1 Channel 3
dma pin B11 0
# pin B11: DMA1 Stream 7 Channel 3
dma pin C06 0
# pin C06: DMA2 Stream 2 Channel 0
dma pin C07 1
# pin C07: DMA2 Stream 3 Channel 7
dma pin A03 0
# pin A03: DMA1 Stream 7 Channel 3
# master
set gyro_to_use = FIRST
set align_mag = DEFAULT
set mag_bustype = I2C
set mag_i2c_device = 2
set mag_i2c_address = 0
set mag_spi_device = 0
set baro_bustype = SPI
set baro_spi_device = 1
set baro_i2c_device = 0
set baro_i2c_address = 0
set adc_device = 1
set blackbox_device = SDCARD
set dshot_burst = OFF
set current_meter = ADC
set battery_meter = ADC
set ibata_scale = 400
set beeper_inversion = ON
set beeper_od = OFF
set beeper_frequency = 0
set sdcard_detect_inverted = ON
set sdcard_mode = SPI
set sdcard_spi_bus = 4
set system_hse_mhz = 8
set max7456_clock = DEFAULT
set max7456_spi_bus = 2
set max7456_preinit_opu = OFF
set led_inversion = 0
set dashboard_i2c_bus = 2
set dashboard_i2c_addr = 60
set usb_msc_pin_pullup = ON
set flash_spi_bus = 0
set gyro_1_bustype = SPI
set gyro_1_spibus = 3
set gyro_1_i2cBus = 0
set gyro_1_i2c_address = 0
set gyro_1_sensor_align = CW90
set gyro_2_bustype = SPI
set gyro_2_spibus = 1
set gyro_2_i2cBus = 0
set gyro_2_i2c_address = 0
set gyro_2_sensor_align = DEFAULT
set i2c1_pullup = OFF
set i2c1_overclock = ON
set i2c2_pullup = OFF
set i2c2_overclock = ON
set i2c3_pullup = OFF
set i2c3_overclock = ON
set i2c4_pullup = OFF
set i2c4_overclock = ON
set mco2_on_pc9 = OFF