diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index b07542984dec..bcadc7811060 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -1023,10 +1023,19 @@ void MissionBlock::updateFailsafeChecks() void MissionBlock::updateMaxHaglFailsafe() { + + if (!_navigator->get_position_setpoint_triplet()->current.valid || + !_navigator->get_global_position()->terrain_alt_valid || + !PX4_ISFINITE(_navigator->get_local_position()->hagl_max)) { + _navigator->update_and_get_terrain_alt_exceeded_state(false, hrt_absolute_time()); + return; + } + const float target_alt = _navigator->get_position_setpoint_triplet()->current.alt; + const bool exceeded = (target_alt - _navigator->get_global_position()->terrain_alt) > + _navigator->get_local_position()->hagl_max; - if (_navigator->get_global_position()->terrain_alt_valid - && ((target_alt - _navigator->get_global_position()->terrain_alt) > _navigator->get_local_position()->hagl_max)) { + if (_navigator->update_and_get_terrain_alt_exceeded_state(exceeded, hrt_absolute_time())) { // Handle case where the altitude setpoint is above the maximum HAGL (height above ground level) mavlink_log_info(_navigator->get_mavlink_log_pub(), "Target altitude higher than max HAGL\t"); events::send(events::ID("navigator_fail_max_hagl"), events::Log::Error, "Target altitude higher than max HAGL"); diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index b3057e53753f..7da70c38c453 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -59,6 +59,7 @@ #include #include +#include #include #include #include @@ -240,6 +241,12 @@ class Navigator : public ModuleBase, public ModuleParams */ void set_cruising_throttle(float throttle = NAN) { _mission_throttle = throttle; } + bool update_and_get_terrain_alt_exceeded_state(bool exceeded, hrt_abstime now) + { + _max_terrain_alt_exceeded_hyst.set_state_and_update(exceeded, now); + return _max_terrain_alt_exceeded_hyst.get_state(); + } + /** * Get if the yaw acceptance is required at the current mission item * @@ -385,6 +392,7 @@ class Navigator : public ModuleBase, public ModuleParams bool _is_capturing_images{false}; // keep track if we need to stop capturing images + systemlib::Hysteresis _max_terrain_alt_exceeded_hyst{false}; // update subscriptions void params_update();