mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Tracker: fix notify initialisation
notify should be initialised before setting the initial startup flag status
This commit is contained in:
parent
028248d1f5
commit
ebf700d736
@ -243,12 +243,14 @@ void setup()
|
||||
// load the default values of variables listed in var_info[]
|
||||
AP_Param::setup_sketch_defaults();
|
||||
|
||||
// initialise notify
|
||||
notify.init(false);
|
||||
|
||||
// antenna tracker does not use pre-arm checks or battery failsafe
|
||||
AP_Notify::flags.pre_arm_check = true;
|
||||
AP_Notify::flags.pre_arm_gps_check = true;
|
||||
AP_Notify::flags.failsafe_battery = false;
|
||||
|
||||
notify.init(false);
|
||||
init_tracker();
|
||||
|
||||
// initialise the main loop scheduler
|
||||
|
Loading…
Reference in New Issue
Block a user