SITL: don't use adjusted terrain in SITL

This commit is contained in:
Andrew Tridgell 2022-03-28 08:27:03 +11:00 committed by Randy Mackay
parent 502539671d
commit 78f83d5411
2 changed files with 3 additions and 3 deletions

View File

@ -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;
}

View File

@ -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