Skip to content

Commit

Permalink
GCS_MAVLink: allow PREFLIGHT_STORAGE as COMMAND_INT and COMMAND_LONG
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and rmackay9 committed Oct 9, 2023
1 parent d8e18a0 commit 805901d
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4830,14 +4830,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
result = handle_command_set_ekf_source_set(packet);
break;

case MAV_CMD_PREFLIGHT_STORAGE:
if (is_equal(packet.param1, 2.0f)) {
AP_Param::erase_all();
send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board");
result= MAV_RESULT_ACCEPTED;
}
break;

default:
result = try_command_long_as_command_int(packet, msg);
break;
Expand Down Expand Up @@ -5141,6 +5133,14 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
case MAV_CMD_PREFLIGHT_CALIBRATION:
return handle_command_preflight_calibration(packet, msg);

case MAV_CMD_PREFLIGHT_STORAGE:
if (is_equal(packet.param1, 2.0f)) {
AP_Param::erase_all();
send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board");
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_DENIED;

case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
return handle_preflight_reboot(packet, msg);

Expand Down

0 comments on commit 805901d

Please sign in to comment.