Browse Source

Plane: notify initialised after parameters loaded

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

2
ArduPlane/ArduPlane.cpp

@ -103,8 +103,6 @@ void Plane::setup() @@ -103,8 +103,6 @@ void Plane::setup()
AP_Notify::flags.failsafe_battery = false;
notify.init(false);
rssi.init();
init_ardupilot();

4
ArduPlane/system.cpp

@ -131,6 +131,10 @@ void Plane::init_ardupilot() @@ -131,6 +131,10 @@ void Plane::init_ardupilot()
// setup any board specific drivers
BoardConfig.init();
// initialise notify system
notify.init(false);
notify_flight_mode(control_mode);
init_rc_out_main();
// allow servo set on all channels except first 4

Loading…
Cancel
Save