diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index fe8a935dc7..b8d6e21db7 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -735,6 +735,9 @@ private: // are we trying to follow terrain? bool terrain_following; + // are we waiting to load terrain data to init terrain following + bool terrain_following_pending; + // target altitude above terrain in cm, valid if terrain_following // is set int32_t terrain_alt_cm; @@ -855,7 +858,7 @@ private: void reset_offset_altitude(void); void set_offset_altitude_location(const Location &start_loc, const Location &destination_loc); bool above_location_current(const Location &loc); - void setup_terrain_target_alt(Location &loc) const; + void setup_terrain_target_alt(Location &loc); int32_t adjusted_altitude_cm(void); int32_t adjusted_relative_altitude_cm(void); float mission_alt_offset(void); diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 04aa72b270..4c3a35f409 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -212,6 +212,12 @@ void Plane::set_target_altitude_location(const Location &loc) target_altitude.amsl_cm += home.alt; } #if AP_TERRAIN_AVAILABLE + if (target_altitude.terrain_following_pending) { + /* we didn't get terrain data to init when we started on this + target, retry + */ + setup_terrain_target_alt(next_WP_loc); + } /* if this location has the terrain_alt flag set and we know the terrain altitude of our current location then treat it as a @@ -469,12 +475,16 @@ bool Plane::above_location_current(const Location &loc) modify a destination to be setup for terrain following if TERRAIN_FOLLOW is enabled */ -void Plane::setup_terrain_target_alt(Location &loc) const +void Plane::setup_terrain_target_alt(Location &loc) { #if AP_TERRAIN_AVAILABLE if (terrain_enabled_in_current_mode()) { - loc.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN); + if (!loc.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN)) { + target_altitude.terrain_following_pending = true; + return; + } } + target_altitude.terrain_following_pending = false; #endif } diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 9ad4f95313..79887fabde 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -8,7 +8,11 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) // default to non-VTOL loiter auto_state.vtol_loiter = false; - // log when new commands start +#if AP_TERRAIN_AVAILABLE + plane.target_altitude.terrain_following_pending = false; +#endif + + // log when new commands start if (should_log(MASK_LOG_CMD)) { logger.Write_Mission_Cmd(mission, cmd); } diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index a9af6555b7..068e5c5ec8 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -97,6 +97,10 @@ bool Mode::enter() quadplane.mode_enter(); #endif +#if AP_TERRAIN_AVAILABLE + plane.target_altitude.terrain_following_pending = false; +#endif + bool enter_result = _enter(); if (enter_result) {