1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 04:45:24 +03:00

Preparation for conversion to parameter groups 8

This commit is contained in:
Martin Budden 2017-02-15 16:59:40 +00:00
parent 981c0455dc
commit df630f1cf4
25 changed files with 108 additions and 110 deletions

View file

@ -40,6 +40,7 @@
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/fc_core.h" #include "fc/fc_core.h"
#include "flight/altitudehold.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/servos.h" #include "flight/servos.h"
@ -98,7 +99,7 @@
#define ppmConfig(x) (&masterConfig.ppmConfig) #define ppmConfig(x) (&masterConfig.ppmConfig)
#define pwmConfig(x) (&masterConfig.pwmConfig) #define pwmConfig(x) (&masterConfig.pwmConfig)
#define adcConfig(x) (&masterConfig.adcConfig) #define adcConfig(x) (&masterConfig.adcConfig)
#define beeperConfig(x) (&masterConfig.beeperConfig) #define beeperDevConfig(x) (&masterConfig.beeperDevConfig)
#define sonarConfig(x) (&masterConfig.sonarConfig) #define sonarConfig(x) (&masterConfig.sonarConfig)
#define ledStripConfig(x) (&masterConfig.ledStripConfig) #define ledStripConfig(x) (&masterConfig.ledStripConfig)
#define statusLedConfig(x) (&masterConfig.statusLedConfig) #define statusLedConfig(x) (&masterConfig.statusLedConfig)
@ -147,7 +148,7 @@
#define ppmConfigMutable(x) (&masterConfig.ppmConfig) #define ppmConfigMutable(x) (&masterConfig.ppmConfig)
#define pwmConfigMutable(x) (&masterConfig.pwmConfig) #define pwmConfigMutable(x) (&masterConfig.pwmConfig)
#define adcConfigMutable(x) (&masterConfig.adcConfig) #define adcConfigMutable(x) (&masterConfig.adcConfig)
#define beeperConfigMutable(x) (&masterConfig.beeperConfig) #define beeperDevConfigMutable(x) (&masterConfig.beeperDevConfig)
#define sonarConfigMutable(x) (&masterConfig.sonarConfig) #define sonarConfigMutable(x) (&masterConfig.sonarConfig)
#define ledStripConfigMutable(x) (&masterConfig.ledStripConfig) #define ledStripConfigMutable(x) (&masterConfig.ledStripConfig)
#define statusLedConfigMutable(x) (&masterConfig.statusLedConfig) #define statusLedConfigMutable(x) (&masterConfig.statusLedConfig)
@ -260,7 +261,7 @@ typedef struct master_s {
#endif #endif
#ifdef BEEPER #ifdef BEEPER
beeperConfig_t beeperConfig; beeperDevConfig_t beeperDevConfig;
#endif #endif
#ifdef SONAR #ifdef SONAR

View file

@ -47,5 +47,5 @@ typedef struct adcConfig_s {
adcChannelConfig_t external1; adcChannelConfig_t external1;
} adcConfig_t; } adcConfig_t;
void adcInit(adcConfig_t *config); void adcInit(const adcConfig_t *config);
uint16_t adcGetChannel(uint8_t channel); uint16_t adcGetChannel(uint8_t channel);

View file

@ -77,7 +77,7 @@ const adcTagMap_t adcTagMap[] = {
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board // NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
// //
void adcInit(adcConfig_t *config) void adcInit(const adcConfig_t *config)
{ {
uint8_t configuredAdcChannels = 0; uint8_t configuredAdcChannels = 0;

View file

@ -104,7 +104,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
return ADCINVALID; return ADCINVALID;
} }
void adcInit(adcConfig_t *config) void adcInit(const adcConfig_t *config)
{ {
ADC_InitTypeDef ADC_InitStructure; ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure; DMA_InitTypeDef DMA_InitStructure;

View file

@ -87,7 +87,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
return ADCINVALID; return ADCINVALID;
} }
void adcInit(adcConfig_t *config) void adcInit(const adcConfig_t *config)
{ {
ADC_InitTypeDef ADC_InitStructure; ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure; DMA_InitTypeDef DMA_InitStructure;

View file

@ -83,7 +83,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
return ADCINVALID; return ADCINVALID;
} }
void adcInit(adcConfig_t *config) void adcInit(const adcConfig_t *config)
{ {
uint8_t i; uint8_t i;
uint8_t configuredAdcChannels = 0; uint8_t configuredAdcChannels = 0;

View file

@ -49,7 +49,7 @@ void systemBeepToggle(void)
#endif #endif
} }
void beeperInit(const beeperConfig_t *config) void beeperInit(const beeperDevConfig_t *config)
{ {
#ifndef BEEPER #ifndef BEEPER
UNUSED(config); UNUSED(config);

View file

@ -29,13 +29,13 @@
#define BEEP_ON do {} while(0) #define BEEP_ON do {} while(0)
#endif #endif
typedef struct beeperConfig_s { typedef struct beeperDevConfig_s {
ioTag_t ioTag; ioTag_t ioTag;
uint8_t isInverted; uint8_t isInverted;
uint8_t isOpenDrain; uint8_t isOpenDrain;
} beeperConfig_t; } beeperDevConfig_t;
void systemBeep(bool on); void systemBeep(bool on);
void systemBeepToggle(void); void systemBeepToggle(void);
void beeperInit(const beeperConfig_t *beeperConfig); void beeperInit(const beeperDevConfig_t *beeperDevConfig);

View file

@ -573,8 +573,8 @@ static const clivalue_t valueTable[] = {
#endif #endif
#ifdef BEEPER #ifdef BEEPER
{ "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperConfig()->isInverted, .config.lookup = { TABLE_OFF_ON } }, { "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperDevConfig()->isInverted, .config.lookup = { TABLE_OFF_ON } },
{ "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperConfig()->isOpenDrain, .config.lookup = { TABLE_OFF_ON } }, { "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperDevConfig()->isOpenDrain, .config.lookup = { TABLE_OFF_ON } },
#endif #endif
#ifdef SERIAL_RX #ifdef SERIAL_RX
@ -884,12 +884,11 @@ static osdConfig_t osdConfigCopy;
#endif #endif
static systemConfig_t systemConfigCopy; static systemConfig_t systemConfigCopy;
#ifdef BEEPER #ifdef BEEPER
static beeperConfig_t beeperConfigCopy; static beeperDevConfig_t beeperDevConfigCopy;
#endif #endif
static controlRateConfig_t controlRateProfilesCopy[MAX_CONTROL_RATE_PROFILE_COUNT]; static controlRateConfig_t controlRateProfilesCopy[MAX_CONTROL_RATE_PROFILE_COUNT];
static pidProfile_t pidProfileCopy[MAX_PROFILE_COUNT]; static pidProfile_t pidProfileCopy[MAX_PROFILE_COUNT];
static modeActivationOperatorConfig_t modeActivationOperatorConfigCopy; static modeActivationOperatorConfig_t modeActivationOperatorConfigCopy;
static beeperConfig_t beeperConfigCopy;
#endif // USE_PARAMETER_GROUPS #endif // USE_PARAMETER_GROUPS
static void cliPrint(const char *str) static void cliPrint(const char *str)
@ -1234,8 +1233,8 @@ static const cliCurrentAndDefaultConfig_t *getCurrentAndDefaultConfigs(pgn_t pgn
ret.defaultConfig = adjustmentRanges(0); ret.defaultConfig = adjustmentRanges(0);
break; break;
case PG_BEEPER_CONFIG: case PG_BEEPER_CONFIG:
ret.currentConfig = &beeperConfigCopy; ret.currentConfig = &beeperDevConfigCopy;
ret.defaultConfig = beeperConfig(); ret.defaultConfig = beeperDevConfig();
break; break;
default: default:
ret.currentConfig = NULL; ret.currentConfig = NULL;
@ -1518,36 +1517,36 @@ static bool isEmpty(const char *string)
return (string == NULL || *string == '\0') ? true : false; return (string == NULL || *string == '\0') ? true : false;
} }
static void printRxFailsafe(uint8_t dumpMask, const rxFailsafeChannelConfiguration_t *failsafeChannelConfigurations, const rxFailsafeChannelConfiguration_t *failsafeChannelConfigurationsDefault) static void printRxFailsafe(uint8_t dumpMask, const rxFailsafeChannelConfig_t *failsafeChannelConfig, const rxFailsafeChannelConfig_t *failsafeChannelConfigDefault)
{ {
// print out rxConfig failsafe settings // print out rxConfig failsafe settings
for (uint32_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) { for (uint32_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
const rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &failsafeChannelConfigurations[channel]; const rxFailsafeChannelConfig_t *channelFailsafeConfig = &failsafeChannelConfig[channel];
const rxFailsafeChannelConfiguration_t *channelFailsafeConfigurationDefault = &failsafeChannelConfigurationsDefault[channel]; const rxFailsafeChannelConfig_t *channelFailsafeConfigDefault = &failsafeChannelConfigDefault[channel];
const bool equalsDefault = channelFailsafeConfiguration->mode == channelFailsafeConfigurationDefault->mode const bool equalsDefault = channelFailsafeConfig->mode == channelFailsafeConfigDefault->mode
&& channelFailsafeConfiguration->step == channelFailsafeConfigurationDefault->step; && channelFailsafeConfig->step == channelFailsafeConfigDefault->step;
const bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET; const bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
if (requireValue) { if (requireValue) {
const char *format = "rxfail %u %c %d\r\n"; const char *format = "rxfail %u %c %d\r\n";
cliDefaultPrintf(dumpMask, equalsDefault, format, cliDefaultPrintf(dumpMask, equalsDefault, format,
channel, channel,
rxFailsafeModeCharacters[channelFailsafeConfigurationDefault->mode], rxFailsafeModeCharacters[channelFailsafeConfigDefault->mode],
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfigurationDefault->step) RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfigDefault->step)
); );
cliDumpPrintf(dumpMask, equalsDefault, format, cliDumpPrintf(dumpMask, equalsDefault, format,
channel, channel,
rxFailsafeModeCharacters[channelFailsafeConfiguration->mode], rxFailsafeModeCharacters[channelFailsafeConfig->mode],
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step) RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
); );
} else { } else {
const char *format = "rxfail %u %c\r\n"; const char *format = "rxfail %u %c\r\n";
cliDefaultPrintf(dumpMask, equalsDefault, format, cliDefaultPrintf(dumpMask, equalsDefault, format,
channel, channel,
rxFailsafeModeCharacters[channelFailsafeConfigurationDefault->mode] rxFailsafeModeCharacters[channelFailsafeConfigDefault->mode]
); );
cliDumpPrintf(dumpMask, equalsDefault, format, cliDumpPrintf(dumpMask, equalsDefault, format,
channel, channel,
rxFailsafeModeCharacters[channelFailsafeConfiguration->mode] rxFailsafeModeCharacters[channelFailsafeConfig->mode]
); );
} }
} }
@ -1568,12 +1567,12 @@ static void cliRxFailsafe(char *cmdline)
channel = atoi(ptr++); channel = atoi(ptr++);
if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) { if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig()->failsafe_channel_configurations[channel]; rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxConfig()->failsafe_channel_configurations[channel];
uint16_t value; uint16_t value;
rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX; rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode; rxFailsafeChannelMode_e mode = channelFailsafeConfig->mode;
bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET; bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
ptr = nextArg(ptr); ptr = nextArg(ptr);
if (ptr) { if (ptr) {
@ -1604,16 +1603,16 @@ static void cliRxFailsafe(char *cmdline)
return; return;
} }
channelFailsafeConfiguration->step = value; channelFailsafeConfig->step = value;
} else if (requireValue) { } else if (requireValue) {
cliShowParseError(); cliShowParseError();
return; return;
} }
channelFailsafeConfiguration->mode = mode; channelFailsafeConfig->mode = mode;
} }
char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode]; char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfig->mode];
// double use of cliPrintf below // double use of cliPrintf below
// 1. acknowledge interpretation on command, // 1. acknowledge interpretation on command,
@ -1623,7 +1622,7 @@ static void cliRxFailsafe(char *cmdline)
cliPrintf("rxfail %u %c %d\r\n", cliPrintf("rxfail %u %c %d\r\n",
channel, channel,
modeCharacter, modeCharacter,
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step) RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
); );
} else { } else {
cliPrintf("rxfail %u %c\r\n", cliPrintf("rxfail %u %c\r\n",
@ -2105,7 +2104,7 @@ static void cliMotorMix(char *cmdline)
#endif #endif
} }
static void printRxRange(uint8_t dumpMask, const rxChannelRangeConfiguration_t *channelRangeConfigs, const rxChannelRangeConfiguration_t *defaultChannelRangeConfigs) static void printRxRange(uint8_t dumpMask, const rxChannelRangeConfig_t *channelRangeConfigs, const rxChannelRangeConfig_t *defaultChannelRangeConfigs)
{ {
const char *format = "rxrange %u %u %u\r\n"; const char *format = "rxrange %u %u %u\r\n";
for (uint32_t i = 0; i < NON_AUX_CHANNEL_COUNT; i++) { for (uint32_t i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
@ -2159,9 +2158,9 @@ static void cliRxRange(char *cmdline)
} else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) { } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
cliShowParseError(); cliShowParseError();
} else { } else {
rxChannelRangeConfiguration_t *channelRangeConfiguration = &rxConfigMutable()->channelRanges[i]; rxChannelRangeConfig_t *channelRangeConfig = &rxConfigMutable()->channelRanges[i];
channelRangeConfiguration->min = rangeMin; channelRangeConfig->min = rangeMin;
channelRangeConfiguration->max = rangeMax; channelRangeConfig->max = rangeMax;
} }
} else { } else {
cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1); cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
@ -3695,7 +3694,7 @@ typedef struct {
const cliResourceValue_t resourceTable[] = { const cliResourceValue_t resourceTable[] = {
#ifdef BEEPER #ifdef BEEPER
{ OWNER_BEEPER, &beeperConfig()->ioTag, 0 }, { OWNER_BEEPER, &beeperDevConfig()->ioTag, 0 },
#endif #endif
{ OWNER_MOTOR, &motorConfig()->ioTags[0], MAX_SUPPORTED_MOTORS }, { OWNER_MOTOR, &motorConfig()->ioTags[0], MAX_SUPPORTED_MOTORS },
#ifdef USE_SERVOS #ifdef USE_SERVOS
@ -4389,7 +4388,7 @@ void cliEnter(serialPort_t *serialPort)
ENABLE_ARMING_FLAG(PREVENT_ARMING); ENABLE_ARMING_FLAG(PREVENT_ARMING);
} }
void cliInit(serialConfig_t *serialConfig) void cliInit(const serialConfig_t *serialConfig)
{ {
UNUSED(serialConfig); UNUSED(serialConfig);
} }

View file

@ -20,7 +20,7 @@
extern uint8_t cliMode; extern uint8_t cliMode;
struct serialConfig_s; struct serialConfig_s;
void cliInit(struct serialConfig_s *serialConfig); void cliInit(const struct serialConfig_s *serialConfig);
void cliProcess(void); void cliProcess(void);
struct serialPort_s; struct serialPort_s;
void cliEnter(struct serialPort_s *serialPort); void cliEnter(struct serialPort_s *serialPort);

View file

@ -340,16 +340,16 @@ void resetAdcConfig(adcConfig_t *adcConfig)
#ifdef BEEPER #ifdef BEEPER
void resetBeeperConfig(beeperConfig_t *beeperConfig) void resetBeeperConfig(beeperDevConfig_t *beeperDevConfig)
{ {
#ifdef BEEPER_INVERTED #ifdef BEEPER_INVERTED
beeperConfig->isOpenDrain = false; beeperDevConfig->isOpenDrain = false;
beeperConfig->isInverted = true; beeperDevConfig->isInverted = true;
#else #else
beeperConfig->isOpenDrain = true; beeperDevConfig->isOpenDrain = true;
beeperConfig->isInverted = false; beeperDevConfig->isInverted = false;
#endif #endif
beeperConfig->ioTag = IO_TAG(BEEPER); beeperDevConfig->ioTag = IO_TAG(BEEPER);
} }
#endif #endif
@ -672,7 +672,7 @@ void createDefaultConfig(master_t *config)
#endif #endif
#ifdef BEEPER #ifdef BEEPER
resetBeeperConfig(&config->beeperConfig); resetBeeperConfig(&config->beeperDevConfig);
#endif #endif
#ifdef SONAR #ifdef SONAR
@ -700,9 +700,9 @@ void createDefaultConfig(master_t *config)
config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i]; rxFailsafeChannelConfig_t *channelFailsafeConfig = &config->rxConfig.failsafe_channel_configurations[i];
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD; channelFailsafeConfig->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc); channelFailsafeConfig->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
} }
config->rxConfig.rssi_channel = 0; config->rxConfig.rssi_channel = 0;
@ -903,8 +903,6 @@ void activateConfig(void)
setAccelerationTrims(&accelerometerConfigMutable()->accZero); setAccelerationTrims(&accelerometerConfigMutable()->accZero);
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz); setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
mixerUseConfigs(&masterConfig.airplaneConfig);
#ifdef USE_SERVOS #ifdef USE_SERVOS
servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.channelForwardingConfig); servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.channelForwardingConfig);
#endif #endif

View file

@ -68,6 +68,13 @@ typedef struct systemConfig_s {
PG_DECLARE(systemConfig_t, systemConfig); PG_DECLARE(systemConfig_t, systemConfig);
/*typedef struct beeperConfig_s {
uint32_t beeper_off_flags;
uint32_t preferred_beeper_off_flags;
} beeperConfig_t;
PG_DECLARE(beeperConfig_t, beeperConfig);
*/
struct profile_s; struct profile_s;
extern struct profile_s *currentProfile; extern struct profile_s *currentProfile;
struct controlRateConfig_s; struct controlRateConfig_s;

View file

@ -308,7 +308,7 @@ void init(void)
systemState |= SYSTEM_STATE_MOTORS_READY; systemState |= SYSTEM_STATE_MOTORS_READY;
#ifdef BEEPER #ifdef BEEPER
beeperInit(beeperConfig()); beeperInit(beeperDevConfig());
#endif #endif
/* temp until PGs are implemented. */ /* temp until PGs are implemented. */
#ifdef USE_INVERTER #ifdef USE_INVERTER

View file

@ -34,6 +34,7 @@
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/altitudehold.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/pid.h" #include "flight/pid.h"

View file

@ -17,9 +17,17 @@
#pragma once #pragma once
#include "common/time.h"
extern int32_t AltHold; extern int32_t AltHold;
extern int32_t vario; extern int32_t vario;
typedef struct airplaneConfig_s {
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
} airplaneConfig_t;
PG_DECLARE(airplaneConfig_t, airplaneConfig);
void calculateEstimatedAltitude(timeUs_t currentTimeUs); void calculateEstimatedAltitude(timeUs_t currentTimeUs);
struct pidProfile_s; struct pidProfile_s;

View file

@ -62,8 +62,6 @@ static float motorMixRange;
int16_t motor[MAX_SUPPORTED_MOTORS]; int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
static airplaneConfig_t *airplaneConfig;
mixerMode_e currentMixerMode; mixerMode_e currentMixerMode;
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS]; static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
@ -291,11 +289,6 @@ void initEscEndpoints(void) {
rcCommandThrottleRange3dHigh = PWM_RANGE_MAX - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle; rcCommandThrottleRange3dHigh = PWM_RANGE_MAX - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
} }
void mixerUseConfigs(airplaneConfig_t *airplaneConfigToUse)
{
airplaneConfig = airplaneConfigToUse;
}
void mixerInit(mixerMode_e mixerMode, const motorMixer_t *initialCustomMixers) void mixerInit(mixerMode_e mixerMode, const motorMixer_t *initialCustomMixers)
{ {
currentMixerMode = mixerMode; currentMixerMode = mixerMode;

View file

@ -118,10 +118,6 @@ typedef struct motorConfig_s {
PG_DECLARE(motorConfig_t, motorConfig); PG_DECLARE(motorConfig_t, motorConfig);
typedef struct airplaneConfig_s {
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
} airplaneConfig_t;
#define CHANNEL_FORWARDING_DISABLED (uint8_t)0xFF #define CHANNEL_FORWARDING_DISABLED (uint8_t)0xFF
extern const mixer_t mixers[]; extern const mixer_t mixers[];
@ -132,8 +128,6 @@ struct rxConfig_s;
uint8_t getMotorCount(); uint8_t getMotorCount();
float getMotorMixRange(); float getMotorMixRange();
void mixerUseConfigs(airplaneConfig_t *airplaneConfigToUse);
void mixerLoadMix(int index, motorMixer_t *customMixers); void mixerLoadMix(int index, motorMixer_t *customMixers);
void mixerInit(mixerMode_e mixerMode, const motorMixer_t *customMotorMixers); void mixerInit(mixerMode_e mixerMode, const motorMixer_t *customMotorMixers);

View file

@ -143,7 +143,7 @@ const mixerRules_t servoMixers[] = {
{ 0, NULL }, { 0, NULL },
}; };
static servoMixer_t *customServoMixers; static const servoMixer_t *customServoMixers;
void servoUseConfigs(servoMixerConfig_t *servoMixerConfigToUse, servoParam_t *servoParamsToUse, struct channelForwardingConfig_s *channelForwardingConfigToUse) void servoUseConfigs(servoMixerConfig_t *servoMixerConfigToUse, servoParam_t *servoParamsToUse, struct channelForwardingConfig_s *channelForwardingConfigToUse)
{ {
@ -173,7 +173,7 @@ int servoDirection(int servoIndex, int inputSource)
return 1; return 1;
} }
void servoMixerInit(servoMixer_t *initialCustomServoMixers) void servoMixerInit(const servoMixer_t *initialCustomServoMixers)
{ {
customServoMixers = initialCustomServoMixers; customServoMixers = initialCustomServoMixers;

View file

@ -133,7 +133,7 @@ bool isMixerUsingServos(void);
void writeServos(void); void writeServos(void);
void filterServos(void); void filterServos(void);
void servoMixerInit(servoMixer_t *customServoMixers); void servoMixerInit(const servoMixer_t *customServoMixers);
void servoUseConfigs(servoMixerConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, struct channelForwardingConfig_s *channelForwardingConfigToUse); void servoUseConfigs(servoMixerConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, struct channelForwardingConfig_s *channelForwardingConfigToUse);
void servoMixerLoadMix(int index, servoMixer_t *customServoMixers); void servoMixerLoadMix(int index, servoMixer_t *customServoMixers);
void loadCustomServoMixer(void); void loadCustomServoMixer(void);

View file

@ -233,7 +233,7 @@ void reevaluateLedConfig(void)
} }
// get specialColor by index // get specialColor by index
static hsvColor_t* getSC(ledSpecialColorIds_e index) static const hsvColor_t* getSC(ledSpecialColorIds_e index)
{ {
return &ledStripConfig()->colors[ledStripConfig()->specialColors.color[index]]; return &ledStripConfig()->colors[ledStripConfig()->specialColors.color[index]];
} }
@ -259,7 +259,7 @@ bool parseLedStripConfig(int ledIndex, const char *config)
}; };
static const char chunkSeparators[PARSE_STATE_COUNT] = {',', ':', ':', ':', '\0'}; static const char chunkSeparators[PARSE_STATE_COUNT] = {',', ':', ':', ':', '\0'};
ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex]; ledConfig_t *ledConfig = &ledStripConfigMutable()->ledConfigs[ledIndex];
memset(ledConfig, 0, sizeof(ledConfig_t)); memset(ledConfig, 0, sizeof(ledConfig_t));
int x = 0, y = 0, color = 0; // initialize to prevent warnings int x = 0, y = 0, color = 0; // initialize to prevent warnings
@ -418,7 +418,7 @@ static const struct {
{LED_DIRECTION_UP, QUADRANT_ANY}, {LED_DIRECTION_UP, QUADRANT_ANY},
}; };
static hsvColor_t* getDirectionalModeColor(const int ledIndex, const modeColorIndexes_t *modeColors) static const hsvColor_t* getDirectionalModeColor(const int ledIndex, const modeColorIndexes_t *modeColors)
{ {
const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex]; const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex];
@ -468,7 +468,7 @@ static void applyLedFixedLayers()
case LED_FUNCTION_FLIGHT_MODE: case LED_FUNCTION_FLIGHT_MODE:
for (unsigned i = 0; i < ARRAYLEN(flightModeToLed); i++) for (unsigned i = 0; i < ARRAYLEN(flightModeToLed); i++)
if (!flightModeToLed[i].flightMode || FLIGHT_MODE(flightModeToLed[i].flightMode)) { if (!flightModeToLed[i].flightMode || FLIGHT_MODE(flightModeToLed[i].flightMode)) {
hsvColor_t *directionalColor = getDirectionalModeColor(ledIndex, &ledStripConfig()->modeColors[flightModeToLed[i].ledMode]); const hsvColor_t *directionalColor = getDirectionalModeColor(ledIndex, &ledStripConfig()->modeColors[flightModeToLed[i].ledMode]);
if (directionalColor) { if (directionalColor) {
color = *directionalColor; color = *directionalColor;
} }
@ -597,7 +597,7 @@ static void applyLedBatteryLayer(bool updateNow, timeUs_t *timer)
*timer += timerDelayUs; *timer += timerDelayUs;
if (!flash) { if (!flash) {
hsvColor_t *bgc = getSC(LED_SCOLOR_BACKGROUND); const hsvColor_t *bgc = getSC(LED_SCOLOR_BACKGROUND);
applyLedHsv(LED_MOV_FUNCTION(LED_FUNCTION_BATTERY), bgc); applyLedHsv(LED_MOV_FUNCTION(LED_FUNCTION_BATTERY), bgc);
} }
} }
@ -626,7 +626,7 @@ static void applyLedRssiLayer(bool updateNow, timeUs_t *timer)
*timer += timerDelay; *timer += timerDelay;
if (!flash) { if (!flash) {
hsvColor_t *bgc = getSC(LED_SCOLOR_BACKGROUND); const hsvColor_t *bgc = getSC(LED_SCOLOR_BACKGROUND);
applyLedHsv(LED_MOV_FUNCTION(LED_FUNCTION_RSSI), bgc); applyLedHsv(LED_MOV_FUNCTION(LED_FUNCTION_RSSI), bgc);
} }
} }
@ -983,7 +983,7 @@ bool parseColor(int index, const char *colorConfig)
{ {
const char *remainingCharacters = colorConfig; const char *remainingCharacters = colorConfig;
hsvColor_t *color = &ledStripConfig()->colors[index]; hsvColor_t *color = &ledStripConfigMutable()->colors[index];
bool result = true; bool result = true;
static const uint16_t hsv_limit[HSV_COLOR_COMPONENT_COUNT] = { static const uint16_t hsv_limit[HSV_COLOR_COMPONENT_COUNT] = {
@ -1036,15 +1036,15 @@ bool setModeColor(ledModeIndex_e modeIndex, int modeColorIndex, int colorIndex)
if (modeIndex < LED_MODE_COUNT) { // modeIndex_e is unsigned, so one-sided test is enough if (modeIndex < LED_MODE_COUNT) { // modeIndex_e is unsigned, so one-sided test is enough
if(modeColorIndex < 0 || modeColorIndex >= LED_DIRECTION_COUNT) if(modeColorIndex < 0 || modeColorIndex >= LED_DIRECTION_COUNT)
return false; return false;
ledStripConfig()->modeColors[modeIndex].color[modeColorIndex] = colorIndex; ledStripConfigMutable()->modeColors[modeIndex].color[modeColorIndex] = colorIndex;
} else if (modeIndex == LED_SPECIAL) { } else if (modeIndex == LED_SPECIAL) {
if (modeColorIndex < 0 || modeColorIndex >= LED_SPECIAL_COLOR_COUNT) if (modeColorIndex < 0 || modeColorIndex >= LED_SPECIAL_COLOR_COUNT)
return false; return false;
ledStripConfig()->specialColors.color[modeColorIndex] = colorIndex; ledStripConfigMutable()->specialColors.color[modeColorIndex] = colorIndex;
} else if (modeIndex == LED_AUX_CHANNEL) { } else if (modeIndex == LED_AUX_CHANNEL) {
if (modeColorIndex < 0 || modeColorIndex >= 1) if (modeColorIndex < 0 || modeColorIndex >= 1)
return false; return false;
ledStripConfig()->ledstrip_aux_channel = colorIndex; ledStripConfigMutable()->ledstrip_aux_channel = colorIndex;
} else { } else {
return false; return false;
} }
@ -1104,8 +1104,7 @@ void applyDefaultSpecialColors(specialColorIndexes_t *specialColors)
void ledStripInit() void ledStripInit()
{ {
ledConfigs = ledStripConfig()->ledConfigs; colors = ledStripConfigMutable()->colors;
colors = ledStripConfig()->colors;
modeColors = ledStripConfig()->modeColors; modeColors = ledStripConfig()->modeColors;
specialColors = ledStripConfig()->specialColors; specialColors = ledStripConfig()->specialColors;
ledStripInitialised = false; ledStripInitialised = false;

View file

@ -152,7 +152,7 @@ PG_DECLARE(ledStripConfig_t, ledStripConfig);
ledConfig_t *ledConfigs; ledConfig_t *ledConfigs;
hsvColor_t *colors; hsvColor_t *colors;
modeColorIndexes_t *modeColors; const modeColorIndexes_t *modeColors;
specialColorIndexes_t specialColors; specialColorIndexes_t specialColors;
#define LF(name) LED_FUNCTION_ ## name #define LF(name) LED_FUNCTION_ ## name

View file

@ -140,12 +140,12 @@ STATIC_UNIT_TESTED void rxUpdateFlightChannelStatus(uint8_t channel, bool valid)
} }
} }
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfiguration_t *rxChannelRangeConfiguration) { void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig) {
// set default calibration to full range and 1:1 mapping // set default calibration to full range and 1:1 mapping
for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) { for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
rxChannelRangeConfiguration->min = PWM_RANGE_MIN; rxChannelRangeConfig->min = PWM_RANGE_MIN;
rxChannelRangeConfiguration->max = PWM_RANGE_MAX; rxChannelRangeConfig->max = PWM_RANGE_MAX;
rxChannelRangeConfiguration++; rxChannelRangeConfig++;
} }
} }
@ -377,9 +377,9 @@ static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
static uint16_t getRxfailValue(uint8_t channel) static uint16_t getRxfailValue(uint8_t channel)
{ {
const rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig()->failsafe_channel_configurations[channel]; const rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxConfig()->failsafe_channel_configurations[channel];
switch(channelFailsafeConfiguration->mode) { switch(channelFailsafeConfig->mode) {
case RX_FAILSAFE_MODE_AUTO: case RX_FAILSAFE_MODE_AUTO:
switch (channel) { switch (channel) {
case ROLL: case ROLL:
@ -400,11 +400,11 @@ static uint16_t getRxfailValue(uint8_t channel)
return rcData[channel]; return rcData[channel];
case RX_FAILSAFE_MODE_SET: case RX_FAILSAFE_MODE_SET:
return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step); return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step);
} }
} }
STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfiguration_t range) STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfig_t range)
{ {
// Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT // Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT
if (sample == PPM_RCVR_TIMEOUT) { if (sample == PPM_RCVR_TIMEOUT) {

View file

@ -101,21 +101,19 @@ typedef enum {
#define RX_FAILSAFE_TYPE_COUNT 2 #define RX_FAILSAFE_TYPE_COUNT 2
typedef struct rxFailsafeChannelConfiguration_s { typedef struct rxFailsafeChannelConfig_s {
uint8_t mode; // See rxFailsafeChannelMode_e uint8_t mode; // See rxFailsafeChannelMode_e
uint8_t step; uint8_t step;
} rxFailsafeChannelConfiguration_t; } rxFailsafeChannelConfig_t;
//!!TODO change to rxFailsafeChannelConfig_t PG_DECLARE_ARRAY(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs);
PG_DECLARE_ARRAY(rxFailsafeChannelConfiguration_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs);
typedef struct rxChannelRangeConfiguration_s { typedef struct rxChannelRangeConfig_s {
uint16_t min; uint16_t min;
uint16_t max; uint16_t max;
} rxChannelRangeConfiguration_t; } rxChannelRangeConfig_t;
//!!TODO change to rxChannelRangeConfig_t PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
PG_DECLARE_ARRAY(rxChannelRangeConfiguration_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
typedef struct rxConfig_s { typedef struct rxConfig_s {
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
@ -141,9 +139,9 @@ typedef struct rxConfig_s {
uint16_t rx_min_usec; uint16_t rx_min_usec;
uint16_t rx_max_usec; uint16_t rx_max_usec;
rxFailsafeChannelConfiguration_t failsafe_channel_configurations[MAX_SUPPORTED_RC_CHANNEL_COUNT]; rxFailsafeChannelConfig_t failsafe_channel_configurations[MAX_SUPPORTED_RC_CHANNEL_COUNT];
rxChannelRangeConfiguration_t channelRanges[NON_AUX_CHANNEL_COUNT]; rxChannelRangeConfig_t channelRanges[NON_AUX_CHANNEL_COUNT];
} rxConfig_t; } rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig); PG_DECLARE(rxConfig_t, rxConfig);
@ -174,7 +172,7 @@ void calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs);
void parseRcChannels(const char *input, rxConfig_t *rxConfig); void parseRcChannels(const char *input, rxConfig_t *rxConfig);
void updateRSSI(timeUs_t currentTimeUs); void updateRSSI(timeUs_t currentTimeUs);
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfiguration_t *rxChannelRangeConfiguration); void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig);
void suspendRxSignal(void); void suspendRxSignal(void);
void resumeRxSignal(void); void resumeRxSignal(void);

View file

@ -35,7 +35,7 @@ void targetConfiguration(master_t *config)
if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) { if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) {
config->gyroConfig.gyro_align = CW180_DEG; config->gyroConfig.gyro_align = CW180_DEG;
config->accelerometerConfig.acc_align = CW180_DEG; config->accelerometerConfig.acc_align = CW180_DEG;
config->beeperConfig.ioTag = IO_TAG(BEEPER_OPT); config->beeperDevConfig.ioTag = IO_TAG(BEEPER_OPT);
} }
if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) { if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) {

View file

@ -88,11 +88,11 @@ void targetConfiguration(master_t *config)
#if !defined(AFROMINI) && !defined(BEEBRAIN) #if !defined(AFROMINI) && !defined(BEEBRAIN)
if (hardwareRevision >= NAZE32_REV5) { if (hardwareRevision >= NAZE32_REV5) {
// naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN. // naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
config->beeperConfig.isOpenDrain = false; config->beeperDevConfig.isOpenDrain = false;
config->beeperConfig.isInverted = true; config->beeperDevConfig.isInverted = true;
} else { } else {
config->beeperConfig.isOpenDrain = true; config->beeperDevConfig.isOpenDrain = true;
config->beeperConfig.isInverted = false; config->beeperDevConfig.isInverted = false;
config->flashConfig.csTag = IO_TAG_NONE; config->flashConfig.csTag = IO_TAG_NONE;
} }
#endif #endif