AP_L1_Control: use set_default for runtime param defaults

This commit is contained in:
Jonathan Challinger 2015-10-22 12:49:49 -07:00 committed by Andrew Tridgell
parent 28f55766fd
commit f0f5239d8f

View File

@ -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