mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 15:25:36 +03:00
small fix + coding style
This commit is contained in:
parent
c19843812c
commit
97c2776644
1 changed files with 8 additions and 16 deletions
|
@ -195,7 +195,7 @@ static uint8_t smartPortMspTxBuffer[SMARTPORT_TX_BUF_SIZE];
|
||||||
static mspPacket_t smartPortMspReply;
|
static mspPacket_t smartPortMspReply;
|
||||||
static bool smartPortMspReplyPending = false;
|
static bool smartPortMspReplyPending = false;
|
||||||
|
|
||||||
#define SMARTPORT_MSP_RES_ERROR -10
|
#define SMARTPORT_MSP_RES_ERROR (-10)
|
||||||
|
|
||||||
enum {
|
enum {
|
||||||
SMARTPORT_MSP_VER_MISMATCH=0,
|
SMARTPORT_MSP_VER_MISMATCH=0,
|
||||||
|
@ -216,8 +216,7 @@ static void smartPortDataReceive(uint16_t c)
|
||||||
smartPortHasRequest = 0;
|
smartPortHasRequest = 0;
|
||||||
skipUntilStart = false;
|
skipUntilStart = false;
|
||||||
return;
|
return;
|
||||||
}
|
} else if (skipUntilStart) {
|
||||||
else if (skipUntilStart) {
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -228,8 +227,7 @@ static void smartPortDataReceive(uint16_t c)
|
||||||
// our slot is starting...
|
// our slot is starting...
|
||||||
smartPortLastRequestTime = now;
|
smartPortLastRequestTime = now;
|
||||||
smartPortHasRequest = 1;
|
smartPortHasRequest = 1;
|
||||||
}
|
} else if (c == FSSP_SENSOR_ID2) {
|
||||||
else if (c == FSSP_SENSOR_ID2) {
|
|
||||||
rxBuffer[smartPortRxBytes++] = c;
|
rxBuffer[smartPortRxBytes++] = c;
|
||||||
checksum = 0;
|
checksum = 0;
|
||||||
}
|
}
|
||||||
|
@ -256,8 +254,7 @@ static void smartPortDataReceive(uint16_t c)
|
||||||
smartPortFrameReceived = true;
|
smartPortFrameReceived = true;
|
||||||
}
|
}
|
||||||
skipUntilStart = true;
|
skipUntilStart = true;
|
||||||
}
|
} else if (smartPortRxBytes < SMARTPORT_FRAME_SIZE) {
|
||||||
else if (smartPortRxBytes < SMARTPORT_FRAME_SIZE) {
|
|
||||||
checksum += c;
|
checksum += c;
|
||||||
checksum += checksum >> 8;
|
checksum += checksum >> 8;
|
||||||
checksum &= 0x00FF;
|
checksum &= 0x00FF;
|
||||||
|
@ -530,12 +527,10 @@ void handleSmartPortMspFrame(smartPortFrame_t* sp_frame)
|
||||||
|
|
||||||
checksum = p_size ^ cmd.cmd;
|
checksum = p_size ^ cmd.cmd;
|
||||||
mspStarted = 1;
|
mspStarted = 1;
|
||||||
}
|
} else if (!mspStarted) {
|
||||||
else if (!mspStarted) {
|
|
||||||
// no start packet yet, throw this one away
|
// no start packet yet, throw this one away
|
||||||
return;
|
return;
|
||||||
}
|
} else if (((lastSeq + 1) & SMARTPORT_MSP_SEQ_MASK) != seq) {
|
||||||
else if (((lastSeq + 1) & SMARTPORT_MSP_SEQ_MASK) != seq) {
|
|
||||||
// packet loss detected!
|
// packet loss detected!
|
||||||
mspStarted = 0;
|
mspStarted = 0;
|
||||||
return;
|
return;
|
||||||
|
@ -772,13 +767,10 @@ void handleSmartPortTelemetry(void)
|
||||||
smartPortSendPackage(id, (STATE(GPS_FIX) ? 1000 : 0) + (STATE(GPS_FIX_HOME) ? 2000 : 0) + GPS_numSat);
|
smartPortSendPackage(id, (STATE(GPS_FIX) ? 1000 : 0) + (STATE(GPS_FIX_HOME) ? 2000 : 0) + GPS_numSat);
|
||||||
smartPortHasRequest = 0;
|
smartPortHasRequest = 0;
|
||||||
#endif
|
#endif
|
||||||
}
|
} else if (feature(FEATURE_GPS)) {
|
||||||
else if (feature(FEATURE_GPS)) {
|
|
||||||
smartPortSendPackage(id, 0);
|
smartPortSendPackage(id, 0);
|
||||||
smartPortHasRequest = 0;
|
smartPortHasRequest = 0;
|
||||||
}
|
} else if (telemetryConfig->pidValuesAsTelemetry){
|
||||||
|
|
||||||
else if (telemetryConfig->pidValuesAsTelemetry){
|
|
||||||
switch (t2Cnt) {
|
switch (t2Cnt) {
|
||||||
case 0:
|
case 0:
|
||||||
tmp2 = currentProfile->pidProfile.P8[ROLL];
|
tmp2 = currentProfile->pidProfile.P8[ROLL];
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue