Motors: use AP_Notify static flags variable
This commit is contained in:
parent
0c1db12538
commit
0797489ad8
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user