diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index f09bf66f00..0a7c64ae9a 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -63,7 +63,7 @@ Aircraft::Aircraft(const char *frame_str) : sitl->ahrs_rotation_inv = sitl->ahrs_rotation.transposed(); } - terrain = &AP::terrain(); + terrain = AP::terrain(); // init rangefinder array to -1 to signify no data for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++){ diff --git a/libraries/SITL/SIM_Ship.cpp b/libraries/SITL/SIM_Ship.cpp index 99aa38cafa..2f3e07408c 100644 --- a/libraries/SITL/SIM_Ship.cpp +++ b/libraries/SITL/SIM_Ship.cpp @@ -178,9 +178,9 @@ void ShipSim::send_report(void) bool have_alt = false; #if AP_TERRAIN_AVAILABLE - auto &terrain = AP::terrain(); + auto terrain = AP::terrain(); float height; - if (terrain.enabled() && terrain.height_amsl(loc, height, true)) { + if (terrain != nullptr && terrain->enabled() && terrain->height_amsl(loc, height, true)) { alt = height * 1000; have_alt = true; }