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

Merge pull request #5760 from jflyper/bfdev-convert-config-c-functionmask

Use config helper function where appropriate
This commit is contained in:
Michael Keller 2018-04-25 00:21:19 +12:00 committed by GitHub
commit 59134f0984
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
12 changed files with 66 additions and 23 deletions

View file

@ -25,9 +25,17 @@
#include "rx/rx.h"
#include "io/serial.h"
#include "config_helper.h"
#define TELEMETRY_UART SERIAL_PORT_USART3
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ TELEMETRY_UART, FUNCTION_TELEMETRY_SMARTPORT },
};
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
rxConfigMutable()->rssi_channel = 8;
}
#endif

View file

@ -131,7 +131,6 @@
#define DEFAULT_FEATURES ( FEATURE_TELEMETRY | FEATURE_LED_STRIP | FEATURE_OSD)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define TELEMETRY_UART SERIAL_PORT_USART3
#define SERIALRX_UART SERIAL_PORT_USART2
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -25,9 +25,17 @@
#include "rx/rx.h"
#include "io/serial.h"
#include "config_helper.h"
#define TELEMETRY_UART SERIAL_PORT_USART6
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ TELEMETRY_UART, FUNCTION_TELEMETRY_SMARTPORT },
};
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
rxConfigMutable()->rssi_channel = 8;
}
#endif

View file

@ -122,7 +122,6 @@
#define DEFAULT_FEATURES (FEATURE_OSD)
#define AVOID_UART1_FOR_PWM_PPM
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define TELEMETRY_UART SERIAL_PORT_USART6
#define SERIALRX_UART SERIAL_PORT_USART1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -30,10 +30,17 @@
#include "telemetry/telemetry.h"
#include "config_helper.h"
#define TELEMETRY_UART SERIAL_PORT_USART1
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ TELEMETRY_UART, FUNCTION_TELEMETRY_SMARTPORT },
};
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
telemetryConfigMutable()->halfDuplex = 0;
telemetryConfigMutable()->telemetry_inverted = true;
}

View file

@ -148,7 +148,6 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART3
#define TELEMETRY_UART SERIAL_PORT_USART1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -21,18 +21,17 @@
#ifdef USE_TARGET_CONFIG
#include "io/serial.h"
#include "config_helper.h"
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ SERIAL_PORT_USART1, FUNCTION_MSP },
{ SERIAL_PORT_USART2, FUNCTION_MSP },
};
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[0].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_MSP;
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
}
#endif

View file

@ -32,12 +32,19 @@
#include "telemetry/telemetry.h"
#include "config_helper.h"
#define TELEMETRY_UART SERIAL_PORT_UART5
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ SERIAL_PORT_USART1, FUNCTION_MSP }, // So SPRacingF3OSD users don't have to change anything.
{ TELEMETRY_UART, FUNCTION_TELEMETRY_SMARTPORT },
};
void targetConfiguration(void)
{
barometerConfigMutable()->baro_hardware = BARO_DEFAULT;
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything.
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
telemetryConfigMutable()->halfDuplex = 0;
telemetryConfigMutable()->telemetry_inverted = true;
}

View file

@ -206,7 +206,6 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP)
#define SERIALRX_UART SERIAL_PORT_USART2
#define TELEMETRY_UART SERIAL_PORT_UART5
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -28,11 +28,21 @@
#include "fc/config.h"
#include "config_helper.h"
#define GPS_UART SERIAL_PORT_USART3
#define TELEMETRY_UART SERIAL_PORT_UART5
#define TELEMETRY_PROVIDER_DEFAULT FUNCTION_TELEMETRY_SMARTPORT
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ GPS_UART, FUNCTION_GPS },
{ TELEMETRY_UART, TELEMETRY_PROVIDER_DEFAULT },
};
#ifdef USE_TARGET_CONFIG
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = TELEMETRY_PROVIDER_DEFAULT;
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
telemetryConfigMutable()->halfDuplex = false;
}
#endif

View file

@ -49,12 +49,23 @@
#include "fc/config.h"
#ifdef USE_TARGET_CONFIG
#include "config_helper.h"
#define TELEMETRY_UART SERIAL_PORT_UART5
#ifdef USE_TELEMETRY
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ TELEMETRY_UART, FUNCTION_TELEMETRY_SMARTPORT },
};
#endif
void targetConfiguration(void)
{
barometerConfigMutable()->baro_hardware = BARO_DEFAULT;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
#ifdef USE_TELEMETRY
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
// change telemetry settings
telemetryConfigMutable()->telemetry_inverted = 1;
telemetryConfigMutable()->halfDuplex = 1;

View file

@ -215,9 +215,6 @@
#define SERIALRX_UART SERIAL_PORT_USART2
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define TELEMETRY_UART SERIAL_PORT_UART5
#define TELEMETRY_PROVIDER_DEFAULT FUNCTION_TELEMETRY_SMARTPORT
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
#define USE_SERIAL_4WAY_BLHELI_INTERFACE