mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 01:48:29 -04:00
Copter: update motors.throttle_interlock every time motors_output is run
This commit is contained in:
parent
7d745587a4
commit
4a0a4de687
@ -752,6 +752,14 @@ static void motors_output()
|
||||
if (ap.motor_test) {
|
||||
motor_test_output();
|
||||
} else {
|
||||
if (ap.using_interlock){
|
||||
// pass in motor interlock status to motors class
|
||||
// true means motors run, false motors don't run
|
||||
motors.set_interlock(ap.motor_interlock);
|
||||
} else {
|
||||
// if not using interlock switch, force interlock true
|
||||
motors.set_interlock(true);
|
||||
}
|
||||
motors.output();
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user