From 2abe12096934f401ca977bf38e17307f9c48b5b9 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 29 Aug 2021 13:18:06 +0100 Subject: [PATCH] SRV_Channel: remove set_safety_limit --- libraries/SRV_Channel/SRV_Channel.h | 3 --- libraries/SRV_Channel/SRV_Channel_aux.cpp | 18 ------------------ 2 files changed, 21 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 8c60e0b683..cc0f965482 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -423,9 +423,6 @@ public: // setup failsafe for an auxiliary channel function static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit); - // setup safety for an auxiliary channel function (used when disarmed) - static void set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit); - // set servo to a Limit static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit); diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 09388fb239..1ce8553e02 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -402,24 +402,6 @@ SRV_Channels::set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV } } -/* - setup safety value for an auxiliary function type to a Limit - */ -void -SRV_Channels::set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::Limit limit) -{ - if (!function_assigned(function)) { - return; - } - for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { - const SRV_Channel &c = channels[i]; - if (c.function.get() == function) { - uint16_t pwm = c.get_limit_pwm(limit); - hal.rcout->set_safety_pwm(1U<