Refactor serial port configuration, stage 1.
Tested and working: * multiple MSP ports at different baud rates. * cli on any MSP port. * GPS * gps passthough on currently active cli port. Example config used for testing: feature SOFTSERIAL feature GPS feature RX_PPM serial_port_1_functions = 1 serial_port_1_baudrate = 115200 serial_port_2_functions = 128 serial_port_2_baudrate = 115200 serial_port_3_functions = 1 serial_port_3_baudrate = 19200 serial_port_4_functions = 0 serial_port_4_baudrate = 0 Known broken: * Telemetry and shared serial ports * Telemetry when unarmed. Probably broken: * Blackbox on shared port. Untested. * Serial RX. * Blackbox.
This commit is contained in:
parent
519cc5f238
commit
5163bef0b2
|
@ -8,8 +8,8 @@ Enable the GPS from the CLI as follows:
|
|||
|
||||
1. first enable the `feature GPS`
|
||||
1. set the `gps_provider`
|
||||
1. if required, set your GPS baud rate using `gps_baudrate`
|
||||
1. connect your GPS to a serial port that supports GPS and set an approprate `serial_port_x_scenario` to `2`. where `x` is a serial port number.
|
||||
1. set your GPS baud rate
|
||||
1. connect your GPS to a serial port that supports GPS and set an approprate `serial_port_x_functions` to include the GPS flag.
|
||||
1. `save`.
|
||||
|
||||
Note: GPS packet loss has been observed at 115200. Try using 57600 if you experience this.
|
||||
|
|
|
@ -31,14 +31,11 @@ verify your aux config is correct - aux settings are not backwards compatible.
|
|||
In general all CLI commands use underscore characters to separate words for consistency. In baseflight the format of CLI commands is somewhat haphazard.
|
||||
|
||||
### gps_baudrate
|
||||
reason: simplify
|
||||
|
||||
Cleanflight uses normal baud rate values for gps baudrate, baseflight uses an index.
|
||||
reason: unified baud rate configuration
|
||||
|
||||
If an unsupported baud rate value is used the gps code will select 115200 baud.
|
||||
|
||||
example: `set gps_baudrate = 115200`
|
||||
|
||||
see `serial_port_x_baudrate`
|
||||
|
||||
### gps_type
|
||||
reason: renamed to `gps_provider` for consistency
|
||||
|
|
|
@ -62,9 +62,7 @@
|
|||
// How many bytes should we transmit per loop iteration?
|
||||
uint8_t blackboxWriteChunkSize = 16;
|
||||
|
||||
static serialPort_t *blackboxPort;
|
||||
static portMode_t previousPortMode;
|
||||
static uint32_t previousBaudRate;
|
||||
static serialPort_t *blackboxPort = NULL;
|
||||
|
||||
void blackboxWrite(uint8_t value)
|
||||
{
|
||||
|
@ -387,21 +385,14 @@ void blackboxDeviceFlush(void)
|
|||
*/
|
||||
bool blackboxDeviceOpen(void)
|
||||
{
|
||||
blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX);
|
||||
if (blackboxPort) {
|
||||
previousPortMode = blackboxPort->mode;
|
||||
previousBaudRate = blackboxPort->baudRate;
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
|
||||
if (!portConfig) {
|
||||
return false;
|
||||
}
|
||||
|
||||
serialSetBaudRate(blackboxPort, BLACKBOX_BAUDRATE);
|
||||
serialSetMode(blackboxPort, BLACKBOX_INITIAL_PORT_MODE);
|
||||
beginSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX);
|
||||
} else {
|
||||
blackboxPort = openSerialPort(FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
|
||||
|
||||
if (blackboxPort) {
|
||||
previousPortMode = blackboxPort->mode;
|
||||
previousBaudRate = blackboxPort->baudRate;
|
||||
}
|
||||
blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
|
||||
if (!blackboxPort) {
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -413,23 +404,13 @@ bool blackboxDeviceOpen(void)
|
|||
*/
|
||||
blackboxWriteChunkSize = MAX((masterConfig.looptime * 9) / 1250, 4);
|
||||
|
||||
return blackboxPort != NULL;
|
||||
return true;
|
||||
}
|
||||
|
||||
void blackboxDeviceClose(void)
|
||||
{
|
||||
serialSetMode(blackboxPort, previousPortMode);
|
||||
serialSetBaudRate(blackboxPort, previousBaudRate);
|
||||
closeSerialPort(blackboxPort);
|
||||
|
||||
endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX);
|
||||
|
||||
/*
|
||||
* Normally this would be handled by mw.c, but since we take an unknown amount
|
||||
* of time to shut down asynchronously, we're the only ones that know when to call it.
|
||||
*/
|
||||
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
}
|
||||
}
|
||||
|
||||
bool isBlackboxDeviceIdle(void)
|
||||
|
|
|
@ -111,7 +111,7 @@ profile_t *currentProfile;
|
|||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 91;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 92;
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
|
@ -213,7 +213,6 @@ void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
|
|||
|
||||
void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
|
||||
{
|
||||
telemetryConfig->telemetry_provider = TELEMETRY_PROVIDER_FRSKY;
|
||||
telemetryConfig->telemetry_inversion = SERIAL_NOT_INVERTED;
|
||||
telemetryConfig->telemetry_switch = 0;
|
||||
telemetryConfig->gpsNoFixLatitude = 0;
|
||||
|
@ -244,31 +243,25 @@ void resetBatteryConfig(batteryConfig_t *batteryConfig)
|
|||
|
||||
void resetSerialConfig(serialConfig_t *serialConfig)
|
||||
{
|
||||
serialConfig->serial_port_scenario[FIRST_PORT_INDEX] = lookupScenarioIndex(SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH);
|
||||
uint8_t index;
|
||||
memset(serialConfig, 0, sizeof(serialConfig_t));
|
||||
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
|
||||
}
|
||||
|
||||
serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
|
||||
serialConfig->portConfigs[0].identifier = serialPortIdentifiers[FIRST_PORT_INDEX];
|
||||
serialConfig->portConfigs[0].baudrate = 115200;
|
||||
|
||||
#ifdef CC3D
|
||||
// Temporary workaround for CC3D non-functional VCP when using OpenPilot bootloader.
|
||||
// This allows MSP connection via USART so the board can be reconfigured.
|
||||
serialConfig->serial_port_scenario[SECOND_PORT_INDEX] = lookupScenarioIndex(SCENARIO_MSP_ONLY);
|
||||
#else
|
||||
serialConfig->serial_port_scenario[SECOND_PORT_INDEX] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
|
||||
serialConfig->portConfigs[1].identifier = serialPortIdentifiers[SECOND_PORT_INDEX];
|
||||
serialConfig->portConfigs[1].baudrate = 115200;
|
||||
#endif
|
||||
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
serialConfig->serial_port_scenario[2] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
#if (SERIAL_PORT_COUNT > 3)
|
||||
serialConfig->serial_port_scenario[3] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
#if (SERIAL_PORT_COUNT > 4)
|
||||
serialConfig->serial_port_scenario[4] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
serialConfig->msp_baudrate = 115200;
|
||||
serialConfig->cli_baudrate = 115200;
|
||||
serialConfig->gps_baudrate = 115200;
|
||||
serialConfig->gps_passthrough_baudrate = 115200;
|
||||
|
||||
serialConfig->reboot_character = 'R';
|
||||
}
|
||||
|
||||
|
@ -743,7 +736,6 @@ void validateAndFixConfig(void)
|
|||
useRxConfig(&masterConfig.rxConfig);
|
||||
|
||||
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
||||
applySerialConfigToPortFunctions(serialConfig);
|
||||
|
||||
if (!isSerialConfigValid(serialConfig)) {
|
||||
resetSerialConfig(serialConfig);
|
||||
|
|
|
@ -202,20 +202,12 @@ static void gpsSetState(uint8_t state)
|
|||
gpsData.messageState = GPS_MESSAGE_STATE_IDLE;
|
||||
}
|
||||
|
||||
// When using PWM input GPS usage reduces number of available channels by 2 - see pwm_common.c/pwmInit()
|
||||
void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
||||
{
|
||||
serialConfig = initialSerialConfig;
|
||||
|
||||
gpsData.baudrateIndex = 0;
|
||||
while (gpsInitData[gpsData.baudrateIndex].baudrate != serialConfig->gps_baudrate) {
|
||||
gpsData.baudrateIndex++;
|
||||
if (gpsData.baudrateIndex >= GPS_INIT_DATA_ENTRY_COUNT) {
|
||||
gpsData.baudrateIndex = DEFAULT_BAUD_RATE_INDEX;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
gpsData.baudrateIndex = 0;
|
||||
gpsData.errors = 0;
|
||||
gpsData.timeouts = 0;
|
||||
|
||||
|
@ -228,13 +220,27 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
|||
|
||||
gpsData.lastMessage = millis();
|
||||
|
||||
serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS);
|
||||
if (!gpsPortConfig) {
|
||||
featureClear(FEATURE_GPS);
|
||||
return;
|
||||
}
|
||||
|
||||
while (gpsInitData[gpsData.baudrateIndex].baudrate != gpsPortConfig->baudrate) {
|
||||
gpsData.baudrateIndex++;
|
||||
if (gpsData.baudrateIndex >= GPS_INIT_DATA_ENTRY_COUNT) {
|
||||
gpsData.baudrateIndex = DEFAULT_BAUD_RATE_INDEX;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
portMode_t mode = MODE_RXTX;
|
||||
// only RX is needed for NMEA-style GPS
|
||||
if (gpsConfig->provider == GPS_NMEA)
|
||||
mode &= ~MODE_TX;
|
||||
|
||||
// no callback - buffer will be consumed in gpsThread()
|
||||
gpsPort = openSerialPort(FUNCTION_GPS, NULL, gpsInitData[gpsData.baudrateIndex].baudrate, mode, SERIAL_NOT_INVERTED);
|
||||
gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, gpsInitData[gpsData.baudrateIndex].baudrate, mode, SERIAL_NOT_INVERTED);
|
||||
if (!gpsPort) {
|
||||
featureClear(FEATURE_GPS);
|
||||
return;
|
||||
|
@ -258,7 +264,7 @@ void gpsInitNmea(void)
|
|||
void gpsInitUblox(void)
|
||||
{
|
||||
uint32_t now;
|
||||
// UBX will run at mcfg.gps_baudrate, it shouldn't be "autodetected". So here we force it to that rate
|
||||
// UBX will run at the serial port's baudrate, it shouldn't be "autodetected". So here we force it to that rate
|
||||
|
||||
// Wait until GPS transmit buffer is empty
|
||||
if (!isSerialTransmitBufferEmpty(gpsPort))
|
||||
|
@ -959,20 +965,11 @@ static bool gpsNewFrameUBLOX(uint8_t data)
|
|||
return parsed;
|
||||
}
|
||||
|
||||
gpsEnablePassthroughResult_e gpsEnablePassthrough(void)
|
||||
void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
|
||||
{
|
||||
serialPort_t *gpsPassthroughPort = findOpenSerialPort(FUNCTION_GPS_PASSTHROUGH);
|
||||
if (gpsPassthroughPort) {
|
||||
waitForSerialPortToFinishTransmitting(gpsPort);
|
||||
waitForSerialPortToFinishTransmitting(gpsPassthroughPort);
|
||||
|
||||
waitForSerialPortToFinishTransmitting(gpsPassthroughPort);
|
||||
serialSetBaudRate(gpsPassthroughPort, serialConfig->gps_passthrough_baudrate);
|
||||
} else {
|
||||
gpsPassthroughPort = openSerialPort(FUNCTION_GPS_PASSTHROUGH, NULL, serialConfig->gps_passthrough_baudrate, MODE_RXTX, SERIAL_NOT_INVERTED);
|
||||
if (!gpsPassthroughPort) {
|
||||
return GPS_PASSTHROUGH_NO_SERIAL_PORT;
|
||||
}
|
||||
}
|
||||
serialSetBaudRate(gpsPort, serialConfig->gps_baudrate);
|
||||
if(!(gpsPort->mode & MODE_TX))
|
||||
serialSetMode(gpsPort, gpsPort->mode | MODE_TX);
|
||||
|
||||
|
@ -1003,9 +1000,7 @@ gpsEnablePassthroughResult_e gpsEnablePassthrough(void)
|
|||
updateDisplay();
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
return GPS_PASSTHROUGH_ENABLED;
|
||||
}
|
||||
|
||||
void updateGpsIndicator(uint32_t currentTime)
|
||||
|
|
|
@ -66,11 +66,6 @@ typedef struct gpsConfig_s {
|
|||
gpsAutoBaud_e autoBaud;
|
||||
} gpsConfig_t;
|
||||
|
||||
typedef enum {
|
||||
GPS_PASSTHROUGH_ENABLED = 1,
|
||||
GPS_PASSTHROUGH_NO_SERIAL_PORT
|
||||
} gpsEnablePassthroughResult_e;
|
||||
|
||||
typedef struct gpsCoordinateDDDMMmmmm_s {
|
||||
int16_t dddmm;
|
||||
int16_t mmmm;
|
||||
|
@ -124,5 +119,4 @@ extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Str
|
|||
|
||||
void gpsThread(void);
|
||||
bool gpsNewFrame(uint8_t c);
|
||||
gpsEnablePassthroughResult_e gpsEnablePassthrough(void);
|
||||
void updateGpsIndicator(uint32_t currentTime);
|
||||
|
|
|
@ -42,565 +42,141 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#endif
|
||||
|
||||
void updateSerialRxFunctionConstraint(functionConstraint_t *functionConstraintToUpdate);
|
||||
|
||||
void cliInit(serialConfig_t *serialConfig);
|
||||
|
||||
// this exists so the user can reference scenarios by a number in the CLI instead of an unuser-friendly bitmask.
|
||||
const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT] = {
|
||||
SCENARIO_UNUSED,
|
||||
|
||||
// common scenarios in order of importance
|
||||
SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH,
|
||||
SCENARIO_GPS_ONLY,
|
||||
SCENARIO_SERIAL_RX_ONLY,
|
||||
SCENARIO_TELEMETRY_ONLY,
|
||||
|
||||
// other scenarios
|
||||
SCENARIO_MSP_CLI_GPS_PASTHROUGH,
|
||||
SCENARIO_CLI_ONLY,
|
||||
SCENARIO_GPS_PASSTHROUGH_ONLY,
|
||||
SCENARIO_MSP_ONLY,
|
||||
SCENARIO_SMARTPORT_TELEMETRY_ONLY,
|
||||
|
||||
SCENARIO_BLACKBOX_ONLY,
|
||||
SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH
|
||||
};
|
||||
|
||||
static serialConfig_t *serialConfig;
|
||||
static serialPort_t *serialPorts[SERIAL_PORT_COUNT];
|
||||
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
|
||||
|
||||
#ifdef STM32F303xC
|
||||
static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||
serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
||||
#ifdef USE_VCP
|
||||
{SERIAL_PORT_USB_VCP, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
SERIAL_PORT_USB_VCP,
|
||||
#endif
|
||||
#ifdef USE_USART1
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
SERIAL_PORT_USART1,
|
||||
#endif
|
||||
#ifdef USE_USART2
|
||||
{SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
SERIAL_PORT_USART2,
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
SERIAL_PORT_USART3,
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
SERIAL_PORT_SOFTSERIAL1,
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL2
|
||||
SERIAL_PORT_SOFTSERIAL2,
|
||||
#endif
|
||||
};
|
||||
|
||||
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
#ifdef USE_VCP
|
||||
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
||||
#endif
|
||||
#ifdef USE_USART1
|
||||
{SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
#endif
|
||||
#ifdef USE_USART2
|
||||
{SERIAL_PORT_USART2, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
{SERIAL_PORT_USART3, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
#endif
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
#ifdef CC3D
|
||||
static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||
#ifdef USE_VCP
|
||||
{SERIAL_PORT_USB_VCP, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
#endif
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
};
|
||||
|
||||
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
#ifdef USE_VCP
|
||||
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
||||
#endif
|
||||
{SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
{SERIAL_PORT_USART3, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
};
|
||||
#else
|
||||
|
||||
static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
#endif
|
||||
};
|
||||
|
||||
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
{SERIAL_PORT_USART2, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
#endif
|
||||
|
||||
const functionConstraint_t functionConstraints[] = {
|
||||
{ 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, 250000, NO_AUTOBAUD, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK },
|
||||
{ FUNCTION_TELEMETRY, 9600, 19200, NO_AUTOBAUD, SPF_NONE },
|
||||
{ FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE },
|
||||
{ FUNCTION_BLACKBOX, 115200,115200, NO_AUTOBAUD, SPF_NONE }
|
||||
};
|
||||
|
||||
#define FUNCTION_CONSTRAINT_COUNT (sizeof(functionConstraints) / sizeof(functionConstraint_t))
|
||||
|
||||
typedef struct serialPortSearchResult_s {
|
||||
serialPortIndex_e portIndex;
|
||||
serialPortFunction_t *portFunction;
|
||||
const serialPortConstraint_t *portConstraint;
|
||||
const functionConstraint_t *functionConstraint;
|
||||
|
||||
// private
|
||||
uint8_t startSerialPortFunctionIndex; // used by findNextSerialPort
|
||||
} serialPortSearchResult_t;
|
||||
|
||||
static const serialPortFunctionList_t serialPortFunctionList = {
|
||||
SERIAL_PORT_COUNT,
|
||||
serialPortFunctions
|
||||
};
|
||||
|
||||
const serialPortFunctionList_t *getSerialPortFunctionList(void)
|
||||
{
|
||||
return &serialPortFunctionList;
|
||||
}
|
||||
|
||||
uint8_t lookupScenarioIndex(serialPortFunctionScenario_e scenario) {
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_SCENARIO_COUNT; index++) {
|
||||
if (serialPortScenarios[index] == scenario) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
return index;
|
||||
}
|
||||
|
||||
static serialPortIndex_e lookupSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
|
||||
{
|
||||
serialPortIndex_e portIndex;
|
||||
for (portIndex = 0; portIndex < SERIAL_PORT_COUNT; portIndex++) {
|
||||
if (serialPortConstraints[portIndex].identifier == identifier) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
return portIndex;
|
||||
}
|
||||
|
||||
#define IDENTIFIER_NOT_FOUND 0xFF
|
||||
|
||||
static uint8_t lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier_e identifier)
|
||||
static serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
|
||||
{
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
if (serialPortFunctions[index].identifier == identifier) {
|
||||
return index;
|
||||
}
|
||||
}
|
||||
return IDENTIFIER_NOT_FOUND;
|
||||
}
|
||||
|
||||
static const functionConstraint_t *findFunctionConstraint(serialPortFunction_e function)
|
||||
{
|
||||
const functionConstraint_t *functionConstraint = NULL;
|
||||
uint8_t functionConstraintIndex;
|
||||
|
||||
for (functionConstraintIndex = 0; functionConstraintIndex < FUNCTION_CONSTRAINT_COUNT; functionConstraintIndex++) {
|
||||
functionConstraint = &functionConstraints[functionConstraintIndex];
|
||||
if (functionConstraint->function == function) {
|
||||
return functionConstraint;
|
||||
serialPortUsage_t *candidate = &serialPortUsageList[index];
|
||||
if (candidate->identifier == identifier) {
|
||||
return candidate;
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static uint8_t countBits_uint32(uint32_t n) {
|
||||
uint8_t c; // c accumulates the total bits set in n
|
||||
for (c = 0; n; c++)
|
||||
n &= n - 1; // clear the least significant bit set
|
||||
return c;
|
||||
}
|
||||
static int serialPortFunctionMostSpecificFirstComparator(const void *aPtr, const void *bPtr)
|
||||
{
|
||||
serialPortFunction_t *a = (serialPortFunction_t *)aPtr;
|
||||
serialPortFunction_t *b = (serialPortFunction_t *)bPtr;
|
||||
|
||||
return countBits_uint32(a->scenario) - countBits_uint32(b->scenario);
|
||||
serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort) {
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortUsage_t *candidate = &serialPortUsageList[index];
|
||||
if (candidate->serialPort == serialPort) {
|
||||
return candidate;
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static void sortSerialPortFunctions(serialPortFunction_t *serialPortFunctions, uint8_t elements)
|
||||
typedef struct findSerialPortConfigState_s {
|
||||
uint8_t lastIndex;
|
||||
} findSerialPortConfigState_t;
|
||||
|
||||
static findSerialPortConfigState_t findSerialPortConfigState;
|
||||
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
|
||||
{
|
||||
serialPortFunction_t swap;
|
||||
memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
|
||||
|
||||
int index1;
|
||||
int index2;
|
||||
return findNextSerialPortConfig(function);
|
||||
}
|
||||
|
||||
// bubble-sort array (TODO - port selection can be implemented as repeated minimum search with bitmask marking used elements)
|
||||
for (index1 = 0; index1 < (elements - 1); index1++) {
|
||||
for (index2 = 0; index2 < elements - index1 - 1; index2++) {
|
||||
if(serialPortFunctionMostSpecificFirstComparator(&serialPortFunctions[index2], &serialPortFunctions[index2 + 1]) > 0) {
|
||||
swap = serialPortFunctions[index2];
|
||||
serialPortFunctions[index2] = serialPortFunctions[index2 + 1];
|
||||
serialPortFunctions[index2 + 1] = swap;
|
||||
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
|
||||
{
|
||||
while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
|
||||
serialPortConfig_t *candidate = &serialConfig->portConfigs[findSerialPortConfigState.lastIndex++];
|
||||
|
||||
if (candidate->functionMask & function) {
|
||||
return candidate;
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
typedef struct findSharedSerialPortState_s {
|
||||
uint8_t lastIndex;
|
||||
} findSharedSerialPortState_t;
|
||||
|
||||
static findSharedSerialPortState_t findSharedSerialPortState;
|
||||
|
||||
serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
|
||||
{
|
||||
memset(&findSharedSerialPortState, 0, sizeof(findSharedSerialPortState));
|
||||
|
||||
return findNextSharedSerialPort(functionMask, sharedWithFunction);
|
||||
}
|
||||
|
||||
serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
|
||||
{
|
||||
while (findSharedSerialPortState.lastIndex < SERIAL_PORT_COUNT) {
|
||||
serialPortConfig_t *candidate = &serialConfig->portConfigs[findSharedSerialPortState.lastIndex++];
|
||||
|
||||
if ((candidate->functionMask & sharedWithFunction) && (candidate->functionMask & functionMask)) {
|
||||
serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
|
||||
if (!serialPortUsage) {
|
||||
continue;
|
||||
}
|
||||
return serialPortUsage->serialPort;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
serialPortSearchResult_t *findNextSerialPort(serialPortFunction_e function, const functionConstraint_t *functionConstraint, serialPortSearchResult_t *resultBuffer)
|
||||
{
|
||||
uint8_t serialPortFunctionIndex;
|
||||
serialPortFunction_t *serialPortFunction;
|
||||
for (serialPortFunctionIndex = resultBuffer->startSerialPortFunctionIndex; serialPortFunctionIndex < SERIAL_PORT_COUNT; serialPortFunctionIndex++) {
|
||||
serialPortFunction = &serialPortFunctions[serialPortFunctionIndex];
|
||||
|
||||
if (!(serialPortFunction->scenario & function)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
uint8_t serialPortIndex = lookupSerialPortIndexByIdentifier(serialPortFunction->identifier);
|
||||
const serialPortConstraint_t *serialPortConstraint = &serialPortConstraints[serialPortIndex];
|
||||
|
||||
#if defined(CC3D)
|
||||
if (!feature(FEATURE_SOFTSERIAL) && (
|
||||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1)) {
|
||||
continue;
|
||||
}
|
||||
#else
|
||||
#if defined(USE_SOFTSERIAL1) ||(defined(USE_SOFTSERIAL2))
|
||||
if (!feature(FEATURE_SOFTSERIAL) && (
|
||||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1 ||
|
||||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2
|
||||
)) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
#if (defined(NAZE) || defined(OLIMEXINO)) && defined(SONAR)
|
||||
if (feature(FEATURE_SONAR) && !feature(FEATURE_RX_PARALLEL_PWM) && (serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2)) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
if ((serialPortConstraint->feature & functionConstraint->requiredSerialPortFeatures) != functionConstraint->requiredSerialPortFeatures) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (functionConstraint->minBaudRate < serialPortConstraint->minBaudRate || functionConstraint->maxBaudRate > serialPortConstraint->maxBaudRate) {
|
||||
continue;
|
||||
}
|
||||
|
||||
resultBuffer->portIndex = serialPortIndex;
|
||||
resultBuffer->portConstraint = serialPortConstraint;
|
||||
resultBuffer->portFunction = serialPortFunction;
|
||||
resultBuffer->functionConstraint = functionConstraint;
|
||||
|
||||
uint8_t nextStartIndex = serialPortFunctionIndex + 1;
|
||||
resultBuffer->startSerialPortFunctionIndex = nextStartIndex;
|
||||
|
||||
return resultBuffer;
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/*
|
||||
* since this method, and other methods that use it, use a single instance of
|
||||
* 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, const functionConstraint_t *functionConstraint)
|
||||
{
|
||||
static serialPortSearchResult_t serialPortSearchResult;
|
||||
|
||||
memset(&serialPortSearchResult, 0, sizeof(serialPortSearchResult));
|
||||
|
||||
// FIXME this only needs to be done once, after the config has been loaded.
|
||||
sortSerialPortFunctions(serialPortFunctions, SERIAL_PORT_COUNT);
|
||||
|
||||
return findNextSerialPort(function, functionConstraint, &serialPortSearchResult);
|
||||
}
|
||||
|
||||
|
||||
static serialPortFunction_t *findSerialPortFunction(uint16_t functionMask)
|
||||
{
|
||||
serialPortIndex_e portIndex;
|
||||
|
||||
// find exact match first
|
||||
for (portIndex = 0; portIndex < SERIAL_PORT_COUNT; portIndex++) {
|
||||
serialPortFunction_t *serialPortFunction = &serialPortFunctions[portIndex];
|
||||
if (serialPortFunction->scenario == functionMask) {
|
||||
return serialPortFunction;
|
||||
}
|
||||
}
|
||||
|
||||
// find the first port that supports the function requested
|
||||
for (portIndex = 0; portIndex < SERIAL_PORT_COUNT; portIndex++) {
|
||||
serialPortFunction_t *serialPortFunction = &serialPortFunctions[portIndex];
|
||||
if (serialPortFunction->scenario & functionMask) {
|
||||
return serialPortFunction;
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/*
|
||||
* find a serial port that is:
|
||||
* a) open
|
||||
* b) matches the function mask exactly, or if an exact match is not found the first port that supports the function
|
||||
*/
|
||||
serialPort_t *findOpenSerialPort(uint16_t functionMask)
|
||||
{
|
||||
serialPortFunction_t *function = findSerialPortFunction(functionMask);
|
||||
if (!function) {
|
||||
return NULL;
|
||||
}
|
||||
return function->port;
|
||||
}
|
||||
|
||||
|
||||
|
||||
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)
|
||||
{
|
||||
UNUSED(function);
|
||||
serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
|
||||
|
||||
serialPortFunction->currentFunction = FUNCTION_NONE;
|
||||
serialPortFunction->port = NULL;
|
||||
}
|
||||
|
||||
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.maxBaudRate = serialConfig->msp_baudrate;
|
||||
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;
|
||||
|
||||
#ifdef TELEMETRY
|
||||
case FUNCTION_TELEMETRY:
|
||||
case FUNCTION_SMARTPORT_TELEMETRY:
|
||||
configuredFunctionConstraint.minBaudRate = getTelemetryProviderBaudRate();
|
||||
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
|
||||
break;
|
||||
#endif
|
||||
#ifdef SERIAL_RX
|
||||
case FUNCTION_SERIAL_RX:
|
||||
updateSerialRxFunctionConstraint(&configuredFunctionConstraint);
|
||||
break;
|
||||
#endif
|
||||
case FUNCTION_GPS:
|
||||
configuredFunctionConstraint.maxBaudRate = serialConfig->gps_baudrate;
|
||||
break;
|
||||
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);
|
||||
// TODO check explicitly for SmartPort config
|
||||
if (!searchResult) {
|
||||
functionConstraint = getConfiguredFunctionConstraint(FUNCTION_SMARTPORT_TELEMETRY);
|
||||
searchResult = findSerialPort(FUNCTION_SMARTPORT_TELEMETRY, functionConstraint);
|
||||
}
|
||||
if (feature(FEATURE_TELEMETRY) && !searchResult) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t functionIndex;
|
||||
uint8_t cliPortCount = 0;
|
||||
uint8_t mspPortCount = 0;
|
||||
for (functionIndex = 0; functionIndex < SERIAL_PORT_COUNT; functionIndex++) {
|
||||
if (serialPortFunctions[functionIndex].scenario & FUNCTION_CLI) {
|
||||
if (++cliPortCount > 1) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
if (serialPortFunctions[functionIndex].scenario & FUNCTION_MSP) {
|
||||
if (++mspPortCount > MAX_MSP_PORT_COUNT) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
UNUSED(serialConfigToCheck);
|
||||
return true; // FIXME implement rules - 1 MSP port minimum.
|
||||
}
|
||||
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier)
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
|
||||
{
|
||||
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) {
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortConfig_t *candidate = &serialConfig->portConfigs[index];
|
||||
if (candidate->identifier == identifier && candidate->functionMask) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool canOpenSerialPort(serialPortFunction_e function)
|
||||
serialPort_t *openSerialPort(
|
||||
serialPortIdentifier_e identifier,
|
||||
serialPortFunction_e function,
|
||||
serialReceiveCallbackPtr callback,
|
||||
uint32_t baudRate,
|
||||
portMode_t mode,
|
||||
serialInversion_e inversion)
|
||||
{
|
||||
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;
|
||||
}
|
||||
|
||||
serialPort_t *findSharedSerialPort(serialPortFunction_e functionToUse, uint16_t functionMask)
|
||||
{
|
||||
functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(functionToUse);
|
||||
serialPortSearchResult_t *result = findSerialPort(functionToUse, functionConstraint);
|
||||
|
||||
if (result->portFunction->scenario & functionMask) {
|
||||
return result->portFunction->port;
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
|
||||
{
|
||||
uint32_t portIndex = 0, serialPortIdentifier, constraintIndex;
|
||||
|
||||
for (constraintIndex = 0; constraintIndex < SERIAL_PORT_COUNT && portIndex < SERIAL_PORT_COUNT; constraintIndex++) {
|
||||
serialPortIdentifier = serialPortConstraints[constraintIndex].identifier;
|
||||
uint32_t functionIndex = lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier);
|
||||
if (functionIndex == IDENTIFIER_NOT_FOUND) {
|
||||
continue;
|
||||
}
|
||||
serialPortFunctions[functionIndex].scenario = serialPortScenarios[serialConfig->serial_port_scenario[portIndex++]];
|
||||
}
|
||||
}
|
||||
|
||||
serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
|
||||
{
|
||||
serialPort_t *serialPort = NULL;
|
||||
|
||||
functionConstraint_t *initialFunctionConstraint = getConfiguredFunctionConstraint(function);
|
||||
|
||||
functionConstraint_t updatedFunctionConstraint;
|
||||
memcpy(&updatedFunctionConstraint, initialFunctionConstraint, sizeof(updatedFunctionConstraint));
|
||||
if (initialFunctionConstraint->autoBaud == NO_AUTOBAUD) {
|
||||
updatedFunctionConstraint.minBaudRate = baudRate;
|
||||
updatedFunctionConstraint.maxBaudRate = baudRate;
|
||||
}
|
||||
functionConstraint_t *functionConstraint = &updatedFunctionConstraint;
|
||||
|
||||
serialPortSearchResult_t *searchResult = findSerialPort(function, functionConstraint);
|
||||
|
||||
while(searchResult && searchResult->portFunction->port) {
|
||||
// port is already open, find the next one
|
||||
searchResult = findNextSerialPort(function, functionConstraint, searchResult);
|
||||
}
|
||||
|
||||
if (!searchResult) {
|
||||
serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
|
||||
if (serialPortUsage->function != FUNCTION_NONE) {
|
||||
// already in use
|
||||
return NULL;
|
||||
}
|
||||
|
||||
serialPortIndex_e portIndex = searchResult->portIndex;
|
||||
serialPort_t *serialPort = NULL;
|
||||
|
||||
const serialPortConstraint_t *serialPortConstraint = searchResult->portConstraint;
|
||||
|
||||
serialPortIdentifier_e identifier = serialPortConstraint->identifier;
|
||||
switch(identifier) {
|
||||
#ifdef USE_VCP
|
||||
case SERIAL_PORT_USB_VCP:
|
||||
|
@ -644,32 +220,36 @@ serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbac
|
|||
|
||||
serialPort->identifier = identifier;
|
||||
|
||||
serialPorts[portIndex] = serialPort;
|
||||
|
||||
serialPortFunction_t *serialPortFunction = searchResult->portFunction;
|
||||
|
||||
serialPortFunction->port = serialPort;
|
||||
//serialPortFunction->identifier = identifier;
|
||||
|
||||
beginSerialPortFunction(serialPort, function);
|
||||
serialPortUsage->function = function;
|
||||
serialPortUsage->serialPort = serialPort;
|
||||
|
||||
return serialPort;
|
||||
}
|
||||
|
||||
void closeSerialPort(serialPort_t *serialPort) {
|
||||
serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
|
||||
if (!serialPortUsage) {
|
||||
// already closed
|
||||
return;
|
||||
}
|
||||
|
||||
serialPort->callback = NULL;
|
||||
|
||||
serialPortUsage->function = FUNCTION_NONE;
|
||||
serialPortUsage->serialPort = NULL;
|
||||
}
|
||||
|
||||
void serialInit(serialConfig_t *initialSerialConfig)
|
||||
{
|
||||
uint8_t index;
|
||||
|
||||
serialConfig = initialSerialConfig;
|
||||
applySerialConfigToPortFunctions(serialConfig);
|
||||
|
||||
#ifdef TELEMETRY
|
||||
if (telemetryAllowsOtherSerial(FUNCTION_MSP))
|
||||
#endif
|
||||
mspInit(serialConfig);
|
||||
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
||||
|
||||
#ifdef TELEMETRY
|
||||
if (telemetryAllowsOtherSerial(FUNCTION_CLI))
|
||||
#endif
|
||||
cliInit(serialConfig);
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
|
||||
}
|
||||
}
|
||||
|
||||
void handleSerial(void)
|
||||
|
@ -680,10 +260,7 @@ void handleSerial(void)
|
|||
return;
|
||||
}
|
||||
|
||||
#ifdef TELEMETRY
|
||||
if (telemetryAllowsOtherSerial(FUNCTION_MSP))
|
||||
#endif
|
||||
mspProcess();
|
||||
mspProcess();
|
||||
}
|
||||
|
||||
void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
|
||||
|
@ -693,12 +270,14 @@ void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
|
|||
};
|
||||
}
|
||||
|
||||
// evaluate all other incoming serial data
|
||||
void evaluateOtherData(uint8_t sr)
|
||||
void cliEnter(serialPort_t *serialPort);
|
||||
|
||||
void evaluateOtherData(serialPort_t *serialPort, uint8_t receivedChar)
|
||||
{
|
||||
if (sr == '#')
|
||||
cliProcess();
|
||||
else if (sr == serialConfig->reboot_character)
|
||||
if (receivedChar == '#') {
|
||||
cliEnter(serialPort);
|
||||
} else if (receivedChar == serialConfig->reboot_character) {
|
||||
systemResetToBootloader();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -21,61 +21,15 @@ typedef enum {
|
|||
FUNCTION_NONE = 0,
|
||||
FUNCTION_MSP = (1 << 0),
|
||||
FUNCTION_CLI = (1 << 1),
|
||||
FUNCTION_TELEMETRY = (1 << 2),
|
||||
FUNCTION_SMARTPORT_TELEMETRY = (1 << 3),
|
||||
FUNCTION_SERIAL_RX = (1 << 4),
|
||||
FUNCTION_GPS = (1 << 5),
|
||||
FUNCTION_GPS_PASSTHROUGH = (1 << 6),
|
||||
FUNCTION_BLACKBOX = (1 << 7)
|
||||
FUNCTION_FRSKY_TELEMETRY = (1 << 2),
|
||||
FUNCTION_HOTT_TELEMETRY = (1 << 3),
|
||||
FUNCTION_MSP_TELEMETRY = (1 << 4),
|
||||
FUNCTION_SMARTPORT_TELEMETRY = (1 << 5),
|
||||
FUNCTION_SERIAL_RX = (1 << 6),
|
||||
FUNCTION_GPS = (1 << 7),
|
||||
FUNCTION_BLACKBOX = (1 << 8)
|
||||
} 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,
|
||||
|
||||
SCENARIO_CLI_ONLY = FUNCTION_CLI,
|
||||
SCENARIO_GPS_ONLY = FUNCTION_GPS,
|
||||
SCENARIO_GPS_PASSTHROUGH_ONLY = FUNCTION_GPS_PASSTHROUGH,
|
||||
SCENARIO_MSP_ONLY = FUNCTION_MSP,
|
||||
SCENARIO_MSP_CLI_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_GPS_PASSTHROUGH,
|
||||
SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH = FUNCTION_MSP | FUNCTION_CLI | FUNCTION_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY | FUNCTION_GPS_PASSTHROUGH,
|
||||
SCENARIO_SERIAL_RX_ONLY = FUNCTION_SERIAL_RX,
|
||||
SCENARIO_TELEMETRY_ONLY = FUNCTION_TELEMETRY,
|
||||
SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY,
|
||||
SCENARIO_BLACKBOX_ONLY = FUNCTION_BLACKBOX,
|
||||
SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_BLACKBOX | FUNCTION_GPS_PASSTHROUGH
|
||||
} serialPortFunctionScenario_e;
|
||||
|
||||
#define SERIAL_PORT_SCENARIO_COUNT 12
|
||||
#define SERIAL_PORT_SCENARIO_MAX (SERIAL_PORT_SCENARIO_COUNT - 1)
|
||||
extern const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT];
|
||||
|
||||
typedef enum {
|
||||
SERIAL_PORT_1 = 0,
|
||||
SERIAL_PORT_2,
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
SERIAL_PORT_3,
|
||||
#if (SERIAL_PORT_COUNT > 3)
|
||||
SERIAL_PORT_4,
|
||||
#if (SERIAL_PORT_COUNT > 4)
|
||||
SERIAL_PORT_5
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
} serialPortIndex_e;
|
||||
|
||||
// serial port identifiers are now fixed, these values are used by MSP commands.
|
||||
typedef enum {
|
||||
SERIAL_PORT_USART1 = 0,
|
||||
|
@ -88,64 +42,62 @@ typedef enum {
|
|||
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
|
||||
} serialPortIdentifier_e;
|
||||
|
||||
serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
|
||||
|
||||
// bitmask
|
||||
typedef enum {
|
||||
SPF_NONE = 0,
|
||||
SPF_SUPPORTS_CALLBACK = (1 << 0),
|
||||
SPF_SUPPORTS_SBUS_MODE = (1 << 1),
|
||||
SPF_SUPPORTS_BIDIR_MODE = (1 << 2),
|
||||
SPF_IS_SOFTWARE_INVERTABLE = (1 << 3)
|
||||
} serialPortFeature_t;
|
||||
|
||||
typedef struct serialPortConstraint_s {
|
||||
const serialPortIdentifier_e identifier;
|
||||
uint32_t minBaudRate;
|
||||
uint32_t maxBaudRate;
|
||||
serialPortFeature_t feature;
|
||||
} serialPortConstraint_t;
|
||||
extern const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT];
|
||||
|
||||
typedef struct serialPortFunction_s {
|
||||
//
|
||||
// runtime
|
||||
//
|
||||
typedef struct serialPortUsage_s {
|
||||
serialPortIdentifier_e identifier;
|
||||
serialPort_t *port; // a NULL values indicates the port has not been opened yet.
|
||||
serialPortFunctionScenario_e scenario;
|
||||
serialPortFunction_e currentFunction;
|
||||
} serialPortFunction_t;
|
||||
serialPort_t *serialPort;
|
||||
serialPortFunction_e function;
|
||||
} serialPortUsage_t;
|
||||
|
||||
typedef struct serialPortFunctionList_s {
|
||||
uint8_t serialPortCount;
|
||||
serialPortFunction_t *functions;
|
||||
} serialPortFunctionList_t;
|
||||
serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);
|
||||
serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);
|
||||
|
||||
//
|
||||
// configuration
|
||||
//
|
||||
|
||||
typedef struct serialPortConfig_s {
|
||||
serialPortIdentifier_e identifier;
|
||||
serialPortFunction_e functionMask;
|
||||
uint32_t baudrate; // not used for all functions, e.g. HoTT only works at 19200.
|
||||
} serialPortConfig_t;
|
||||
|
||||
typedef struct serialConfig_s {
|
||||
uint8_t serial_port_scenario[SERIAL_PORT_COUNT];
|
||||
uint32_t msp_baudrate;
|
||||
uint32_t cli_baudrate;
|
||||
uint32_t gps_baudrate;
|
||||
uint32_t gps_passthrough_baudrate;
|
||||
|
||||
uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else.
|
||||
serialPortConfig_t portConfigs[SERIAL_PORT_COUNT];
|
||||
} serialConfig_t;
|
||||
|
||||
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);
|
||||
//
|
||||
// configuration
|
||||
//
|
||||
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
|
||||
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
|
||||
|
||||
bool canOpenSerialPort(serialPortFunction_e function);
|
||||
void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function);
|
||||
void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function);
|
||||
|
||||
//
|
||||
// runtime
|
||||
//
|
||||
serialPort_t *openSerialPort(
|
||||
serialPortIdentifier_e identifier,
|
||||
serialPortFunction_e function,
|
||||
serialReceiveCallbackPtr callback,
|
||||
uint32_t baudrate,
|
||||
portMode_t mode,
|
||||
serialInversion_e inversion
|
||||
);
|
||||
void closeSerialPort(serialPort_t *serialPort);
|
||||
|
||||
void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
|
||||
|
||||
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig);
|
||||
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
|
||||
bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask);
|
||||
serialPort_t *findSharedSerialPort(serialPortFunction_e functionToUse, uint16_t functionMask);
|
||||
|
||||
const serialPortFunctionList_t *getSerialPortFunctionList(void);
|
||||
|
||||
void evaluateOtherData(uint8_t sr);
|
||||
//
|
||||
// msp/cli/bootloader
|
||||
//
|
||||
void evaluateOtherData(serialPort_t *serialPort, uint8_t receivedChar);
|
||||
void handleSerial(void);
|
||||
|
|
|
@ -83,6 +83,8 @@
|
|||
|
||||
extern uint16_t cycleTime; // FIXME dependency on mw.c
|
||||
|
||||
void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
|
||||
|
||||
static serialPort_t *cliPort;
|
||||
|
||||
static void cliAux(char *cmdline);
|
||||
|
@ -252,32 +254,33 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, -1, 1 },
|
||||
|
||||
{ "serial_port_1_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[0], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_2_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[1], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
{ "serial_port_3_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[2], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#if (SERIAL_PORT_COUNT > 3)
|
||||
{ "serial_port_4_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[3], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#if (SERIAL_PORT_COUNT > 4)
|
||||
{ "serial_port_5_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[4], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_1_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_1_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].baudrate, 1200, 115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 2)
|
||||
{ "serial_port_2_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_2_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].baudrate, 1200, 115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 3)
|
||||
{ "serial_port_3_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].functionMask, 0, 0xFFFF},
|
||||
{ "serial_port_3_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].baudrate, 1200, 115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 4)
|
||||
{ "serial_port_4_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_4_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].baudrate, 1200, 115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 5)
|
||||
{ "serial_port_5_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_5_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].baudrate, 1200, 115200 },
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
{ "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
||||
{ "msp_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.msp_baudrate, 1200, 115200 },
|
||||
{ "cli_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.cli_baudrate, 1200, 115200 },
|
||||
|
||||
#ifdef GPS
|
||||
{ "gps_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.gps_baudrate, 0, 115200 },
|
||||
{ "gps_passthrough_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.gps_passthrough_baudrate, 1200, 115200 },
|
||||
|
||||
{ "gps_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
|
||||
{ "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
|
||||
{ "gps_auto_config", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoConfig, GPS_AUTOCONFIG_OFF, GPS_AUTOCONFIG_ON },
|
||||
{ "gps_auto_baud", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoBaud, GPS_AUTOBAUD_OFF, GPS_AUTOBAUD_ON },
|
||||
|
||||
|
||||
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], 0, 200 },
|
||||
|
@ -297,7 +300,6 @@ const clivalue_t valueTable[] = {
|
|||
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
||||
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX},
|
||||
|
||||
{ "telemetry_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
||||
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
|
||||
{ "telemetry_inversion", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_inversion, 0, 1 },
|
||||
{ "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, -90.0, 90.0 },
|
||||
|
@ -891,10 +893,10 @@ static void cliDump(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void cliEnter(void)
|
||||
void cliEnter(serialPort_t *serialPort)
|
||||
{
|
||||
cliMode = 1;
|
||||
beginSerialPortFunction(cliPort, FUNCTION_CLI);
|
||||
cliPort = serialPort;
|
||||
setPrintfSerialPort(cliPort);
|
||||
cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
|
||||
cliPrompt();
|
||||
|
@ -903,6 +905,7 @@ static void cliEnter(void)
|
|||
static void cliExit(char *cmdline)
|
||||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
|
||||
*cliBuffer = '\0';
|
||||
bufferIndex = 0;
|
||||
|
@ -910,6 +913,8 @@ static void cliExit(char *cmdline)
|
|||
// incase a motor was left running during motortest, clear it here
|
||||
mixerResetMotors();
|
||||
cliReboot();
|
||||
|
||||
cliPort = NULL;
|
||||
}
|
||||
|
||||
static void cliFeature(char *cmdline)
|
||||
|
@ -988,16 +993,7 @@ static void cliGpsPassthrough(char *cmdline)
|
|||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
gpsEnablePassthroughResult_e result = gpsEnablePassthrough();
|
||||
|
||||
switch (result) {
|
||||
case GPS_PASSTHROUGH_NO_SERIAL_PORT:
|
||||
cliPrint("Error: Enable and plug in GPS first\r\n");
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
gpsEnablePassthrough(cliPort);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -1402,10 +1398,10 @@ static void cliVersion(char *cmdline)
|
|||
);
|
||||
}
|
||||
|
||||
void cliProcess(void)
|
||||
void cliProcess()
|
||||
{
|
||||
if (!cliMode) {
|
||||
cliEnter();
|
||||
if (!cliPort) {
|
||||
return;
|
||||
}
|
||||
|
||||
while (serialTotalBytesWaiting(cliPort)) {
|
||||
|
@ -1496,9 +1492,5 @@ void cliProcess(void)
|
|||
|
||||
void cliInit(serialConfig_t *serialConfig)
|
||||
{
|
||||
cliPort = findOpenSerialPort(FUNCTION_CLI);
|
||||
if (!cliPort) {
|
||||
cliPort = openSerialPort(FUNCTION_CLI, NULL, serialConfig->cli_baudrate, MODE_RXTX, SERIAL_NOT_INVERTED);
|
||||
}
|
||||
|
||||
UNUSED(serialConfig);
|
||||
}
|
||||
|
|
|
@ -21,5 +21,6 @@
|
|||
extern uint8_t cliMode;
|
||||
|
||||
void cliProcess(void);
|
||||
bool cliIsActiveOnPort(serialPort_t *serialPort);
|
||||
|
||||
#endif /* CLI_H_ */
|
||||
|
|
|
@ -130,7 +130,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
|||
#define MSP_PROTOCOL_VERSION 0
|
||||
|
||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||
#define API_VERSION_MINOR 5 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
#define API_VERSION_MINOR 6 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
|
||||
#define API_VERSION_LENGTH 2
|
||||
|
||||
|
@ -357,6 +357,7 @@ typedef enum {
|
|||
HEADER_ARROW,
|
||||
HEADER_SIZE,
|
||||
HEADER_CMD,
|
||||
COMMAND_RECEIVED
|
||||
} mspState_e;
|
||||
|
||||
typedef enum {
|
||||
|
@ -539,48 +540,30 @@ static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, ms
|
|||
mspPortToReset->mspPortUsage = usage;
|
||||
}
|
||||
|
||||
// This rate is chosen since softserial supports it.
|
||||
#define MSP_FALLBACK_BAUDRATE 19200
|
||||
|
||||
void mspAllocateSerialPorts(serialConfig_t *serialConfig)
|
||||
{
|
||||
serialPort_t *port;
|
||||
UNUSED(serialConfig);
|
||||
|
||||
uint8_t portIndex;
|
||||
serialPort_t *serialPort;
|
||||
|
||||
for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
||||
uint8_t portIndex = 0;
|
||||
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
|
||||
|
||||
while (portConfig && portIndex < MAX_MSP_PORT_COUNT) {
|
||||
mspPort_t *mspPort = &mspPorts[portIndex];
|
||||
if (mspPort->mspPortUsage != UNUSED_PORT) {
|
||||
continue;
|
||||
}
|
||||
|
||||
uint32_t baudRate = serialConfig->msp_baudrate;
|
||||
|
||||
bool triedFallbackRate = false;
|
||||
do {
|
||||
|
||||
port = openSerialPort(FUNCTION_MSP, NULL, baudRate, MODE_RXTX, SERIAL_NOT_INVERTED);
|
||||
if (!port) {
|
||||
if (triedFallbackRate) {
|
||||
break;
|
||||
}
|
||||
|
||||
baudRate = MSP_FALLBACK_BAUDRATE;
|
||||
triedFallbackRate = true;
|
||||
}
|
||||
} while (!port);
|
||||
|
||||
if (port && portIndex < MAX_MSP_PORT_COUNT) {
|
||||
resetMspPort(mspPort, port, FOR_GENERAL_MSP);
|
||||
}
|
||||
if (!port) {
|
||||
break;
|
||||
serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, portConfig->baudrate, MODE_RXTX, SERIAL_NOT_INVERTED);
|
||||
if (serialPort) {
|
||||
resetMspPort(mspPort, serialPort, FOR_GENERAL_MSP);
|
||||
portIndex++;
|
||||
}
|
||||
|
||||
portConfig = findNextSerialPortConfig(FUNCTION_MSP);
|
||||
}
|
||||
|
||||
// XXX this function might help with adding support for MSP on more than one port, if not delete it.
|
||||
const serialPortFunctionList_t *serialPortFunctionList = getSerialPortFunctionList();
|
||||
UNUSED(serialPortFunctionList);
|
||||
}
|
||||
|
||||
void mspReleasePortIfAllocated(serialPort_t *serialPort)
|
||||
|
@ -589,7 +572,7 @@ void mspReleasePortIfAllocated(serialPort_t *serialPort)
|
|||
for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
||||
mspPort_t *candidateMspPort = &mspPorts[portIndex];
|
||||
if (candidateMspPort->port == serialPort) {
|
||||
endSerialPortFunction(serialPort, FUNCTION_MSP);
|
||||
closeSerialPort(serialPort);
|
||||
memset(candidateMspPort, 0, sizeof(mspPort_t));
|
||||
}
|
||||
}
|
||||
|
@ -1120,17 +1103,13 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
|
||||
case MSP_CF_SERIAL_CONFIG:
|
||||
headSerialReply(
|
||||
((sizeof(uint8_t) * 2) * SERIAL_PORT_COUNT) +
|
||||
(sizeof(uint32_t) * 4)
|
||||
((sizeof(uint8_t) + sizeof(uint16_t) + sizeof(uint32_t)) * SERIAL_PORT_COUNT)
|
||||
);
|
||||
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
serialize8(serialPortConstraints[i].identifier);
|
||||
serialize8(masterConfig.serialConfig.serial_port_scenario[i]);
|
||||
serialize8(masterConfig.serialConfig.portConfigs[i].identifier);
|
||||
serialize16(masterConfig.serialConfig.portConfigs[i].functionMask);
|
||||
serialize32(masterConfig.serialConfig.portConfigs[i].baudrate);
|
||||
}
|
||||
serialize32(masterConfig.serialConfig.msp_baudrate);
|
||||
serialize32(masterConfig.serialConfig.cli_baudrate);
|
||||
serialize32(masterConfig.serialConfig.gps_baudrate);
|
||||
serialize32(masterConfig.serialConfig.gps_passthrough_baudrate);
|
||||
break;
|
||||
|
||||
#ifdef LED_STRIP
|
||||
|
@ -1476,19 +1455,17 @@ static bool processInCommand(void)
|
|||
|
||||
case MSP_SET_CF_SERIAL_CONFIG:
|
||||
{
|
||||
uint8_t baudRateSize = (sizeof(uint32_t) * 4);
|
||||
uint8_t serialPortCount = currentPort->dataSize - baudRateSize;
|
||||
if (serialPortCount != SERIAL_PORT_COUNT) {
|
||||
uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + sizeof(uint32_t);
|
||||
|
||||
if ((SERIAL_PORT_COUNT * portConfigSize) != SERIAL_PORT_COUNT) {
|
||||
headSerialError(0);
|
||||
break;
|
||||
}
|
||||
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
masterConfig.serialConfig.serial_port_scenario[i] = read8();
|
||||
masterConfig.serialConfig.portConfigs[i].identifier = read8();
|
||||
masterConfig.serialConfig.portConfigs[i].functionMask = read16();
|
||||
masterConfig.serialConfig.portConfigs[i].baudrate = read32();
|
||||
}
|
||||
masterConfig.serialConfig.msp_baudrate = read32();
|
||||
masterConfig.serialConfig.cli_baudrate = read32();
|
||||
masterConfig.serialConfig.gps_baudrate = read32();
|
||||
masterConfig.serialConfig.gps_passthrough_baudrate = read32();
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -1543,51 +1520,53 @@ static bool processInCommand(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
static void mspProcessPort(void)
|
||||
static void mspProcessReceivedCommand() {
|
||||
if (!(processOutCommand(currentPort->cmdMSP) || processInCommand())) {
|
||||
headSerialError(0);
|
||||
}
|
||||
tailSerialReply();
|
||||
currentPort->c_state = IDLE;
|
||||
}
|
||||
|
||||
static bool mspProcessReceivedData(uint8_t c)
|
||||
{
|
||||
uint8_t c;
|
||||
if (currentPort->c_state == IDLE) {
|
||||
if (c == '$') {
|
||||
currentPort->c_state = HEADER_START;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
} else if (currentPort->c_state == HEADER_START) {
|
||||
currentPort->c_state = (c == 'M') ? HEADER_M : IDLE;
|
||||
} else if (currentPort->c_state == HEADER_M) {
|
||||
currentPort->c_state = (c == '<') ? HEADER_ARROW : IDLE;
|
||||
} else if (currentPort->c_state == HEADER_ARROW) {
|
||||
if (c > INBUF_SIZE) {
|
||||
currentPort->c_state = IDLE;
|
||||
|
||||
while (serialTotalBytesWaiting(mspSerialPort)) {
|
||||
c = serialRead(mspSerialPort);
|
||||
|
||||
if (currentPort->c_state == IDLE) {
|
||||
currentPort->c_state = (c == '$') ? HEADER_START : IDLE;
|
||||
if (currentPort->c_state == IDLE && !ARMING_FLAG(ARMED))
|
||||
evaluateOtherData(c); // if not armed evaluate all other incoming serial data
|
||||
} else if (currentPort->c_state == HEADER_START) {
|
||||
currentPort->c_state = (c == 'M') ? HEADER_M : IDLE;
|
||||
} else if (currentPort->c_state == HEADER_M) {
|
||||
currentPort->c_state = (c == '<') ? HEADER_ARROW : IDLE;
|
||||
} else if (currentPort->c_state == HEADER_ARROW) {
|
||||
if (c > INBUF_SIZE) { // now we are expecting the payload size
|
||||
currentPort->c_state = IDLE;
|
||||
continue;
|
||||
}
|
||||
} else {
|
||||
currentPort->dataSize = c;
|
||||
currentPort->offset = 0;
|
||||
currentPort->checksum = 0;
|
||||
currentPort->indRX = 0;
|
||||
currentPort->checksum ^= c;
|
||||
currentPort->c_state = HEADER_SIZE; // the command is to follow
|
||||
} else if (currentPort->c_state == HEADER_SIZE) {
|
||||
currentPort->cmdMSP = c;
|
||||
currentPort->checksum ^= c;
|
||||
currentPort->c_state = HEADER_CMD;
|
||||
} else if (currentPort->c_state == HEADER_CMD && currentPort->offset < currentPort->dataSize) {
|
||||
currentPort->checksum ^= c;
|
||||
currentPort->inBuf[currentPort->offset++] = c;
|
||||
} else if (currentPort->c_state == HEADER_CMD && currentPort->offset >= currentPort->dataSize) {
|
||||
if (currentPort->checksum == c) { // compare calculated and transferred checksum
|
||||
// we got a valid packet, evaluate it
|
||||
if (!(processOutCommand(currentPort->cmdMSP) || processInCommand())) {
|
||||
headSerialError(0);
|
||||
}
|
||||
tailSerialReply();
|
||||
}
|
||||
currentPort->c_state = HEADER_SIZE;
|
||||
}
|
||||
} else if (currentPort->c_state == HEADER_SIZE) {
|
||||
currentPort->cmdMSP = c;
|
||||
currentPort->checksum ^= c;
|
||||
currentPort->c_state = HEADER_CMD;
|
||||
} else if (currentPort->c_state == HEADER_CMD && currentPort->offset < currentPort->dataSize) {
|
||||
currentPort->checksum ^= c;
|
||||
currentPort->inBuf[currentPort->offset++] = c;
|
||||
} else if (currentPort->c_state == HEADER_CMD && currentPort->offset >= currentPort->dataSize) {
|
||||
if (currentPort->checksum == c) {
|
||||
currentPort->c_state = COMMAND_RECEIVED;
|
||||
} else {
|
||||
currentPort->c_state = IDLE;
|
||||
break; // process one command so as not to block.
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void setCurrentPort(mspPort_t *port)
|
||||
|
@ -1608,7 +1587,21 @@ void mspProcess(void)
|
|||
}
|
||||
|
||||
setCurrentPort(candidatePort);
|
||||
mspProcessPort();
|
||||
|
||||
while (serialTotalBytesWaiting(mspSerialPort)) {
|
||||
|
||||
uint8_t c = serialRead(mspSerialPort);
|
||||
bool consumed = mspProcessReceivedData(c);
|
||||
|
||||
if (!consumed && !ARMING_FLAG(ARMED)) {
|
||||
evaluateOtherData(mspSerialPort, c);
|
||||
}
|
||||
|
||||
if (currentPort->c_state == COMMAND_RECEIVED) {
|
||||
mspProcessReceivedCommand();
|
||||
break; // process one command at a time so as not to block.
|
||||
}
|
||||
}
|
||||
|
||||
if (isRebootScheduled) {
|
||||
// pause a little while to allow response to be sent
|
||||
|
|
|
@ -101,6 +101,8 @@ void printfSupportInit(void);
|
|||
void timerInit(void);
|
||||
void telemetryInit(void);
|
||||
void serialInit(serialConfig_t *initialSerialConfig);
|
||||
void mspInit(serialConfig_t *serialConfig);
|
||||
void cliInit(serialConfig_t *serialConfig);
|
||||
failsafe_t* failsafeInit(rxConfig_t *intialRxConfig);
|
||||
pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init);
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMixers);
|
||||
|
@ -289,13 +291,16 @@ void init(void)
|
|||
|
||||
serialInit(&masterConfig.serialConfig);
|
||||
|
||||
mspInit(&masterConfig.serialConfig);
|
||||
cliInit(&masterConfig.serialConfig);
|
||||
|
||||
memset(&pwm_params, 0, sizeof(pwm_params));
|
||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||
if (masterConfig.mixerMode == MIXER_AIRPLANE || masterConfig.mixerMode == MIXER_FLYING_WING)
|
||||
pwm_params.airplane = true;
|
||||
else
|
||||
pwm_params.airplane = false;
|
||||
#if defined(SERIAL_PORT_USART2) && defined(STM32F10X)
|
||||
#if defined(USE_USART2) && defined(STM32F10X)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
#endif
|
||||
pwm_params.useVbat = feature(FEATURE_VBAT);
|
||||
|
|
|
@ -310,9 +310,7 @@ void mwDisarm(void)
|
|||
if (feature(FEATURE_TELEMETRY)) {
|
||||
// the telemetry state must be checked immediately so that shared serial ports are released.
|
||||
checkTelemetryState();
|
||||
if (isSerialPortFunctionShared(FUNCTION_TELEMETRY, FUNCTION_MSP)) {
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
}
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -324,6 +322,8 @@ void mwDisarm(void)
|
|||
}
|
||||
}
|
||||
|
||||
#define TELEMETRY_FUNCTION_MASK (FUNCTION_FRSKY_TELEMETRY | FUNCTION_HOTT_TELEMETRY | FUNCTION_MSP_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY)
|
||||
|
||||
void mwArm(void)
|
||||
{
|
||||
if (ARMING_FLAG(OK_TO_ARM)) {
|
||||
|
@ -336,9 +336,12 @@ void mwArm(void)
|
|||
|
||||
#ifdef TELEMETRY
|
||||
if (feature(FEATURE_TELEMETRY)) {
|
||||
serialPort_t *sharedTelemetryAndMspPort = findSharedSerialPort(FUNCTION_TELEMETRY, FUNCTION_MSP);
|
||||
if (sharedTelemetryAndMspPort) {
|
||||
mspReleasePortIfAllocated(sharedTelemetryAndMspPort);
|
||||
|
||||
|
||||
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||
while (sharedPort) {
|
||||
mspReleasePortIfAllocated(sharedPort);
|
||||
sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -86,31 +86,6 @@ void useRxConfig(rxConfig_t *rxConfigToUse)
|
|||
rxConfig = rxConfigToUse;
|
||||
}
|
||||
|
||||
#ifdef SERIAL_RX
|
||||
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;
|
||||
case SERIALRX_SUMH:
|
||||
sumhUpdateSerialRxFunctionConstraint(functionConstraintToUpdate);
|
||||
break;
|
||||
case SERIALRX_XBUS_MODE_B:
|
||||
case SERIALRX_XBUS_MODE_B_RJ01:
|
||||
xBusUpdateSerialRxFunctionConstraint(functionConstraintToUpdate);
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#define STICK_CHANNEL_COUNT 4
|
||||
|
||||
void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
|
||||
|
|
|
@ -52,28 +52,26 @@ static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
|||
|
||||
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
|
||||
|
||||
static serialPort_t *sBusPort;
|
||||
static uint32_t sbusSignalLostEventCount = 0;
|
||||
static serialPort_t *sBusPort = NULL;
|
||||
|
||||
void sbusUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
|
||||
{
|
||||
functionConstraint->minBaudRate = SBUS_BAUDRATE;
|
||||
functionConstraint->maxBaudRate = SBUS_BAUDRATE;
|
||||
functionConstraint->requiredSerialPortFeatures = SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE;
|
||||
}
|
||||
static uint32_t sbusSignalLostEventCount = 0;
|
||||
|
||||
bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
int b;
|
||||
|
||||
sBusPort = openSerialPort(FUNCTION_SERIAL_RX, sbusDataReceive, SBUS_BAUDRATE, (portMode_t)(MODE_RX | MODE_SBUS), SERIAL_INVERTED);
|
||||
|
||||
for (b = 0; b < SBUS_MAX_CHANNEL; b++)
|
||||
sbusChannelData[b] = (1.6f * rxConfig->midrc) - 1408;
|
||||
if (callback)
|
||||
*callback = sbusReadRawRC;
|
||||
rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
|
||||
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX);
|
||||
if (!portConfig) {
|
||||
return false;
|
||||
}
|
||||
|
||||
sBusPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, sbusDataReceive, SBUS_BAUDRATE, (portMode_t)(MODE_RX | MODE_SBUS), SERIAL_INVERTED);
|
||||
|
||||
return sBusPort != NULL;
|
||||
}
|
||||
|
||||
|
|
|
@ -18,4 +18,3 @@
|
|||
#pragma once
|
||||
|
||||
bool sbusFrameComplete(void);
|
||||
void sbusUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -56,14 +56,7 @@ static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
|
|||
static void spektrumDataReceive(uint16_t c);
|
||||
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||
|
||||
static serialPort_t *spektrumPort;
|
||||
|
||||
void spektrumUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
|
||||
{
|
||||
functionConstraint->minBaudRate = SPEKTRUM_BAUDRATE;
|
||||
functionConstraint->maxBaudRate = SPEKTRUM_BAUDRATE;
|
||||
functionConstraint->requiredSerialPortFeatures = SPF_SUPPORTS_CALLBACK;
|
||||
}
|
||||
static serialPort_t *spektrumPort = NULL;
|
||||
|
||||
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
|
@ -84,10 +77,16 @@ bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcRe
|
|||
break;
|
||||
}
|
||||
|
||||
spektrumPort = openSerialPort(FUNCTION_SERIAL_RX, spektrumDataReceive, SPEKTRUM_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
if (callback)
|
||||
*callback = spektrumReadRawRC;
|
||||
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX);
|
||||
if (!portConfig) {
|
||||
return false;
|
||||
}
|
||||
|
||||
spektrumPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, spektrumDataReceive, SPEKTRUM_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
|
||||
return spektrumPort != NULL;
|
||||
}
|
||||
|
||||
|
|
|
@ -21,4 +21,3 @@
|
|||
#define SPEKTRUM_SAT_BIND_MAX 10
|
||||
|
||||
bool spektrumFrameComplete(void);
|
||||
void spektrumUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -44,27 +44,28 @@
|
|||
|
||||
static bool sumdFrameDone = false;
|
||||
static uint32_t sumdChannels[SUMD_MAX_CHANNEL];
|
||||
static serialPort_t *sumdPort;
|
||||
|
||||
static serialPort_t *sumdPort = NULL;
|
||||
|
||||
static void sumdDataReceive(uint16_t c);
|
||||
static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||
|
||||
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)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
sumdPort = openSerialPort(FUNCTION_SERIAL_RX, sumdDataReceive, SUMD_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
|
||||
if (callback)
|
||||
*callback = sumdReadRawRC;
|
||||
|
||||
rxRuntimeConfig->channelCount = SUMD_MAX_CHANNEL;
|
||||
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX);
|
||||
if (!portConfig) {
|
||||
return false;
|
||||
}
|
||||
|
||||
sumdPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, sumdDataReceive, SUMD_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
|
||||
return sumdPort != NULL;
|
||||
}
|
||||
|
||||
|
|
|
@ -18,4 +18,3 @@
|
|||
#pragma once
|
||||
|
||||
bool sumdFrameComplete(void);
|
||||
void sumdUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -47,29 +47,30 @@ static uint32_t sumhChannels[SUMH_MAX_CHANNEL_COUNT];
|
|||
static void sumhDataReceive(uint16_t c);
|
||||
static uint16_t sumhReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||
|
||||
static serialPort_t *sumhPort;
|
||||
static serialPort_t *sumhPort = NULL;
|
||||
|
||||
|
||||
static void sumhDataReceive(uint16_t c);
|
||||
static uint16_t sumhReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||
|
||||
|
||||
void sumhUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
|
||||
{
|
||||
functionConstraint->minBaudRate = SUMH_BAUDRATE;
|
||||
functionConstraint->maxBaudRate = SUMH_BAUDRATE;
|
||||
functionConstraint->requiredSerialPortFeatures = SPF_SUPPORTS_CALLBACK;
|
||||
}
|
||||
|
||||
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
sumhPort = openSerialPort(FUNCTION_SERIAL_RX, sumhDataReceive, SUMH_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
|
||||
if (callback)
|
||||
*callback = sumhReadRawRC;
|
||||
|
||||
rxRuntimeConfig->channelCount = SUMH_MAX_CHANNEL_COUNT;
|
||||
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX);
|
||||
if (!portConfig) {
|
||||
return false;
|
||||
}
|
||||
|
||||
sumhPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, sumhDataReceive, SUMH_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
|
||||
return sumhPort != NULL;
|
||||
}
|
||||
|
||||
|
|
|
@ -18,4 +18,3 @@
|
|||
#pragma once
|
||||
|
||||
bool sumhFrameComplete(void);
|
||||
void sumhUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -86,13 +86,6 @@ static uint16_t xBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
|||
|
||||
static serialPort_t *xBusPort;
|
||||
|
||||
void xBusUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
|
||||
{
|
||||
functionConstraint->minBaudRate = XBUS_BAUDRATE;
|
||||
functionConstraint->maxBaudRate = XBUS_RJ01_BAUDRATE;
|
||||
functionConstraint->requiredSerialPortFeatures = SPF_SUPPORTS_CALLBACK;
|
||||
}
|
||||
|
||||
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
uint32_t baudRate;
|
||||
|
@ -123,11 +116,17 @@ bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
|
|||
break;
|
||||
}
|
||||
|
||||
xBusPort = openSerialPort(FUNCTION_SERIAL_RX, xBusDataReceive, baudRate, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
if (callback) {
|
||||
*callback = xBusReadRawRC;
|
||||
}
|
||||
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX);
|
||||
if (!portConfig) {
|
||||
return false;
|
||||
}
|
||||
|
||||
xBusPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, xBusDataReceive, baudRate, MODE_RX, SERIAL_NOT_INVERTED);
|
||||
|
||||
return xBusPort != NULL;
|
||||
}
|
||||
|
||||
|
|
|
@ -21,4 +21,3 @@
|
|||
|
||||
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
bool xBusFrameComplete(void);
|
||||
void xBusUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||
|
|
|
@ -61,7 +61,7 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/frsky.h"
|
||||
|
||||
static serialPort_t *frskyPort;
|
||||
static serialPort_t *frskyPort = NULL;
|
||||
#define FRSKY_BAUDRATE 9600
|
||||
#define FRSKY_INITIAL_PORT_MODE MODE_TX
|
||||
|
||||
|
@ -404,43 +404,26 @@ void initFrSkyTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
|||
telemetryConfig = initialTelemetryConfig;
|
||||
}
|
||||
|
||||
static portMode_t previousPortMode;
|
||||
static uint32_t previousBaudRate;
|
||||
|
||||
void freeFrSkyTelemetryPort(void)
|
||||
{
|
||||
// FIXME only need to reset the port if the port is shared
|
||||
serialSetMode(frskyPort, previousPortMode);
|
||||
serialSetBaudRate(frskyPort, previousBaudRate);
|
||||
|
||||
endSerialPortFunction(frskyPort, FUNCTION_TELEMETRY);
|
||||
closeSerialPort(frskyPort);
|
||||
frskyPort = NULL;
|
||||
}
|
||||
|
||||
void configureFrSkyTelemetryPort(void)
|
||||
{
|
||||
frskyPort = findOpenSerialPort(FUNCTION_TELEMETRY);
|
||||
if (frskyPort) {
|
||||
previousPortMode = frskyPort->mode;
|
||||
previousBaudRate = frskyPort->baudRate;
|
||||
|
||||
//waitForSerialPortToFinishTransmitting(frskyPort); // FIXME locks up the system
|
||||
|
||||
serialSetBaudRate(frskyPort, FRSKY_BAUDRATE);
|
||||
serialSetMode(frskyPort, FRSKY_INITIAL_PORT_MODE);
|
||||
beginSerialPortFunction(frskyPort, FUNCTION_TELEMETRY);
|
||||
} else {
|
||||
frskyPort = openSerialPort(FUNCTION_TELEMETRY, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig->telemetry_inversion);
|
||||
|
||||
// FIXME only need these values to reset the port if the port is shared
|
||||
previousPortMode = frskyPort->mode;
|
||||
previousBaudRate = frskyPort->baudRate;
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_FRSKY_TELEMETRY);
|
||||
if (!portConfig) {
|
||||
return;
|
||||
}
|
||||
|
||||
frskyPort = openSerialPort(portConfig->identifier, FUNCTION_FRSKY_TELEMETRY, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig->telemetry_inversion);
|
||||
}
|
||||
|
||||
|
||||
bool canSendFrSkyTelemetry(void)
|
||||
{
|
||||
return serialTotalBytesWaiting(frskyPort) == 0;
|
||||
return frskyPort && serialTotalBytesWaiting(frskyPort) == 0;
|
||||
}
|
||||
|
||||
bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis)
|
||||
|
@ -510,7 +493,4 @@ void handleFrSkyTelemetry(void)
|
|||
}
|
||||
}
|
||||
|
||||
uint32_t getFrSkyTelemetryProviderBaudRate(void) {
|
||||
return FRSKY_BAUDRATE;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -103,7 +103,7 @@ static uint8_t hottMsgCrc;
|
|||
#define HOTT_BAUDRATE 19200
|
||||
#define HOTT_INITIAL_PORT_MODE MODE_RX
|
||||
|
||||
static serialPort_t *hottPort;
|
||||
static serialPort_t *hottPort = NULL;
|
||||
|
||||
static telemetryConfig_t *telemetryConfig;
|
||||
|
||||
|
@ -249,16 +249,10 @@ static void hottSerialWrite(uint8_t c)
|
|||
serialWrite(hottPort, c);
|
||||
}
|
||||
|
||||
static portMode_t previousPortMode;
|
||||
static uint32_t previousBaudRate;
|
||||
|
||||
void freeHoTTTelemetryPort(void)
|
||||
{
|
||||
// FIXME only need to do this if the port is shared
|
||||
serialSetMode(hottPort, previousPortMode);
|
||||
serialSetBaudRate(hottPort, previousBaudRate);
|
||||
|
||||
endSerialPortFunction(hottPort, FUNCTION_TELEMETRY);
|
||||
closeSerialPort(hottPort);
|
||||
hottPort = NULL;
|
||||
}
|
||||
|
||||
void initHoTTTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
||||
|
@ -270,33 +264,27 @@ void initHoTTTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
|||
|
||||
void configureHoTTTelemetryPort(void)
|
||||
{
|
||||
hottPort = findOpenSerialPort(FUNCTION_TELEMETRY);
|
||||
if (hottPort) {
|
||||
previousPortMode = hottPort->mode;
|
||||
previousBaudRate = hottPort->baudRate;
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_HOTT_TELEMETRY);
|
||||
if (!portConfig) {
|
||||
return;
|
||||
}
|
||||
|
||||
//waitForSerialPortToFinishTransmitting(hottPort); // FIXME locks up the system
|
||||
hottPort = openSerialPort(portConfig->identifier, FUNCTION_HOTT_TELEMETRY, NULL, HOTT_BAUDRATE, HOTT_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
|
||||
|
||||
serialSetBaudRate(hottPort, HOTT_BAUDRATE);
|
||||
serialSetMode(hottPort, HOTT_INITIAL_PORT_MODE);
|
||||
beginSerialPortFunction(hottPort, FUNCTION_TELEMETRY);
|
||||
} else {
|
||||
hottPort = openSerialPort(FUNCTION_TELEMETRY, NULL, HOTT_BAUDRATE, HOTT_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
|
||||
if (!hottPort) {
|
||||
return;
|
||||
}
|
||||
|
||||
// FIXME only need to do this if the port is shared
|
||||
previousPortMode = hottPort->mode;
|
||||
previousBaudRate = hottPort->baudRate;
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
if (hottPort->identifier == SERIAL_PORT_SOFTSERIAL1) {
|
||||
useSoftserialRxFailureWorkaround = true;
|
||||
}
|
||||
if (hottPort->identifier == SERIAL_PORT_SOFTSERIAL1) {
|
||||
useSoftserialRxFailureWorkaround = true;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL2
|
||||
if (hottPort->identifier == SERIAL_PORT_SOFTSERIAL2) {
|
||||
useSoftserialRxFailureWorkaround = true;
|
||||
}
|
||||
#endif
|
||||
if (hottPort->identifier == SERIAL_PORT_SOFTSERIAL2) {
|
||||
useSoftserialRxFailureWorkaround = true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
static void hottSendResponse(uint8_t *buffer, int length)
|
||||
|
@ -488,7 +476,4 @@ void handleHoTTTelemetry(void)
|
|||
serialTimer = now;
|
||||
}
|
||||
|
||||
uint32_t getHoTTTelemetryProviderBaudRate(void) {
|
||||
return HOTT_BAUDRATE;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -41,10 +41,7 @@ static telemetryConfig_t *telemetryConfig;
|
|||
#define MSP_TELEMETRY_BAUDRATE 19200 // TODO make this configurable
|
||||
#define MSP_TELEMETRY_INITIAL_PORT_MODE MODE_TX
|
||||
|
||||
static serialPort_t *mspTelemetryPort;
|
||||
|
||||
static portMode_t previousPortMode;
|
||||
static uint32_t previousBaudRate;
|
||||
static serialPort_t *mspTelemetryPort = NULL;
|
||||
|
||||
void initMSPTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
||||
{
|
||||
|
@ -53,43 +50,32 @@ void initMSPTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
|||
|
||||
void handleMSPTelemetry(void)
|
||||
{
|
||||
if (!mspTelemetryPort) {
|
||||
return;
|
||||
}
|
||||
|
||||
sendMspTelemetry();
|
||||
}
|
||||
|
||||
void freeMSPTelemetryPort(void)
|
||||
{
|
||||
// FIXME only need to reset the port if the port is shared
|
||||
serialSetMode(mspTelemetryPort, previousPortMode);
|
||||
serialSetBaudRate(mspTelemetryPort, previousBaudRate);
|
||||
|
||||
endSerialPortFunction(mspTelemetryPort, FUNCTION_TELEMETRY);
|
||||
closeSerialPort(mspTelemetryPort);
|
||||
mspTelemetryPort = NULL;
|
||||
}
|
||||
|
||||
void configureMSPTelemetryPort(void)
|
||||
{
|
||||
mspTelemetryPort = findOpenSerialPort(FUNCTION_TELEMETRY);
|
||||
if (mspTelemetryPort) {
|
||||
previousPortMode = mspTelemetryPort->mode;
|
||||
previousBaudRate = mspTelemetryPort->baudRate;
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP_TELEMETRY);
|
||||
if (!portConfig) {
|
||||
return;
|
||||
}
|
||||
|
||||
//waitForSerialPortToFinishTransmitting(mspTelemetryPort); // FIXME locks up the system
|
||||
mspTelemetryPort = openSerialPort(portConfig->identifier, FUNCTION_MSP_TELEMETRY, NULL, MSP_TELEMETRY_BAUDRATE, MSP_TELEMETRY_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
|
||||
|
||||
serialSetBaudRate(mspTelemetryPort, MSP_TELEMETRY_BAUDRATE);
|
||||
serialSetMode(mspTelemetryPort, MSP_TELEMETRY_INITIAL_PORT_MODE);
|
||||
beginSerialPortFunction(mspTelemetryPort, FUNCTION_TELEMETRY);
|
||||
} else {
|
||||
mspTelemetryPort = openSerialPort(FUNCTION_TELEMETRY, NULL, MSP_TELEMETRY_BAUDRATE, MSP_TELEMETRY_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
|
||||
|
||||
// FIXME only need these values to reset the port if the port is shared
|
||||
previousPortMode = mspTelemetryPort->mode;
|
||||
previousBaudRate = mspTelemetryPort->baudRate;
|
||||
if (!mspTelemetryPort) {
|
||||
return;
|
||||
}
|
||||
mspSetTelemetryPort(mspTelemetryPort);
|
||||
}
|
||||
|
||||
uint32_t getMSPTelemetryProviderBaudRate(void)
|
||||
{
|
||||
return MSP_TELEMETRY_BAUDRATE;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -66,7 +66,6 @@ enum
|
|||
SPSTATE_INITIALIZED,
|
||||
SPSTATE_WORKING,
|
||||
SPSTATE_TIMEDOUT,
|
||||
SPSTATE_DEINITIALIZED,
|
||||
};
|
||||
|
||||
enum
|
||||
|
@ -139,10 +138,9 @@ const uint16_t frSkyDataIdTable[] = {
|
|||
#define SMARTPORT_SERVICE_DELAY_MS 5 // telemetry requests comes in at roughly 12 ms intervals, keep this under that
|
||||
#define SMARTPORT_NOT_CONNECTED_TIMEOUT_MS 7000
|
||||
|
||||
static serialPort_t *smartPortSerialPort; // The 'SmartPort'(tm) Port.
|
||||
static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port.
|
||||
static telemetryConfig_t *telemetryConfig;
|
||||
static portMode_t previousPortMode;
|
||||
static uint32_t previousBaudRate;
|
||||
|
||||
extern void serialInit(serialConfig_t *); // from main.c // FIXME remove this dependency
|
||||
|
||||
char smartPortState = SPSTATE_UNINITIALIZED;
|
||||
|
@ -216,68 +214,31 @@ void initSmartPortTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
|||
|
||||
void freeSmartPortTelemetryPort(void)
|
||||
{
|
||||
if (smartPortState == SPSTATE_UNINITIALIZED)
|
||||
return;
|
||||
if (smartPortState == SPSTATE_DEINITIALIZED)
|
||||
return;
|
||||
|
||||
if (isTelemetryPortShared()) {
|
||||
endSerialPortFunction(smartPortSerialPort, FUNCTION_SMARTPORT_TELEMETRY);
|
||||
smartPortState = SPSTATE_DEINITIALIZED;
|
||||
serialInit(&masterConfig.serialConfig);
|
||||
}
|
||||
else {
|
||||
serialSetMode(smartPortSerialPort, previousPortMode);
|
||||
serialSetBaudRate(smartPortSerialPort, previousBaudRate);
|
||||
endSerialPortFunction(smartPortSerialPort, FUNCTION_SMARTPORT_TELEMETRY);
|
||||
smartPortState = SPSTATE_DEINITIALIZED;
|
||||
}
|
||||
closeSerialPort(smartPortSerialPort);
|
||||
smartPortSerialPort = NULL;
|
||||
|
||||
smartPortState = SPSTATE_UNINITIALIZED;
|
||||
}
|
||||
|
||||
void configureSmartPortTelemetryPort(void)
|
||||
{
|
||||
if (smartPortState != SPSTATE_UNINITIALIZED) {
|
||||
// do not allow reinitialization
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SMARTPORT_TELEMETRY);
|
||||
if (!portConfig) {
|
||||
return;
|
||||
}
|
||||
|
||||
smartPortSerialPort = findOpenSerialPort(FUNCTION_SMARTPORT_TELEMETRY);
|
||||
if (smartPortSerialPort) {
|
||||
previousPortMode = smartPortSerialPort->mode;
|
||||
previousBaudRate = smartPortSerialPort->baudRate;
|
||||
smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_SMARTPORT_TELEMETRY, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, telemetryConfig->telemetry_inversion);
|
||||
|
||||
//waitForSerialPortToFinishTransmitting(smartPortPort); // FIXME locks up the system
|
||||
|
||||
serialSetBaudRate(smartPortSerialPort, SMARTPORT_BAUD);
|
||||
serialSetMode(smartPortSerialPort, SMARTPORT_UART_MODE);
|
||||
beginSerialPortFunction(smartPortSerialPort, FUNCTION_SMARTPORT_TELEMETRY);
|
||||
} else {
|
||||
smartPortSerialPort = openSerialPort(FUNCTION_SMARTPORT_TELEMETRY, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, telemetryConfig->telemetry_inversion);
|
||||
|
||||
if (smartPortSerialPort) {
|
||||
smartPortState = SPSTATE_INITIALIZED;
|
||||
previousPortMode = smartPortSerialPort->mode;
|
||||
previousBaudRate = smartPortSerialPort->baudRate;
|
||||
}
|
||||
else {
|
||||
// failed, resume MSP and CLI
|
||||
if (isTelemetryPortShared()) {
|
||||
smartPortState = SPSTATE_DEINITIALIZED;
|
||||
serialInit(&masterConfig.serialConfig);
|
||||
}
|
||||
}
|
||||
if (!smartPortSerialPort) {
|
||||
return;
|
||||
}
|
||||
|
||||
smartPortState = SPSTATE_INITIALIZED;
|
||||
}
|
||||
|
||||
bool canSendSmartPortTelemetry(void)
|
||||
{
|
||||
return smartPortState == SPSTATE_INITIALIZED || smartPortState == SPSTATE_WORKING;
|
||||
}
|
||||
|
||||
bool canSmartPortAllowOtherSerial(void)
|
||||
{
|
||||
return smartPortState == SPSTATE_DEINITIALIZED;
|
||||
return smartPortSerialPort && (smartPortState == SPSTATE_INITIALIZED || smartPortState == SPSTATE_WORKING);
|
||||
}
|
||||
|
||||
bool isSmartPortTimedOut(void)
|
||||
|
@ -285,15 +246,11 @@ bool isSmartPortTimedOut(void)
|
|||
return smartPortState >= SPSTATE_TIMEDOUT;
|
||||
}
|
||||
|
||||
uint32_t getSmartPortTelemetryProviderBaudRate(void)
|
||||
{
|
||||
return SMARTPORT_BAUD;
|
||||
}
|
||||
|
||||
void handleSmartPortTelemetry(void)
|
||||
{
|
||||
if (!canSendSmartPortTelemetry())
|
||||
if (!canSendSmartPortTelemetry()) {
|
||||
return;
|
||||
}
|
||||
|
||||
while (serialTotalBytesWaiting(smartPortSerialPort) > 0) {
|
||||
uint8_t c = serialRead(smartPortSerialPort);
|
||||
|
|
|
@ -42,9 +42,7 @@
|
|||
#include "telemetry/smartport.h"
|
||||
|
||||
|
||||
static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks
|
||||
static bool telemetryEnabled = false;
|
||||
static bool telemetryPortIsShared;
|
||||
|
||||
static telemetryConfig_t *telemetryConfig;
|
||||
|
||||
|
@ -53,72 +51,15 @@ void useTelemetryConfig(telemetryConfig_t *telemetryConfigToUse)
|
|||
telemetryConfig = telemetryConfigToUse;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderFrSky(void)
|
||||
{
|
||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_FRSKY;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderHoTT(void)
|
||||
{
|
||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_HOTT;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderMSP(void)
|
||||
{
|
||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_MSP;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderSmartPort(void)
|
||||
{
|
||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_SMARTPORT;
|
||||
}
|
||||
|
||||
bool isTelemetryPortShared(void)
|
||||
{
|
||||
return telemetryPortIsShared;
|
||||
}
|
||||
|
||||
bool canUseTelemetryWithCurrentConfiguration(void)
|
||||
{
|
||||
if (!feature(FEATURE_TELEMETRY)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (telemetryConfig->telemetry_provider != TELEMETRY_PROVIDER_SMARTPORT && !canOpenSerialPort(FUNCTION_TELEMETRY)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_SMARTPORT && !canOpenSerialPort(FUNCTION_SMARTPORT_TELEMETRY)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void telemetryInit()
|
||||
{
|
||||
if (isTelemetryProviderSmartPort()) {
|
||||
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_SMARTPORT_TELEMETRY, FUNCTION_MSP);
|
||||
} else {
|
||||
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_TELEMETRY, FUNCTION_MSP);
|
||||
}
|
||||
isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration();
|
||||
initFrSkyTelemetry(telemetryConfig);
|
||||
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
initFrSkyTelemetry(telemetryConfig);
|
||||
}
|
||||
initHoTTTelemetry(telemetryConfig);
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
initHoTTTelemetry(telemetryConfig);
|
||||
}
|
||||
initMSPTelemetry(telemetryConfig);
|
||||
|
||||
if (isTelemetryProviderMSP()) {
|
||||
initMSPTelemetry(telemetryConfig);
|
||||
}
|
||||
|
||||
if (isTelemetryProviderSmartPort()) {
|
||||
initSmartPortTelemetry(telemetryConfig);
|
||||
}
|
||||
initSmartPortTelemetry(telemetryConfig);
|
||||
|
||||
checkTelemetryState();
|
||||
}
|
||||
|
@ -127,18 +68,10 @@ bool determineNewTelemetryEnabledState(void)
|
|||
{
|
||||
bool enabled = true;
|
||||
|
||||
if (telemetryPortIsShared) {
|
||||
if (telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_SMARTPORT) {
|
||||
if (isSmartPortTimedOut()) {
|
||||
enabled = false;
|
||||
}
|
||||
} else {
|
||||
if (telemetryConfig->telemetry_switch)
|
||||
enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
|
||||
else
|
||||
enabled = ARMING_FLAG(ARMED);
|
||||
}
|
||||
}
|
||||
if (telemetryConfig->telemetry_switch)
|
||||
enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
|
||||
else
|
||||
enabled = ARMING_FLAG(ARMED);
|
||||
|
||||
return enabled;
|
||||
}
|
||||
|
@ -148,72 +81,24 @@ bool shouldChangeTelemetryStateNow(bool newState)
|
|||
return newState != telemetryEnabled;
|
||||
}
|
||||
|
||||
uint32_t getTelemetryProviderBaudRate(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
return getFrSkyTelemetryProviderBaudRate();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
return getHoTTTelemetryProviderBaudRate();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderMSP()) {
|
||||
return getMSPTelemetryProviderBaudRate();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderSmartPort()) {
|
||||
return getSmartPortTelemetryProviderBaudRate();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void configureTelemetryPort(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
configureFrSkyTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
configureHoTTTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderMSP()) {
|
||||
configureMSPTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderSmartPort()) {
|
||||
configureSmartPortTelemetryPort();
|
||||
}
|
||||
configureFrSkyTelemetryPort();
|
||||
configureHoTTTelemetryPort();
|
||||
configureMSPTelemetryPort();
|
||||
configureSmartPortTelemetryPort();
|
||||
}
|
||||
|
||||
|
||||
void freeTelemetryPort(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
freeFrSkyTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
freeHoTTTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderMSP()) {
|
||||
freeMSPTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderSmartPort()) {
|
||||
freeSmartPortTelemetryPort();
|
||||
}
|
||||
freeFrSkyTelemetryPort();
|
||||
freeHoTTTelemetryPort();
|
||||
freeMSPTelemetryPort();
|
||||
freeSmartPortTelemetryPort();
|
||||
}
|
||||
|
||||
void checkTelemetryState(void)
|
||||
{
|
||||
if (!isTelemetryConfigurationValid) {
|
||||
return;
|
||||
}
|
||||
|
||||
bool newEnabledState = determineNewTelemetryEnabledState();
|
||||
|
||||
if (!shouldChangeTelemetryStateNow(newEnabledState)) {
|
||||
|
@ -230,41 +115,17 @@ void checkTelemetryState(void)
|
|||
|
||||
void handleTelemetry(void)
|
||||
{
|
||||
if (!isTelemetryConfigurationValid || !determineNewTelemetryEnabledState())
|
||||
if (!determineNewTelemetryEnabledState())
|
||||
return;
|
||||
|
||||
if (!telemetryEnabled) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
handleFrSkyTelemetry();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
handleHoTTTelemetry();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderMSP()) {
|
||||
handleMSPTelemetry();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderSmartPort()) {
|
||||
handleSmartPortTelemetry();
|
||||
}
|
||||
}
|
||||
|
||||
bool telemetryAllowsOtherSerial(int serialPortFunction)
|
||||
{
|
||||
if (!feature(FEATURE_TELEMETRY)) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (isTelemetryProviderSmartPort() && isSerialPortFunctionShared(FUNCTION_SMARTPORT_TELEMETRY, (serialPortFunction_e)serialPortFunction)) {
|
||||
return canSmartPortAllowOtherSerial();
|
||||
}
|
||||
|
||||
return true;
|
||||
handleFrSkyTelemetry();
|
||||
handleHoTTTelemetry();
|
||||
handleMSPTelemetry();
|
||||
handleSmartPortTelemetry();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -25,14 +25,6 @@
|
|||
#ifndef TELEMETRY_COMMON_H_
|
||||
#define TELEMETRY_COMMON_H_
|
||||
|
||||
typedef enum {
|
||||
TELEMETRY_PROVIDER_FRSKY = 0,
|
||||
TELEMETRY_PROVIDER_HOTT,
|
||||
TELEMETRY_PROVIDER_MSP,
|
||||
TELEMETRY_PROVIDER_SMARTPORT,
|
||||
TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_SMARTPORT
|
||||
} telemetryProvider_e;
|
||||
|
||||
typedef enum {
|
||||
FRSKY_FORMAT_DMS = 0,
|
||||
FRSKY_FORMAT_NMEA
|
||||
|
@ -42,8 +34,8 @@ typedef enum {
|
|||
FRSKY_UNIT_METRICS = 0,
|
||||
FRSKY_UNIT_IMPERIALS
|
||||
} frskyUnit_e;
|
||||
|
||||
typedef struct telemetryConfig_s {
|
||||
telemetryProvider_e telemetry_provider;
|
||||
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
|
||||
serialInversion_e telemetry_inversion; // also shared with smartport inversion
|
||||
float gpsNoFixLatitude;
|
||||
|
@ -55,7 +47,6 @@ typedef struct telemetryConfig_s {
|
|||
void checkTelemetryState(void);
|
||||
void handleTelemetry(void);
|
||||
|
||||
uint32_t getTelemetryProviderBaudRate(void);
|
||||
void useTelemetryConfig(telemetryConfig_t *telemetryConfig);
|
||||
bool telemetryAllowsOtherSerial(int serialPortFunction);
|
||||
bool isTelemetryPortShared(void);
|
||||
|
|
|
@ -16,8 +16,8 @@
|
|||
*/
|
||||
|
||||
#define FC_VERSION_MAJOR 1 // increment when a major release is made (big new feature, etc)
|
||||
#define FC_VERSION_MINOR 7 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed
|
||||
#define FC_VERSION_MINOR 8 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
|
||||
|
||||
#define STR_HELPER(x) #x
|
||||
#define STR(x) STR_HELPER(x)
|
||||
|
|
Loading…
Reference in New Issue