From 573b02fc2365ccaeba20d83fbcd9e741f0142ed4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Nov 2024 18:40:03 +1100 Subject: [PATCH] AP_Periph: create and use a singleton for SRV_Channels --- Tools/AP_Periph/rc_out.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/AP_Periph/rc_out.cpp b/Tools/AP_Periph/rc_out.cpp index 2dbfbe07f5..b4d9d410a5 100644 --- a/Tools/AP_Periph/rc_out.cpp +++ b/Tools/AP_Periph/rc_out.cpp @@ -71,7 +71,7 @@ void AP_Periph_FW::rcout_init() hal.rcout->set_freq(esc_mask, g.esc_rate.get()); // setup ESCs with the desired PWM type, allowing for DShot - SRV_Channels::init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get()); + AP::srv().init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get()); // run DShot at 1kHz hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), 400); @@ -83,7 +83,7 @@ void AP_Periph_FW::rcout_init() void AP_Periph_FW::rcout_init_1Hz() { // this runs at 1Hz to allow for run-time param changes - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); for (uint8_t i=0; i= esc_telem_update_period_ms) { last_esc_telem_update_ms = now_ms;