From dce439643072aea71efe905fb8327fba1f7a1763 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 13 Nov 2024 08:10:00 +1100 Subject: [PATCH] Tools: make SRV_Channels::cork non-static for symmetry with the push function --- Tools/AP_Periph/rc_out.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Tools/AP_Periph/rc_out.cpp b/Tools/AP_Periph/rc_out.cpp index b4d9d410a5..8feb3e0805 100644 --- a/Tools/AP_Periph/rc_out.cpp +++ b/Tools/AP_Periph/rc_out.cpp @@ -156,10 +156,11 @@ void AP_Periph_FW::rcout_update() } rcout_has_new_data_to_update = false; + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); - SRV_Channels::cork(); + srv.cork(); SRV_Channels::output_ch_all(); - AP::srv().push(); + srv.push(); #if HAL_WITH_ESC_TELEM if (now_ms - last_esc_telem_update_ms >= esc_telem_update_period_ms) { last_esc_telem_update_ms = now_ms;