From e977d85e0cbf4bdab2287dc66f02f2d00424f97c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 30 May 2016 09:54:36 +1000 Subject: [PATCH] Copter: move telemetry_delayed up into base class --- ArduCopter/Copter.h | 1 - ArduCopter/GCS_Mavlink.cpp | 18 +++--------------- ArduCopter/GCS_Mavlink.h | 2 ++ 3 files changed, 5 insertions(+), 16 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 742386e5ee..8f522f0924 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -649,7 +649,6 @@ private: void send_rpm(mavlink_channel_t chan); void rpm_update(); void send_pid_tuning(mavlink_channel_t chan); - bool telemetry_delayed(mavlink_channel_t chan); void gcs_send_message(enum ap_message id); void gcs_send_mission_item_reached_message(uint16_t mission_index); void gcs_data_stream_send(void); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 37186b3381..5a0f3e466e 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -499,27 +499,15 @@ void Copter::send_pid_tuning(mavlink_channel_t chan) } } -// are we still delaying telemetry to try to avoid Xbee bricking? -bool Copter::telemetry_delayed(mavlink_channel_t chan) +uint32_t GCS_MAVLINK_Copter::telem_delay() const { - uint32_t tnow = millis() >> 10; - if (tnow > (uint32_t)g.telem_delay) { - return false; - } - if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) { - // this is USB telemetry, so won't be an Xbee - return false; - } - // we're either on the 2nd UART, or no USB cable is connected - // we need to delay telemetry by the TELEM_DELAY time - return true; + return (uint32_t)(copter.g.telem_delay); } - // try to send a message, return false if it won't fit in the serial tx buffer bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) { - if (copter.telemetry_delayed(chan)) { + if (telemetry_delayed(chan)) { return false; } diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 275b36300e..bee241f320 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -11,6 +11,8 @@ public: protected: + uint32_t telem_delay() const override; + private: void handleMessage(mavlink_message_t * msg) override;