GCS_MAVLink: added method to lockup autopilot

used for watchdog testing

# Conflicts:
#	libraries/GCS_MAVLink/GCS_Common.cpp
This commit is contained in:
Andrew Tridgell 2019-05-07 12:13:36 +10:00 committed by Randy Mackay
parent 6a052a5042
commit 756a629b24

View File

@ -1784,6 +1784,24 @@ void GCS_MAVLINK::send_vfr_hud()
*/
MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides)
{
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)) {
if (disable_overrides) {
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
@ -1803,7 +1821,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
#endif
}
// force safety on
// force safety on
hal.rcout->force_safety_on();
hal.rcout->force_safety_no_wait();
hal.scheduler->delay(200);