mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: correct AP_Terrain cast-align compilation failure on SITL_arm_linux_gnueabihf
This commit is contained in:
parent
f1fc61cb41
commit
38e3d63fac
|
@ -77,9 +77,6 @@ void SITL_State::_sitl_setup(const char *home_str)
|
||||||
_barometer = AP_Baro::get_singleton();
|
_barometer = AP_Baro::get_singleton();
|
||||||
_ins = AP_InertialSensor::get_singleton();
|
_ins = AP_InertialSensor::get_singleton();
|
||||||
_compass = Compass::get_singleton();
|
_compass = Compass::get_singleton();
|
||||||
#if AP_TERRAIN_AVAILABLE
|
|
||||||
_terrain = reinterpret_cast<AP_Terrain *>(AP_Param::find_object("TERRAIN_"));
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (_sitl != nullptr) {
|
if (_sitl != nullptr) {
|
||||||
// setup some initial values
|
// setup some initial values
|
||||||
|
@ -891,8 +888,7 @@ void SITL_State::set_height_agl(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
if (_terrain != nullptr &&
|
if (_sitl != nullptr &&
|
||||||
_sitl != nullptr &&
|
|
||||||
_sitl->terrain_enable) {
|
_sitl->terrain_enable) {
|
||||||
// get height above terrain from AP_Terrain. This assumes
|
// get height above terrain from AP_Terrain. This assumes
|
||||||
// AP_Terrain is working
|
// AP_Terrain is working
|
||||||
|
@ -901,7 +897,9 @@ void SITL_State::set_height_agl(void)
|
||||||
location.lat = _sitl->state.latitude*1.0e7;
|
location.lat = _sitl->state.latitude*1.0e7;
|
||||||
location.lng = _sitl->state.longitude*1.0e7;
|
location.lng = _sitl->state.longitude*1.0e7;
|
||||||
|
|
||||||
if (_terrain->height_amsl(location, terrain_height_amsl, false)) {
|
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->height_agl = _sitl->state.altitude - terrain_height_amsl;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -187,9 +187,6 @@ private:
|
||||||
AP_InertialSensor *_ins;
|
AP_InertialSensor *_ins;
|
||||||
Scheduler *_scheduler;
|
Scheduler *_scheduler;
|
||||||
Compass *_compass;
|
Compass *_compass;
|
||||||
#if AP_TERRAIN_AVAILABLE
|
|
||||||
AP_Terrain *_terrain;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
SocketAPM _sitl_rc_in{true};
|
SocketAPM _sitl_rc_in{true};
|
||||||
SITL::SITL *_sitl;
|
SITL::SITL *_sitl;
|
||||||
|
|
Loading…
Reference in New Issue