mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
Merge pull request #2164 from raphaelcoeffic/sport-no-timeout
smartport: removed disabling on timeout
This commit is contained in:
commit
85ce599bdd
2 changed files with 2 additions and 20 deletions
|
@ -64,8 +64,7 @@ enum
|
||||||
{
|
{
|
||||||
SPSTATE_UNINITIALIZED,
|
SPSTATE_UNINITIALIZED,
|
||||||
SPSTATE_INITIALIZED,
|
SPSTATE_INITIALIZED,
|
||||||
SPSTATE_WORKING,
|
SPSTATE_WORKING
|
||||||
SPSTATE_TIMEDOUT
|
|
||||||
};
|
};
|
||||||
|
|
||||||
enum
|
enum
|
||||||
|
@ -145,7 +144,6 @@ const uint16_t frSkyDataIdTable[] = {
|
||||||
#define SMARTPORT_BAUD 57600
|
#define SMARTPORT_BAUD 57600
|
||||||
#define SMARTPORT_UART_MODE MODE_RXTX
|
#define SMARTPORT_UART_MODE MODE_RXTX
|
||||||
#define SMARTPORT_SERVICE_TIMEOUT_MS 1 // max allowed time to find a value to send
|
#define SMARTPORT_SERVICE_TIMEOUT_MS 1 // max allowed time to find a value to send
|
||||||
#define SMARTPORT_NOT_CONNECTED_TIMEOUT_MS 7000
|
|
||||||
|
|
||||||
static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port.
|
static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port.
|
||||||
static serialPortConfig_t *portConfig;
|
static serialPortConfig_t *portConfig;
|
||||||
|
@ -352,15 +350,9 @@ bool canSendSmartPortTelemetry(void)
|
||||||
return smartPortSerialPort && (smartPortState == SPSTATE_INITIALIZED || smartPortState == SPSTATE_WORKING);
|
return smartPortSerialPort && (smartPortState == SPSTATE_INITIALIZED || smartPortState == SPSTATE_WORKING);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isSmartPortTimedOut(void)
|
|
||||||
{
|
|
||||||
return smartPortState >= SPSTATE_TIMEDOUT;
|
|
||||||
}
|
|
||||||
|
|
||||||
void checkSmartPortTelemetryState(void)
|
void checkSmartPortTelemetryState(void)
|
||||||
{
|
{
|
||||||
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(smartPortPortSharing);
|
bool newTelemetryEnabledValue = (smartPortPortSharing == PORTSHARING_NOT_SHARED);
|
||||||
|
|
||||||
if (newTelemetryEnabledValue == smartPortTelemetryEnabled) {
|
if (newTelemetryEnabledValue == smartPortTelemetryEnabled) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -578,14 +570,6 @@ void handleSmartPortTelemetry(void)
|
||||||
smartPortDataReceive(c);
|
smartPortDataReceive(c);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t now = millis();
|
|
||||||
|
|
||||||
// if timed out, reconfigure the UART back to normal so the GUI or CLI works
|
|
||||||
if ((now - smartPortLastRequestTime) > SMARTPORT_NOT_CONNECTED_TIMEOUT_MS) {
|
|
||||||
smartPortState = SPSTATE_TIMEDOUT;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if(smartPortFrameReceived) {
|
if(smartPortFrameReceived) {
|
||||||
smartPortFrameReceived = false;
|
smartPortFrameReceived = false;
|
||||||
// do not check the physical ID here again
|
// do not check the physical ID here again
|
||||||
|
|
|
@ -15,5 +15,3 @@ void checkSmartPortTelemetryState(void);
|
||||||
void configureSmartPortTelemetryPort(void);
|
void configureSmartPortTelemetryPort(void);
|
||||||
void freeSmartPortTelemetryPort(void);
|
void freeSmartPortTelemetryPort(void);
|
||||||
|
|
||||||
bool isSmartPortTimedOut(void);
|
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue