mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_L1_Control: added set_default_period()
used by the rover code
This commit is contained in:
parent
0c37bcbb10
commit
341dca4dfe
@ -50,6 +50,13 @@ public:
|
||||
void update_level_flight(void);
|
||||
bool reached_loiter_target(void);
|
||||
|
||||
// set the default NAVL1_PERIOD
|
||||
void set_default_period(float period) {
|
||||
if (!_L1_period.load()) {
|
||||
_L1_period.set(period);
|
||||
}
|
||||
}
|
||||
|
||||
// this supports the NAVl1_* user settable parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user