Tracker: notify initialised after parameters loaded

This commit is contained in:
Randy Mackay 2017-01-21 15:17:26 +09:00 committed by Lucas De Marchi
parent c701d6a715
commit a04cdce1bc
2 changed files with 6 additions and 8 deletions

View File

@ -57,14 +57,6 @@ void Tracker::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;
init_tracker();
// initialise the main loop scheduler

View File

@ -42,6 +42,12 @@ void Tracker::init_tracker()
BoardConfig.init();
// initialise notify
notify.init(false);
AP_Notify::flags.pre_arm_check = true;
AP_Notify::flags.pre_arm_gps_check = true;
AP_Notify::flags.failsafe_battery = false;
// init baro before we start the GCS, so that the CLI baro test works
barometer.init();