Motors: use AP_Notify static flags variable

This commit is contained in:
Randy Mackay 2013-08-14 11:51:54 +09:00 committed by Andrew Tridgell
parent 0c1db12538
commit 0797489ad8

View File

@ -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)