Browse Source

Sub: Implement reset all params via MAV_CMD_PREFLIGHT_STORAGE

mission-4.1.18
Jacob Walser 8 years ago
parent
commit
e2a41c0a6c
  1. 7
      ArduSub/GCS_Mavlink.cpp

7
ArduSub/GCS_Mavlink.cpp

@ -1157,6 +1157,13 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg) @@ -1157,6 +1157,13 @@ 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();
sub.gcs_send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board");
result= MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_START_RX_PAIR:
// initiate bind procedure

Loading…
Cancel
Save