mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: Location.cpp: add sanity checks
This commit is contained in:
parent
6031f5b6a9
commit
ab7ee4fefb
@ -102,6 +102,11 @@ Location::AltFrame Location::get_alt_frame() const
|
||||
/// get altitude in desired frame
|
||||
bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
|
||||
{
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (lat == 0 && lng == 0) {
|
||||
AP_HAL::panic("Should not be called on invalid location");
|
||||
}
|
||||
#endif
|
||||
Location::AltFrame frame = get_alt_frame();
|
||||
|
||||
// shortcut if desired and underlying frame are the same
|
||||
|
Loading…
Reference in New Issue
Block a user