ArduPlane: make SRV_Channels::cork non-static

for symmetry with the push function
This commit is contained in:
Peter Barker 2024-11-13 08:09:59 +11:00 committed by Andrew Tridgell
parent a2f35b3150
commit aadc37ebeb
1 changed files with 5 additions and 4 deletions

View File

@ -858,8 +858,8 @@ void Plane::set_servos(void)
// start with output corked. the cork is released when we run
// servos_output(), which is run from all code paths in this
// function
SRV_Channels::cork();
AP::srv().cork();
// this is to allow the failsafe module to deliberately crash
// the plane. Only used in extreme circumstances to meet the
// OBC rules
@ -1017,7 +1017,8 @@ void Plane::indicate_waiting_for_rud_neutral_to_takeoff(void)
*/
void Plane::servos_output(void)
{
SRV_Channels::cork();
auto &srv = AP::srv();
srv.cork();
// support twin-engine aircraft
servos_twin_engine_mix();
@ -1055,7 +1056,7 @@ void Plane::servos_output(void)
SRV_Channels::output_ch_all();
AP::srv().push();
srv.push();
if (g2.servo_channels.auto_trim_enabled()) {
servos_auto_trim();