Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_RCProtocol: CRSF: use subtraction with times, not time+timedelta #26274

Closed
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading