diff --git a/Makefile b/Makefile
index 06ff7c09a1..f89361dbb6 100644
--- a/Makefile
+++ b/Makefile
@@ -712,6 +712,7 @@ COMMON_SRC = \
fc/fc_dispatch.c \
fc/fc_hardfaults.c \
fc/fc_msp.c \
+ fc/fc_msp_box.c \
fc/fc_tasks.c \
fc/runtime_config.c \
io/beeper.c \
diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c
index 05a8e18f27..9479050cba 100644
--- a/src/main/blackbox/blackbox.c
+++ b/src/main/blackbox/blackbox.c
@@ -92,9 +92,6 @@ PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
#define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
#define SLOW_FRAME_INTERVAL 4096
-#define STATIC_ASSERT(condition, name ) \
- typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
-
// Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
#define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)
diff --git a/src/main/common/utils.h b/src/main/common/utils.h
index 001181977f..2cc6f3a443 100644
--- a/src/main/common/utils.h
+++ b/src/main/common/utils.h
@@ -55,6 +55,9 @@
#define UNUSED(x) (void)(x)
#endif
#define BUILD_BUG_ON(condition) ((void)sizeof(char[1 - 2*!!(condition)]))
+#define STATIC_ASSERT(condition, name) \
+ typedef char assert_failed_ ## name [(condition) ? 1 : -1 ] __attribute__((unused))
+
#define BIT(x) (1 << (x))
diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c
index 714359de58..5a90fbef0c 100644
--- a/src/main/drivers/sdcard.c
+++ b/src/main/drivers/sdcard.c
@@ -52,9 +52,6 @@
*/
#define SDCARD_NON_DMA_CHUNK_SIZE 256
-#define STATIC_ASSERT(condition, name ) \
- typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
-
typedef enum {
// In these states we run at the initialization 400kHz clockspeed:
SDCARD_STATE_NOT_PRESENT = 0,
diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c
index b8540b0960..736236f30d 100755
--- a/src/main/fc/cli.c
+++ b/src/main/fc/cli.c
@@ -84,10 +84,11 @@ extern uint8_t __config_end;
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/fc_core.h"
+#include "fc/fc_msp.h"
+#include "fc/fc_msp_box.h"
#include "fc/rc_adjustments.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
-#include "fc/fc_msp.h"
#include "flight/altitude.h"
#include "flight/failsafe.h"
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index e067605d94..7bc72d45bd 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -59,6 +59,7 @@
#include "fc/controlrate_profile.h"
#include "fc/fc_core.h"
#include "fc/fc_msp.h"
+#include "fc/fc_msp_box.h"
#include "fc/fc_rc.h"
#include "fc/rc_adjustments.h"
#include "fc/rc_controls.h"
@@ -113,56 +114,10 @@
#include "hardware_revision.h"
#endif
-#define STATIC_ASSERT(condition, name) \
- typedef char assert_failed_ ## name [(condition) ? 1 : -1 ] __attribute__((unused))
-
static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#ifndef USE_OSD_SLAVE
-// permanent IDs must uniquely identify BOX meaning, DO NOT REUSE THEM!
-static const box_t boxes[CHECKBOX_ITEM_COUNT] = {
- { BOXARM, "ARM", 0 },
- { BOXANGLE, "ANGLE", 1 },
- { BOXHORIZON, "HORIZON", 2 },
- { BOXBARO, "BARO", 3 },
- { BOXANTIGRAVITY, "ANTI GRAVITY", 4 },
- { BOXMAG, "MAG", 5 },
- { BOXHEADFREE, "HEADFREE", 6 },
- { BOXHEADADJ, "HEADADJ", 7 },
- { BOXCAMSTAB, "CAMSTAB", 8 },
- { BOXCAMTRIG, "CAMTRIG", 9 },
- { BOXGPSHOME, "GPS HOME", 10 },
- { BOXGPSHOLD, "GPS HOLD", 11 },
- { BOXPASSTHRU, "PASSTHRU", 12 },
- { BOXBEEPERON, "BEEPER", 13 },
- { BOXLEDMAX, "LEDMAX", 14 },
- { BOXLEDLOW, "LEDLOW", 15 },
- { BOXLLIGHTS, "LLIGHTS", 16 },
- { BOXCALIB, "CALIB", 17 },
- { BOXGOV, "GOVERNOR", 18 },
- { BOXOSD, "OSD DISABLE SW", 19 },
- { BOXTELEMETRY, "TELEMETRY", 20 },
- { BOXGTUNE, "GTUNE", 21 },
- { BOXSONAR, "SONAR", 22 },
- { BOXSERVO1, "SERVO1", 23 },
- { BOXSERVO2, "SERVO2", 24 },
- { BOXSERVO3, "SERVO3", 25 },
- { BOXBLACKBOX, "BLACKBOX", 26 },
- { BOXFAILSAFE, "FAILSAFE", 27 },
- { BOXAIRMODE, "AIR MODE", 28 },
- { BOX3DDISABLE, "DISABLE 3D", 29},
- { BOXFPVANGLEMIX, "FPV ANGLE MIX", 30},
- { BOXBLACKBOXERASE, "BLACKBOX ERASE (>30s)", 31 },
- { BOXCAMERA1, "CAMERA CONTROL 1", 32},
- { BOXCAMERA2, "CAMERA CONTROL 2", 33},
- { BOXCAMERA3, "CAMERA CONTROL 3", 34 },
- { BOXDSHOTREVERSE, "DSHOT REVERSE MOTORS", 35 },
-};
-
-// mask of enabled IDs, calculated on startup based on enabled features. boxId_e is used as bit index
-
-static boxBitmask_t activeBoxIds;
static const char pidnames[] =
"ROLL;"
@@ -189,7 +144,7 @@ typedef enum {
} mspSDCardFlags_e;
#define RATEPROFILE_MASK (1 << 7)
-#endif
+#endif //USE_OSD_SLAVE
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#define ESC_4WAY 0xff
@@ -248,7 +203,7 @@ static void mspFc4waySerialCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr
sbufWriteU8(dst, 0);
}
}
-#endif
+#endif //USE_SERIAL_4WAY_BLHELI_INTERFACE
static void mspRebootFn(serialPort_t *serialPort)
{
@@ -264,243 +219,6 @@ static void mspRebootFn(serialPort_t *serialPort)
}
#ifndef USE_OSD_SLAVE
-const box_t *findBoxByBoxId(boxId_e boxId)
-{
- for (unsigned i = 0; i < ARRAYLEN(boxes); i++) {
- const box_t *candidate = &boxes[i];
- if (candidate->boxId == boxId)
- return candidate;
- }
- return NULL;
-}
-
-const box_t *findBoxByPermanentId(uint8_t permanentId)
-{
- for (unsigned i = 0; i < ARRAYLEN(boxes); i++) {
- const box_t *candidate = &boxes[i];
- if (candidate->permanentId == permanentId)
- return candidate;
- }
- return NULL;
-}
-
-static bool activeBoxIdGet(boxId_e boxId)
-{
- if (boxId > sizeof(activeBoxIds) * 8)
- return false;
- return bitArrayGet(&activeBoxIds, boxId);
-}
-
-
-// callcack for box serialization
-typedef void serializeBoxFn(sbuf_t *dst, const box_t *box);
-
-static void serializeBoxNameFn(sbuf_t *dst, const box_t *box)
-{
- sbufWriteString(dst, box->boxName);
- sbufWriteU8(dst, ';');
-}
-
-static void serializeBoxPermanentIdFn(sbuf_t *dst, const box_t *box)
-{
- sbufWriteU8(dst, box->permanentId);
-}
-
-// serialize 'page' of boxNames.
-// Each page contains at most 32 boxes
-static void serializeBoxReply(sbuf_t *dst, int page, serializeBoxFn *serializeBox)
-{
- unsigned boxIdx = 0;
- unsigned pageStart = page * 32;
- unsigned pageEnd = pageStart + 32;
- for (boxId_e id = 0; id < CHECKBOX_ITEM_COUNT; id++) {
- if (activeBoxIdGet(id)) {
- if (boxIdx >= pageStart && boxIdx < pageEnd) {
- (*serializeBox)(dst, findBoxByBoxId(id));
- }
- boxIdx++; // count active boxes
- }
- }
-}
-
-void initActiveBoxIds(void)
-{
- // calculate used boxes based on features and set corresponding activeBoxIds bits
- boxBitmask_t ena; // temporary variable to collect result
- memset(&ena, 0, sizeof(ena));
-
- // macro to enable boxId (BoxidMaskEnable). Reference to ena is hidden, local use only
-#define BME(boxId) do { bitArraySet(&ena, boxId); } while (0)
- BME(BOXARM);
-
- if (!feature(FEATURE_AIRMODE)) {
- BME(BOXAIRMODE);
- }
-
- if (!feature(FEATURE_ANTI_GRAVITY)) {
- BME(BOXANTIGRAVITY);
- }
-
- if (sensors(SENSOR_ACC)) {
- BME(BOXANGLE);
- BME(BOXHORIZON);
- BME(BOXHEADFREE);
- BME(BOXHEADADJ);
- }
-
-#ifdef BARO
- if (sensors(SENSOR_BARO)) {
- BME(BOXBARO);
- }
-#endif
-
-#ifdef MAG
- if (sensors(SENSOR_MAG)) {
- BME(BOXMAG);
- }
-#endif
-
-#ifdef GPS
- if (feature(FEATURE_GPS)) {
- BME(BOXGPSHOME);
- BME(BOXGPSHOLD);
- }
-#endif
-
-#ifdef SONAR
- if (feature(FEATURE_SONAR)) {
- BME(BOXSONAR);
- }
-#endif
-
- BME(BOXFAILSAFE);
-
- if (mixerConfig()->mixerMode == MIXER_FLYING_WING || mixerConfig()->mixerMode == MIXER_AIRPLANE || mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) {
- BME(BOXPASSTHRU);
- }
-
- BME(BOXBEEPERON);
-
-#ifdef LED_STRIP
- if (feature(FEATURE_LED_STRIP)) {
- BME(BOXLEDLOW);
- }
-#endif
-
-#ifdef BLACKBOX
- BME(BOXBLACKBOX);
-#ifdef USE_FLASHFS
- BME(BOXBLACKBOXERASE);
-#endif
-#endif
-
- BME(BOXFPVANGLEMIX);
-
- if (feature(FEATURE_3D)) {
- BME(BOX3DDISABLE);
- }
-
- if (isMotorProtocolDshot()) {
- BME(BOXDSHOTREVERSE);
- }
-
- if (feature(FEATURE_SERVO_TILT)) {
- BME(BOXCAMSTAB);
- }
-
- if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
- BME(BOXCALIB);
- }
-
- BME(BOXOSD);
-
-#ifdef TELEMETRY
- if (feature(FEATURE_TELEMETRY) && telemetryConfig()->telemetry_switch) {
- BME(BOXTELEMETRY);
- }
-#endif
-
-#ifdef USE_SERVOS
- if (mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) {
- BME(BOXSERVO1);
- BME(BOXSERVO2);
- BME(BOXSERVO3);
- }
-#endif
-
-#ifdef USE_RCSPLIT
- BME(BOXCAMERA1);
- BME(BOXCAMERA2);
- BME(BOXCAMERA3);
-#endif
-
-#undef BME
- // check that all enabled IDs are in boxes array (check may be skipped when using findBoxById() functions)
- for (boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++)
- if (bitArrayGet(&ena, boxId)
- && findBoxByBoxId(boxId) == NULL)
- bitArrayClr(&ena, boxId); // this should not happen, but handle it gracefully
-
- activeBoxIds = ena; // set global variable
-}
-
-// pack used flightModeFlags into supplied array
-// returns number of bits used
-static int packFlightModeFlags(boxBitmask_t *mspFlightModeFlags)
-{
- // Serialize the flags in the order we delivered them, ignoring BOXNAMES and BOXINDEXES
- memset(mspFlightModeFlags, 0, sizeof(boxBitmask_t));
-
- // enabled BOXes, bits indexed by boxId_e
- boxBitmask_t boxEnabledMask;
- memset(&boxEnabledMask, 0, sizeof(boxEnabledMask));
-
- // enable BOXes dependent on FLIGHT_MODE, use mapping table (from runtime_config.h)
- // flightMode_boxId_map[HORIZON_MODE] == BOXHORIZON
- static const int8_t flightMode_boxId_map[] = FLIGHT_MODE_BOXID_MAP_INITIALIZER;
- flightModeFlags_e flightModeCopyMask = ~0; // only modes with bit set will be copied
- for (unsigned i = 0; i < ARRAYLEN(flightMode_boxId_map); i++) {
- if (flightMode_boxId_map[i] != -1 // boxId_e does exist for this FLIGHT_MODE
- && (flightModeCopyMask & (1 << i)) // this flightmode is copy is enabled
- && FLIGHT_MODE(1 << i)) { // this flightmode is active
- bitArraySet(&boxEnabledMask, flightMode_boxId_map[i]);
- }
- }
-
- // enable BOXes dependent on rcMode bits, indexes are the same.
- // only subset of BOXes depend on rcMode, use mask to select them
-#define BM(x) (1ULL << (x))
- // limited to 64 BOXes now to keep code simple
- const uint64_t rcModeCopyMask = BM(BOXHEADADJ) | BM(BOXCAMSTAB) | BM(BOXCAMTRIG) | BM(BOXBEEPERON)
- | BM(BOXLEDMAX) | BM(BOXLEDLOW) | BM(BOXLLIGHTS) | BM(BOXCALIB) | BM(BOXGOV) | BM(BOXOSD)
- | BM(BOXTELEMETRY) | BM(BOXGTUNE) | BM(BOXBLACKBOX) | BM(BOXBLACKBOXERASE) | BM(BOXAIRMODE)
- | BM(BOXANTIGRAVITY) | BM(BOXFPVANGLEMIX) | BM(BOXDSHOTREVERSE) | BM(BOX3DDISABLE);
- STATIC_ASSERT(sizeof(rcModeCopyMask) * 8 >= CHECKBOX_ITEM_COUNT, copy_mask_too_small_for_boxes);
- for (unsigned i = 0; i < CHECKBOX_ITEM_COUNT; i++) {
- if ((rcModeCopyMask & BM(i)) // mode copy is enabled
- && IS_RC_MODE_ACTIVE(i)) { // mode is active
- bitArraySet(&boxEnabledMask, i);
- }
- }
-#undef BM
- // copy ARM state
- if (ARMING_FLAG(ARMED))
- bitArraySet(&boxEnabledMask, BOXARM);
-
- // map boxId_e enabled bits to MSP status indexes
- // only active boxIds are sent in status over MSP, other bits are not counted
- unsigned mspBoxIdx = 0; // index of active boxId (matches sent permanentId and boxNames)
- for (boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++) {
- if (activeBoxIdGet(boxId)) {
- if (bitArrayGet(&boxEnabledMask, boxId))
- bitArraySet(mspFlightModeFlags, mspBoxIdx); // box is enabled
- mspBoxIdx++; // box is active, count it
- }
- }
- // return count of used bits
- return mspBoxIdx;
-}
-
static void serializeSDCardSummaryReply(sbuf_t *dst)
{
#ifdef USE_SDCARD
@@ -601,8 +319,8 @@ static void serializeDataflashReadReply(sbuf_t *dst, uint32_t address, const uin
}
}
}
-#endif
-#endif
+#endif // USE_FLASHFS
+#endif // USE_OSD_SLAVE
/*
* Returns true if the command was processd, false otherwise.
@@ -2391,18 +2109,13 @@ void mspFcProcessReply(mspPacket_t *reply)
}
}
-/*
- * Return a pointer to the process command function
- */
-#ifndef USE_OSD_SLAVE
-void mspFcInit(void)
-{
- initActiveBoxIds();
-}
-#endif
-
#ifdef USE_OSD_SLAVE
void mspOsdSlaveInit(void)
{
}
-#endif
+#else
+void mspFcInit(void)
+{
+ initActiveBoxIds();
+}
+#endif // USE_OSD_SLAVE
diff --git a/src/main/fc/fc_msp.h b/src/main/fc/fc_msp.h
index 92e0cc2647..3697100c0f 100644
--- a/src/main/fc/fc_msp.h
+++ b/src/main/fc/fc_msp.h
@@ -18,16 +18,6 @@
#pragma once
#include "msp/msp.h"
-#include "fc/rc_modes.h"
-
-typedef struct box_e {
- const uint8_t boxId; // see boxId_e
- const char *boxName; // GUI-readable box name
- const uint8_t permanentId; // permanent ID used to identify BOX. This ID is unique for one function, DO NOT REUSE IT
-} box_t;
-
-const box_t *findBoxByBoxId(boxId_e boxId);
-const box_t *findBoxByPermanentId(uint8_t permenantId);
void mspFcInit(void);
void mspOsdSlaveInit(void);
diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c
new file mode 100644
index 0000000000..e48e7eba15
--- /dev/null
+++ b/src/main/fc/fc_msp_box.c
@@ -0,0 +1,318 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it 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 is distributed in the hope that it 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 Cleanflight. If not, see .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#include "common/bitarray.h"
+#include "common/streambuf.h"
+#include "common/utils.h"
+
+#include "config/feature.h"
+
+#include "fc/config.h"
+#include "fc/fc_msp_box.h"
+#include "fc/runtime_config.h"
+
+#include "flight/mixer.h"
+
+#include "sensors/sensors.h"
+
+#include "telemetry/telemetry.h"
+
+
+#ifndef USE_OSD_SLAVE
+// permanent IDs must uniquely identify BOX meaning, DO NOT REUSE THEM!
+static const box_t boxes[CHECKBOX_ITEM_COUNT] = {
+ { BOXARM, "ARM", 0 },
+ { BOXANGLE, "ANGLE", 1 },
+ { BOXHORIZON, "HORIZON", 2 },
+ { BOXBARO, "BARO", 3 },
+ { BOXANTIGRAVITY, "ANTI GRAVITY", 4 },
+ { BOXMAG, "MAG", 5 },
+ { BOXHEADFREE, "HEADFREE", 6 },
+ { BOXHEADADJ, "HEADADJ", 7 },
+ { BOXCAMSTAB, "CAMSTAB", 8 },
+ { BOXCAMTRIG, "CAMTRIG", 9 },
+ { BOXGPSHOME, "GPS HOME", 10 },
+ { BOXGPSHOLD, "GPS HOLD", 11 },
+ { BOXPASSTHRU, "PASSTHRU", 12 },
+ { BOXBEEPERON, "BEEPER", 13 },
+ { BOXLEDMAX, "LEDMAX", 14 },
+ { BOXLEDLOW, "LEDLOW", 15 },
+ { BOXLLIGHTS, "LLIGHTS", 16 },
+ { BOXCALIB, "CALIB", 17 },
+ { BOXGOV, "GOVERNOR", 18 },
+ { BOXOSD, "OSD DISABLE SW", 19 },
+ { BOXTELEMETRY, "TELEMETRY", 20 },
+ { BOXGTUNE, "GTUNE", 21 },
+ { BOXSONAR, "SONAR", 22 },
+ { BOXSERVO1, "SERVO1", 23 },
+ { BOXSERVO2, "SERVO2", 24 },
+ { BOXSERVO3, "SERVO3", 25 },
+ { BOXBLACKBOX, "BLACKBOX", 26 },
+ { BOXFAILSAFE, "FAILSAFE", 27 },
+ { BOXAIRMODE, "AIR MODE", 28 },
+ { BOX3DDISABLE, "DISABLE 3D", 29},
+ { BOXFPVANGLEMIX, "FPV ANGLE MIX", 30},
+ { BOXBLACKBOXERASE, "BLACKBOX ERASE (>30s)", 31 },
+ { BOXCAMERA1, "CAMERA CONTROL 1", 32},
+ { BOXCAMERA2, "CAMERA CONTROL 2", 33},
+ { BOXCAMERA3, "CAMERA CONTROL 3", 34 },
+ { BOXDSHOTREVERSE, "DSHOT REVERSE MOTORS", 35 },
+};
+
+// mask of enabled IDs, calculated on startup based on enabled features. boxId_e is used as bit index
+
+static boxBitmask_t activeBoxIds;
+
+const box_t *findBoxByBoxId(boxId_e boxId)
+{
+ for (unsigned i = 0; i < ARRAYLEN(boxes); i++) {
+ const box_t *candidate = &boxes[i];
+ if (candidate->boxId == boxId)
+ return candidate;
+ }
+ return NULL;
+}
+
+const box_t *findBoxByPermanentId(uint8_t permanentId)
+{
+ for (unsigned i = 0; i < ARRAYLEN(boxes); i++) {
+ const box_t *candidate = &boxes[i];
+ if (candidate->permanentId == permanentId)
+ return candidate;
+ }
+ return NULL;
+}
+
+static bool activeBoxIdGet(boxId_e boxId)
+{
+ if (boxId > sizeof(activeBoxIds) * 8)
+ return false;
+ return bitArrayGet(&activeBoxIds, boxId);
+}
+
+void serializeBoxNameFn(sbuf_t *dst, const box_t *box)
+{
+ sbufWriteString(dst, box->boxName);
+ sbufWriteU8(dst, ';');
+}
+
+void serializeBoxPermanentIdFn(sbuf_t *dst, const box_t *box)
+{
+ sbufWriteU8(dst, box->permanentId);
+}
+
+// serialize 'page' of boxNames.
+// Each page contains at most 32 boxes
+void serializeBoxReply(sbuf_t *dst, int page, serializeBoxFn *serializeBox)
+{
+ unsigned boxIdx = 0;
+ unsigned pageStart = page * 32;
+ unsigned pageEnd = pageStart + 32;
+ for (boxId_e id = 0; id < CHECKBOX_ITEM_COUNT; id++) {
+ if (activeBoxIdGet(id)) {
+ if (boxIdx >= pageStart && boxIdx < pageEnd) {
+ (*serializeBox)(dst, findBoxByBoxId(id));
+ }
+ boxIdx++; // count active boxes
+ }
+ }
+}
+
+void initActiveBoxIds(void)
+{
+ // calculate used boxes based on features and set corresponding activeBoxIds bits
+ boxBitmask_t ena; // temporary variable to collect result
+ memset(&ena, 0, sizeof(ena));
+
+ // macro to enable boxId (BoxidMaskEnable). Reference to ena is hidden, local use only
+#define BME(boxId) do { bitArraySet(&ena, boxId); } while (0)
+ BME(BOXARM);
+
+ if (!feature(FEATURE_AIRMODE)) {
+ BME(BOXAIRMODE);
+ }
+
+ if (!feature(FEATURE_ANTI_GRAVITY)) {
+ BME(BOXANTIGRAVITY);
+ }
+
+ if (sensors(SENSOR_ACC)) {
+ BME(BOXANGLE);
+ BME(BOXHORIZON);
+ BME(BOXHEADFREE);
+ BME(BOXHEADADJ);
+ }
+
+#ifdef BARO
+ if (sensors(SENSOR_BARO)) {
+ BME(BOXBARO);
+ }
+#endif
+
+#ifdef MAG
+ if (sensors(SENSOR_MAG)) {
+ BME(BOXMAG);
+ }
+#endif
+
+#ifdef GPS
+ if (feature(FEATURE_GPS)) {
+ BME(BOXGPSHOME);
+ BME(BOXGPSHOLD);
+ }
+#endif
+
+#ifdef SONAR
+ if (feature(FEATURE_SONAR)) {
+ BME(BOXSONAR);
+ }
+#endif
+
+ BME(BOXFAILSAFE);
+
+ if (mixerConfig()->mixerMode == MIXER_FLYING_WING || mixerConfig()->mixerMode == MIXER_AIRPLANE || mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) {
+ BME(BOXPASSTHRU);
+ }
+
+ BME(BOXBEEPERON);
+
+#ifdef LED_STRIP
+ if (feature(FEATURE_LED_STRIP)) {
+ BME(BOXLEDLOW);
+ }
+#endif
+
+#ifdef BLACKBOX
+ BME(BOXBLACKBOX);
+#ifdef USE_FLASHFS
+ BME(BOXBLACKBOXERASE);
+#endif
+#endif
+
+ BME(BOXFPVANGLEMIX);
+
+ if (feature(FEATURE_3D)) {
+ BME(BOX3DDISABLE);
+ }
+
+ if (isMotorProtocolDshot()) {
+ BME(BOXDSHOTREVERSE);
+ }
+
+ if (feature(FEATURE_SERVO_TILT)) {
+ BME(BOXCAMSTAB);
+ }
+
+ if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
+ BME(BOXCALIB);
+ }
+
+ BME(BOXOSD);
+
+#ifdef TELEMETRY
+ if (feature(FEATURE_TELEMETRY) && telemetryConfig()->telemetry_switch) {
+ BME(BOXTELEMETRY);
+ }
+#endif
+
+#ifdef USE_SERVOS
+ if (mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) {
+ BME(BOXSERVO1);
+ BME(BOXSERVO2);
+ BME(BOXSERVO3);
+ }
+#endif
+
+#ifdef USE_RCSPLIT
+ BME(BOXCAMERA1);
+ BME(BOXCAMERA2);
+ BME(BOXCAMERA3);
+#endif
+
+#undef BME
+ // check that all enabled IDs are in boxes array (check may be skipped when using findBoxById() functions)
+ for (boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++)
+ if (bitArrayGet(&ena, boxId)
+ && findBoxByBoxId(boxId) == NULL)
+ bitArrayClr(&ena, boxId); // this should not happen, but handle it gracefully
+
+ activeBoxIds = ena; // set global variable
+}
+
+// pack used flightModeFlags into supplied array
+// returns number of bits used
+int packFlightModeFlags(boxBitmask_t *mspFlightModeFlags)
+{
+ // Serialize the flags in the order we delivered them, ignoring BOXNAMES and BOXINDEXES
+ memset(mspFlightModeFlags, 0, sizeof(boxBitmask_t));
+
+ // enabled BOXes, bits indexed by boxId_e
+ boxBitmask_t boxEnabledMask;
+ memset(&boxEnabledMask, 0, sizeof(boxEnabledMask));
+
+ // enable BOXes dependent on FLIGHT_MODE, use mapping table (from runtime_config.h)
+ // flightMode_boxId_map[HORIZON_MODE] == BOXHORIZON
+ static const int8_t flightMode_boxId_map[] = FLIGHT_MODE_BOXID_MAP_INITIALIZER;
+ flightModeFlags_e flightModeCopyMask = ~0; // only modes with bit set will be copied
+ for (unsigned i = 0; i < ARRAYLEN(flightMode_boxId_map); i++) {
+ if (flightMode_boxId_map[i] != -1 // boxId_e does exist for this FLIGHT_MODE
+ && (flightModeCopyMask & (1 << i)) // this flightmode is copy is enabled
+ && FLIGHT_MODE(1 << i)) { // this flightmode is active
+ bitArraySet(&boxEnabledMask, flightMode_boxId_map[i]);
+ }
+ }
+
+ // enable BOXes dependent on rcMode bits, indexes are the same.
+ // only subset of BOXes depend on rcMode, use mask to select them
+#define BM(x) (1ULL << (x))
+ // limited to 64 BOXes now to keep code simple
+ const uint64_t rcModeCopyMask = BM(BOXHEADADJ) | BM(BOXCAMSTAB) | BM(BOXCAMTRIG) | BM(BOXBEEPERON)
+ | BM(BOXLEDMAX) | BM(BOXLEDLOW) | BM(BOXLLIGHTS) | BM(BOXCALIB) | BM(BOXGOV) | BM(BOXOSD)
+ | BM(BOXTELEMETRY) | BM(BOXGTUNE) | BM(BOXBLACKBOX) | BM(BOXBLACKBOXERASE) | BM(BOXAIRMODE)
+ | BM(BOXANTIGRAVITY) | BM(BOXFPVANGLEMIX) | BM(BOXDSHOTREVERSE) | BM(BOX3DDISABLE);
+ STATIC_ASSERT(sizeof(rcModeCopyMask) * 8 >= CHECKBOX_ITEM_COUNT, copy_mask_too_small_for_boxes);
+ for (unsigned i = 0; i < CHECKBOX_ITEM_COUNT; i++) {
+ if ((rcModeCopyMask & BM(i)) // mode copy is enabled
+ && IS_RC_MODE_ACTIVE(i)) { // mode is active
+ bitArraySet(&boxEnabledMask, i);
+ }
+ }
+#undef BM
+ // copy ARM state
+ if (ARMING_FLAG(ARMED))
+ bitArraySet(&boxEnabledMask, BOXARM);
+
+ // map boxId_e enabled bits to MSP status indexes
+ // only active boxIds are sent in status over MSP, other bits are not counted
+ unsigned mspBoxIdx = 0; // index of active boxId (matches sent permanentId and boxNames)
+ for (boxId_e boxId = 0; boxId < CHECKBOX_ITEM_COUNT; boxId++) {
+ if (activeBoxIdGet(boxId)) {
+ if (bitArrayGet(&boxEnabledMask, boxId))
+ bitArraySet(mspFlightModeFlags, mspBoxIdx); // box is enabled
+ mspBoxIdx++; // box is active, count it
+ }
+ }
+ // return count of used bits
+ return mspBoxIdx;
+}
+#endif // USE_OSD_SLAVE
diff --git a/src/main/fc/fc_msp_box.h b/src/main/fc/fc_msp_box.h
new file mode 100644
index 0000000000..c1497a7409
--- /dev/null
+++ b/src/main/fc/fc_msp_box.h
@@ -0,0 +1,39 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it 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 is distributed in the hope that it 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 Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#include "fc/rc_modes.h"
+
+typedef struct box_s {
+ const uint8_t boxId; // see boxId_e
+ const char *boxName; // GUI-readable box name
+ const uint8_t permanentId; // permanent ID used to identify BOX. This ID is unique for one function, DO NOT REUSE IT
+} box_t;
+
+const box_t *findBoxByBoxId(boxId_e boxId);
+const box_t *findBoxByPermanentId(uint8_t permanentId);
+
+struct boxBitmask_s;
+int packFlightModeFlags(struct boxBitmask_s *mspFlightModeFlags);
+struct sbuf_s;
+void serializeBoxNameFn(struct sbuf_s *dst, const box_t *box);
+void serializeBoxPermanentIdFn(struct sbuf_s *dst, const box_t *box);
+typedef void serializeBoxFn(struct sbuf_s *dst, const box_t *box);
+void serializeBoxReply(struct sbuf_s *dst, int page, serializeBoxFn *serializeBox);
+void initActiveBoxIds(void);
+
diff --git a/src/main/fc/rc_modes.h b/src/main/fc/rc_modes.h
index 400f370a54..d4495e3e69 100644
--- a/src/main/fc/rc_modes.h
+++ b/src/main/fc/rc_modes.h
@@ -62,7 +62,7 @@ typedef enum {
} boxId_e;
// type to hold enough bits for CHECKBOX_ITEM_COUNT. Struct used for value-like behavior
-typedef struct { uint32_t bits[(CHECKBOX_ITEM_COUNT + 31) / 32]; } boxBitmask_t;
+typedef struct boxBitmask_s { uint32_t bits[(CHECKBOX_ITEM_COUNT + 31) / 32]; } boxBitmask_t;
#define MAX_MODE_ACTIVATION_CONDITION_COUNT 20
diff --git a/src/main/io/rcsplit.c b/src/main/io/rcsplit.c
index bf6b8ac646..ce195cd906 100644
--- a/src/main/io/rcsplit.c
+++ b/src/main/io/rcsplit.c
@@ -27,21 +27,23 @@
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
+#include "drivers/serial.h"
+
#include "fc/rc_controls.h"
+#include "fc/rc_modes.h"
#include "io/beeper.h"
+#include "io/rcsplit.h"
#include "io/serial.h"
#include "scheduler/scheduler.h"
-#include "drivers/serial.h"
-
-#include "io/rcsplit.h"
// communicate with camera device variables
-serialPort_t *rcSplitSerialPort = NULL;
-rcsplitSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
-rcsplitState_e cameraState = RCSPLIT_STATE_UNKNOWN;
+STATIC_UNIT_TESTED serialPort_t *rcSplitSerialPort = NULL;
+STATIC_UNIT_TESTED rcsplitState_e cameraState = RCSPLIT_STATE_UNKNOWN;
+// only for unit test
+STATIC_UNIT_TESTED rcsplitSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
static uint8_t crc_high_first(uint8_t *ptr, uint8_t len)
{
diff --git a/src/main/io/rcsplit.h b/src/main/io/rcsplit.h
index 85b4d347a6..56f0efb913 100644
--- a/src/main/io/rcsplit.h
+++ b/src/main/io/rcsplit.h
@@ -48,8 +48,3 @@ typedef enum {
bool rcSplitInit(void);
void rcSplitProcess(timeUs_t currentTimeUs);
-
-// only for unit test
-extern rcsplitState_e cameraState;
-extern serialPort_t *rcSplitSerialPort;
-extern rcsplitSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
diff --git a/src/test/unit/cli_unittest.cc b/src/test/unit/cli_unittest.cc
index 565023837d..1738f62eac 100644
--- a/src/test/unit/cli_unittest.cc
+++ b/src/test/unit/cli_unittest.cc
@@ -28,6 +28,7 @@ extern "C" {
#include "target.h"
#include "fc/runtime_config.h"
#include "fc/fc_msp.h"
+ #include "fc/fc_msp_box.h"
#include "config/parameter_group.h"
#include "config/feature.h"
#include "config/parameter_group_ids.h"
diff --git a/src/test/unit/rcsplit_unittest.cc b/src/test/unit/rcsplit_unittest.cc
index 59364ce299..d07f357ddf 100644
--- a/src/test/unit/rcsplit_unittest.cc
+++ b/src/test/unit/rcsplit_unittest.cc
@@ -45,6 +45,10 @@ extern "C" {
#include "rx/rx.h"
+ extern rcsplitState_e cameraState;
+ extern serialPort_t *rcSplitSerialPort;
+ extern rcsplitSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
+
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
rcsplitState_e unitTestRCsplitState()