Skip to content

Commit

Permalink
AP_RCProtocol: CRSF: use subtraction with times, not time+timedelta
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and andyp1per committed Feb 21, 2024
1 parent c051bbe commit b464712
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,13 +58,13 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend {
bool is_rx_active() const override {
// later versions of CRSFv3 will send link rate frames every 200ms
// but only before an initial failsafe
return AP_HAL::micros() < _last_rx_frame_time_us + CRSF_RX_TIMEOUT;
return _last_rx_frame_time_us != 0 && AP_HAL::micros() - _last_rx_frame_time_us < CRSF_RX_TIMEOUT;
}

// is the transmitter active, used to adjust telemetry data
bool is_tx_active() const {
// this is the same as the Copter failsafe timeout
return AP_HAL::micros() < _last_tx_frame_time_us + CRSF_TX_TIMEOUT;
return _last_tx_frame_time_us != 0 && AP_HAL::micros() - _last_tx_frame_time_us < CRSF_TX_TIMEOUT;
}

// get singleton instance
Expand Down

0 comments on commit b464712

Please sign in to comment.