From 78f83d5411cae6d30159c2e3d1fbc2092f52ca36 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 28 Mar 2022 08:27:03 +1100 Subject: [PATCH] SITL: don't use adjusted terrain in SITL --- libraries/SITL/SIM_Aircraft.cpp | 4 ++-- libraries/SITL/SIM_Ship.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index ad1a4d1f36..2f8464448a 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -108,8 +108,8 @@ float Aircraft::ground_height_difference() const if (sitl && terrain != nullptr && sitl->terrain_enable && - terrain->height_amsl(home, h1) && - terrain->height_amsl(location, h2)) { + terrain->height_amsl(home, h1, false) && + terrain->height_amsl(location, h2, false)) { h2 += local_ground_level; return h2 - h1; } diff --git a/libraries/SITL/SIM_Ship.cpp b/libraries/SITL/SIM_Ship.cpp index c5807a31df..7baaff3ec6 100644 --- a/libraries/SITL/SIM_Ship.cpp +++ b/libraries/SITL/SIM_Ship.cpp @@ -204,7 +204,7 @@ void ShipSim::send_report(void) #if AP_TERRAIN_AVAILABLE auto terrain = AP::terrain(); float height; - if (terrain != nullptr && terrain->enabled() && terrain->height_amsl(loc, height)) { + if (terrain != nullptr && terrain->enabled() && terrain->height_amsl(loc, height, false)) { alt_mm = height * 1000; } #endif