mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_L1_Control: use set_default for runtime param defaults
This commit is contained in:
parent
28f55766fd
commit
f0f5239d8f
@ -53,9 +53,7 @@ public:
|
|||||||
|
|
||||||
// set the default NAVL1_PERIOD
|
// set the default NAVL1_PERIOD
|
||||||
void set_default_period(float period) {
|
void set_default_period(float period) {
|
||||||
if (!_L1_period.load()) {
|
_L1_period.set_default(period);
|
||||||
_L1_period.set(period);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// this supports the NAVl1_* user settable parameters
|
// this supports the NAVl1_* user settable parameters
|
||||||
|
Loading…
Reference in New Issue
Block a user