mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 09:16:07 +03:00
Remove telemetry_*.c's dependency on mw.h/board.h.
Finally, the only dependency on mw.h/board.h is now mw.c itself.
This commit is contained in:
parent
7af9ca4fdc
commit
cb63f6e2b5
10 changed files with 96 additions and 34 deletions
16
src/config.c
16
src/config.c
|
@ -91,7 +91,8 @@ void activateConfig(void)
|
|||
generatePitchCurve(¤tProfile.controlRateConfig);
|
||||
generateThrottleCurve(¤tProfile.controlRateConfig, &masterConfig.escAndServoConfig);
|
||||
|
||||
useGyroConfig(&masterConfig.gyroConfig);
|
||||
useGyroConfig(&masterConfig.gyroConfig);
|
||||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
||||
setPIDController(currentProfile.pidController);
|
||||
gpsUseProfile(¤tProfile.gpsProfile);
|
||||
gpsUsePIDs(¤tProfile.pidProfile);
|
||||
|
@ -271,6 +272,13 @@ void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
|
|||
flight3DConfig->deadband3d_throttle = 50;
|
||||
}
|
||||
|
||||
void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
|
||||
{
|
||||
telemetryConfig->telemetry_provider = TELEMETRY_PROVIDER_FRSKY;
|
||||
telemetryConfig->telemetry_port = TELEMETRY_PORT_UART;
|
||||
telemetryConfig->telemetry_switch = 0;
|
||||
|
||||
}
|
||||
// Default settings
|
||||
static void resetConf(void)
|
||||
{
|
||||
|
@ -307,9 +315,9 @@ static void resetConf(void)
|
|||
masterConfig.batteryConfig.vbatmaxcellvoltage = 43;
|
||||
masterConfig.batteryConfig.vbatmincellvoltage = 33;
|
||||
masterConfig.power_adc_channel = 0;
|
||||
masterConfig.telemetry_provider = TELEMETRY_PROVIDER_FRSKY;
|
||||
masterConfig.telemetry_port = TELEMETRY_PORT_UART;
|
||||
masterConfig.telemetry_switch = 0;
|
||||
|
||||
resetTelemetryConfig(&masterConfig.telemetryConfig);
|
||||
|
||||
masterConfig.rxConfig.serialrx_type = 0;
|
||||
masterConfig.rxConfig.midrc = 1500;
|
||||
masterConfig.rxConfig.mincheck = 1100;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue