Browse Source

Rover: notify initialised after parameters loaded

mission-4.1.18
Randy Mackay 8 years ago committed by Lucas De Marchi
parent
commit
cc64c5e44a
  1. 4
      APMrover2/APMrover2.cpp
  2. 5
      APMrover2/system.cpp

4
APMrover2/APMrover2.cpp

@ -98,10 +98,6 @@ void Rover::setup() @@ -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();

5
APMrover2/system.cpp

@ -108,6 +108,11 @@ void Rover::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…
Cancel
Save