mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: get mav heartbeats out when board detection fails
This commit is contained in:
parent
6726d94537
commit
4aaeb4bfed
@ -348,7 +348,11 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
||||
// if we don't have at least 250 micros remaining before the main loop
|
||||
// wants to fire then don't send a mavlink message. We want to
|
||||
// prioritise the main flight control loop over communications
|
||||
if (copter.scheduler.time_available_usec() < 250 && copter.motors->armed()) {
|
||||
|
||||
// the check for nullptr here doesn't just save a nullptr
|
||||
// dereference; it means that we send messages out even if we're
|
||||
// failing to detect a PX4 board type (see delay(3000) in px_drivers).
|
||||
if (copter.motors != nullptr && copter.scheduler.time_available_usec() < 250 && copter.motors->armed()) {
|
||||
copter.gcs_out_of_time = true;
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user