From bbccdce22926cbecf86310b5ec74c02bc5798a01 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 22 Dec 2016 15:46:26 +1100 Subject: [PATCH] AP_Terrain: prevent use of invalid Location loc is not initialised and can cause a fault on startup --- libraries/AP_Terrain/AP_Terrain.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index def509e77b..aabfc88994 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -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;