AP_Periph: solve a potential case where last_transmit_us can change inside irqs
This commit is contained in:
parent
fb26bbfc4c
commit
ec2e92de30
@ -1136,8 +1136,9 @@ void AP_Periph_FW::processTx(void)
|
|||||||
active if it has had a successful transmit in the
|
active if it has had a successful transmit in the
|
||||||
last 2 seconds
|
last 2 seconds
|
||||||
*/
|
*/
|
||||||
const auto *stats = _ins.iface->get_statistics();
|
volatile const auto *stats = _ins.iface->get_statistics();
|
||||||
if (stats == nullptr || now_us - stats->last_transmit_us < 2000000UL) {
|
uint64_t last_transmit_us = stats->last_transmit_us;
|
||||||
|
if (stats == nullptr || AP_HAL::micros64() - last_transmit_us < 2000000UL) {
|
||||||
sent = false;
|
sent = false;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user