GCS_MAVLink: added method to lockup autopilot

used for watchdog testing
This commit is contained in:
Andrew Tridgell 2019-04-20 14:36:29 +10:00
parent f5c45bf184
commit 337cc16880

View File

@ -1809,6 +1809,24 @@ void GCS_MAVLINK::disable_overrides()
*/
MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet)
{
if (is_equal(packet.param1, 42.0f) &&
is_equal(packet.param2, 24.0f) &&
is_equal(packet.param3, 71.0f) &&
is_equal(packet.param4, 93.0f)) {
// this is a magic sequence to force the main loop to
// lockup. This is for testing the stm32 watchdog
// functionality
while (true) {
send_text(MAV_SEVERITY_WARNING,"entering lockup");
hal.scheduler->delay(250);
}
}
if (hal.util->get_soft_armed()) {
// refuse reboot when armed
return MAV_RESULT_FAILED;
}
if (!(is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f))) {
// param1 must be 1 or 3 - 1 being reboot, 3 being reboot-to-bootloader
return MAV_RESULT_UNSUPPORTED;