Skip to content

Commit b19f8ed

Browse files
peterbarkertridge
authored andcommitted
AP_RCProtocol: CRSF: use subtraction with times, not time+timedelta
1 parent b071d76 commit b19f8ed

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -58,13 +58,13 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend {
5858
bool is_rx_active() const override {
5959
// later versions of CRSFv3 will send link rate frames every 200ms
6060
// but only before an initial failsafe
61-
return AP_HAL::micros() < _last_rx_frame_time_us + CRSF_RX_TIMEOUT;
61+
return _last_rx_frame_time_us != 0 && AP_HAL::micros() - _last_rx_frame_time_us < CRSF_RX_TIMEOUT;
6262
}
6363

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

7070
// get singleton instance

0 commit comments

Comments
 (0)