mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
RXMSP is no longer a serial rx provider since it uses MSP and not it's
own dedicated serial port. Added a feature to enable/disable RX_MSP. Renamed feature SERIALRX to RX_SERIAL. Renamed feature PARALLEL_PWM to RX_PARALLEL_PWM Renamed PPM to RX_PPM. Update serial configuration checking to better support Serial RX and telemetry by verifiying serial port features and supported baud rates. It's now possible to use a low-speed serial rx provider via softserial - only problem is all the current serial rx providers are 100000/115200 baud. The code changes however open the door for using serial rx and any capable serial port such as uart3-5 on the STM32F30x It's also now possible to use GPS at low speeds on software serial ports.
This commit is contained in:
parent
a947ef8fbb
commit
5d460766e9
22 changed files with 363 additions and 179 deletions
|
@ -7,7 +7,7 @@
|
|||
0 UNUSED
|
||||
1 MSP, CLI, TELEMETRY, GPS-PASTHROUGH
|
||||
2 GPS ONLY
|
||||
3 SERIAL-RX ONLY
|
||||
3 RX SERIAL ONLY
|
||||
4 TELEMETRY ONLY
|
||||
5 MSP, CLI, GPS-PASTHROUGH
|
||||
6 CLI ONLY
|
||||
|
@ -38,44 +38,61 @@ feature GPS
|
|||
save
|
||||
```
|
||||
|
||||
b) SERIAL_RX and TELEMETRY (when armed)
|
||||
b) RX SERIAL and TELEMETRY (when armed)
|
||||
|
||||
- TELEMETRY,MSP,CLI,GPS PASSTHROUGH on UART1
|
||||
- SERIAL_RX on UART2
|
||||
- RX SERIAL on UART2
|
||||
|
||||
```
|
||||
feature -PARALLEL_PWM
|
||||
feature -RX_PARALLEL_PWM
|
||||
feature RX_SERIAL
|
||||
feature TELEMETRY
|
||||
feature SERIAL_RX
|
||||
set serial_port_2_scenario = 3
|
||||
save
|
||||
```
|
||||
|
||||
b) RX SERIAL and TELEMETRY via softserial
|
||||
|
||||
- MSP,CLI,GPS PASSTHROUGH on UART1
|
||||
- RX SERIAL on UART2
|
||||
- TELEMETRY on SOFTSERIAL1
|
||||
|
||||
```
|
||||
feature -RX_PARALLEL_PWM
|
||||
feature RX_SERIAL
|
||||
feature TELEMETRY
|
||||
feature SOFTSERIAL
|
||||
set serial_port_2_scenario = 3
|
||||
set serial_port_3_scenario = 4
|
||||
save
|
||||
```
|
||||
|
||||
c) GPS and TELEMETRY via softserial
|
||||
|
||||
- TELEMETRY,MSP,CLI,GPS PASSTHROUGH on UART1
|
||||
- MSP,CLI,GPS PASSTHROUGH on UART1
|
||||
- GPS on UART2
|
||||
- TELEMETRY on SOFTSERIAL1
|
||||
|
||||
```
|
||||
feature -PARALLEL_PWM
|
||||
feature PPM
|
||||
feature -RX_PARALLEL_PWM
|
||||
feature RX_PPM
|
||||
feature TELEMETRY
|
||||
feature GPS
|
||||
feature SOFTSERIAL
|
||||
set serial_port_3_scenario = 4
|
||||
save
|
||||
```
|
||||
d) SERIAL_RX, GPS and TELEMETRY (when armed) MSP/CLI via softserial
|
||||
d) RX SERIAL, GPS and TELEMETRY (when armed) MSP/CLI via softserial
|
||||
|
||||
- GPS on UART1
|
||||
- SERIAL RX on UART2
|
||||
- RX SERIAL on UART2
|
||||
- TELEMETRY,MSP,CLI,GPS PASSTHROUGH on SOFTSERIAL1
|
||||
|
||||
```
|
||||
feature -PARALLEL_PWM
|
||||
feature -RX_PARALLEL_PWM
|
||||
feature TELEMETRY
|
||||
feature GPS
|
||||
feature SERIALRX
|
||||
feature RX_SERIAL
|
||||
feature SOFTSERIAL
|
||||
set serial_port_1_scenario = 2
|
||||
set serial_port_2_scenario = 3
|
||||
|
|
38
src/config.c
38
src/config.c
|
@ -345,40 +345,54 @@ void activateConfig(void)
|
|||
|
||||
void validateAndFixConfig(void)
|
||||
{
|
||||
if (!(feature(FEATURE_PARALLEL_PWM) || feature(FEATURE_PPM) || feature(FEATURE_SERIALRX))) {
|
||||
featureSet(FEATURE_PARALLEL_PWM); // Consider changing the default to PPM
|
||||
if (!(feature(FEATURE_RX_PARALLEL_PWM) || feature(FEATURE_RX_PPM) || feature(FEATURE_RX_SERIAL) || feature(FEATURE_RX_MSP))) {
|
||||
featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
|
||||
}
|
||||
|
||||
if (feature(FEATURE_SERIALRX)) {
|
||||
if (feature(FEATURE_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_PARALLEL_PWM);
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
featureClear(FEATURE_RX_SERIAL);
|
||||
}
|
||||
if (feature(FEATURE_PPM)) {
|
||||
featureClear(FEATURE_PPM);
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
}
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
featureClear(FEATURE_RX_PPM);
|
||||
}
|
||||
}
|
||||
|
||||
if (feature(FEATURE_PPM)) {
|
||||
if (feature(FEATURE_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_PARALLEL_PWM);
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
}
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
featureClear(FEATURE_RX_PPM);
|
||||
}
|
||||
}
|
||||
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef SONAR
|
||||
if (feature(FEATURE_SONAR)) {
|
||||
// sonar needs a free PWM port
|
||||
if (!feature(FEATURE_PARALLEL_PWM)) {
|
||||
if (!feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_SONAR);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if (feature(FEATURE_SOFTSERIAL)) {
|
||||
// software serial needs free PWM ports
|
||||
if (feature(FEATURE_PARALLEL_PWM)) {
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_SOFTSERIAL);
|
||||
}
|
||||
}
|
||||
|
||||
useRxConfig(&masterConfig.rxConfig);
|
||||
|
||||
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
||||
applySerialConfigToPortFunctions(serialConfig);
|
||||
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
typedef enum {
|
||||
FEATURE_PPM = 1 << 0,
|
||||
FEATURE_RX_PPM = 1 << 0,
|
||||
FEATURE_VBAT = 1 << 1,
|
||||
FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
|
||||
FEATURE_SERIALRX = 1 << 3,
|
||||
FEATURE_RX_SERIAL = 1 << 3,
|
||||
FEATURE_MOTOR_STOP = 1 << 4,
|
||||
FEATURE_SERVO_TILT = 1 << 5,
|
||||
FEATURE_SOFTSERIAL = 1 << 6,
|
||||
|
@ -16,7 +16,8 @@ typedef enum {
|
|||
FEATURE_POWERMETER = 1 << 12,
|
||||
FEATURE_VARIO = 1 << 13,
|
||||
FEATURE_3D = 1 << 14,
|
||||
FEATURE_PARALLEL_PWM = 1 << 15,
|
||||
FEATURE_RX_PARALLEL_PWM = 1 << 15,
|
||||
FEATURE_RX_MSP = 1 << 16,
|
||||
} AvailableFeatures;
|
||||
|
||||
bool feature(uint32_t mask);
|
||||
|
|
|
@ -167,8 +167,8 @@ void init(void)
|
|||
#endif
|
||||
|
||||
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
|
||||
pwm_params.useParallelPWM = feature(FEATURE_PARALLEL_PWM);
|
||||
pwm_params.usePPM = feature(FEATURE_PPM);
|
||||
pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM);
|
||||
pwm_params.usePPM = feature(FEATURE_RX_PPM);
|
||||
pwm_params.useServos = isMixerUsingServos();
|
||||
pwm_params.extraServos = currentProfile.gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX;
|
||||
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
|
||||
|
|
7
src/mw.c
7
src/mw.c
|
@ -37,6 +37,7 @@
|
|||
#include "rc_controls.h"
|
||||
#include "rc_curves.h"
|
||||
#include "rx_common.h"
|
||||
#include "rx_msp.h"
|
||||
#include "telemetry_common.h"
|
||||
|
||||
#include "runtime_config.h"
|
||||
|
@ -241,10 +242,14 @@ void loop(void)
|
|||
bool rcReady = false;
|
||||
|
||||
// calculate rc stuff from serial-based receivers (spek/sbus)
|
||||
if (feature(FEATURE_SERIALRX)) {
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
rcReady = isSerialRxFrameComplete(&masterConfig.rxConfig);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
rcReady = rxMspFrameComplete();
|
||||
}
|
||||
|
||||
if (((int32_t)(currentTime - rcTime) >= 0) || rcReady) { // 50Hz or data driven
|
||||
rcReady = false;
|
||||
rcTime = currentTime + 20000;
|
||||
|
|
|
@ -8,6 +8,9 @@
|
|||
|
||||
#include "config.h"
|
||||
|
||||
#include "drivers/serial_common.h"
|
||||
#include "serial_common.h"
|
||||
|
||||
#include "failsafe.h"
|
||||
|
||||
#include "rx_pwm.h"
|
||||
|
@ -38,14 +41,37 @@ int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
|||
static rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
|
||||
|
||||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
static rxConfig_t *rxConfig;
|
||||
|
||||
void serialRxInit(rxConfig_t *rxConfig);
|
||||
|
||||
static failsafe_t *failsafe;
|
||||
|
||||
void useRxConfig(rxConfig_t *rxConfigToUse)
|
||||
{
|
||||
rxConfig = rxConfigToUse;
|
||||
}
|
||||
|
||||
void updateSerialRxFunctionConstraint(functionConstraint_t *functionConstraintToUpdate)
|
||||
{
|
||||
switch (rxConfig->serialrx_provider) {
|
||||
case SERIALRX_SPEKTRUM1024:
|
||||
case SERIALRX_SPEKTRUM2048:
|
||||
spektrumUpdateSerialRxFunctionConstraint(functionConstraintToUpdate);
|
||||
break;
|
||||
case SERIALRX_SBUS:
|
||||
sbusUpdateSerialRxFunctionConstraint(functionConstraintToUpdate);
|
||||
break;
|
||||
case SERIALRX_SUMD:
|
||||
sumdUpdateSerialRxFunctionConstraint(functionConstraintToUpdate);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
|
||||
{
|
||||
uint8_t i;
|
||||
useRxConfig(rxConfig);
|
||||
|
||||
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
|
||||
rcData[i] = rxConfig->midrc;
|
||||
|
@ -53,11 +79,15 @@ void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
|
|||
|
||||
failsafe = initialFailsafe;
|
||||
|
||||
if (feature(FEATURE_SERIALRX)) {
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
serialRxInit(rxConfig);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_PPM) || feature(FEATURE_PARALLEL_PWM)) {
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
rxPwmInit(&rxRuntimeConfig, &rcReadRawFunc);
|
||||
}
|
||||
}
|
||||
|
@ -76,13 +106,10 @@ void serialRxInit(rxConfig_t *rxConfig)
|
|||
case SERIALRX_SUMD:
|
||||
enabled = sumdInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||
break;
|
||||
case SERIALRX_MSP:
|
||||
enabled = rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||
break;
|
||||
}
|
||||
|
||||
if (!enabled) {
|
||||
featureClear(FEATURE_SERIALRX);
|
||||
featureClear(FEATURE_RX_SERIAL);
|
||||
rcReadRawFunc = NULL;
|
||||
}
|
||||
}
|
||||
|
@ -97,8 +124,6 @@ bool isSerialRxFrameComplete(rxConfig_t *rxConfig)
|
|||
return sbusFrameComplete();
|
||||
case SERIALRX_SUMD:
|
||||
return sumdFrameComplete();
|
||||
case SERIALRX_MSP:
|
||||
return rxMspFrameComplete();
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -118,7 +143,7 @@ void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
failsafe->vTable->incrementCounter();
|
||||
}
|
||||
|
||||
if (!feature(FEATURE_SERIALRX)) {
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM) || feature(FEATURE_RX_PPM)) {
|
||||
rcSampleIndex++;
|
||||
currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT;
|
||||
}
|
||||
|
@ -143,7 +168,7 @@ void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
if (sample < PULSE_MIN || sample > PULSE_MAX)
|
||||
sample = rxConfig->midrc;
|
||||
|
||||
if (feature(FEATURE_SERIALRX)) {
|
||||
if (!(feature(FEATURE_RX_PARALLEL_PWM) || feature(FEATURE_RX_PPM))) {
|
||||
rcData[chan] = sample;
|
||||
continue;
|
||||
}
|
||||
|
|
|
@ -13,10 +13,11 @@ typedef enum {
|
|||
SERIALRX_SPEKTRUM2048 = 1,
|
||||
SERIALRX_SBUS = 2,
|
||||
SERIALRX_SUMD = 3,
|
||||
SERIALRX_MSP = 4,
|
||||
SERIALRX_PROVIDER_MAX = SERIALRX_MSP
|
||||
SERIALRX_PROVIDER_MAX = SERIALRX_SUMD
|
||||
} SerialRXType;
|
||||
|
||||
#define SERIALRX_PROVIDER_COUNT (SERIALRX_PROVIDER_MAX + 1)
|
||||
|
||||
#define MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT 8
|
||||
#define MAX_SUPPORTED_RC_CHANNEL_COUNT (18)
|
||||
|
||||
|
@ -26,7 +27,7 @@ extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2
|
|||
|
||||
typedef struct rxConfig_s {
|
||||
uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order
|
||||
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_SERIALRX first.
|
||||
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||
uint16_t mincheck; // minimum rc end
|
||||
uint16_t maxcheck; // maximum rc end
|
||||
|
@ -38,6 +39,8 @@ typedef struct rxRuntimeConfig_s {
|
|||
|
||||
extern rxRuntimeConfig_t rxRuntimeConfig;
|
||||
|
||||
void useRxConfig(rxConfig_t *rxConfigToUse);
|
||||
|
||||
typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
|
||||
|
||||
void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
#define SBUS_SYNCBYTE 0x0F
|
||||
#define SBUS_OFFSET 988
|
||||
|
||||
#define SBUS_BAUDRATE 100000
|
||||
|
||||
static bool sbusFrameDone = false;
|
||||
static void sbusDataReceive(uint16_t c);
|
||||
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||
|
@ -28,11 +30,17 @@ static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
|
|||
|
||||
static serialPort_t *sBusPort;
|
||||
|
||||
void sbusUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
|
||||
{
|
||||
functionConstraint->minBaudRate = SBUS_BAUDRATE;
|
||||
functionConstraint->maxBaudRate = SBUS_BAUDRATE;
|
||||
functionConstraint->requiredSerialPortFeatures = SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE;
|
||||
}
|
||||
|
||||
bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
int b;
|
||||
|
||||
sBusPort = openSerialPort(FUNCTION_SERIAL_RX, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS), SERIAL_NOT_INVERTED);
|
||||
sBusPort = openSerialPort(FUNCTION_SERIAL_RX, sbusDataReceive, SBUS_BAUDRATE, (portMode_t)(MODE_RX | MODE_SBUS), SERIAL_NOT_INVERTED);
|
||||
|
||||
for (b = 0; b < SBUS_MAX_CHANNEL; b++)
|
||||
sbusChannelData[b] = 2 * (rxConfig->midrc - SBUS_OFFSET);
|
||||
|
|
|
@ -1,3 +1,4 @@
|
|||
#pragma once
|
||||
|
||||
bool sbusFrameComplete(void);
|
||||
void sbusUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
|
||||
#define SPEK_FRAME_SIZE 16
|
||||
|
||||
#define SPEKTRUM_BAUDRATE 115200
|
||||
|
||||
static uint8_t spek_chan_shift;
|
||||
static uint8_t spek_chan_mask;
|
||||
static bool rcFrameComplete = false;
|
||||
|
@ -34,6 +36,13 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
|
|||
|
||||
static serialPort_t *spektrumPort;
|
||||
|
||||
void spektrumUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
|
||||
{
|
||||
functionConstraint->minBaudRate = SPEKTRUM_BAUDRATE;
|
||||
functionConstraint->maxBaudRate = SPEKTRUM_BAUDRATE;
|
||||
functionConstraint->requiredSerialPortFeatures = SPF_SUPPORTS_CALLBACK;
|
||||
}
|
||||
|
||||
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
switch (rxConfig->serialrx_provider) {
|
||||
|
@ -53,7 +62,7 @@ bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcRe
|
|||
break;
|
||||
}
|
||||
|
||||
spektrumPort = openSerialPort(FUNCTION_SERIAL_RX, spektrumDataReceive, 115200, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
spektrumPort = openSerialPort(FUNCTION_SERIAL_RX, spektrumDataReceive, SPEKTRUM_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
if (callback)
|
||||
*callback = spektrumReadRawRC;
|
||||
|
||||
|
|
|
@ -1,3 +1,4 @@
|
|||
#pragma once
|
||||
|
||||
bool spektrumFrameComplete(void);
|
||||
void spektrumUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -19,6 +19,8 @@
|
|||
#define SUMD_MAX_CHANNEL 8
|
||||
#define SUMD_BUFFSIZE (SUMD_MAX_CHANNEL * 2 + 5) // 6 channels + 5 -> 17 bytes for 6 channels
|
||||
|
||||
#define SUMD_BAUDRATE 115200
|
||||
|
||||
static bool sumdFrameDone = false;
|
||||
static void sumdDataReceive(uint16_t c);
|
||||
static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||
|
@ -27,9 +29,16 @@ static uint32_t sumdChannelData[SUMD_MAX_CHANNEL];
|
|||
|
||||
static serialPort_t *sumdPort;
|
||||
|
||||
void sumdUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
|
||||
{
|
||||
functionConstraint->minBaudRate = SUMD_BAUDRATE;
|
||||
functionConstraint->maxBaudRate = SUMD_BAUDRATE;
|
||||
functionConstraint->requiredSerialPortFeatures = SPF_SUPPORTS_CALLBACK;
|
||||
}
|
||||
|
||||
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
sumdPort = openSerialPort(FUNCTION_SERIAL_RX, sumdDataReceive, 115200, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
sumdPort = openSerialPort(FUNCTION_SERIAL_RX, sumdDataReceive, SUMD_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
if (callback)
|
||||
*callback = sumdReadRawRC;
|
||||
|
||||
|
|
|
@ -1,3 +1,4 @@
|
|||
#pragma once
|
||||
|
||||
bool sumdFrameComplete(void);
|
||||
void sumdUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -83,10 +83,10 @@ static const char * const mixerNames[] = {
|
|||
|
||||
// sync this with AvailableFeatures enum from board.h
|
||||
static const char * const featureNames[] = {
|
||||
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP",
|
||||
"RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
|
||||
"SERVO_TILT", "SOFTSERIAL", "LED_RING", "GPS", "FAILSAFE",
|
||||
"SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "PARALLEL_PWM",
|
||||
NULL
|
||||
"SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "RX_PARALLEL_PWM",
|
||||
"RX_MSP", NULL
|
||||
};
|
||||
|
||||
// sync this with AvailableSensors enum from board.h
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -17,6 +18,9 @@
|
|||
#include "serial_common.h"
|
||||
#include "config.h"
|
||||
|
||||
uint32_t getTelemetryProviderBaudRate(void);
|
||||
void updateSerialRxFunctionConstraint(functionConstraint_t *functionConstraintToUpdate);
|
||||
|
||||
void mspInit(serialConfig_t *serialConfig);
|
||||
void cliInit(serialConfig_t *serialConfig);
|
||||
|
||||
|
@ -53,18 +57,13 @@ const static serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
|||
{SERIAL_PORT_SOFTSERIAL2, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
};
|
||||
|
||||
typedef struct functionConstraint_s {
|
||||
serialPortFunction_e function;
|
||||
uint8_t requiredSerialPortFeatures;
|
||||
} functionConstraint_t;
|
||||
|
||||
const functionConstraint_t functionConstraints[] = {
|
||||
{ FUNCTION_CLI, SPF_NONE },
|
||||
{ FUNCTION_GPS, SPF_NONE },
|
||||
{ FUNCTION_GPS_PASSTHROUGH, SPF_NONE },
|
||||
{ FUNCTION_MSP, SPF_NONE },
|
||||
{ FUNCTION_SERIAL_RX, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK },
|
||||
{ FUNCTION_TELEMETRY, SPF_NONE }
|
||||
{ FUNCTION_CLI, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
|
||||
{ FUNCTION_GPS, 9600, 115200, AUTOBAUD, SPF_NONE },
|
||||
{ FUNCTION_GPS_PASSTHROUGH, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
|
||||
{ FUNCTION_MSP, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
|
||||
{ FUNCTION_SERIAL_RX, 9600, 115200, NO_AUTOBAUD, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK },
|
||||
{ FUNCTION_TELEMETRY, 9600, 19200, NO_AUTOBAUD, SPF_NONE }
|
||||
};
|
||||
|
||||
#define FUNCTION_CONSTRAINT_COUNT (sizeof(functionConstraints) / sizeof(functionConstraint_t))
|
||||
|
@ -146,15 +145,10 @@ static void sortSerialPortFunctions(serialPortFunction_t *serialPortFunctions, u
|
|||
* searchPortSearchResult be sure to copy the data out of it before it gets overwritten by another caller.
|
||||
* If this becomes a problem perhaps change the implementation to use a destination argument.
|
||||
*/
|
||||
static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function)
|
||||
static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function, const functionConstraint_t *functionConstraint)
|
||||
{
|
||||
static serialPortSearchResult_t serialPortSearchResult;
|
||||
|
||||
const functionConstraint_t *functionConstraint = findFunctionConstraint(function);
|
||||
if (!functionConstraint) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
sortSerialPortFunctions(serialPortFunctions, SERIAL_PORT_COUNT);
|
||||
|
||||
uint8_t serialPortFunctionIndex;
|
||||
|
@ -182,6 +176,10 @@ static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function)
|
|||
}
|
||||
}
|
||||
|
||||
if (functionConstraint->minBaudRate < serialPortConstraint->minBaudRate || functionConstraint->maxBaudRate > serialPortConstraint->maxBaudRate) {
|
||||
continue;
|
||||
}
|
||||
|
||||
// TODO check speed and mode
|
||||
|
||||
serialPortSearchResult.portIndex = serialPortIndex;
|
||||
|
@ -194,12 +192,6 @@ static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
bool canOpenSerialPort(uint16_t functionMask)
|
||||
{
|
||||
serialPortSearchResult_t *result = findSerialPort(functionMask);
|
||||
return result != NULL;
|
||||
}
|
||||
|
||||
static serialPortFunction_t *findSerialPortFunction(uint16_t functionMask)
|
||||
{
|
||||
serialPortIndex_e portIndex;
|
||||
|
@ -223,16 +215,6 @@ static serialPortFunction_t *findSerialPortFunction(uint16_t functionMask)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask)
|
||||
{
|
||||
serialPortSearchResult_t *result = findSerialPort(functionToUse);
|
||||
if (!result) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return result->portFunction->scenario & functionMask;
|
||||
}
|
||||
|
||||
/*
|
||||
* find a serial port that is:
|
||||
* a) open
|
||||
|
@ -248,11 +230,169 @@ serialPort_t *findOpenSerialPort(uint16_t functionMask)
|
|||
}
|
||||
|
||||
|
||||
|
||||
static serialPortFunction_t * findSerialPortFunctionByPort(serialPort_t *port)
|
||||
{
|
||||
serialPortFunction_t *serialPortFunction;
|
||||
uint8_t functionIndex;
|
||||
|
||||
for (functionIndex = 0; functionIndex < SERIAL_PORT_COUNT; functionIndex++) {
|
||||
serialPortFunction = &serialPortFunctions[functionIndex];
|
||||
if (serialPortFunction->port == port) {
|
||||
return serialPortFunction;
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
|
||||
{
|
||||
serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
|
||||
|
||||
serialPortFunction->currentFunction = function;
|
||||
}
|
||||
|
||||
void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
|
||||
{
|
||||
serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
|
||||
|
||||
serialPortFunction->currentFunction = FUNCTION_NONE;
|
||||
}
|
||||
|
||||
functionConstraint_t *getConfiguredFunctionConstraint(serialPortFunction_e function)
|
||||
{
|
||||
static functionConstraint_t configuredFunctionConstraint;
|
||||
const functionConstraint_t *functionConstraint;
|
||||
|
||||
functionConstraint = findFunctionConstraint(function);
|
||||
if (!functionConstraint) {
|
||||
return NULL;
|
||||
}
|
||||
memcpy(&configuredFunctionConstraint, functionConstraint, sizeof(functionConstraint_t));
|
||||
|
||||
switch(function) {
|
||||
case FUNCTION_MSP:
|
||||
configuredFunctionConstraint.minBaudRate = serialConfig->msp_baudrate;
|
||||
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
|
||||
break;
|
||||
|
||||
case FUNCTION_CLI:
|
||||
configuredFunctionConstraint.minBaudRate = serialConfig->cli_baudrate;
|
||||
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
|
||||
break;
|
||||
|
||||
case FUNCTION_GPS_PASSTHROUGH:
|
||||
configuredFunctionConstraint.minBaudRate = serialConfig->gps_passthrough_baudrate;
|
||||
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
|
||||
break;
|
||||
|
||||
case FUNCTION_TELEMETRY:
|
||||
configuredFunctionConstraint.minBaudRate = getTelemetryProviderBaudRate();
|
||||
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
|
||||
break;
|
||||
case FUNCTION_SERIAL_RX:
|
||||
updateSerialRxFunctionConstraint(&configuredFunctionConstraint);
|
||||
break;
|
||||
case FUNCTION_GPS:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return &configuredFunctionConstraint;
|
||||
}
|
||||
|
||||
bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
|
||||
{
|
||||
serialPortSearchResult_t *searchResult;
|
||||
functionConstraint_t *functionConstraint;
|
||||
|
||||
serialConfig = serialConfigToCheck;
|
||||
|
||||
functionConstraint = getConfiguredFunctionConstraint(FUNCTION_MSP);
|
||||
searchResult = findSerialPort(FUNCTION_MSP, functionConstraint);
|
||||
if (!searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
functionConstraint = getConfiguredFunctionConstraint(FUNCTION_CLI);
|
||||
searchResult = findSerialPort(FUNCTION_CLI, functionConstraint);
|
||||
if (!searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
functionConstraint = getConfiguredFunctionConstraint(FUNCTION_GPS);
|
||||
searchResult = findSerialPort(FUNCTION_GPS, functionConstraint);
|
||||
if (feature(FEATURE_GPS) && !searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
functionConstraint = getConfiguredFunctionConstraint(FUNCTION_SERIAL_RX);
|
||||
searchResult = findSerialPort(FUNCTION_SERIAL_RX, functionConstraint);
|
||||
if (feature(FEATURE_RX_SERIAL) && !searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
functionConstraint = getConfiguredFunctionConstraint(FUNCTION_TELEMETRY);
|
||||
searchResult = findSerialPort(FUNCTION_TELEMETRY, functionConstraint);
|
||||
if (feature(FEATURE_TELEMETRY) && !searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier)
|
||||
{
|
||||
serialPortSearchResult_t *searchResult;
|
||||
const functionConstraint_t *functionConstraint;
|
||||
serialPortFunction_e function;
|
||||
|
||||
uint8_t index;
|
||||
for (index = 0; index < FUNCTION_CONSTRAINT_COUNT; index++) {
|
||||
function = functionConstraints[index].function;
|
||||
functionConstraint = findFunctionConstraint(function);
|
||||
searchResult = findSerialPort(function, functionConstraint);
|
||||
if (searchResult->portConstraint->identifier == portIdentifier) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool canOpenSerialPort(serialPortFunction_e function)
|
||||
{
|
||||
functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(function);
|
||||
|
||||
serialPortSearchResult_t *result = findSerialPort(function, functionConstraint);
|
||||
return result != NULL;
|
||||
}
|
||||
|
||||
bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask)
|
||||
{
|
||||
functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(functionToUse);
|
||||
serialPortSearchResult_t *result = findSerialPort(functionToUse, functionConstraint);
|
||||
if (!result) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return result->portFunction->scenario & functionMask;
|
||||
}
|
||||
|
||||
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
|
||||
{
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART1)].scenario = serialPortScenarios[serialConfig->serial_port_1_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART2)].scenario = serialPortScenarios[serialConfig->serial_port_2_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL1)].scenario = serialPortScenarios[serialConfig->serial_port_3_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL2)].scenario = serialPortScenarios[serialConfig->serial_port_4_scenario];
|
||||
}
|
||||
|
||||
serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
|
||||
{
|
||||
serialPort_t *serialPort = NULL;
|
||||
|
||||
serialPortSearchResult_t *searchResult = findSerialPort(function);
|
||||
functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(function);
|
||||
|
||||
serialPortSearchResult_t *searchResult = findSerialPort(function, functionConstraint);
|
||||
|
||||
if (!searchResult) {
|
||||
return NULL;
|
||||
|
@ -297,90 +437,6 @@ serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbac
|
|||
return serialPort;
|
||||
}
|
||||
|
||||
static serialPortFunction_t * findSerialPortFunctionByPort(serialPort_t *port)
|
||||
{
|
||||
serialPortFunction_t *serialPortFunction;
|
||||
uint8_t functionIndex;
|
||||
|
||||
for (functionIndex = 0; functionIndex < SERIAL_PORT_COUNT; functionIndex++) {
|
||||
serialPortFunction = &serialPortFunctions[functionIndex];
|
||||
if (serialPortFunction->port == port) {
|
||||
return serialPortFunction;
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
|
||||
{
|
||||
serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
|
||||
|
||||
serialPortFunction->currentFunction = function;
|
||||
}
|
||||
|
||||
void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
|
||||
{
|
||||
serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
|
||||
|
||||
serialPortFunction->currentFunction = FUNCTION_NONE;
|
||||
}
|
||||
|
||||
bool isSerialConfigValid(serialConfig_t *serialConfig)
|
||||
{
|
||||
serialPortSearchResult_t *searchResult;
|
||||
|
||||
searchResult = findSerialPort(FUNCTION_MSP);
|
||||
if (!searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
searchResult = findSerialPort(FUNCTION_CLI);
|
||||
if (!searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
searchResult = findSerialPort(FUNCTION_GPS);
|
||||
if (feature(FEATURE_GPS) && !searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
searchResult = findSerialPort(FUNCTION_SERIAL_RX);
|
||||
if (feature(FEATURE_SERIALRX) && !searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
searchResult = findSerialPort(FUNCTION_TELEMETRY);
|
||||
if (feature(FEATURE_TELEMETRY) && !searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier)
|
||||
{
|
||||
serialPortSearchResult_t *searchResult;
|
||||
uint8_t index;
|
||||
for (index = 0; index < FUNCTION_CONSTRAINT_COUNT; index++) {
|
||||
searchResult = findSerialPort(functionConstraints[index].function);
|
||||
if (searchResult->portConstraint->identifier == portIdentifier) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
|
||||
{
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART1)].scenario = serialPortScenarios[serialConfig->serial_port_1_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART2)].scenario = serialPortScenarios[serialConfig->serial_port_2_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL1)].scenario = serialPortScenarios[serialConfig->serial_port_3_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL2)].scenario = serialPortScenarios[serialConfig->serial_port_4_scenario];
|
||||
}
|
||||
|
||||
|
||||
void serialInit(serialConfig_t *initialSerialConfig)
|
||||
{
|
||||
serialConfig = initialSerialConfig;
|
||||
|
|
|
@ -10,6 +10,19 @@ typedef enum {
|
|||
FUNCTION_GPS_PASSTHROUGH = (1 << 5)
|
||||
} serialPortFunction_e;
|
||||
|
||||
typedef enum {
|
||||
NO_AUTOBAUD = 0,
|
||||
AUTOBAUD
|
||||
} autoBaud_e;
|
||||
|
||||
typedef struct functionConstraint_s {
|
||||
serialPortFunction_e function;
|
||||
uint32_t minBaudRate;
|
||||
uint32_t maxBaudRate;
|
||||
autoBaud_e autoBaud;
|
||||
uint8_t requiredSerialPortFeatures;
|
||||
} functionConstraint_t;
|
||||
|
||||
typedef enum {
|
||||
SCENARIO_UNUSED = FUNCTION_NONE,
|
||||
|
||||
|
@ -85,7 +98,7 @@ uint8_t lookupScenarioIndex(serialPortFunctionScenario_e scenario);
|
|||
serialPort_t *findOpenSerialPort(uint16_t functionMask);
|
||||
serialPort_t *openSerialPort(serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion);
|
||||
|
||||
bool canOpenSerialPort(uint16_t functionMask);
|
||||
bool canOpenSerialPort(serialPortFunction_e function);
|
||||
void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function);
|
||||
void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function);
|
||||
|
||||
|
|
|
@ -19,6 +19,8 @@
|
|||
|
||||
|
||||
static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks
|
||||
static bool telemetryEnabled = false;
|
||||
static bool telemetryPortIsShared;
|
||||
|
||||
static telemetryConfig_t *telemetryConfig;
|
||||
|
||||
|
@ -52,22 +54,16 @@ bool canUseTelemetryWithCurrentConfiguration(void)
|
|||
|
||||
void initTelemetry()
|
||||
{
|
||||
|
||||
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_TELEMETRY, FUNCTION_MSP);
|
||||
isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration();
|
||||
|
||||
checkTelemetryState();
|
||||
}
|
||||
|
||||
static bool telemetryEnabled = false;
|
||||
|
||||
bool determineNewTelemetryEnabledState(void)
|
||||
{
|
||||
bool telemetryPortIsShared;
|
||||
bool enabled = true;
|
||||
|
||||
|
||||
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_TELEMETRY, FUNCTION_MSP);
|
||||
|
||||
if (telemetryPortIsShared) {
|
||||
if (telemetryConfig->telemetry_switch)
|
||||
enabled = rcOptions[BOXTELEMETRY];
|
||||
|
@ -83,6 +79,18 @@ bool shouldChangeTelemetryStateNow(bool newState)
|
|||
return newState != telemetryEnabled;
|
||||
}
|
||||
|
||||
uint32_t getTelemetryProviderBaudRate(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
return getFrSkyTelemetryProviderBaudRate();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
return getHoTTTelemetryProviderBaudRate();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void configureTelemetryPort(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
|
@ -94,6 +102,7 @@ static void configureTelemetryPort(void)
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
void freeTelemetryPort(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
|
|
|
@ -23,6 +23,7 @@ typedef struct telemetryConfig_s {
|
|||
void checkTelemetryState(void);
|
||||
void handleTelemetry(void);
|
||||
|
||||
uint32_t getTelemetryProviderBaudRate(void);
|
||||
void useTelemetryConfig(telemetryConfig_t *telemetryConfig);
|
||||
|
||||
#endif /* TELEMETRY_COMMON_H_ */
|
||||
|
|
|
@ -337,3 +337,6 @@ void handleFrSkyTelemetry(void)
|
|||
}
|
||||
}
|
||||
|
||||
uint32_t getFrSkyTelemetryProviderBaudRate(void) {
|
||||
return FRSKY_BAUDRATE;
|
||||
}
|
||||
|
|
|
@ -14,4 +14,6 @@ void checkFrSkyTelemetryState(void);
|
|||
void configureFrSkyTelemetryPort(telemetryConfig_t *telemetryConfig);
|
||||
void freeFrSkyTelemetryPort(void);
|
||||
|
||||
uint32_t getFrSkyTelemetryProviderBaudRate(void);
|
||||
|
||||
#endif /* TELEMETRY_FRSKY_H_ */
|
||||
|
|
|
@ -322,3 +322,8 @@ void handleHoTTTelemetry(void)
|
|||
}
|
||||
}
|
||||
|
||||
uint32_t getHoTTTelemetryProviderBaudRate(void) {
|
||||
return HOTT_BAUDRATE;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -206,4 +206,5 @@ void checkTelemetryState(void);
|
|||
void configureHoTTTelemetryPort(telemetryConfig_t *telemetryConfig);
|
||||
void freeHoTTTelemetryPort(void);
|
||||
|
||||
uint32_t getHoTTTelemetryProviderBaudRate(void);
|
||||
#endif /* TELEMETRY_HOTT_H_ */
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue