mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
GCS_MAVLink: added method to lockup autopilot
used for watchdog testing # Conflicts: # libraries/GCS_MAVLink/GCS_Common.cpp
This commit is contained in:
parent
6a052a5042
commit
756a629b24
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user