mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: move servo calc logic to motors_output() and cork SRV_Channels for improved performance
This commit is contained in:
parent
b0d89c6862
commit
2b60e93410
@ -158,10 +158,7 @@ void Sub::fifty_hz_loop()
|
|||||||
|
|
||||||
failsafe_sensors_check();
|
failsafe_sensors_check();
|
||||||
|
|
||||||
// Update rc input/output
|
|
||||||
rc().read_input();
|
rc().read_input();
|
||||||
SRV_Channels::calc_pwm();
|
|
||||||
SRV_Channels::output_ch_all();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// update_batt_compass - read battery and compass
|
// update_batt_compass - read battery and compass
|
||||||
|
@ -18,7 +18,11 @@ void Sub::motors_output()
|
|||||||
verify_motor_test();
|
verify_motor_test();
|
||||||
} else {
|
} else {
|
||||||
motors.set_interlock(true);
|
motors.set_interlock(true);
|
||||||
|
SRV_Channels::cork();
|
||||||
|
SRV_Channels::calc_pwm();
|
||||||
|
SRV_Channels::output_ch_all();
|
||||||
motors.output();
|
motors.output();
|
||||||
|
SRV_Channels::push();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user