From f0f5239d8f3ae03dd715f8d537d655a563c9def1 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 22 Oct 2015 12:49:49 -0700 Subject: [PATCH] AP_L1_Control: use set_default for runtime param defaults --- libraries/AP_L1_Control/AP_L1_Control.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/libraries/AP_L1_Control/AP_L1_Control.h b/libraries/AP_L1_Control/AP_L1_Control.h index cd90e9dde7..0997fc95fa 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.h +++ b/libraries/AP_L1_Control/AP_L1_Control.h @@ -53,9 +53,7 @@ public: // set the default NAVL1_PERIOD void set_default_period(float period) { - if (!_L1_period.load()) { - _L1_period.set(period); - } + _L1_period.set_default(period); } // this supports the NAVl1_* user settable parameters