From dee40f3fe57a790f6aaf107c238c4cb34a5c5902 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 8 May 2018 16:17:08 +1000 Subject: [PATCH] Copter: make scheduler track whether it has called the delay callback --- ArduCopter/Copter.h | 3 --- ArduCopter/GCS_Mavlink.cpp | 6 ++---- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index a2cb195116..022f9156da 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -572,9 +572,6 @@ private: AP_Avoidance_Copter avoidance_adsb{ahrs, adsb}; #endif - // use this to prevent recursion during sensor init - bool in_mavlink_delay; - // last valid RC input time uint32_t last_radio_update_ms; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 96e753817f..63c07ece48 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -569,7 +569,7 @@ GCS_MAVLINK_Copter::data_stream_send(void) if (gcs().out_of_time()) return; - if (copter.in_mavlink_delay) { + if (hal.scheduler->in_delay_callback()) { // don't send any other stream types while in the delay callback return; } @@ -1713,9 +1713,8 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) void Copter::mavlink_delay_cb() { static uint32_t last_1hz, last_50hz, last_5s; - if (!gcs().chan(0).initialised || in_mavlink_delay) return; + if (!gcs().chan(0).initialised) return; - in_mavlink_delay = true; DataFlash.EnableWrites(false); uint32_t tnow = millis(); @@ -1738,7 +1737,6 @@ void Copter::mavlink_delay_cb() check_usb_mux(); DataFlash.EnableWrites(true); - in_mavlink_delay = false; } /*