1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 19:40:31 +03:00

Added calibration menu to CMS.

This commit is contained in:
mikeller 2019-11-16 12:24:49 +13:00 committed by Michael Keller
parent c6e5882dd9
commit cedcf2d7e2
41 changed files with 387 additions and 143 deletions

View file

@ -130,11 +130,12 @@ COMMON_SRC = \
blackbox/blackbox_io.c \
cms/cms.c \
cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \
cms/cms_menu_firmware.c \
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
cms/cms_menu_main.c \
cms/cms_menu_misc.c \
cms/cms_menu_osd.c \
cms/cms_menu_power.c \
@ -320,11 +321,12 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
msp/msp_serial.c \
cms/cms.c \
cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \
cms/cms_menu_firmware.c \
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
cms/cms_menu_main.c \
cms/cms_menu_misc.c \
cms/cms_menu_osd.c \
cms/cms_menu_power.c \

View file

@ -23,6 +23,7 @@
#include "common/utils.h"
#define FC_FIRMWARE_NAME "Betaflight"
#define FC_FIRMWARE_IDENTIFIER "BTFL"
#define FC_VERSION_MAJOR 4 // increment when a major release is made (big new feature, etc)
#define FC_VERSION_MINOR 2 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed

View file

@ -41,7 +41,7 @@
#include "build/version.h"
#include "cms/cms.h"
#include "cms/cms_menu_builtin.h"
#include "cms/cms_menu_main.h"
#include "cms/cms_menu_saveexit.h"
#include "cms/cms_types.h"
@ -394,15 +394,16 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
case OME_Submenu:
case OME_Funcall:
if (IS_PRINTVALUE(*flags)) {
buff[0]= 0x0;
if ((p->type == OME_Submenu) && p->func && (*flags & OPTSTRING)) {
if (p->type == OME_Submenu && p->func && *flags & OPTSTRING) {
// Special case of sub menu entry with optional value display.
char *str = ((CMSMenuOptFuncPtr)p->func)();
strncpy( buff, str, CMS_DRAW_BUFFER_LEN);
strncpy(buff, str, CMS_DRAW_BUFFER_LEN);
} else if (p->type == OME_Funcall && p->data) {
strncpy(buff, p->data, CMS_DRAW_BUFFER_LEN);
}
strncat(buff, ">", CMS_DRAW_BUFFER_LEN);
@ -526,7 +527,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
// Shouldn't happen. Notify creator of this menu content
#ifdef CMS_OSD_RIGHT_ALIGNED_VALUES
cnt = displayWrite(pDisplay, rightMenuColumn - 6, row, "BADENT");
#else.
#else
cnt = displayWrite(pDisplay, rightMenuColumn, row, "BADENT");
#endif
#endif
@ -536,6 +537,8 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
return cnt;
}
STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay); // Forward; will be resolved after merging
static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
{
if (!pageTop)
@ -572,8 +575,9 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
// Cursor manipulation
while ((pageTop + currentCtx.cursorRow)->type == OME_Label) // skip label
while ((pageTop + currentCtx.cursorRow)->type == OME_Label || (pageTop + currentCtx.cursorRow)->type == OME_String) { // skip labels and strings
currentCtx.cursorRow++;
}
cmsPageDebug();
@ -581,16 +585,27 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
room -= displayWrite(pDisplay, leftMenuColumn, top + pDisplay->cursorRow * linesPerMenuItem, " ");
}
if (room < 30)
if (room < 30) {
return;
}
if (pDisplay->cursorRow != currentCtx.cursorRow) {
room -= displayWrite(pDisplay, leftMenuColumn, top + currentCtx.cursorRow * linesPerMenuItem, ">");
pDisplay->cursorRow = currentCtx.cursorRow;
}
if (room < 30)
if (room < 30) {
return;
}
if (currentCtx.menu->onDisplayUpdate) {
long result = currentCtx.menu->onDisplayUpdate(pageTop + currentCtx.cursorRow);
if (result == MENU_CHAIN_BACK) {
cmsMenuBack(pDisplay);
return;
}
}
// Print text labels
for (i = 0, p = pageTop; (p <= pageTop + pageMaxRow); i++, p++) {
@ -599,9 +614,10 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
coloff += (p->type == OME_Label) ? 0 : 1;
room -= displayWrite(pDisplay, coloff, top + i * linesPerMenuItem, p->text);
CLR_PRINTLABEL(runtimeEntryFlags[i]);
if (room < 30)
if (room < 30) {
return;
}
}
// Print values
@ -625,8 +641,6 @@ static void cmsMenuCountPage(displayPort_t *pDisplay)
pageCount = (p - currentCtx.menu->entries - 1) / maxMenuItems + 1;
}
STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay); // Forward; will be resolved after merging
long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
{
const CMS_Menu *pMenu = (const CMS_Menu *)ptr;
@ -666,9 +680,12 @@ long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
currentCtx.menu = pMenu;
currentCtx.cursorRow = 0;
if (pMenu->onEnter && (pMenu->onEnter() == MENU_CHAIN_BACK)) {
if (pMenu->onEnter) {
long result = pMenu->onEnter();
if (result == MENU_CHAIN_BACK) {
return cmsMenuBack(pDisplay);
}
}
cmsMenuCountPage(pDisplay);
cmsPageSelect(pDisplay, 0);
@ -691,8 +708,11 @@ STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay)
{
// Let onExit function decide whether to allow exit or not.
if (currentCtx.menu->onExit && currentCtx.menu->onExit(pageTop + currentCtx.cursorRow) < 0) {
return -1;
if (currentCtx.menu->onExit) {
long result = currentCtx.menu->onExit(pageTop + currentCtx.cursorRow);
if (result < 0) {
return MENU_CHAIN_BACK;
}
}
if (!menuStackIdx) {
@ -717,7 +737,7 @@ void cmsMenuOpen(void)
if (!pCurrentDisplay)
return;
cmsInMenu = true;
currentCtx = (cmsCtx_t){ &menuMain, 0, 0 };
currentCtx = (cmsCtx_t){ &cmsx_menuMain, 0, 0 };
menuStackIdx = 0;
setArmingDisabled(ARMING_DISABLED_CMS_MENU);
displayLayerSelect(pCurrentDisplay, DISPLAYPORT_LAYER_FOREGROUND); // make sure the foreground layer is active
@ -783,7 +803,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
case CMS_POPUP_SAVE:
case CMS_POPUP_SAVEREBOOT:
cmsTraverseGlobalExit(&menuMain);
cmsTraverseGlobalExit(&cmsx_menuMain);
if (currentCtx.menu->onExit) {
currentCtx.menu->onExit((OSD_Entry *)NULL); // Forced exit
@ -1261,10 +1281,9 @@ static void cmsUpdate(uint32_t currentTimeUs)
void cmsHandler(timeUs_t currentTimeUs)
{
if (cmsDeviceCount < 0)
if (cmsDeviceCount < 0) {
return;
}
static timeUs_t lastCalledUs = 0;

View file

@ -222,6 +222,7 @@ CMS_Menu cmsx_menuBlackbox = {
.onEnter = cmsx_Blackbox_onEnter,
.onExit = cmsx_Blackbox_onExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuBlackboxEntries
};

View file

@ -92,6 +92,7 @@ CMS_Menu cmsx_menuFailsafe = {
.onEnter = cmsx_Failsafe_onEnter,
.onExit = cmsx_Failsafe_onExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuFailsafeEntries
};

View file

@ -0,0 +1,192 @@
/*
* 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/>.
*/
//
// Firmware related menu contents and support functions
//
#include <stdbool.h>
#include "platform.h"
#ifdef USE_CMS
#include "build/version.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "common/printf.h"
#include "config/config.h"
#include "drivers/system.h"
#include "fc/runtime_config.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/gyro.h"
#include "cms_menu_firmware.h"
// Calibration
#define CALIBRATION_STATUS_MAX_LENGTH 6
#define CALIBRATION_STATUS_OFF " --- "
#define CALIBRATION_STATUS_NOK " NOK "
#define CALIBRATION_STATUS_WAIT "WAIT "
#define CALIBRATION_STATUS_OK " OK "
static char gyroCalibrationStatus[CALIBRATION_STATUS_MAX_LENGTH];
#if defined(USE_ACC)
static char accCalibrationStatus[CALIBRATION_STATUS_MAX_LENGTH];
#endif
#if defined(USE_BARO)
static char baroCalibrationStatus[CALIBRATION_STATUS_MAX_LENGTH];
#endif
static long cmsx_CalibrationOnDisplayUpdate(const OSD_Entry *selected)
{
UNUSED(selected);
tfp_sprintf(gyroCalibrationStatus, sensors(SENSOR_GYRO) ? gyroIsCalibrationComplete() ? CALIBRATION_STATUS_OK : CALIBRATION_STATUS_WAIT: CALIBRATION_STATUS_OFF);
#if defined(USE_ACC)
tfp_sprintf(accCalibrationStatus, sensors(SENSOR_ACC) ? accIsCalibrationComplete() ? accHasBeenCalibrated() ? CALIBRATION_STATUS_OK : CALIBRATION_STATUS_NOK : CALIBRATION_STATUS_WAIT: CALIBRATION_STATUS_OFF);
#endif
#if defined(USE_BARO)
tfp_sprintf(baroCalibrationStatus, sensors(SENSOR_BARO) ? baroIsCalibrationComplete() ? CALIBRATION_STATUS_OK : CALIBRATION_STATUS_WAIT: CALIBRATION_STATUS_OFF);
#endif
return 0;
}
static long cmsCalibrateGyro(displayPort_t *pDisp, const void *self)
{
UNUSED(pDisp);
UNUSED(self);
if (sensors(SENSOR_GYRO)) {
gyroStartCalibration(false);
}
return 0;
}
#if defined(USE_ACC)
static long cmsCalibrateAcc(displayPort_t *pDisp, const void *self)
{
UNUSED(pDisp);
UNUSED(self);
if (sensors(SENSOR_ACC)) {
accStartCalibration();
}
return 0;
}
#endif
#if defined(USE_BARO)
static long cmsCalibrateBaro(displayPort_t *pDisp, const void *self)
{
UNUSED(pDisp);
UNUSED(self);
if (sensors(SENSOR_BARO)) {
baroStartCalibration();
}
return 0;
}
#endif
static const OSD_Entry menuCalibrationEntries[] = {
{ "--- CALIBRATE ---", OME_Label, NULL, NULL, 0 },
{ "GYRO", OME_Funcall, cmsCalibrateGyro, gyroCalibrationStatus, DYNAMIC },
#if defined(USE_ACC)
{ "ACC", OME_Funcall, cmsCalibrateAcc, accCalibrationStatus, DYNAMIC },
#endif
#if defined(USE_BARO)
{ "BARO", OME_Funcall, cmsCalibrateBaro, baroCalibrationStatus, DYNAMIC },
#endif
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu cmsx_menuCalibration = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUCALIBRATION",
.GUARD_type = OME_MENU,
#endif
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = cmsx_CalibrationOnDisplayUpdate,
.entries = menuCalibrationEntries
};
// Info
static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1];
static char infoTargetName[] = __TARGET__;
static long cmsx_FirmwareInit(void)
{
unsigned i;
for (i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
if (shortGitRevision[i] >= 'a' && shortGitRevision[i] <= 'f') {
infoGitRev[i] = shortGitRevision[i] - 'a' + 'A';
} else {
infoGitRev[i] = shortGitRevision[i];
}
}
infoGitRev[i] = 0x0; // Terminate string
return 0;
}
static const OSD_Entry menuFirmwareEntries[] = {
{ "--- INFO ---", OME_Label, NULL, NULL, 0 },
{ "FWID", OME_String, NULL, FC_FIRMWARE_IDENTIFIER, 0 },
{ "FWVER", OME_String, NULL, FC_VERSION_STRING, 0 },
{ "GITREV", OME_String, NULL, infoGitRev, 0 },
{ "TARGET", OME_String, NULL, infoTargetName, 0 },
{ "--- SETUP ---", OME_Label, NULL, NULL, 0 },
{ "CALIBRATE", OME_Submenu, cmsMenuChange, &cmsx_menuCalibration, 0},
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
CMS_Menu cmsx_menuFirmware = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUFIRMWARE",
.GUARD_type = OME_MENU,
#endif
.onEnter = cmsx_FirmwareInit,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = menuFirmwareEntries
};
#endif

View file

@ -0,0 +1,25 @@
/*
* 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
#include "cms/cms_types.h"
extern CMS_Menu cmsx_menuFirmware;

View file

@ -118,6 +118,7 @@ CMS_Menu cms_menuGpsRescuePid = {
.onEnter = cms_menuGpsRescuePidOnEnter,
.onExit = cms_menuGpsRescuePidOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cms_menuGpsRescuePidEntries,
};
@ -200,6 +201,7 @@ CMS_Menu cmsx_menuGpsRescue = {
.onEnter = cmsx_menuGpsRescueOnEnter,
.onExit = cmsx_menuGpsRescueOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuGpsRescueEntries,
};

View file

@ -224,6 +224,7 @@ static CMS_Menu cmsx_menuPid = {
.onEnter = cmsx_PidOnEnter,
.onExit = cmsx_PidWriteback,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuPidEntries
};
@ -291,6 +292,7 @@ static CMS_Menu cmsx_menuRateProfile = {
.onEnter = cmsx_RateProfileOnEnter,
.onExit = cmsx_RateProfileWriteback,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuRateProfileEntries
};
@ -350,6 +352,7 @@ static CMS_Menu cmsx_menuLaunchControl = {
.onEnter = cmsx_launchControlOnEnter,
.onExit = cmsx_launchControlOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuLaunchControlEntries,
};
#endif
@ -496,6 +499,7 @@ static CMS_Menu cmsx_menuProfileOther = {
.onEnter = cmsx_profileOtherOnEnter,
.onExit = cmsx_profileOtherOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuProfileOtherEntries,
};
@ -564,6 +568,7 @@ static CMS_Menu cmsx_menuFilterGlobal = {
.onEnter = cmsx_menuGyro_onEnter,
.onExit = cmsx_menuGyro_onExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuFilterGlobalEntries,
};
@ -652,6 +657,7 @@ static CMS_Menu cmsx_menuDynFilt = {
.onEnter = cmsx_menuDynFilt_onEnter,
.onExit = cmsx_menuDynFilt_onExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuDynFiltEntries,
};
@ -713,6 +719,7 @@ static CMS_Menu cmsx_menuFilterPerProfile = {
.onEnter = cmsx_FilterPerProfileRead,
.onExit = cmsx_FilterPerProfileWriteback,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuFilterPerProfileEntries,
};
@ -784,6 +791,7 @@ CMS_Menu cmsx_menuCopyProfile = {
.onEnter = cmsx_menuCopyProfile_onEnter,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuCopyProfileEntries,
};
@ -822,6 +830,7 @@ CMS_Menu cmsx_menuImu = {
.onEnter = cmsx_menuImu_onEnter,
.onExit = cmsx_menuImu_onExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuImuEntries,
};

View file

@ -128,6 +128,7 @@ CMS_Menu cmsx_menuLedstrip = {
.onEnter = cmsx_Ledstrip_OnEnter,
.onExit = cmsx_Ledstrip_OnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuLedstripEntries
};
#endif // LED_STRIP

View file

@ -19,20 +19,15 @@
*/
//
// Built-in menu contents and support functions
// Main menu structure and support functions
//
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef USE_CMS
#include "build/version.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
@ -41,6 +36,7 @@
#include "cms/cms_menu_imu.h"
#include "cms/cms_menu_blackbox.h"
#include "cms/cms_menu_failsafe.h"
#include "cms/cms_menu_firmware.h"
#include "cms/cms_menu_ledstrip.h"
#include "cms/cms_menu_misc.h"
#include "cms/cms_menu_osd.h"
@ -51,54 +47,10 @@
#include "cms/cms_menu_vtx_common.h"
#include "drivers/system.h"
#include "config/config.h"
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
#include "cms_menu_main.h"
#include "cms_menu_builtin.h"
// Info
static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1];
static char infoTargetName[] = __TARGET__;
static long cmsx_InfoInit(void)
{
int i;
for ( i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
if (shortGitRevision[i] >= 'a' && shortGitRevision[i] <= 'f')
infoGitRev[i] = shortGitRevision[i] - 'a' + 'A';
else
infoGitRev[i] = shortGitRevision[i];
}
infoGitRev[i] = 0x0; // Terminate string
return 0;
}
static const OSD_Entry menuInfoEntries[] = {
{ "--- INFO ---", OME_Label, NULL, NULL, 0 },
{ "FWID", OME_String, NULL, BETAFLIGHT_IDENTIFIER, 0 },
{ "FWVER", OME_String, NULL, FC_VERSION_STRING, 0 },
{ "GITREV", OME_String, NULL, infoGitRev, 0 },
{ "TARGET", OME_String, NULL, infoTargetName, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static CMS_Menu menuInfo = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUINFO",
.GUARD_type = OME_MENU,
#endif
.onEnter = cmsx_InfoInit,
.onExit = NULL,
.checkRedirect = NULL,
.entries = menuInfoEntries
};
// Features
@ -125,7 +77,7 @@ static const OSD_Entry menuFeaturesEntries[] =
{NULL, OME_END, NULL, NULL, 0}
};
static CMS_Menu menuFeatures = {
static CMS_Menu cmsx_menuFeatures = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUFEATURES",
.GUARD_type = OME_MENU,
@ -133,6 +85,7 @@ static CMS_Menu menuFeatures = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = menuFeaturesEntries,
};
@ -155,21 +108,17 @@ static const OSD_Entry menuMainEntries[] =
{"-- MAIN --", OME_Label, NULL, NULL, 0},
{"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0},
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
{"FEATURES", OME_Submenu, cmsMenuChange, &cmsx_menuFeatures, 0},
#ifdef USE_OSD
{"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd, 0},
#endif
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
{"FC&FIRMWARE", OME_Submenu, cmsMenuChange, &cmsx_menuFirmware, 0},
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0},
{"SAVE/EXIT", OME_Funcall, cmsx_SaveExitMenu, NULL, 0},
#ifdef CMS_MENU_DEBUG
{"ERR SAMPLE", OME_Submenu, cmsMenuChange, &menuInfoEntries[0], 0},
#endif
{NULL,OME_END, NULL, NULL, 0}
{NULL,OME_END, NULL, NULL, 0},
};
CMS_Menu menuMain = {
CMS_Menu cmsx_menuMain = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUMAIN",
.GUARD_type = OME_MENU,
@ -177,6 +126,7 @@ CMS_Menu menuMain = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = menuMainEntries,
};
#endif

View file

@ -22,4 +22,4 @@
#include "cms/cms_types.h"
extern CMS_Menu menuMain;
extern CMS_Menu cmsx_menuMain;

View file

@ -30,29 +30,32 @@
#include "build/debug.h"
#include "build/version.h"
#include "drivers/time.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_ledstrip.h"
#include "common/utils.h"
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/motor.h"
#include "pg/rx.h"
#include "config/config.h"
#include "config/feature.h"
#include "drivers/time.h"
#include "fc/rc_controls.h"
#include "flight/mixer.h"
#include "pg/motor.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/battery.h"
#include "cms_menu_misc.h"
//
// Misc
//
@ -94,6 +97,7 @@ CMS_Menu cmsx_menuRcPreview = {
.onEnter = NULL,
.onExit = cmsx_menuRcConfirmBack,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuRcEntries
};
@ -146,6 +150,7 @@ CMS_Menu cmsx_menuMisc = {
.onEnter = cmsx_menuMiscOnEnter,
.onExit = cmsx_menuMiscOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = menuMiscEntries
};

View file

@ -20,4 +20,6 @@
#pragma once
#include "cms_types.h"
extern CMS_Menu cmsx_menuMisc;

View file

@ -151,7 +151,7 @@ const OSD_Entry menuOsdActiveElemsEntries[] =
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu menuOsdActiveElems = {
static CMS_Menu menuOsdActiveElems = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUOSDACT",
.GUARD_type = OME_MENU,
@ -159,6 +159,7 @@ CMS_Menu menuOsdActiveElems = {
.onEnter = menuOsdActiveElemsOnEnter,
.onExit = menuOsdActiveElemsOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = menuOsdActiveElemsEntries
};
@ -216,7 +217,7 @@ const OSD_Entry menuAlarmsEntries[] =
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu menuAlarms = {
static CMS_Menu menuAlarms = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUALARMS",
.GUARD_type = OME_MENU,
@ -224,6 +225,7 @@ CMS_Menu menuAlarms = {
.onEnter = menuAlarmsOnEnter,
.onExit = menuAlarmsOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = menuAlarmsEntries,
};
@ -269,7 +271,7 @@ const OSD_Entry menuTimersEntries[] =
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu menuTimers = {
static CMS_Menu menuTimers = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUTIMERS",
.GUARD_type = OME_MENU,
@ -277,6 +279,7 @@ CMS_Menu menuTimers = {
.onEnter = menuTimersOnEnter,
.onExit = menuTimersOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = menuTimersEntries,
};
#endif /* USE_EXTENDED_CMS_MENUS */
@ -351,6 +354,7 @@ CMS_Menu cmsx_menuOsd = {
.onEnter = cmsx_menuOsdOnEnter,
.onExit = cmsx_menuOsdOnExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuOsdEntries
};
#endif // CMS

View file

@ -127,6 +127,7 @@ CMS_Menu cmsx_menuPower = {
.onEnter = cmsx_Power_onEnter,
.onExit = cmsx_Power_onExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuPowerEntries
};

View file

@ -52,6 +52,7 @@ CMS_Menu cmsx_menuSaveExit = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuSaveExitEntries
};
@ -72,6 +73,7 @@ CMS_Menu cmsx_menuSaveExitReboot = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuSaveExitRebootEntries
};

View file

@ -114,6 +114,7 @@ CMS_Menu cmsx_menuVtxRedirect = {
.onEnter = setStatusMessage,
.onExit = NULL,
.checkRedirect = vtxMenuRedirect,
.onDisplayUpdate = NULL,
.entries = vtxRedirectMenuEntries,
};

View file

@ -165,6 +165,7 @@ CMS_Menu cmsx_menuVtxRTC6705 = {
.onEnter = cmsx_Vtx_onEnter,
.onExit = cmsx_Vtx_onExit,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = cmsx_menuVtxEntries
};

View file

@ -417,6 +417,7 @@ static CMS_Menu saCmsMenuStats = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = saCmsMenuStatsEntries
};
#endif /* USE_EXTENDED_CMS_MENUS */
@ -615,6 +616,7 @@ static CMS_Menu saCmsMenuPORFreq =
.onEnter = saCmsSetPORFreqOnEnter,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = saCmsMenuPORFreqEntries,
};
@ -638,6 +640,7 @@ static CMS_Menu saCmsMenuUserFreq =
.onEnter = saCmsSetUserFreqOnEnter,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = saCmsMenuUserFreqEntries,
};
@ -666,6 +669,7 @@ static CMS_Menu saCmsMenuConfig = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = saCmsMenuConfigEntries
};
@ -686,6 +690,7 @@ static CMS_Menu saCmsMenuCommence = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = saCmsMenuCommenceEntries,
};
@ -759,6 +764,7 @@ CMS_Menu cmsx_menuVtxSmartAudio = {
.onEnter = sacms_SetupTopMenu,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = saCmsMenuOfflineEntries,
};

View file

@ -244,6 +244,7 @@ static CMS_Menu trampCmsMenuCommence = {
.onEnter = NULL,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = trampCmsMenuCommenceEntries,
};
@ -272,6 +273,7 @@ CMS_Menu cmsx_menuVtxTramp = {
.onEnter = trampCmsOnEnter,
.onExit = NULL,
.checkRedirect = NULL,
.onDisplayUpdate = NULL,
.entries = trampMenuEntries,
};
#endif

View file

@ -98,6 +98,8 @@ typedef long (*CMSMenuOnExitPtr)(const OSD_Entry *self);
typedef const void * (*CMSMenuCheckRedirectPtr)(void);
typedef long (*CMSMenuOnDisplayUpdatePtr)(const OSD_Entry *selected);
typedef struct
{
#ifdef CMS_MENU_DEBUG
@ -108,6 +110,7 @@ typedef struct
const CMSMenuFuncPtr onEnter;
const CMSMenuOnExitPtr onExit;
const CMSMenuCheckRedirectPtr checkRedirect;
const CMSMenuOnDisplayUpdatePtr onDisplayUpdate;
const OSD_Entry *entries;
} CMS_Menu;

View file

@ -276,6 +276,12 @@ static void validateAndFixConfig(void)
buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(1)->customAlignment, gyroDeviceConfig(1)->alignment);
#endif
if (accelerometerConfig()->accZero.values.roll != 0 ||
accelerometerConfig()->accZero.values.pitch != 0 ||
accelerometerConfig()->accZero.values.yaw != 0) {
accelerometerConfigMutable()->accZero.values.calibrationCompleted = 1;
}
if (!(featureIsConfigured(FEATURE_RX_PARALLEL_PWM) || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_SERIAL) || featureIsConfigured(FEATURE_RX_MSP) || featureIsConfigured(FEATURE_RX_SPI))) {
featureEnable(DEFAULT_RX_FEATURE);
}

View file

@ -177,15 +177,15 @@ PG_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig,
static bool isCalibrating(void)
{
return !isGyroCalibrationComplete()
return (sensors(SENSOR_GYRO) && !gyroIsCalibrationComplete())
#ifdef USE_ACC
|| (sensors(SENSOR_ACC) && !accIsCalibrationComplete())
#endif
#ifdef USE_BARO
|| (sensors(SENSOR_BARO) && !isBaroCalibrationComplete())
|| (sensors(SENSOR_BARO) && !baroIsCalibrationComplete())
#endif
#ifdef USE_MAG
|| (sensors(SENSOR_MAG) && !isCompassCalibrationComplete())
|| (sensors(SENSOR_MAG) && !compassIsCalibrationComplete())
#endif
;
}
@ -216,11 +216,7 @@ static bool accNeedsCalibration(void)
if (sensors(SENSOR_ACC)) {
// Check to see if the ACC has already been calibrated
if (accelerometerConfig()->accZero.values.calibrationCompleted ||
accelerometerConfig()->accZero.values.roll != 0 ||
accelerometerConfig()->accZero.values.pitch != 0 ||
accelerometerConfig()->accZero.values.yaw != 0) {
if (accHasBeenCalibrated()) {
return false;
}

View file

@ -109,7 +109,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
bool haveGpsAlt = false;
#ifdef USE_BARO
if (sensors(SENSOR_BARO)) {
if (!isBaroCalibrationComplete()) {
if (!baroIsCalibrationComplete()) {
performBaroCalibrationCycle();
} else {
baroAlt = baroCalculateAltitude();

View file

@ -261,7 +261,7 @@ static const emfat_entry_t entriesPredefined[] =
#ifdef USE_EMFAT_README
{ "readme.txt", false, 0, 1, 0, README_SIZE, 1024*1024, (long)readme_file, CMA, memory_read_proc, NULL, { 0 } },
#endif
{ "BTFL_ALL.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } },
{ FC_FIRMWARE_IDENTIFIER "_ALL.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } },
{ "PADDING.TXT", 0, ATTR_HIDDEN, 1, 0, 0, 0, 0, CMA, NULL, NULL, { 0 } },
};
@ -288,7 +288,7 @@ static void emfat_set_entry_cma(emfat_entry_t *entry)
static void emfat_add_log(emfat_entry_t *entry, int number, uint32_t offset, uint32_t size)
{
tfp_sprintf(logNames[number], "BTFL_%03d.BBL", number + 1);
tfp_sprintf(logNames[number], FC_FIRMWARE_IDENTIFIER "_%03d.BBL", number + 1);
entry->name = logNames[number];
entry->level = 1;
entry->offset = offset;

View file

@ -141,7 +141,7 @@
#include "msp.h"
static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
static const char * const flightControllerIdentifier = FC_FIRMWARE_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
enum {
MSP_REBOOT_FIRMWARE = 0,

View file

@ -68,7 +68,7 @@
#define MULTIWII_IDENTIFIER "MWII";
#define BASEFLIGHT_IDENTIFIER "BAFL";
#define BETAFLIGHT_IDENTIFIER "BTFL"
//#define BETAFLIGHT_IDENTIFIER "BTFL" Actual value stored in FC_FIRMWARE_IDENTIFIER in build/version.h
#define CLEANFLIGHT_IDENTIFIER "CLFL"
#define INAV_IDENTIFIER "INAV"
#define RACEFLIGHT_IDENTIFIER "RCFL"

View file

@ -99,6 +99,11 @@ static void setConfigCalibrationCompleted(void)
accelerometerConfigMutable()->accZero.values.calibrationCompleted = 1;
}
bool accHasBeenCalibrated(void)
{
return accelerometerConfig()->accZero.values.calibrationCompleted;
}
void accResetRollAndPitchTrims(void)
{
resetRollAndPitchTrims(&accelerometerConfigMutable()->accelerometerTrims);

View file

@ -79,6 +79,7 @@ PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
bool accInit(uint32_t gyroTargetLooptime);
bool accIsCalibrationComplete(void);
bool accHasBeenCalibrated(void);
void accStartCalibration(void);
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims);

View file

@ -275,7 +275,7 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
return true;
}
bool isBaroCalibrationComplete(void)
bool baroIsCalibrationComplete(void)
{
return calibratingB == 0;
}
@ -434,7 +434,7 @@ int32_t baroCalculateAltitude(void)
// calculates height from ground via baro readings
// see: https://github.com/diydrones/ardupilot/blob/master/libraries/AP_Baro/AP_Baro.cpp#L140
if (isBaroCalibrationComplete()) {
if (baroIsCalibrationComplete()) {
BaroAlt_tmp = lrintf((1.0f - pow_approx((float)(baroPressureSum / PRESSURE_SAMPLE_COUNT) / 101325.0f, 0.190259f)) * 4433000.0f); // in cm
BaroAlt_tmp -= baroGroundAltitude;
baro.BaroAlt = lrintf((float)baro.BaroAlt * CONVERT_PARAMETER_TO_FLOAT(barometerConfig()->baro_noise_lpf) + (float)BaroAlt_tmp * (1.0f - CONVERT_PARAMETER_TO_FLOAT(barometerConfig()->baro_noise_lpf))); // additional LPF to reduce baro noise
@ -453,11 +453,11 @@ void performBaroCalibrationCycle(void)
baroGroundPressure += baroPressureSum / PRESSURE_SAMPLE_COUNT;
baroGroundAltitude = (1.0f - pow_approx((baroGroundPressure / 8) / 101325.0f, 0.190259f)) * 4433000.0f;
if (baroGroundPressure == savedGroundPressure)
if (baroGroundPressure == savedGroundPressure) {
calibratingB = 0;
else {
} else {
calibratingB--;
savedGroundPressure=baroGroundPressure;
savedGroundPressure = baroGroundPressure;
}
}

View file

@ -63,7 +63,7 @@ extern baro_t baro;
void baroPreInit(void);
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse);
bool isBaroCalibrationComplete(void);
bool baroIsCalibrationComplete(void);
void baroStartCalibration(void);
void baroSetGroundLevel(void);
uint32_t baroUpdate(void);

View file

@ -332,7 +332,7 @@ void compassStartCalibration(void)
}
}
bool isCompassCalibrationComplete(void)
bool compassIsCalibrationComplete(void)
{
return tCal == 0;
}

View file

@ -68,5 +68,5 @@ void compassUpdate(timeUs_t currentTime);
bool compassInit(void);
void compassPreInit(void);
void compassStartCalibration(void);
bool isCompassCalibrationComplete(void);
bool compassIsCalibrationComplete(void);

View file

@ -119,7 +119,7 @@ typedef struct gyroCalibration_s {
int32_t cyclesRemaining;
} gyroCalibration_t;
bool firstArmingCalibrationWasStarted = false;
static bool firstArmingCalibrationWasStarted = false;
typedef struct gyroSensor_s {
gyroDev_t gyroDev;
@ -773,7 +773,7 @@ FAST_CODE bool isGyroSensorCalibrationComplete(const gyroSensor_t *gyroSensor)
return gyroSensor->calibration.cyclesRemaining == 0;
}
FAST_CODE bool isGyroCalibrationComplete(void)
FAST_CODE bool gyroIsCalibrationComplete(void)
{
switch (gyroToUse) {
default:
@ -819,7 +819,10 @@ static void gyroSetCalibrationCycles(gyroSensor_t *gyroSensor)
void gyroStartCalibration(bool isFirstArmingCalibration)
{
if (!(isFirstArmingCalibration && firstArmingCalibrationWasStarted)) {
if (isFirstArmingCalibration && firstArmingCalibrationWasStarted) {
return;
}
gyroSetCalibrationCycles(&gyroSensor1);
#ifdef USE_MULTI_GYRO
gyroSetCalibrationCycles(&gyroSensor2);
@ -828,12 +831,11 @@ void gyroStartCalibration(bool isFirstArmingCalibration)
if (isFirstArmingCalibration) {
firstArmingCalibrationWasStarted = true;
}
}
}
bool isFirstArmingGyroCalibrationRunning(void)
{
return firstArmingCalibrationWasStarted && !isGyroCalibrationComplete();
return firstArmingCalibrationWasStarted && !gyroIsCalibrationComplete();
}
STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t gyroMovementCalibrationThreshold)
@ -879,8 +881,8 @@ STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t
beeper(BEEPER_GYRO_CALIBRATED);
}
}
--gyroSensor->calibration.cyclesRemaining;
--gyroSensor->calibration.cyclesRemaining;
}
#if defined(USE_GYRO_SLEW_LIMITER)

View file

@ -167,7 +167,7 @@ struct mpuDetectionResult_s;
const struct mpuDetectionResult_s *gyroMpuDetectionResult(void);
void gyroStartCalibration(bool isFirstArmingCalibration);
bool isFirstArmingGyroCalibrationRunning(void);
bool isGyroCalibrationComplete(void);
bool gyroIsCalibrationComplete(void);
void gyroReadTemperature(void);
int16_t gyroGetTemperature(void);
int16_t gyroRateDps(int axis);

View file

@ -88,6 +88,7 @@ TEST(ArmingPreventionTest, CalibrationPowerOnGraceAngleThrottleArmSwitch)
// given
simulationTime = 0;
gyroCalibDone = false;
sensorsSet(SENSOR_GYRO);
// and
modeActivationConditionsMutable(0)->auxChannelIndex = 0;
@ -178,6 +179,7 @@ TEST(ArmingPreventionTest, ArmingGuardRadioLeftOnAndArmed)
// given
simulationTime = 0;
gyroCalibDone = false;
sensorsSet(SENSOR_GYRO);
// and
modeActivationConditionsMutable(0)->auxChannelIndex = 0;
@ -1036,8 +1038,8 @@ extern "C" {
void saveConfigAndNotify(void) {}
void blackboxFinish(void) {}
bool accIsCalibrationComplete(void) { return true; }
bool isBaroCalibrationComplete(void) { return true; }
bool isGyroCalibrationComplete(void) { return gyroCalibDone; }
bool baroIsCalibrationComplete(void) { return true; }
bool gyroIsCalibrationComplete(void) { return gyroCalibDone; }
void gyroStartCalibration(bool) {}
bool isFirstArmingGyroCalibrationRunning(void) { return false; }
void pidController(const pidProfile_t *, timeUs_t) {}
@ -1072,6 +1074,7 @@ extern "C" {
void transponderUpdate(timeUs_t) {}
void GPS_reset_home_position(void) {}
void accStartCalibration(void) {}
bool accHasBeenCalibrated(void) { return true; }
void baroSetGroundLevel(void) {}
void changePidProfile(uint8_t) {}
void changeControlRateProfile(uint8_t) {}
@ -1093,6 +1096,6 @@ extern "C" {
void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {}
bool isFixedWing(void) { return false; }
void compassStartCalibration(void) {}
bool isCompassCalibrationComplete(void) { return true; }
bool compassIsCalibrationComplete(void) { return true; }
bool isUpright(void) { return mockIsUpright; }
}

View file

@ -125,7 +125,7 @@ static OSD_Entry menuMainEntries[] =
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void*)0, 0},
{NULL, OME_END, NULL, NULL, 0}
};
CMS_Menu menuMain = {
CMS_Menu cmsx_menuMain = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUMAIN",
.GUARD_type = OME_MENU,

View file

@ -242,7 +242,7 @@ uint32_t millis(void) { return 0; }
uint32_t micros(void) { return 0; }
bool compassIsHealthy(void) { return true; }
bool isBaroCalibrationComplete(void) { return true; }
bool baroIsCalibrationComplete(void) { return true; }
void performBaroCalibrationCycle(void) {}
int32_t baroCalculateAltitude(void) { return 0; }
bool gyroGetAccumulationAverage(float *) { return false; }

View file

@ -100,8 +100,8 @@ TEST(SensorGyro, Calibrate)
EXPECT_EQ(9, gyroDevPtr->gyroZero[Y]);
EXPECT_EQ(10, gyroDevPtr->gyroZero[Z]);
gyroStartCalibration(false);
EXPECT_EQ(false, isGyroCalibrationComplete());
while (!isGyroCalibrationComplete()) {
EXPECT_EQ(false, gyroIsCalibrationComplete());
while (!gyroIsCalibrationComplete()) {
gyroDevPtr->readFn(gyroDevPtr);
performGyroCalibration(gyroSensorPtr, gyroMovementCalibrationThreshold);
}
@ -121,16 +121,16 @@ TEST(SensorGyro, Update)
gyroInit();
gyroDevPtr->readFn = fakeGyroRead;
gyroStartCalibration(false);
EXPECT_EQ(false, isGyroCalibrationComplete());
EXPECT_EQ(false, gyroIsCalibrationComplete());
timeUs_t currentTimeUs = 0;
fakeGyroSet(gyroDevPtr, 5, 6, 7);
gyroUpdate(currentTimeUs);
while (!isGyroCalibrationComplete()) {
while (!gyroIsCalibrationComplete()) {
fakeGyroSet(gyroDevPtr, 5, 6, 7);
gyroUpdate(currentTimeUs);
}
EXPECT_EQ(true, isGyroCalibrationComplete());
EXPECT_EQ(true, gyroIsCalibrationComplete());
EXPECT_EQ(5, gyroDevPtr->gyroZero[X]);
EXPECT_EQ(6, gyroDevPtr->gyroZero[Y]);
EXPECT_EQ(7, gyroDevPtr->gyroZero[Z]);

View file

@ -129,8 +129,9 @@ extern "C" {
void saveConfigAndNotify(void) {}
void blackboxFinish(void) {}
bool accIsCalibrationComplete(void) { return true; }
bool isBaroCalibrationComplete(void) { return true; }
bool isGyroCalibrationComplete(void) { return gyroCalibDone; }
bool accHasBeenCalibrated(void) { return true; }
bool baroIsCalibrationComplete(void) { return true; }
bool gyroIsCalibrationComplete(void) { return gyroCalibDone; }
void gyroStartCalibration(bool) {}
bool isFirstArmingGyroCalibrationRunning(void) { return false; }
void pidController(const pidProfile_t *, timeUs_t) {}
@ -180,6 +181,6 @@ extern "C" {
void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {}
bool isFixedWing(void) { return false; }
void compassStartCalibration(void) {}
bool isCompassCalibrationComplete(void) { return true; }
bool compassIsCalibrationComplete(void) { return true; }
bool isUpright(void) { return true; }
}