From d2f7c21eb30df9c6e0c37a075510a75605d175b3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 29 Jul 2015 14:47:51 +0900 Subject: [PATCH] Baro: update climb rate only if healthy --- libraries/AP_Baro/AP_Baro.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 9f287d92a5..ffc6d8977a 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -347,7 +347,9 @@ void AP_Baro::update(void) } // ensure the climb rate filter is updated - _climb_rate_filter.update(get_altitude(), get_last_update()); + if (healthy()) { + _climb_rate_filter.update(get_altitude(), get_last_update()); + } } /*