AP_Vehicle: make bad-mode-number notification consistent across vehicles

This commit is contained in:
Peter Barker 2021-08-25 12:04:50 +10:00 committed by Randy Mackay
parent 96be74bdc2
commit 7a06c941df
2 changed files with 12 additions and 0 deletions

View File

@ -355,6 +355,12 @@ void AP_Vehicle::update_dynamic_notch_at_specified_rate()
}
}
void AP_Vehicle::notify_no_such_mode(uint8_t mode_number)
{
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"No such mode %u", mode_number);
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode_number));
}
// reboot the vehicle in an orderly manner, doing various cleanups and
// flashing LEDs as appropriate
void AP_Vehicle::reboot(bool hold_in_bootloader)

View File

@ -85,6 +85,12 @@ public:
return control_mode_reason;
}
// perform any notifications required to indicate a mode change
// failed due to a bad mode number being supplied. This can
// happen for many reasons - bad mavlink packet and bad mode
// parameters for example.
void notify_no_such_mode(uint8_t mode_number);
/*
common parameters for fixed wing aircraft
*/