mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Merge pull request #834 from martinbudden/bf_rom_saving
Added some further build flags for ROM saving
This commit is contained in:
commit
6f80b55da1
10 changed files with 37 additions and 10 deletions
|
@ -92,7 +92,9 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
int i = 0;
|
int i = 0;
|
||||||
const uint16_t *setup;
|
const uint16_t *setup;
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
int channelIndex = 0;
|
int channelIndex = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration));
|
memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration));
|
||||||
|
|
||||||
|
@ -289,15 +291,19 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (type == MAP_TO_PPM_INPUT) {
|
if (type == MAP_TO_PPM_INPUT) {
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
||||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
ppmInConfig(timerHardwarePtr);
|
ppmInConfig(timerHardwarePtr);
|
||||||
|
#endif
|
||||||
} else if (type == MAP_TO_PWM_INPUT) {
|
} else if (type == MAP_TO_PWM_INPUT) {
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
pwmInConfig(timerHardwarePtr, channelIndex);
|
pwmInConfig(timerHardwarePtr, channelIndex);
|
||||||
channelIndex++;
|
channelIndex++;
|
||||||
|
#endif
|
||||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||||
|
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
|
|
||||||
#include "build_config.h"
|
#include "build_config.h"
|
||||||
#include "debug.h"
|
#include "debug.h"
|
||||||
|
|
||||||
|
@ -419,3 +421,4 @@ uint16_t pwmRead(uint8_t channel)
|
||||||
{
|
{
|
||||||
return captures[channel];
|
return captures[channel];
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -477,7 +477,7 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU
|
||||||
|
|
||||||
adjustmentState_t adjustmentStates[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT];
|
adjustmentState_t adjustmentStates[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT];
|
||||||
|
|
||||||
void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig) {
|
static void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig) {
|
||||||
adjustmentState_t *adjustmentState = &adjustmentStates[index];
|
adjustmentState_t *adjustmentState = &adjustmentStates[index];
|
||||||
|
|
||||||
if (adjustmentState->config == adjustmentConfig) {
|
if (adjustmentState->config == adjustmentConfig) {
|
||||||
|
@ -491,7 +491,7 @@ void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adj
|
||||||
MARK_ADJUSTMENT_FUNCTION_AS_READY(index);
|
MARK_ADJUSTMENT_FUNCTION_AS_READY(index);
|
||||||
}
|
}
|
||||||
|
|
||||||
void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta) {
|
static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta) {
|
||||||
int newValue;
|
int newValue;
|
||||||
|
|
||||||
if (delta > 0) {
|
if (delta > 0) {
|
||||||
|
@ -600,7 +600,7 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
static void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
||||||
{
|
{
|
||||||
bool applied = false;
|
bool applied = false;
|
||||||
|
|
||||||
|
|
|
@ -249,7 +249,6 @@ typedef struct adjustmentState_s {
|
||||||
bool isAirmodeActive(void);
|
bool isAirmodeActive(void);
|
||||||
bool isSuperExpoActive(void);
|
bool isSuperExpoActive(void);
|
||||||
void resetAdjustmentStates(void);
|
void resetAdjustmentStates(void);
|
||||||
void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig);
|
|
||||||
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
|
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
|
||||||
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig);
|
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig);
|
||||||
|
|
||||||
|
|
|
@ -517,12 +517,15 @@ void mspInit(serialConfig_t *serialConfig)
|
||||||
|
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXOSD;
|
activeBoxIds[activeBoxIdCount++] = BOXOSD;
|
||||||
|
|
||||||
|
#ifdef TELEMETRY
|
||||||
if (feature(FEATURE_TELEMETRY) && masterConfig.telemetryConfig.telemetry_switch)
|
if (feature(FEATURE_TELEMETRY) && masterConfig.telemetryConfig.telemetry_switch)
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXTELEMETRY;
|
activeBoxIds[activeBoxIdCount++] = BOXTELEMETRY;
|
||||||
|
#endif
|
||||||
|
#ifdef SONAR
|
||||||
if (feature(FEATURE_SONAR)){
|
if (feature(FEATURE_SONAR)){
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXSONAR;
|
activeBoxIds[activeBoxIdCount++] = BOXSONAR;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
if (masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
if (masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||||
|
@ -1296,6 +1299,7 @@ static bool processInCommand(void)
|
||||||
magHold = read16();
|
magHold = read16();
|
||||||
break;
|
break;
|
||||||
case MSP_SET_RAW_RC:
|
case MSP_SET_RAW_RC:
|
||||||
|
#ifndef SKIP_RX_MSP
|
||||||
{
|
{
|
||||||
uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
|
uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
|
||||||
if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) {
|
if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) {
|
||||||
|
@ -1310,6 +1314,7 @@ static bool processInCommand(void)
|
||||||
rxMspFrameReceive(frame, channelCount);
|
rxMspFrameReceive(frame, channelCount);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
case MSP_SET_ACC_TRIM:
|
case MSP_SET_ACC_TRIM:
|
||||||
masterConfig.accelerometerTrims.values.pitch = read16();
|
masterConfig.accelerometerTrims.values.pitch = read16();
|
||||||
|
|
|
@ -327,7 +327,9 @@ void init(void)
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
|
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
|
||||||
#endif
|
#endif
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
pwmRxInit(masterConfig.inputFilteringMode);
|
pwmRxInit(masterConfig.inputFilteringMode);
|
||||||
|
#endif
|
||||||
|
|
||||||
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
|
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
|
||||||
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
|
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
|
||||||
|
|
|
@ -451,7 +451,7 @@ void handleInflightCalibrationStickPosition(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateInflightCalibrationState(void)
|
static void updateInflightCalibrationState(void)
|
||||||
{
|
{
|
||||||
if (AccInflightCalibrationArmed && ARMING_FLAG(ARMED) && rcData[THROTTLE] > masterConfig.rxConfig.mincheck && !IS_RC_MODE_ACTIVE(BOXARM)) { // Copter is airborne and you are turning it off via boxarm : start measurement
|
if (AccInflightCalibrationArmed && ARMING_FLAG(ARMED) && rcData[THROTTLE] > masterConfig.rxConfig.mincheck && !IS_RC_MODE_ACTIVE(BOXARM)) { // Copter is airborne and you are turning it off via boxarm : start measurement
|
||||||
InflightcalibratingA = 50;
|
InflightcalibratingA = 50;
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_MSP
|
||||||
|
|
||||||
#include "build_config.h"
|
#include "build_config.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
@ -71,3 +73,4 @@ void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadR
|
||||||
if (callback)
|
if (callback)
|
||||||
*callback = rxMspReadRawRC;
|
*callback = rxMspReadRawRC;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -21,10 +21,12 @@
|
||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "build_config.h"
|
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
|
|
||||||
|
#include "build_config.h"
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
#include "drivers/gpio.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/pwm_rx.h"
|
#include "drivers/pwm_rx.h"
|
||||||
|
@ -59,4 +61,5 @@ void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfigPtr, rcReadRawDataPtr *callback
|
||||||
*callback = ppmReadRawRC;
|
*callback = ppmReadRawRC;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // SKIP_RX_PWM_PPM
|
||||||
|
|
||||||
|
|
|
@ -189,14 +189,18 @@ void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationCondi
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_MSP
|
||||||
if (feature(FEATURE_RX_MSP)) {
|
if (feature(FEATURE_RX_MSP)) {
|
||||||
rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) {
|
if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||||
rxRefreshRate = 20000;
|
rxRefreshRate = 20000;
|
||||||
rxPwmInit(&rxRuntimeConfig, &rcReadRawFunc);
|
rxPwmInit(&rxRuntimeConfig, &rcReadRawFunc);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
rxRuntimeConfig.auxChannelCount = rxRuntimeConfig.channelCount - STICK_CHANNEL_COUNT;
|
rxRuntimeConfig.auxChannelCount = rxRuntimeConfig.channelCount - STICK_CHANNEL_COUNT;
|
||||||
}
|
}
|
||||||
|
@ -349,16 +353,18 @@ void updateRx(uint32_t currentTime)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_MSP
|
||||||
if (feature(FEATURE_RX_MSP)) {
|
if (feature(FEATURE_RX_MSP)) {
|
||||||
rxDataReceived = rxMspFrameComplete();
|
rxDataReceived = rxMspFrameComplete();
|
||||||
|
|
||||||
if (rxDataReceived) {
|
if (rxDataReceived) {
|
||||||
rxSignalReceived = true;
|
rxSignalReceived = true;
|
||||||
rxIsInFailsafeMode = false;
|
rxIsInFailsafeMode = false;
|
||||||
needRxSignalBefore = currentTime + DELAY_5_HZ;
|
needRxSignalBefore = currentTime + DELAY_5_HZ;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
if (feature(FEATURE_RX_PPM)) {
|
if (feature(FEATURE_RX_PPM)) {
|
||||||
if (isPPMDataBeingReceived()) {
|
if (isPPMDataBeingReceived()) {
|
||||||
rxSignalReceivedNotDataDriven = true;
|
rxSignalReceivedNotDataDriven = true;
|
||||||
|
@ -375,7 +381,7 @@ void updateRx(uint32_t currentTime)
|
||||||
needRxSignalBefore = currentTime + DELAY_10_HZ;
|
needRxSignalBefore = currentTime + DELAY_10_HZ;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
bool shouldProcessRx(uint32_t currentTime)
|
bool shouldProcessRx(uint32_t currentTime)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue