1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Moved free standing items out of masterConfig into separate configs

This commit is contained in:
Martin Budden 2017-02-20 15:22:56 +00:00
parent e4ae2526e0
commit faf1ecf0e2
15 changed files with 111 additions and 107 deletions

View file

@ -1178,8 +1178,8 @@ static bool blackboxWriteSysinfo()
return false;
}
const profile_t *currentProfile = &masterConfig.profile[masterConfig.current_profile_index];
const controlRateConfig_t *currentControlRateProfile = &currentProfile->controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile];
const profile_t *currentProfile = &masterConfig.profile[systemConfig()->current_profile_index];
const controlRateConfig_t *currentControlRateProfile = &currentProfile->controlRateProfile[masterConfig.profile[systemConfig()->current_profile_index].activeRateProfile];
switch (xmitState.headerIndex) {
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);

View file

@ -64,7 +64,7 @@ static controlRateConfig_t rateProfile;
static long cmsx_menuImu_onEnter(void)
{
profileIndex = masterConfig.current_profile_index;
profileIndex = systemConfig()->current_profile_index;
tmpProfileIndex = profileIndex + 1;
rateProfileIndex = masterConfig.profile[profileIndex].activeRateProfile;
@ -77,7 +77,7 @@ static long cmsx_menuImu_onExit(const OSD_Entry *self)
{
UNUSED(self);
masterConfig.current_profile_index = profileIndex;
systemConfigMutable()->current_profile_index = profileIndex;
masterConfig.profile[profileIndex].activeRateProfile = rateProfileIndex;
return 0;

View file

@ -77,25 +77,25 @@ static OSD_UINT8_t entryVtxChannel = {&cmsx_vtxChannel, 1, 8, 1};
static void cmsx_Vtx_ConfigRead(void)
{
#ifdef VTX
cmsx_vtxBand = masterConfig.vtx_band;
cmsx_vtxChannel = masterConfig.vtx_channel + 1;
cmsx_vtxBand = vtxConfig()->vtx_band;
cmsx_vtxChannel = vtxConfig()->vtx_channel + 1;
#endif // VTX
#ifdef USE_RTC6705
cmsx_vtxBand = masterConfig.vtx_channel / 8;
cmsx_vtxChannel = masterConfig.vtx_channel % 8 + 1;
cmsx_vtxBand = vtxConfig()->vtx_channel / 8;
cmsx_vtxChannel = vtxConfig()->vtx_channel % 8 + 1;
#endif // USE_RTC6705
}
static void cmsx_Vtx_ConfigWriteback(void)
{
#ifdef VTX
masterConfig.vtx_band = cmsx_vtxBand;
masterConfig.vtx_channel = cmsx_vtxChannel - 1;
vtxConfig()->vtx_band = cmsx_vtxBand;
vtxConfig()->vtx_channel = cmsx_vtxChannel - 1;
#endif // VTX
#ifdef USE_RTC6705
masterConfig.vtx_channel = cmsx_vtxBand * 8 + cmsx_vtxChannel - 1;
vtxConfig()->vtx_channel = cmsx_vtxBand * 8 + cmsx_vtxChannel - 1;
#endif // USE_RTC6705
}
@ -117,8 +117,8 @@ static long cmsx_Vtx_onExit(const OSD_Entry *self)
}
#ifdef VTX
static OSD_UINT8_t entryVtxMode = {&masterConfig.vtx_mode, 0, 2, 1};
static OSD_UINT16_t entryVtxMhz = {&masterConfig.vtx_mhz, 5600, 5950, 1};
static OSD_UINT8_t entryVtxMode = {&vtxConfig()->vtx_mode, 0, 2, 1};
static OSD_UINT16_t entryVtxMhz = {&vtxConfig()->vtx_mhz, 5600, 5950, 1};
#endif // VTX
static OSD_Entry cmsx_menuVtxEntries[] =
@ -132,7 +132,7 @@ static OSD_Entry cmsx_menuVtxEntries[] =
{"BAND", OME_TAB, NULL, &entryVtxBand, 0},
{"CHANNEL", OME_UINT8, NULL, &entryVtxChannel, 0},
#ifdef USE_RTC6705
{"LOW POWER", OME_Bool, NULL, &masterConfig.vtx_power, 0},
{"LOW POWER", OME_Bool, NULL, &vtxConfig()->vtx_power, 0},
#endif // USE_RTC6705
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}

View file

@ -49,12 +49,13 @@
#include "flight/navigation.h"
#include "flight/pid.h"
#include "io/serial.h"
#include "io/beeper.h"
#include "io/gimbal.h"
#include "io/servos.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/ledstrip.h"
#include "io/osd.h"
#include "io/serial.h"
#include "io/servos.h"
#include "io/vtx.h"
#include "rx/rx.h"
@ -119,6 +120,8 @@
#define displayPortProfileMsp(x) (&masterConfig.displayPortProfileMsp)
#define displayPortProfileMax7456(x) (&masterConfig.displayPortProfileMax7456)
#define displayPortProfileOled(x) (&masterConfig.displayPortProfileOled)
#define vtxConfig(x) (&masterConfig.vtxConfig)
#define beeperConfig(x) (&masterConfig.beeperConfig)
#define featureConfigMutable(x) (&masterConfig.featureConfig)
@ -168,6 +171,8 @@
#define displayPortProfileMspMutable(x) (&masterConfig.displayPortProfileMsp)
#define displayPortProfileMax7456Mutable(x) (&masterConfig.displayPortProfileMax7456)
#define displayPortProfileOledMutable(x) (&masterConfig.displayPortProfileOled)
#define vtxConfigMutable(x) (&masterConfig.vtxConfig)
#define beeperConfigMutable(x) (&masterConfig.beeperConfig)
#define servoParams(x) (&servoProfile()->servoConf[x])
#define adjustmentRanges(x) (&adjustmentProfile()->adjustmentRanges[x])
@ -214,8 +219,6 @@ typedef struct master_s {
pidConfig_t pidConfig;
uint8_t task_statistics;
gyroConfig_t gyroConfig;
compassConfig_t compassConfig;
@ -278,11 +281,6 @@ typedef struct master_s {
uint8_t transponderData[6];
#endif
#if defined(USE_RTC6705)
uint8_t vtx_channel;
uint8_t vtx_power;
#endif
#ifdef OSD
osd_profile_t osdProfile;
#endif
@ -303,19 +301,12 @@ typedef struct master_s {
#endif
profile_t profile[MAX_PROFILE_COUNT];
uint8_t current_profile_index;
modeActivationProfile_t modeActivationProfile;
adjustmentProfile_t adjustmentProfile;
#ifdef VTX
uint8_t vtx_band; //1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Raceband
uint8_t vtx_channel; //1-8
uint8_t vtx_mode; //0=ch+band 1=mhz
uint16_t vtx_mhz; //5740
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
#if defined(USE_RTC6705) || defined(VTX)
vtxConfig_t vtxConfig;
#endif
#ifdef BLACKBOX
blackboxConfig_t blackboxConfig;
#endif
@ -324,8 +315,7 @@ typedef struct master_s {
flashConfig_t flashConfig;
#endif
uint32_t beeper_off_flags;
uint32_t preferred_beeper_off_flags;
beeperConfig_t beeperConfig;
char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER)];

View file

@ -562,7 +562,7 @@ typedef struct {
static const clivalue_t valueTable[] = {
#ifndef SKIP_TASK_STATISTICS
{ "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.task_statistics, .config.lookup = { TABLE_OFF_ON } },
{ "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &systemConfig()->task_statistics, .config.lookup = { TABLE_OFF_ON } },
#endif
{ "mid_rc", VAR_UINT16 | MASTER_VALUE, &rxConfig()->midrc, .config.minmax = { 1200, 1700 } },
{ "min_check", VAR_UINT16 | MASTER_VALUE, &rxConfig()->mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
@ -818,10 +818,10 @@ static const clivalue_t valueTable[] = {
#endif
#ifdef VTX
{ "vtx_band", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_band, .config.minmax = { 1, 5 } },
{ "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 1, 8 } },
{ "vtx_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_mode, .config.minmax = { 0, 2 } },
{ "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } },
{ "vtx_band", VAR_UINT8 | MASTER_VALUE, &vtxConfig()->vtx_band, .config.minmax = { 1, 5 } },
{ "vtx_channel", VAR_UINT8 | MASTER_VALUE, &vtxConfig()->vtx_channel, .config.minmax = { 1, 8 } },
{ "vtx_mode", VAR_UINT8 | MASTER_VALUE, &vtxConfig()->vtx_mode, .config.minmax = { 0, 2 } },
{ "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &vtxConfig()->vtx_mhz, .config.minmax = { 5600, 5950 } },
#endif
#ifdef MAG
@ -833,8 +833,8 @@ static const clivalue_t valueTable[] = {
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &ledStripConfig()->ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
#endif
#if defined(USE_RTC6705)
{ "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
{ "vtx_channel", VAR_UINT8 | MASTER_VALUE, &vtxConfig()->vtx_channel, .config.minmax = { 0, 39 } },
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, &vtxConfig()->vtx_power, .config.minmax = { 0, 1 } },
#endif
#ifdef USE_SDCARD
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sdcardConfig()->useDma, .config.lookup = { TABLE_OFF_ON } },
@ -1366,11 +1366,11 @@ void *getValuePointer(const clivalue_t *value)
void *ptr = value->ptr;
if ((value->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * systemConfig()->current_profile_index);
}
if ((value->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * systemConfig()->current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
}
return ptr;
@ -2841,9 +2841,9 @@ static void printVtx(uint8_t dumpMask, const master_t *defaultConfig)
const char *format = "vtx %u %u %u %u %u %u\r\n";
bool equalsDefault = false;
for (uint32_t i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
const vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
const vtxChannelActivationCondition_t *cac = &vtxConfig()->vtxChannelActivationConditions[i];
if (defaultConfig) {
const vtxChannelActivationCondition_t *cacDefault = &defaultConfig->vtxChannelActivationConditions[i];
const vtxChannelActivationCondition_t *cacDefault = &defaultConfig->vtxConfig.vtxChannelActivationConditions[i];
equalsDefault = cac->auxChannelIndex == cacDefault->auxChannelIndex
&& cac->band == cacDefault->band
&& cac->channel == cacDefault->channel
@ -2880,7 +2880,7 @@ static void cliVtx(char *cmdline)
ptr = cmdline;
i = atoi(ptr++);
if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
vtxChannelActivationCondition_t *cac = &vtxConfig()->vtxChannelActivationConditions[i];
uint8_t validArgumentCount = 0;
ptr = nextArg(ptr);
if (ptr) {
@ -3032,7 +3032,7 @@ static void printBeeper(uint8_t dumpMask, const master_t *defaultConfig)
{
const uint8_t beeperCount = beeperTableEntryCount();
const uint32_t mask = getBeeperOffMask();
const uint32_t defaultMask = defaultConfig->beeper_off_flags;
const uint32_t defaultMask = defaultConfig->beeperConfig.beeper_off_flags;
for (int32_t i = 0; i < beeperCount - 2; i++) {
const char *formatOff = "beeper -%s\r\n";
const char *formatOn = "beeper %s\r\n";
@ -3407,7 +3407,7 @@ static void cliProfile(char *cmdline)
} else {
const int i = atoi(cmdline);
if (i >= 0 && i < MAX_PROFILE_COUNT) {
masterConfig.current_profile_index = i;
systemConfigMutable()->current_profile_index = i;
writeEEPROM();
readEEPROM();
cliProfile("");
@ -3659,7 +3659,7 @@ static void cliTasks(char *cmdline)
int averageLoadSum = 0;
#ifndef MINIMAL_CLI
if (masterConfig.task_statistics) {
if (systemConfig()->task_statistics) {
cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
} else {
cliPrintf("Task list\r\n");
@ -3690,7 +3690,7 @@ static void cliTasks(char *cmdline)
maxLoadSum += maxLoad;
averageLoadSum += averageLoad;
}
if (masterConfig.task_statistics) {
if (systemConfig()->task_statistics) {
cliPrintf("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d\r\n",
taskFrequency, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime,
maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10, taskInfo.totalExecutionTime / 1000);
@ -3702,7 +3702,7 @@ static void cliTasks(char *cmdline)
}
}
}
if (masterConfig.task_statistics) {
if (systemConfig()->task_statistics) {
cfCheckFuncInfo_t checkFuncInfo;
getCheckFuncInfo(&checkFuncInfo);
cliPrintf("RX Check Function %17d %7d %25d\r\n", checkFuncInfo.maxExecutionTime, checkFuncInfo.averageExecutionTime, checkFuncInfo.totalExecutionTime / 1000);
@ -4127,7 +4127,7 @@ static void printConfig(char *cmdline, bool doDiff)
dumpValues(MASTER_VALUE, dumpMask, &defaultConfig);
if (dumpMask & DUMP_ALL) {
uint8_t activeProfile = masterConfig.current_profile_index;
uint8_t activeProfile = systemConfig()->current_profile_index;
for (uint32_t profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
cliDumpProfile(profileCount, dumpMask, &defaultConfig);
@ -4148,13 +4148,13 @@ static void printConfig(char *cmdline, bool doDiff)
cliPrintHashLine("save configuration");
cliPrint("save");
} else {
cliDumpProfile(masterConfig.current_profile_index, dumpMask, &defaultConfig);
cliDumpProfile(systemConfig()->current_profile_index, dumpMask, &defaultConfig);
cliDumpRateProfile(currentProfile->activeRateProfile, dumpMask, &defaultConfig);
}
}
if (dumpMask & DUMP_PROFILE) {
cliDumpProfile(masterConfig.current_profile_index, dumpMask, &defaultConfig);
cliDumpProfile(systemConfig()->current_profile_index, dumpMask, &defaultConfig);
}
if (dumpMask & DUMP_RATES) {
@ -4425,7 +4425,7 @@ void cliEnter(serialPort_t *serialPort)
setPrintfSerialPort(cliPort);
cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer), (bufWrite_t)serialWriteBufShim, serialPort);
schedulerSetCalulateTaskStatistics(masterConfig.task_statistics);
schedulerSetCalulateTaskStatistics(systemConfig()->task_statistics);
#ifndef MINIMAL_CLI
cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");

View file

@ -723,7 +723,8 @@ void resetFlashConfig(flashConfig_t *flashConfig)
uint8_t getCurrentProfile(void)
{
return masterConfig.current_profile_index;
return systemConfig()->current_profile_index;
;
}
static void setProfile(uint8_t profileIndex)
@ -794,7 +795,7 @@ void createDefaultConfig(master_t *config)
config->version = EEPROM_CONF_VERSION;
// global settings
config->current_profile_index = 0; // default profile
config->systemConfig.current_profile_index = 0; // default profile
config->imuConfig.dcm_kp = 2500; // 1.0 * 10000
config->imuConfig.dcm_ki = 0; // 0.003 * 10000
#ifndef USE_PARAMETER_GROUPS
@ -820,7 +821,7 @@ void createDefaultConfig(master_t *config)
#endif
config->systemConfig.debug_mode = DEBUG_MODE;
config->task_statistics = true;
config->systemConfig.task_statistics = true;
@ -1009,10 +1010,10 @@ void createDefaultConfig(master_t *config)
}
#ifdef VTX
config->vtx_band = 4; //Fatshark/Airwaves
config->vtx_channel = 1; //CH1
config->vtx_mode = 0; //CH+BAND mode
config->vtx_mhz = 5740; //F0
config->vtxConfig.vtx_band = 4; //Fatshark/Airwaves
config->vtxConfig.vtx_channel = 1; //CH1
config->vtxConfig.vtx_mode = 0; //CH+BAND mode
config->vtxConfig.vtx_mhz = 5740; //F0
#endif
#ifdef TRANSPONDER
@ -1265,11 +1266,11 @@ void readEEPROM(void)
// pgActivateProfile(getCurrentProfile());
// setControlRateProfile(rateProfileSelection()->defaultRateProfileIndex);
if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) {// sanity check
masterConfig.current_profile_index = 0;
if (systemConfig()->current_profile_index > MAX_PROFILE_COUNT - 1) {// sanity check
systemConfig()->current_profile_index = 0;
}
setProfile(masterConfig.current_profile_index);
setProfile(systemConfig()->current_profile_index);
validateAndFixConfig();
activateConfig();
@ -1312,7 +1313,7 @@ void changeProfile(uint8_t profileIndex)
if (profileIndex >= MAX_PROFILE_COUNT) {
profileIndex = MAX_PROFILE_COUNT - 1;
}
masterConfig.current_profile_index = profileIndex;
systemConfig()->current_profile_index = profileIndex;
writeEEPROM();
readEEPROM();
beeperConfirmationBeeps(profileIndex + 1);
@ -1329,40 +1330,40 @@ void changeControlRateProfile(uint8_t profileIndex)
void beeperOffSet(uint32_t mask)
{
masterConfig.beeper_off_flags |= mask;
beeperConfigMutable()->beeper_off_flags |= mask;
}
void beeperOffSetAll(uint8_t beeperCount)
{
masterConfig.beeper_off_flags = (1 << beeperCount) -1;
beeperConfigMutable()->beeper_off_flags = (1 << beeperCount) -1;
}
void beeperOffClear(uint32_t mask)
{
masterConfig.beeper_off_flags &= ~(mask);
beeperConfigMutable()->beeper_off_flags &= ~(mask);
}
void beeperOffClearAll(void)
{
masterConfig.beeper_off_flags = 0;
beeperConfigMutable()->beeper_off_flags = 0;
}
uint32_t getBeeperOffMask(void)
{
return masterConfig.beeper_off_flags;
return beeperConfig()->beeper_off_flags;
}
void setBeeperOffMask(uint32_t mask)
{
masterConfig.beeper_off_flags = mask;
beeperConfigMutable()->beeper_off_flags = mask;
}
uint32_t getPreferredBeeperOffMask(void)
{
return masterConfig.preferred_beeper_off_flags;
return beeperConfig()->preferred_beeper_off_flags;
}
void setPreferredBeeperOffMask(uint32_t mask)
{
masterConfig.preferred_beeper_off_flags = mask;
beeperConfigMutable()->preferred_beeper_off_flags = mask;
}

View file

@ -70,7 +70,9 @@ typedef enum {
} features_e;
typedef struct systemConfig_s {
uint8_t current_profile_index;
uint8_t debug_mode;
uint8_t task_statistics;
char name[MAX_NAME_LENGTH + 1];
} systemConfig_t;
@ -84,13 +86,6 @@ PG_DECLARE(vcdProfile_t, vcdProfile);
PG_DECLARE(sdcardConfig_t, sdcardConfig);
PG_DECLARE(serialPinConfig_t, serialPinConfig);
/*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;
extern struct profile_s *currentProfile;
struct controlRateConfig_s;

View file

@ -386,9 +386,9 @@ void init(void)
#ifdef USE_RTC6705
if (feature(FEATURE_VTX)) {
rtc6705_soft_spi_init();
current_vtx_channel = masterConfig.vtx_channel;
current_vtx_channel = vtxConfig()->vtx_channel;
rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
rtc6705_soft_spi_set_rf_power(masterConfig.vtx_power);
rtc6705_soft_spi_set_rf_power(vtxConfig()->vtx_power);
}
#endif

View file

@ -636,7 +636,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
#endif
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4);
sbufWriteU32(dst, packFlightModeFlags());
sbufWriteU8(dst, masterConfig.current_profile_index);
sbufWriteU8(dst, systemConfig()->current_profile_index);
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
sbufWriteU16(dst, 0); // gyro cycle time
break;
@ -1663,9 +1663,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
uint16_t tmp = sbufReadU16(src);
#if defined(USE_RTC6705)
if (tmp < 40)
masterConfig.vtx_channel = tmp;
if (current_vtx_channel != masterConfig.vtx_channel) {
current_vtx_channel = masterConfig.vtx_channel;
vtxConfig()->vtx_channel = tmp;
if (current_vtx_channel != vtxConfig()->vtx_channel) {
current_vtx_channel = vtxConfig()->vtx_channel;
rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
}
#else

View file

@ -18,6 +18,7 @@
#pragma once
#include "common/time.h"
#include "config/parameter_group.h"
typedef enum {
// IMPORTANT: these are in priority order, 0 = Highest
@ -47,6 +48,14 @@ typedef enum {
// BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum
} beeperMode_e;
typedef struct beeperConfig_s {
uint32_t beeper_off_flags;
uint32_t preferred_beeper_off_flags;
} beeperConfig_t;
PG_DECLARE(beeperConfig_t, beeperConfig);
void beeper(beeperMode_e mode);
void beeperSilence(void);
void beeperUpdate(timeUs_t currentTimeUs);

View file

@ -393,7 +393,7 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_PIDRATE_PROFILE:
{
const uint8_t profileIndex = masterConfig.current_profile_index;
const uint8_t profileIndex = systemConfig()->current_profile_index;
const uint8_t rateProfileIndex = masterConfig.profile[profileIndex].activeRateProfile;
sprintf(buff, "%d-%d", profileIndex + 1, rateProfileIndex + 1);
break;

View file

@ -44,10 +44,10 @@ static uint8_t locked = 0;
void vtxInit(void)
{
rtc6705Init();
if (masterConfig.vtx_mode == 0) {
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
} else if (masterConfig.vtx_mode == 1) {
rtc6705SetFreq(masterConfig.vtx_mhz);
if (vtxConfig()->vtx_mode == 0) {
rtc6705SetChannel(vtxConfig()->vtx_band, vtxConfig()->vtx_channel);
} else if (vtxConfig()->vtx_mode == 1) {
rtc6705SetFreq(vtxConfig()->vtx_mhz);
}
}
@ -57,12 +57,12 @@ static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_
locked = 1;
}
if (masterConfig.vtx_mode == 0 && !locked) {
if (vtxConfig()->vtx_mode == 0 && !locked) {
uint8_t temp = (*bandOrChannel) + step;
temp = constrain(temp, min, max);
*bandOrChannel = temp;
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
rtc6705SetChannel(vtxConfig()->vtx_band, vtxConfig()->vtx_channel);
writeEEPROM();
readEEPROM();
beeperConfirmationBeeps(temp);
@ -71,22 +71,22 @@ static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_
void vtxIncrementBand(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_band), 1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
setChannelSaveAndNotify(&(vtxConfig()->vtx_band), 1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
}
void vtxDecrementBand(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_band), -1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
setChannelSaveAndNotify(&(vtxConfig()->vtx_band), -1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
}
void vtxIncrementChannel(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_channel), 1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
setChannelSaveAndNotify(&(vtxConfig()->vtx_channel), 1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
}
void vtxDecrementChannel(void)
{
setChannelSaveAndNotify(&(masterConfig.vtx_channel), -1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
setChannelSaveAndNotify(&(vtxConfig()->vtx_channel), -1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
}
void vtxUpdateActivatedChannel(void)
@ -95,12 +95,12 @@ void vtxUpdateActivatedChannel(void)
locked = 1;
}
if (masterConfig.vtx_mode == 2 && !locked) {
if (vtxConfig()->vtx_mode == 2 && !locked) {
static uint8_t lastIndex = -1;
uint8_t index;
for (index = 0; index < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; index++) {
vtxChannelActivationCondition_t *vtxChannelActivationCondition = &masterConfig.vtxChannelActivationConditions[index];
vtxChannelActivationCondition_t *vtxChannelActivationCondition = &vtxConfig()->vtxChannelActivationConditions[index];
if (isRangeActive(vtxChannelActivationCondition->auxChannelIndex, &vtxChannelActivationCondition->range)
&& index != lastIndex) {

View file

@ -32,6 +32,15 @@ typedef struct vtxChannelActivationCondition_s {
channelRange_t range;
} vtxChannelActivationCondition_t;
typedef struct vtxConfig_s {
uint8_t vtx_power;
uint8_t vtx_channel; //1-8
uint8_t vtx_band; //1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Raceband
uint8_t vtx_mode; //0=ch+band 1=mhz
uint16_t vtx_mhz; //5740
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
} vtxConfig_t;
void vtxInit(void);
void vtxIncrementBand(void);
void vtxDecrementBand(void);

View file

@ -598,7 +598,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
junk |= 1 << i;
}
bstWrite32(junk);
bstWrite8(masterConfig.current_profile_index);
bstWrite8(systemConfig()->current_profile_index);
break;
case BST_RAW_IMU:
{
@ -1002,9 +1002,9 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
switch(bstWriteCommand) {
case BST_SELECT_SETTING:
if (!ARMING_FLAG(ARMED)) {
masterConfig.current_profile_index = bstRead8();
if (masterConfig.current_profile_index > 2) {
masterConfig.current_profile_index = 0;
systemConfigMutable()->current_profile_index = bstRead8();
if (systemConfig()->current_profile_index > 2) {
systemConfigMutable()->current_profile_index = 0;
}
writeEEPROM();
readEEPROM();