diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 27803566d0bfd2..4fcbc2ed97ba90 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -129,9 +129,11 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const #if AP_TERRAIN_AVAILABLE AP_Terrain *terrain = AP::terrain(); if (terrain == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Location:get_alt_cm terrain == nullptr"); return false; } if (!terrain->height_amsl(*this, alt_terr_cm)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Location:get_alt_cm height_amsl false"); return false; } // convert terrain alt to cm