Merge pull request #828 from martinbudden/bf_rom_saving

Improved use of build #defines to save some ROM
This commit is contained in:
Martin Budden 2016-07-26 23:45:31 +01:00 committed by GitHub
commit 61166efae4
9 changed files with 97 additions and 38 deletions

View File

@ -280,6 +280,7 @@ void resetGpsProfile(gpsProfile_t *gpsProfile)
}
#endif
#ifdef BARO
void resetBarometerConfig(barometerConfig_t *barometerConfig)
{
barometerConfig->baro_sample_count = 21;
@ -287,6 +288,7 @@ void resetBarometerConfig(barometerConfig_t *barometerConfig)
barometerConfig->baro_cf_vel = 0.985f;
barometerConfig->baro_cf_alt = 0.965f;
}
#endif
void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
{
@ -316,6 +318,7 @@ void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
flight3DConfig->deadband3d_throttle = 50;
}
#ifdef TELEMETRY
void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
{
telemetryConfig->telemetry_inversion = 0;
@ -328,6 +331,7 @@ void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
telemetryConfig->frsky_vfas_cell_voltage = 0;
telemetryConfig->hottAlarmSoundInterval = 5;
}
#endif
void resetBatteryConfig(batteryConfig_t *batteryConfig)
{
@ -491,7 +495,9 @@ static void resetConf(void)
resetBatteryConfig(&masterConfig.batteryConfig);
#ifdef TELEMETRY
resetTelemetryConfig(&masterConfig.telemetryConfig);
#endif
#ifdef SERIALRX_PROVIDER
masterConfig.rxConfig.serialrx_provider = SERIALRX_PROVIDER;
@ -578,7 +584,9 @@ static void resetConf(void)
masterConfig.accDeadband.z = 40;
masterConfig.acc_unarmedcal = 1;
#ifdef BARO
resetBarometerConfig(&masterConfig.barometerConfig);
#endif
// Radio
parseRcChannels("AETR1234", &masterConfig.rxConfig);

View File

@ -21,6 +21,8 @@
#include "platform.h"
#ifdef USE_ADC
#include "build_config.h"
#include "system.h"
@ -176,3 +178,4 @@ void adcInit(drv_adc_config_t *init)
ADC_SoftwareStartConvCmd(adc.ADCx, ENABLE);
}
#endif

View File

@ -65,10 +65,15 @@ uint8_t PIDweight[3];
static int32_t errorGyroI[3];
static float errorGyroIf[3];
#ifdef SKIP_PID_FLOAT
static void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
pidControllerFuncPtr pid_controller = pidLegacy; // which pid controller are we using
#else
static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
pidControllerFuncPtr pid_controller = pidBetaflight; // which pid controller are we using
#endif
void setTargetPidLooptime(uint8_t pidProcessDenom)
{
@ -101,6 +106,7 @@ const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
static pt1Filter_t deltaFilter[3];
static pt1Filter_t yawFilter;
#ifndef SKIP_PID_FLOAT
// Experimental betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage
static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
@ -288,6 +294,7 @@ static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inc
#endif
}
}
#endif
// Legacy pid controller betaflight evolved pid rewrite based on 2.9 releae. Good for fastest cycletimes for those who believe in that. Don't expect much development in the future
static void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
@ -438,8 +445,10 @@ void pidSetController(pidControllerType_e type)
case PID_CONTROLLER_LEGACY:
pid_controller = pidLegacy;
break;
#ifndef SKIP_PID_FLOAT
case PID_CONTROLLER_BETAFLIGHT:
pid_controller = pidBetaflight;
#endif
}
}

View File

@ -144,8 +144,9 @@ static void cliTasks(char *cmdline);
#endif
static void cliVersion(char *cmdline);
static void cliRxRange(char *cmdline);
#if (FLASH_SIZE > 64)
static void cliResource(char *cmdline);
#endif
#ifdef GPS
static void cliGpsPassthrough(char *cmdline);
#endif
@ -218,7 +219,7 @@ static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT
{ RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
};
#ifndef CJMCU
#if (FLASH_SIZE > 64)
// sync this with sensors_e
static const char * const sensorTypeNames[] = {
"GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
@ -306,7 +307,9 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("profile", "change profile",
"[<index>]", cliProfile),
CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
#if (FLASH_SIZE > 64)
CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
#endif
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
@ -381,19 +384,23 @@ static const char * const lookupTableCurrentSensor[] = {
"NONE", "ADC", "VIRTUAL"
};
#ifdef USE_SERVOS
static const char * const lookupTableGimbalMode[] = {
"NORMAL", "MIXTILT"
};
#endif
#ifdef BLACKBOX
static const char * const lookupTableBlackboxDevice[] = {
"SERIAL", "SPIFLASH", "SDCARD"
};
#endif
static const char * const lookupTablePidController[] = {
"LEGACY", "BETAFLIGHT"
};
#ifdef SERIAL_RX
static const char * const lookupTableSerialRX[] = {
"SPEK1024",
"SPEK2048",
@ -405,6 +412,7 @@ static const char * const lookupTableSerialRX[] = {
"IBUS",
"JETIEXBUS"
};
#endif
static const char * const lookupTableGyroLpf[] = {
"OFF",
@ -430,6 +438,7 @@ static const char * const lookupTableAccHardware[] = {
"FAKE"
};
#ifdef BARO
static const char * const lookupTableBaroHardware[] = {
"AUTO",
"NONE",
@ -437,7 +446,9 @@ static const char * const lookupTableBaroHardware[] = {
"MS5611",
"BMP280"
};
#endif
#ifdef MAG
static const char * const lookupTableMagHardware[] = {
"AUTO",
"NONE",
@ -445,6 +456,7 @@ static const char * const lookupTableMagHardware[] = {
"AK8975",
"AK8963"
};
#endif
static const char * const lookupTableDebug[DEBUG_COUNT] = {
"NONE",
@ -491,16 +503,24 @@ typedef enum {
TABLE_GPS_SBAS_MODE,
#endif
#ifdef BLACKBOX
TABLE_BLACKBOX_DEVICE,
TABLE_BLACKBOX_DEVICE,
#endif
TABLE_CURRENT_SENSOR,
#ifdef USE_SERVOS
TABLE_GIMBAL_MODE,
#endif
TABLE_PID_CONTROLLER,
#ifdef SERIAL_RX
TABLE_SERIAL_RX,
#endif
TABLE_GYRO_LPF,
TABLE_ACC_HARDWARE,
#ifdef BARO
TABLE_BARO_HARDWARE,
#endif
#ifdef MAG
TABLE_MAG_HARDWARE,
#endif
TABLE_DEBUG,
TABLE_SUPEREXPO_YAW,
TABLE_MOTOR_PWM_PROTOCOL,
@ -522,13 +542,21 @@ static const lookupTableEntry_t lookupTables[] = {
{ lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
#endif
{ lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
#ifdef USE_SERVOS
{ lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
#endif
{ lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
#ifdef SERIAL_RX
{ lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
#endif
{ lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
{ lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
#ifdef BARO
{ lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
#endif
#ifdef MAG
{ lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
#endif
{ lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
{ lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
{ lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
@ -576,7 +604,6 @@ typedef struct cliLookupTableConfig_s {
typedef union {
cliLookupTableConfig_t lookup;
cliMinMaxConfig_t minmax;
} cliValueConfig_t;
typedef struct {
@ -660,11 +687,16 @@ const clivalue_t valueTable[] = {
{ "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
#endif
#ifdef SERIAL_RX
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
#endif
{ "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } },
#ifdef SPEKTRUM_BIND
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
{ "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind_autoreset, .config.minmax = { 0, 1} },
#endif
#ifdef TELEMETRY
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
{ "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
{ "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
@ -674,6 +706,7 @@ const clivalue_t valueTable[] = {
{ "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
{ "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_vfas_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
{ "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
#endif
{ "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
@ -758,14 +791,18 @@ const clivalue_t valueTable[] = {
{ "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
{ "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
#ifdef BARO
{ "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
{ "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
{ "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
{ "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
#endif
#ifdef MAG
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
#endif
{ "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
{ "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
{ "zero_throttle_stabilisation",VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.zeroThrottleStabilisation, .config.lookup = { TABLE_OFF_ON } },
@ -817,9 +854,11 @@ const clivalue_t valueTable[] = {
{ "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } },
#endif
#ifdef MAG
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
{ "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
#endif
#ifdef LED_STRIP
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
#endif
@ -2600,7 +2639,8 @@ static void cliProfile(char *cmdline)
}
}
static void cliRateProfile(char *cmdline) {
static void cliRateProfile(char *cmdline)
{
int i;
if (isEmpty(cmdline)) {
@ -2732,6 +2772,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
break;
}
}
static void cliPrintVarRange(const clivalue_t *var)
{
switch (var->type & VALUE_MODE_MASK) {
@ -2753,6 +2794,7 @@ static void cliPrintVarRange(const clivalue_t *var)
break;
}
}
static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
{
void *ptr = var->ptr;
@ -3129,6 +3171,7 @@ void cliProcess(void)
}
}
#if (FLASH_SIZE > 64)
static void cliResource(char *cmdline)
{
UNUSED(cmdline);
@ -3147,6 +3190,7 @@ static void cliResource(char *cmdline)
}
}
}
#endif
void cliDfu(char *cmdLine)
{

View File

@ -856,16 +856,17 @@ void taskUpdateBeeper(void)
void taskUpdateBattery(void)
{
#ifdef USE_ADC
static uint32_t vbatLastServiced = 0;
static uint32_t ibatLastServiced = 0;
if (feature(FEATURE_VBAT)) {
if (cmp32(currentTime, vbatLastServiced) >= VBATINTERVAL) {
vbatLastServiced = currentTime;
updateBattery();
}
}
#endif
static uint32_t ibatLastServiced = 0;
if (feature(FEATURE_CURRENT_METER)) {
int32_t ibatTimeSinceLastServiced = cmp32(currentTime, ibatLastServiced);

View File

@ -52,7 +52,7 @@ int32_t mAhDrawn = 0; // milliampere hours drawn from the battery
static batteryState_e batteryState;
uint16_t batteryAdcToVoltage(uint16_t src)
static uint16_t batteryAdcToVoltage(uint16_t src)
{
// calculate battery voltage based on ADC reading
// result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V

View File

@ -69,7 +69,6 @@ extern uint16_t amperageLatestADC;
extern int32_t amperage;
extern int32_t mAhDrawn;
uint16_t batteryAdcToVoltage(uint16_t src);
batteryState_e getBatteryState(void);
const char * getBatteryStateString(void);
void updateBattery(void);

View File

@ -26,8 +26,16 @@
#define BEEPER_OPT PB2
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PA3
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN PA4
@ -40,19 +48,12 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USABLE_TIMER_CHANNEL_COUNT 12
#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
// MPU6000 interrupts
@ -85,13 +86,6 @@
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA0
@ -109,20 +103,17 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define DISPLAY
#define SONAR
#define SONAR_ECHO_PIN PB0
#define SONAR_TRIGGER_PIN PB5
#undef GPS
#undef BARO
#undef MAG
#ifdef CC3D_OPBL
#define SKIP_CLI_COMMAND_HELP
#undef LED_STRIP
#undef DISPLAY
#define SKIP_CLI_COMMAND_HELP
#undef BARO
//#undef MAG
#undef SONAR
#endif
@ -133,4 +124,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(14) )
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View File

@ -47,22 +47,25 @@
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#if (FLASH_SIZE > 64)
#define BLACKBOX
#define USE_SERVOS
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
#else
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
#undef USE_CLI
#define USE_QUAD_MIXER_ONLY
#undef SERIAL_RX
#define SKIP_TASK_STATISTICS
#define SKIP_CLI_COMMAND_HELP
#define SKIP_PID_FLOAT
#endif
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
#define USE_QUAD_MIXER_ONLY
#define SKIP_SERIAL_PASSTHROUGH
// IO - assuming all IOs on 48pin package TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff