diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 87d3b6cdaa..37186b3381 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -842,15 +842,6 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { AP_GROUPEND }; -float GCS_MAVLINK_Copter::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_Copter::data_stream_send(void) { diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index ecd5244221..275b36300e 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/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;