Added osdProfile, vcdProfile, sdcard, and blackbox config macros

This commit is contained in:
Martin Budden 2016-11-30 23:43:10 +00:00
parent 57a9393f5f
commit 4498f58918
9 changed files with 106 additions and 102 deletions

View File

@ -349,7 +349,7 @@ bool blackboxMayEditConfig()
}
static bool blackboxIsOnlyLoggingIntraframes() {
return masterConfig.blackboxConfig.rate_num == 1 && masterConfig.blackboxConfig.rate_denom == 32;
return blackboxConfig()->rate_num == 1 && blackboxConfig()->rate_denom == 32;
}
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
@ -407,7 +407,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
return rxConfig()->rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
return masterConfig.blackboxConfig.rate_num < masterConfig.blackboxConfig.rate_denom;
return blackboxConfig()->rate_num < blackboxConfig()->rate_denom;
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
return false;
@ -758,22 +758,22 @@ static void validateBlackboxConfig()
{
int div;
if (masterConfig.blackboxConfig.rate_num == 0 || masterConfig.blackboxConfig.rate_denom == 0
|| masterConfig.blackboxConfig.rate_num >= masterConfig.blackboxConfig.rate_denom) {
masterConfig.blackboxConfig.rate_num = 1;
masterConfig.blackboxConfig.rate_denom = 1;
if (blackboxConfig()->rate_num == 0 || blackboxConfig()->rate_denom == 0
|| blackboxConfig()->rate_num >= blackboxConfig()->rate_denom) {
blackboxConfig()->rate_num = 1;
blackboxConfig()->rate_denom = 1;
} else {
/* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
* itself more frequently)
*/
div = gcd(masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
div = gcd(blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
masterConfig.blackboxConfig.rate_num /= div;
masterConfig.blackboxConfig.rate_denom /= div;
blackboxConfig()->rate_num /= div;
blackboxConfig()->rate_denom /= div;
}
// If we've chosen an unsupported device, change the device to serial
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
#endif
@ -785,7 +785,7 @@ static void validateBlackboxConfig()
break;
default:
masterConfig.blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
blackboxConfig()->device = BLACKBOX_DEVICE_SERIAL;
}
}
@ -867,7 +867,7 @@ bool startedLoggingInTestMode = false;
void startInTestMode(void)
{
if(!startedLoggingInTestMode) {
if (masterConfig.blackboxConfig.device == BLACKBOX_DEVICE_SERIAL) {
if (blackboxConfig()->device == BLACKBOX_DEVICE_SERIAL) {
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
if (sharedBlackboxAndMspPort) {
return; // When in test mode, we cannot share the MSP and serial logger port!
@ -1172,7 +1172,7 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", motorConfig()->minthrottle);
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", motorConfig()->maxthrottle);
BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
@ -1376,10 +1376,10 @@ static void blackboxCheckAndLogFlightMode()
*/
static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
{
/* Adding a magic shift of "masterConfig.blackboxConfig.rate_num - 1" in here creates a better spread of
/* Adding a magic shift of "blackboxConfig()->rate_num - 1" in here creates a better spread of
* recorded / skipped frames when the I frame's position is considered:
*/
return (pFrameIndex + masterConfig.blackboxConfig.rate_num - 1) % masterConfig.blackboxConfig.rate_denom < masterConfig.blackboxConfig.rate_num;
return (pFrameIndex + blackboxConfig()->rate_num - 1) % blackboxConfig()->rate_denom < blackboxConfig()->rate_num;
}
static bool blackboxShouldLogIFrame() {
@ -1595,7 +1595,7 @@ void handleBlackbox(uint32_t currentTime)
if (startedLoggingInTestMode) startedLoggingInTestMode = false;
} else { // Only log in test mode if there is room!
if(masterConfig.blackboxConfig.on_motor_test) {
if(blackboxConfig()->on_motor_test) {
// Handle Motor Test Mode
if(inMotorTestMode()) {
if(blackboxState==BLACKBOX_STATE_STOPPED)

View File

@ -65,7 +65,7 @@ static struct {
void blackboxWrite(uint8_t value)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
flashfsWriteByte(value); // Write byte asynchronously
@ -137,7 +137,7 @@ int blackboxPrint(const char *s)
int length;
const uint8_t *pos;
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
@ -479,7 +479,7 @@ void blackboxWriteFloat(float value)
*/
void blackboxDeviceFlush(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
/*
* This is our only output device which requires us to call flush() in order for it to write anything. The other
@ -502,7 +502,7 @@ void blackboxDeviceFlush(void)
*/
bool blackboxDeviceFlushForce(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
// Nothing to speed up flushing on serial, as serial is continuously being drained out of its buffer
return isSerialTransmitBufferEmpty(blackboxPort);
@ -530,7 +530,7 @@ bool blackboxDeviceFlushForce(void)
*/
bool blackboxDeviceOpen(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
{
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
@ -604,7 +604,7 @@ bool blackboxDeviceOpen(void)
*/
void blackboxDeviceClose(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
// Since the serial port could be shared with other processes, we have to give it back here
closeSerialPort(blackboxPort);
@ -748,7 +748,7 @@ static bool blackboxSDCardBeginLog()
*/
bool blackboxDeviceBeginLog(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
return blackboxSDCardBeginLog();
@ -772,7 +772,7 @@ bool blackboxDeviceEndLog(bool retainLog)
(void) retainLog;
#endif
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
// Keep retrying until the close operation queues
@ -794,7 +794,7 @@ bool blackboxDeviceEndLog(bool retainLog)
bool isBlackboxDeviceFull(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
return false;
@ -821,7 +821,7 @@ void blackboxReplenishHeaderBudget()
{
int32_t freeSpace;
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
freeSpace = serialTxBytesFree(blackboxPort);
break;
@ -867,7 +867,7 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
}
// Handle failure:
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
/*
* One byte of the tx buffer isn't available for user data (due to its circular list implementation),

View File

@ -90,7 +90,7 @@ static OSD_Entry cmsx_menuBlackboxEntries[] =
{
{ "-- BLACKBOX --", OME_Label, NULL, NULL, 0},
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureBlackbox, 0 },
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &masterConfig.blackboxConfig.rate_denom,1,32,1 }, 0 },
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &blackboxConfig()->rate_denom,1,32,1 }, 0 },
#ifdef USE_FLASHFS
{ "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 },

View File

@ -33,10 +33,10 @@
#if defined(OSD) && defined(CMS)
OSD_UINT8_t entryAlarmRssi = {&masterConfig.osdProfile.rssi_alarm, 5, 90, 5};
OSD_UINT16_t entryAlarmCapacity = {&masterConfig.osdProfile.cap_alarm, 50, 30000, 50};
OSD_UINT16_t enryAlarmFlyTime = {&masterConfig.osdProfile.time_alarm, 1, 200, 1};
OSD_UINT16_t entryAlarmAltitude = {&masterConfig.osdProfile.alt_alarm, 1, 200, 1};
OSD_UINT8_t entryAlarmRssi = {&osdProfile()->rssi_alarm, 5, 90, 5};
OSD_UINT16_t entryAlarmCapacity = {&osdProfile()->cap_alarm, 50, 30000, 50};
OSD_UINT16_t enryAlarmFlyTime = {&osdProfile()->time_alarm, 1, 200, 1};
OSD_UINT16_t entryAlarmAltitude = {&osdProfile()->alt_alarm, 1, 200, 1};
OSD_Entry cmsx_menuAlarmsEntries[] =
{
@ -61,25 +61,25 @@ CMS_Menu cmsx_menuAlarms = {
OSD_Entry menuOsdActiveElemsEntries[] =
{
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"HORIZON", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], 0},
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], 0},
{"UPTIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ONTIME], 0},
{"FLY TIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], 0},
{"FLY MODE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], 0},
{"NAME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], 0},
{"THROTTLE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], 0},
{"RSSI", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"HORIZON", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ARTIFICIAL_HORIZON], 0},
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_HORIZON_SIDEBARS], 0},
{"UPTIME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ONTIME], 0},
{"FLY TIME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_FLYTIME], 0},
{"FLY MODE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_FLYMODE], 0},
{"NAME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_CRAFT_NAME], 0},
{"THROTTLE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_THROTTLE_POS], 0},
#ifdef VTX
{"VTX CHAN", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL]},
{"VTX CHAN", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_VTX_CHANNEL]},
#endif // VTX
{"CURRENT (A)", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], 0},
{"USED MAH", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], 0},
{"CURRENT (A)", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_CURRENT_DRAW], 0},
{"USED MAH", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_MAH_DRAWN], 0},
#ifdef GPS
{"GPS SPEED", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], 0},
{"GPS SATS.", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], 0},
{"GPS SPEED", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_GPS_SPEED], 0},
{"GPS SATS.", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_GPS_SATS], 0},
#endif // GPS
{"ALTITUDE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], 0},
{"ALTITUDE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ALTITUDE], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};

View File

@ -93,6 +93,10 @@
#define beeperConfig(x) (&masterConfig.beeperConfig)
#define sonarConfig(x) (&masterConfig.sonarConfig)
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
#define osdProfile(x) (&masterConfig.osdProfile)
#define vcdProfile(x) (&masterConfig.vcdProfile)
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
// System-wide

View File

@ -1005,9 +1005,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
case MSP_BLACKBOX_CONFIG:
#ifdef BLACKBOX
sbufWriteU8(dst, 1); //Blackbox supported
sbufWriteU8(dst, masterConfig.blackboxConfig.device);
sbufWriteU8(dst, masterConfig.blackboxConfig.rate_num);
sbufWriteU8(dst, masterConfig.blackboxConfig.rate_denom);
sbufWriteU8(dst, blackboxConfig()->device);
sbufWriteU8(dst, blackboxConfig()->rate_num);
sbufWriteU8(dst, blackboxConfig()->rate_denom);
#else
sbufWriteU8(dst, 0); // Blackbox not supported
sbufWriteU8(dst, 0);
@ -1036,17 +1036,17 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, 1); // OSD supported
// send video system (AUTO/PAL/NTSC)
#ifdef USE_MAX7456
sbufWriteU8(dst, masterConfig.vcdProfile.video_system);
sbufWriteU8(dst, vcdProfile()->video_system);
#else
sbufWriteU8(dst, 0);
#endif
sbufWriteU8(dst, masterConfig.osdProfile.units);
sbufWriteU8(dst, masterConfig.osdProfile.rssi_alarm);
sbufWriteU16(dst, masterConfig.osdProfile.cap_alarm);
sbufWriteU16(dst, masterConfig.osdProfile.time_alarm);
sbufWriteU16(dst, masterConfig.osdProfile.alt_alarm);
sbufWriteU8(dst, osdProfile()->units);
sbufWriteU8(dst, osdProfile()->rssi_alarm);
sbufWriteU16(dst, osdProfile()->cap_alarm);
sbufWriteU16(dst, osdProfile()->time_alarm);
sbufWriteU16(dst, osdProfile()->alt_alarm);
for (int i = 0; i < OSD_ITEM_COUNT; i++) {
sbufWriteU16(dst, masterConfig.osdProfile.item_pos[i]);
sbufWriteU16(dst, osdProfile()->item_pos[i]);
}
#else
sbufWriteU8(dst, 0); // OSD not supported
@ -1517,9 +1517,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_BLACKBOX_CONFIG:
// Don't allow config to be updated while Blackbox is logging
if (blackboxMayEditConfig()) {
masterConfig.blackboxConfig.device = sbufReadU8(src);
masterConfig.blackboxConfig.rate_num = sbufReadU8(src);
masterConfig.blackboxConfig.rate_denom = sbufReadU8(src);
blackboxConfig()->device = sbufReadU8(src);
blackboxConfig()->rate_num = sbufReadU8(src);
blackboxConfig()->rate_denom = sbufReadU8(src);
}
break;
#endif
@ -1544,18 +1544,18 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
// set all the other settings
if ((int8_t)addr == -1) {
#ifdef USE_MAX7456
masterConfig.vcdProfile.video_system = sbufReadU8(src);
vcdProfile()->video_system = sbufReadU8(src);
#else
sbufReadU8(src); // Skip video system
#endif
masterConfig.osdProfile.units = sbufReadU8(src);
masterConfig.osdProfile.rssi_alarm = sbufReadU8(src);
masterConfig.osdProfile.cap_alarm = sbufReadU16(src);
masterConfig.osdProfile.time_alarm = sbufReadU16(src);
masterConfig.osdProfile.alt_alarm = sbufReadU16(src);
osdProfile()->units = sbufReadU8(src);
osdProfile()->rssi_alarm = sbufReadU8(src);
osdProfile()->cap_alarm = sbufReadU16(src);
osdProfile()->time_alarm = sbufReadU16(src);
osdProfile()->alt_alarm = sbufReadU16(src);
} else {
// set a position setting
masterConfig.osdProfile.item_pos[addr] = sbufReadU16(src);
osdProfile()->item_pos[addr] = sbufReadU16(src);
}
}
break;

View File

@ -109,7 +109,7 @@ static displayPort_t *osdDisplayPort;
*/
static char osdGetAltitudeSymbol()
{
switch (masterConfig.osdProfile.units) {
switch (osdProfile()->units) {
case OSD_UNIT_IMPERIAL:
return 0xF;
default:
@ -123,7 +123,7 @@ static char osdGetAltitudeSymbol()
*/
static int32_t osdGetAltitude(int32_t alt)
{
switch (masterConfig.osdProfile.units) {
switch (osdProfile()->units) {
case OSD_UNIT_IMPERIAL:
return (alt * 328) / 100; // Convert to feet / 100
default:
@ -133,11 +133,11 @@ static int32_t osdGetAltitude(int32_t alt)
static void osdDrawSingleElement(uint8_t item)
{
if (!VISIBLE(masterConfig.osdProfile.item_pos[item]) || BLINK(masterConfig.osdProfile.item_pos[item]))
if (!VISIBLE(osdProfile()->item_pos[item]) || BLINK(osdProfile()->item_pos[item]))
return;
uint8_t elemPosX = OSD_X(masterConfig.osdProfile.item_pos[item]);
uint8_t elemPosY = OSD_Y(masterConfig.osdProfile.item_pos[item]);
uint8_t elemPosX = OSD_X(osdProfile()->item_pos[item]);
uint8_t elemPosY = OSD_Y(osdProfile()->item_pos[item]);
char buff[32];
switch(item) {
@ -449,7 +449,7 @@ void osdUpdateAlarms(void)
osd_profile_t *pOsdProfile = &masterConfig.osdProfile;
// This is overdone?
// uint16_t *itemPos = masterConfig.osdProfile.item_pos;
// uint16_t *itemPos = osdProfile()->item_pos;
int32_t alt = osdGetAltitude(BaroAlt) / 100;
statRssi = rssi * 100 / 1024;

View File

@ -930,10 +930,10 @@ const clivalue_t valueTable[] = {
{ "level_sensitivity", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelSensitivity, .config.minmax = { 0.1, 3.0 } },
#ifdef BLACKBOX
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackboxConfig.rate_num, .config.minmax = { 1, 32 } },
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackboxConfig.rate_denom, .config.minmax = { 1, 32 } },
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackboxConfig.device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackboxConfig.on_motor_test, .config.lookup = { TABLE_OFF_ON } },
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &blackboxConfig()->rate_num, .config.minmax = { 1, 32 } },
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &blackboxConfig()->rate_denom, .config.minmax = { 1, 32 } },
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &blackboxConfig()->device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &blackboxConfig()->on_motor_test, .config.lookup = { TABLE_OFF_ON } },
#endif
#ifdef VTX
@ -956,36 +956,36 @@ const clivalue_t valueTable[] = {
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
#endif
#ifdef USE_SDCARD
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sdcardConfig.useDma, .config.lookup = { TABLE_OFF_ON } },
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sdcardConfig()->useDma, .config.lookup = { TABLE_OFF_ON } },
#endif
#ifdef OSD
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.osdProfile.units, .config.lookup = { TABLE_UNIT } },
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &osdProfile()->units, .config.lookup = { TABLE_UNIT } },
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.rssi_alarm, .config.minmax = { 0, 100 } },
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.cap_alarm, .config.minmax = { 0, 20000 } },
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.time_alarm, .config.minmax = { 0, 60 } },
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.alt_alarm, .config.minmax = { 0, 10000 } },
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &osdProfile()->rssi_alarm, .config.minmax = { 0, 100 } },
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->cap_alarm, .config.minmax = { 0, 20000 } },
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->time_alarm, .config.minmax = { 0, 60 } },
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->alt_alarm, .config.minmax = { 0, 10000 } },
{ "osd_main_voltage_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { 0, 65536 } },
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], .config.minmax = { 0, 65536 } },
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], .config.minmax = { 0, 65536 } },
{ "osd_ontime_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ONTIME], .config.minmax = { 0, 65536 } },
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], .config.minmax = { 0, 65536 } },
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, 65536 } },
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, 65536 } },
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, 65536 } },
{ "osd_artificial_horizon", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, 65536 } },
{ "osd_current_draw_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, 65536 } },
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, 65536 } },
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, 65536 } },
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], .config.minmax = { 0, 65536 } },
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], .config.minmax = { 0, 65536 } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } },
{ "osd_main_voltage_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { 0, 65536 } },
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_RSSI_VALUE], .config.minmax = { 0, 65536 } },
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYTIME], .config.minmax = { 0, 65536 } },
{ "osd_ontime_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ONTIME], .config.minmax = { 0, 65536 } },
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYMODE], .config.minmax = { 0, 65536 } },
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, 65536 } },
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, 65536 } },
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, 65536 } },
{ "osd_artificial_horizon", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, 65536 } },
{ "osd_current_draw_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, 65536 } },
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, 65536 } },
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, 65536 } },
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SPEED], .config.minmax = { 0, 65536 } },
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SATS], .config.minmax = { 0, 65536 } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } },
#endif
#ifdef USE_MAX7456
{ "vcd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.vcdProfile.video_system, .config.minmax = { 0, 2 } },
{ "vcd_h_offset", VAR_INT8 | MASTER_VALUE, &masterConfig.vcdProfile.h_offset, .config.minmax = { -32, 31 } },
{ "vcd_v_offset", VAR_INT8 | MASTER_VALUE, &masterConfig.vcdProfile.v_offset, .config.minmax = { -15, 16 } },
{ "vcd_video_system", VAR_UINT8 | MASTER_VALUE, &vcdProfile()->video_system, .config.minmax = { 0, 2 } },
{ "vcd_h_offset", VAR_INT8 | MASTER_VALUE, &vcdProfile()->h_offset, .config.minmax = { -32, 31 } },
{ "vcd_v_offset", VAR_INT8 | MASTER_VALUE, &vcdProfile()->v_offset, .config.minmax = { -15, 16 } },
#endif
};

View File

@ -531,7 +531,7 @@ void init(void)
#ifdef USE_SDCARD
if (feature(FEATURE_SDCARD)) {
sdcardInsertionDetectInit();
sdcard_init(masterConfig.sdcardConfig.useDma);
sdcard_init(sdcardConfig()->useDma);
afatfs_init();
}
#endif