Moved target specific configuration into 'config.c'
Moved target specific configuration into 'config.c'
This commit is contained in:
parent
08b401737b
commit
6a39d35c37
|
@ -142,20 +142,6 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(TELEMETRY_UART) && defined(TELEMETRY_PROVIDER_DEFAULT)
|
||||
serialPortConfig_t *serialTelemetryConfig = serialFindPortConfiguration(TELEMETRY_UART);
|
||||
if (serialTelemetryConfig) {
|
||||
serialTelemetryConfig->functionMask = TELEMETRY_PROVIDER_DEFAULT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(GPS_UART)
|
||||
serialPortConfig_t *serialGPSConfig = serialFindPortConfiguration(GPS_UART);
|
||||
if (serialGPSConfig) {
|
||||
serialGPSConfig->functionMask = FUNCTION_GPS;
|
||||
}
|
||||
#endif
|
||||
|
||||
serialConfig->reboot_character = 'R';
|
||||
serialConfig->serial_update_rate_hz = 100;
|
||||
}
|
||||
|
|
|
@ -99,11 +99,6 @@ static uint8_t rcSampleIndex = 0;
|
|||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||
#endif
|
||||
|
||||
#ifndef SBUS_INVERSION_DEFAULT
|
||||
#define SBUS_INVERSION_DEFAULT 1
|
||||
#endif
|
||||
|
||||
#ifndef SERIALRX_PROVIDER
|
||||
#define SERIALRX_PROVIDER 0
|
||||
#endif
|
||||
|
@ -119,7 +114,7 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
|||
.halfDuplex = 0,
|
||||
.serialrx_provider = SERIALRX_PROVIDER,
|
||||
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
|
||||
.sbus_inversion = SBUS_INVERSION_DEFAULT,
|
||||
.sbus_inversion = 1,
|
||||
.spektrum_sat_bind = 0,
|
||||
.spektrum_sat_bind_autoreset = 1,
|
||||
.midrc = RX_MID_USEC,
|
||||
|
|
|
@ -51,6 +51,11 @@ void targetConfiguration(void)
|
|||
{
|
||||
barometerConfigMutable()->baro_hardware = BARO_DEFAULT;
|
||||
compassConfigMutable()->mag_hardware = MAG_DEFAULT;
|
||||
rxConfigMutable()->sbus_inversion = true;
|
||||
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So Bluetooth users don't have to change anything.
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = TELEMETRY_PROVIDER_DEFAULT;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
|
||||
telemetryConfigMutable()->telemetry_inversion = true;
|
||||
telemetryConfigMutable()->halfDuplex = true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = TELEMETRY_PROVIDER_DEFAULT
|
||||
telemetryConfigMutable()->halfDuplex = TELEMETRY_DEFAULT_HALFDUPLEX;
|
||||
}
|
||||
#endif
|
||||
|
|
@ -58,13 +58,9 @@ PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY
|
|||
|
||||
#define TELEMETRY_DEFAULT_INVERSION 1
|
||||
|
||||
#ifndef TELEMETRY_DEFAULT_HALFDUPLEX
|
||||
#define TELEMETRY_DEFAULT_HALFDUPLEX 1
|
||||
#endif
|
||||
|
||||
PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
|
||||
.telemetry_inversion = TELEMETRY_DEFAULT_INVERSION,
|
||||
.halfDuplex = TELEMETRY_DEFAULT_HALFDUPLEX,
|
||||
.halfDuplex = 1,
|
||||
.telemetry_switch = 0,
|
||||
.gpsNoFixLatitude = 0,
|
||||
.gpsNoFixLongitude = 0,
|
||||
|
|
Loading…
Reference in New Issue