mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
Added some further build flags for ROM saving
This commit is contained in:
parent
4790e857e4
commit
b5c62df3f8
10 changed files with 37 additions and 10 deletions
|
@ -517,12 +517,15 @@ void mspInit(serialConfig_t *serialConfig)
|
|||
|
||||
activeBoxIds[activeBoxIdCount++] = BOXOSD;
|
||||
|
||||
#ifdef TELEMETRY
|
||||
if (feature(FEATURE_TELEMETRY) && masterConfig.telemetryConfig.telemetry_switch)
|
||||
activeBoxIds[activeBoxIdCount++] = BOXTELEMETRY;
|
||||
|
||||
#endif
|
||||
#ifdef SONAR
|
||||
if (feature(FEATURE_SONAR)){
|
||||
activeBoxIds[activeBoxIdCount++] = BOXSONAR;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
if (masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
|
@ -1296,6 +1299,7 @@ static bool processInCommand(void)
|
|||
magHold = read16();
|
||||
break;
|
||||
case MSP_SET_RAW_RC:
|
||||
#ifndef SKIP_RX_MSP
|
||||
{
|
||||
uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
|
||||
if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) {
|
||||
|
@ -1310,6 +1314,7 @@ static bool processInCommand(void)
|
|||
rxMspFrameReceive(frame, channelCount);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case MSP_SET_ACC_TRIM:
|
||||
masterConfig.accelerometerTrims.values.pitch = read16();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue