Browse Source

SITL: don't use adjusted terrain in SITL

apm_2208
Andrew Tridgell 3 years ago
parent
commit
536b59ed42
  1. 4
      libraries/SITL/SIM_Aircraft.cpp
  2. 2
      libraries/SITL/SIM_Ship.cpp

4
libraries/SITL/SIM_Aircraft.cpp

@ -111,8 +111,8 @@ float Aircraft::ground_height_difference() const @@ -111,8 +111,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;
}

2
libraries/SITL/SIM_Ship.cpp

@ -204,7 +204,7 @@ void ShipSim::send_report(void) @@ -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

Loading…
Cancel
Save