Browse Source

AP_L1_Control: use set_default for runtime param defaults

master
Jonathan Challinger 9 years ago committed by Andrew Tridgell
parent
commit
f0f5239d8f
  1. 4
      libraries/AP_L1_Control/AP_L1_Control.h

4
libraries/AP_L1_Control/AP_L1_Control.h

@ -53,9 +53,7 @@ public: @@ -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

Loading…
Cancel
Save