diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index e270c52fa1..7ecb4fea0c 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -84,7 +84,7 @@ void AP_Motors::Init() void AP_Motors::armed(bool arm) { _armed = arm; - notify.flags.armed = _armed; + AP_Notify::flags.armed = _armed; }; // set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)