Skip to content

Commit

Permalink
Sub: move reset params to default handling to GCS base class
Browse files Browse the repository at this point in the history
  • Loading branch information
jaxxzer authored and tridge committed Feb 19, 2018
1 parent 582ef7c commit 8f22720
Showing 1 changed file with 0 additions and 8 deletions.
8 changes: 0 additions & 8 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 8f22720

Please sign in to comment.