From 8f227201e071312316765c21bd8023e24f465617 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Wed, 14 Feb 2018 13:20:21 -0500 Subject: [PATCH] Sub: move reset params to default handling to GCS base class --- ArduSub/GCS_Mavlink.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index fd885d578e..606c1b95c1 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -1020,14 +1020,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg) mavlink_msg_command_long_decode(msg, &packet); switch (packet.command) { - case MAV_CMD_PREFLIGHT_STORAGE: - if (is_equal(packet.param1, 2.0f)) { - AP_Param::erase_all(); - gcs().send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board"); - result= MAV_RESULT_ACCEPTED; - } - break; - case MAV_CMD_NAV_LOITER_UNLIM: if (sub.set_mode(POSHOLD, MODE_REASON_GCS_COMMAND)) { result = MAV_RESULT_ACCEPTED;