mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Terrain: prevent use of invalid Location
loc is not initialised and can cause a fault on startup
This commit is contained in:
parent
b845668f23
commit
bbccdce229
@ -316,7 +316,7 @@ void AP_Terrain::update(void)
|
||||
// update the cached current location height
|
||||
Location loc;
|
||||
bool pos_valid = ahrs.get_position(loc);
|
||||
bool terrain_valid = height_amsl(loc, height, false);
|
||||
bool terrain_valid = pos_valid && height_amsl(loc, height, false);
|
||||
if (pos_valid && terrain_valid) {
|
||||
last_current_loc_height = height;
|
||||
have_current_loc_height = true;
|
||||
|
Loading…
Reference in New Issue
Block a user