mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 01:35:41 +03:00
Removed calls to (latching) 'feature()'.
This commit is contained in:
parent
f463dad8bd
commit
c99629bbf1
36 changed files with 432 additions and 145 deletions
|
@ -2946,7 +2946,7 @@ static void cliDshotProg(char *cmdline)
|
|||
pwmWriteDshotCommand(escIndex, getMotorCount(), command, true);
|
||||
} else {
|
||||
#if defined(USE_ESC_SENSOR) && defined(USE_ESC_SENSOR_INFO)
|
||||
if (feature(FEATURE_ESC_SENSOR)) {
|
||||
if (featureConfigured(FEATURE_ESC_SENSOR)) {
|
||||
if (escIndex != ALL_MOTORS) {
|
||||
executeEscInfoCommand(escIndex);
|
||||
} else {
|
||||
|
|
|
@ -1018,7 +1018,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
|||
|
||||
#if defined(USE_ESC_SENSOR)
|
||||
case MSP_ESC_SENSOR_DATA:
|
||||
if (feature(FEATURE_ESC_SENSOR)) {
|
||||
if (featureConfigured(FEATURE_ESC_SENSOR)) {
|
||||
sbufWriteU8(dst, getMotorCount());
|
||||
for (int i = 0; i < getMotorCount(); i++) {
|
||||
const escSensorData_t *escData = getEscSensorData(i);
|
||||
|
|
|
@ -166,11 +166,11 @@ void initActiveBoxIds(void)
|
|||
#define BME(boxId) do { bitArraySet(&ena, boxId); } while (0)
|
||||
BME(BOXARM);
|
||||
BME(BOXPREARM);
|
||||
if (!feature(FEATURE_AIRMODE)) {
|
||||
if (!featureConfigured(FEATURE_AIRMODE)) {
|
||||
BME(BOXAIRMODE);
|
||||
}
|
||||
|
||||
if (!feature(FEATURE_ANTI_GRAVITY)) {
|
||||
if (!featureConfigured(FEATURE_ANTI_GRAVITY)) {
|
||||
BME(BOXANTIGRAVITY);
|
||||
}
|
||||
|
||||
|
@ -188,9 +188,9 @@ void initActiveBoxIds(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_GPS
|
||||
if (feature(FEATURE_GPS)) {
|
||||
if (featureConfigured(FEATURE_GPS)) {
|
||||
#ifdef USE_GPS_RESCUE
|
||||
if (!feature(FEATURE_3D)) {
|
||||
if (!featureConfigured(FEATURE_3D)) {
|
||||
BME(BOXGPSRESCUE);
|
||||
}
|
||||
#endif
|
||||
|
@ -207,7 +207,7 @@ void initActiveBoxIds(void)
|
|||
BME(BOXBEEPERON);
|
||||
|
||||
#ifdef USE_LED_STRIP
|
||||
if (feature(FEATURE_LED_STRIP)) {
|
||||
if (featureConfigured(FEATURE_LED_STRIP)) {
|
||||
BME(BOXLEDLOW);
|
||||
}
|
||||
#endif
|
||||
|
@ -221,7 +221,7 @@ void initActiveBoxIds(void)
|
|||
|
||||
BME(BOXFPVANGLEMIX);
|
||||
|
||||
if (feature(FEATURE_3D)) {
|
||||
if (featureConfigured(FEATURE_3D)) {
|
||||
BME(BOX3D);
|
||||
}
|
||||
|
||||
|
@ -229,18 +229,18 @@ void initActiveBoxIds(void)
|
|||
BME(BOXFLIPOVERAFTERCRASH);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_SERVO_TILT)) {
|
||||
if (featureConfigured(FEATURE_SERVO_TILT)) {
|
||||
BME(BOXCAMSTAB);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
|
||||
if (featureConfigured(FEATURE_INFLIGHT_ACC_CAL)) {
|
||||
BME(BOXCALIB);
|
||||
}
|
||||
|
||||
BME(BOXOSD);
|
||||
|
||||
#ifdef USE_TELEMETRY
|
||||
if (feature(FEATURE_TELEMETRY)) {
|
||||
if (featureConfigured(FEATURE_TELEMETRY)) {
|
||||
BME(BOXTELEMETRY);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue