From 2d2f2c436061b6092e8948ece7e689328884111a Mon Sep 17 00:00:00 2001 From: murata Date: Mon, 16 Sep 2019 09:00:00 +0900 Subject: [PATCH] AP_AdvancedFailsafe: Change the unit of barometric pressure from mbar to hPa. --- libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index edd36e27cd..9af4f5c478 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -100,7 +100,7 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = { // @Param: QNH_PRESSURE // @DisplayName: QNH pressure // @Description: This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit. - // @Units: mbar + // @Units: hPa // @User: Advanced AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),