AP_HAL_SITL: calls to terrain:height_amsl provide extrapolate and corrected params

This commit is contained in:
Randy Mackay 2016-04-18 20:42:48 +09:00
parent 1c4b2be16a
commit 3d646a26e2
1 changed files with 1 additions and 1 deletions

View File

@ -487,7 +487,7 @@ float SITL_State::height_agl(void)
location.lat = _sitl->state.latitude*1.0e7;
location.lng = _sitl->state.longitude*1.0e7;
if (_terrain->height_amsl(location, terrain_height_amsl)) {
if (_terrain->height_amsl(location, terrain_height_amsl, false)) {
return _sitl->state.altitude - terrain_height_amsl;
}
}