mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: move simulated height_agl into fdm structure
allows value to be shipped via multicast to simulated peripherals
This commit is contained in:
parent
af898220e7
commit
147c5ad78d
|
@ -384,7 +384,7 @@ void SIMState::set_height_agl(void)
|
|||
AP_Terrain *_terrain = AP_Terrain::get_singleton();
|
||||
if (_terrain != nullptr &&
|
||||
_terrain->height_amsl(location, terrain_height_amsl)) {
|
||||
_sitl->height_agl = _sitl->state.altitude - terrain_height_amsl;
|
||||
_sitl->state.height_agl = _sitl->state.altitude - terrain_height_amsl;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
@ -392,7 +392,7 @@ void SIMState::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;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue