1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 21:05:35 +03:00

Merge pull request #6060 from jirif/npr_6056

Fixed null pointer reference
This commit is contained in:
Michael Keller 2018-06-08 20:45:04 +12:00 committed by GitHub
commit cb3d1d6ad4
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
2 changed files with 8 additions and 11 deletions

View file

@ -347,7 +347,7 @@ static bool fportProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
if (clearToSend) {
DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT_TELEMETRY_DELAY, currentTimeUs - lastTelemetryFrameReceivedUs);
if (consecutiveSensorCount >= FPORT_TELEMETRY_MAX_CONSECUTIVE_SENSORS && !smartPortPayloadContainsMSP(mspPayload)) {
if (consecutiveSensorCount >= FPORT_TELEMETRY_MAX_CONSECUTIVE_SENSORS && !(mspPayload && smartPortPayloadContainsMSP(mspPayload))) {
// Stop one cycle to avoid saturating the buffer in the RX, since the
// downstream bandwidth doesn't allow sensor sensors on every cycle.
// We allow MSP frames to run over the resting period, expecting that

View file

@ -464,18 +464,15 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
static uint8_t smartPortIdOffset = 0;
#endif
if (payload) {
// do not check the physical ID here again
// unless we start receiving other sensors' packets
#if defined(USE_MSP_OVER_TELEMETRY)
if (smartPortPayloadContainsMSP(payload)) {
// Pass only the payload: skip frameId
uint8_t *frameStart = (uint8_t *)&payload->valueId;
smartPortMspReplyPending = handleMspFrame(frameStart, SMARTPORT_MSP_PAYLOAD_SIZE);
}
#endif
if (payload && smartPortPayloadContainsMSP(payload)) {
// Do not check the physical ID here again
// unless we start receiving other sensors' packets
// Pass only the payload: skip frameId
uint8_t *frameStart = (uint8_t *)&payload->valueId;
smartPortMspReplyPending = handleMspFrame(frameStart, SMARTPORT_MSP_PAYLOAD_SIZE);
}
#endif
bool doRun = true;
while (doRun && *clearToSend) {