mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Tracker: make scheduler track whether it has called the delay callback
This commit is contained in:
parent
dee40f3fe5
commit
a386c6100c
@ -320,7 +320,7 @@ GCS_MAVLINK_Tracker::data_stream_send(void)
|
||||
{
|
||||
send_queued_parameters();
|
||||
|
||||
if (tracker.in_mavlink_delay) {
|
||||
if (hal.scheduler->in_delay_callback()) {
|
||||
// don't send any other stream types while in the delay callback
|
||||
return;
|
||||
}
|
||||
@ -703,7 +703,6 @@ void Tracker::mavlink_delay_cb()
|
||||
return;
|
||||
}
|
||||
|
||||
tracker.in_mavlink_delay = true;
|
||||
DataFlash.EnableWrites(false);
|
||||
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
@ -723,7 +722,6 @@ void Tracker::mavlink_delay_cb()
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
||||
}
|
||||
DataFlash.EnableWrites(true);
|
||||
tracker.in_mavlink_delay = false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -193,9 +193,6 @@ private:
|
||||
uint8_t one_second_counter = 0;
|
||||
bool target_set = false;
|
||||
|
||||
// use this to prevent recursion during sensor init
|
||||
bool in_mavlink_delay = false;
|
||||
|
||||
static const AP_Scheduler::Task scheduler_tasks[];
|
||||
static const AP_Param::Info var_info[];
|
||||
static const struct LogStructure log_structure[];
|
||||
|
Loading…
Reference in New Issue
Block a user