mirror of https://github.com/ArduPilot/ardupilot
Rover: notify initialised after parameters loaded
This commit is contained in:
parent
fc4741395d
commit
cc64c5e44a
|
@ -98,10 +98,6 @@ void Rover::setup()
|
|||
// load the default values of variables listed in var_info[]
|
||||
AP_Param::setup_sketch_defaults();
|
||||
|
||||
notify.init(false);
|
||||
|
||||
AP_Notify::flags.failsafe_battery = false;
|
||||
|
||||
rssi.init();
|
||||
|
||||
init_ardupilot();
|
||||
|
|
|
@ -108,6 +108,11 @@ void Rover::init_ardupilot()
|
|||
|
||||
BoardConfig.init();
|
||||
|
||||
// initialise notify system
|
||||
notify.init(false);
|
||||
AP_Notify::flags.failsafe_battery = false;
|
||||
notify_mode(control_mode);
|
||||
|
||||
ServoRelayEvents.set_channel_mask(0xFFF0);
|
||||
|
||||
set_control_channels();
|
||||
|
|
Loading…
Reference in New Issue