mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
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
31 changed files with 459 additions and 1247 deletions
|
@ -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
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue