mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLINK: support deliberate parameter corruption
This commit is contained in:
parent
e6b1ef2d1e
commit
b14232c85e
|
@ -2512,8 +2512,8 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
|
|||
{
|
||||
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)) {
|
||||
is_equal(packet.param3, 71.0f)) {
|
||||
if (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
|
||||
|
@ -2522,6 +2522,35 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
|
|||
hal.scheduler->delay(250);
|
||||
}
|
||||
}
|
||||
if (is_equal(packet.param4, 94.0f)) {
|
||||
// the following text is unlikely to make it out...
|
||||
send_text(MAV_SEVERITY_WARNING,"deferencing a bad thing");
|
||||
|
||||
void *foo = (void*)0xE000ED38;
|
||||
|
||||
typedef void (*fptr)();
|
||||
fptr gptr = (fptr) (void *) foo;
|
||||
gptr();
|
||||
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
if (is_equal(packet.param4, 95.0f)) {
|
||||
// the following text is unlikely to make it out...
|
||||
send_text(MAV_SEVERITY_WARNING,"calling AP_HAL::panic(...)");
|
||||
|
||||
AP_HAL::panic("panicing");
|
||||
|
||||
// keep calm and carry on
|
||||
}
|
||||
if (is_equal(packet.param4, 96.0f)) {
|
||||
// deliberately corrupt parameter storage
|
||||
send_text(MAV_SEVERITY_WARNING,"wiping parameter storage header");
|
||||
StorageAccess param_storage{StorageManager::StorageParam};
|
||||
uint8_t zeros[40] {};
|
||||
param_storage.write_block(0, zeros, sizeof(zeros));
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
}
|
||||
|
||||
if (hal.util->get_soft_armed()) {
|
||||
// refuse reboot when armed
|
||||
|
|
Loading…
Reference in New Issue