mirror of https://github.com/ArduPilot/ardupilot
SITL: don't use adjusted terrain in SITL
This commit is contained in:
parent
502539671d
commit
78f83d5411
|
@ -108,8 +108,8 @@ float Aircraft::ground_height_difference() const
|
||||||
if (sitl &&
|
if (sitl &&
|
||||||
terrain != nullptr &&
|
terrain != nullptr &&
|
||||||
sitl->terrain_enable &&
|
sitl->terrain_enable &&
|
||||||
terrain->height_amsl(home, h1) &&
|
terrain->height_amsl(home, h1, false) &&
|
||||||
terrain->height_amsl(location, h2)) {
|
terrain->height_amsl(location, h2, false)) {
|
||||||
h2 += local_ground_level;
|
h2 += local_ground_level;
|
||||||
return h2 - h1;
|
return h2 - h1;
|
||||||
}
|
}
|
||||||
|
|
|
@ -204,7 +204,7 @@ void ShipSim::send_report(void)
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
auto terrain = AP::terrain();
|
auto terrain = AP::terrain();
|
||||||
float height;
|
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;
|
alt_mm = height * 1000;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue