From aadc37ebeb58dd6162806ed7a8b049ba8ba9969a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 13 Nov 2024 08:09:59 +1100 Subject: [PATCH] ArduPlane: make SRV_Channels::cork non-static for symmetry with the push function --- ArduPlane/servos.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index b8db6e14b8..aa3de533d3 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -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();