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

Move freestanding masterConfig items into structs

This commit is contained in:
Martin Budden 2016-11-24 17:11:12 +00:00
parent 75110a8299
commit d85eed0933
25 changed files with 190 additions and 177 deletions

View file

@ -349,7 +349,7 @@ bool blackboxMayEditConfig()
}
static bool blackboxIsOnlyLoggingIntraframes() {
return masterConfig.blackbox_rate_num == 1 && masterConfig.blackbox_rate_denom == 32;
return masterConfig.blackboxConfig.rate_num == 1 && masterConfig.blackboxConfig.rate_denom == 32;
}
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
@ -369,7 +369,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
return masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI;
return masterConfig.mixerConfig.mixerMode == MIXER_TRI || masterConfig.mixerConfig.mixerMode == MIXER_CUSTOM_TRI;
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
@ -407,7 +407,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
return masterConfig.rxConfig.rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
return masterConfig.blackbox_rate_num < masterConfig.blackbox_rate_denom;
return masterConfig.blackboxConfig.rate_num < masterConfig.blackboxConfig.rate_denom;
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
return false;
@ -758,22 +758,22 @@ static void validateBlackboxConfig()
{
int div;
if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0
|| masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) {
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
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;
} else {
/* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
* itself more frequently)
*/
div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
div = gcd(masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
masterConfig.blackbox_rate_num /= div;
masterConfig.blackbox_rate_denom /= div;
masterConfig.blackboxConfig.rate_num /= div;
masterConfig.blackboxConfig.rate_denom /= div;
}
// If we've chosen an unsupported device, change the device to serial
switch (masterConfig.blackbox_device) {
switch (masterConfig.blackboxConfig.device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
#endif
@ -785,7 +785,7 @@ static void validateBlackboxConfig()
break;
default:
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
masterConfig.blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
}
}
@ -867,7 +867,7 @@ bool startedLoggingInTestMode = false;
void startInTestMode(void)
{
if(!startedLoggingInTestMode) {
if (masterConfig.blackbox_device == BLACKBOX_DEVICE_SERIAL) {
if (masterConfig.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.blackbox_rate_num, masterConfig.blackbox_rate_denom);
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.motorConfig.minthrottle);
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.motorConfig.maxthrottle);
BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
@ -1270,10 +1270,10 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", masterConfig.gyro_soft_notch_cutoff_1,
masterConfig.gyro_soft_notch_cutoff_2);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm);
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.sensorSelectionConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.sensorSelectionConfig.baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.sensorSelectionConfig.mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.armingConfig.gyro_cal_on_first_arm);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation:%d", masterConfig.rxConfig.rcInterpolation);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", masterConfig.rxConfig.rcInterpolationInterval);
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold);
@ -1376,10 +1376,10 @@ static void blackboxCheckAndLogFlightMode()
*/
static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
{
/* Adding a magic shift of "masterConfig.blackbox_rate_num - 1" in here creates a better spread of
/* Adding a magic shift of "masterConfig.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.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num;
return (pFrameIndex + masterConfig.blackboxConfig.rate_num - 1) % masterConfig.blackboxConfig.rate_denom < masterConfig.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.blackbox_on_motor_test) {
if(masterConfig.blackboxConfig.on_motor_test) {
// Handle Motor Test Mode
if(inMotorTestMode()) {
if(blackboxState==BLACKBOX_STATE_STOPPED)