AP_HAL_SITL: move simulated height_agl into fdm structure

allows value to be shipped via multicast to simulated peripherals
This commit is contained in:
Peter Barker 2024-01-08 13:07:46 +11:00 committed by Andrew Tridgell
parent 147c5ad78d
commit 7201eae4ed
1 changed files with 2 additions and 2 deletions

View File

@ -598,7 +598,7 @@ void SITL_State::set_height_agl(void)
AP_Terrain *_terrain = AP_Terrain::get_singleton();
if (_terrain != nullptr &&
_terrain->height_amsl(location, terrain_height_amsl, false)) {
_sitl->height_agl = _sitl->state.altitude - terrain_height_amsl;
_sitl->state.height_agl = _sitl->state.altitude - terrain_height_amsl;
return;
}
}
@ -606,7 +606,7 @@ void SITL_State::set_height_agl(void)
if (_sitl != nullptr) {
// fall back to flat earth model
_sitl->height_agl = _sitl->state.altitude - home_alt;
_sitl->state.height_agl = _sitl->state.altitude - home_alt;
}
}