From de452eb7604d166172a8e883bd60e8a3a634b434 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 28 May 2016 23:03:04 +1000 Subject: [PATCH] Rover: move adjust_rate_for_stream up --- APMrover2/GCS_Mavlink.cpp | 10 ---------- APMrover2/GCS_Mavlink.h | 1 - 2 files changed, 11 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index f9bb5eb741..93db560f4c 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -694,16 +694,6 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { AP_GROUPEND }; -float GCS_MAVLINK_Rover::adjust_rate_for_stream_trigger(enum streams stream_num) -{ - if ((stream_num != STREAM_PARAMS) && - (waypoint_receiving || _queued_parameter != NULL)) { - return 0.25f; - } - - return 1.0f; -} - void GCS_MAVLINK_Rover::data_stream_send(void) { diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index 3ffb8e3800..986bcb7198 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -13,7 +13,6 @@ protected: private: - float adjust_rate_for_stream_trigger(enum streams stream_num) override; void handleMessage(mavlink_message_t * msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;