From 134ea338dafea22082f23368474719bff967afb9 Mon Sep 17 00:00:00 2001 From: skyscraper Date: Thu, 5 May 2016 16:05:27 +0100 Subject: [PATCH] RC_Channel: remove unused control_mix method --- libraries/RC_Channel/RC_Channel.cpp | 6 ------ libraries/RC_Channel/RC_Channel.h | 2 -- 2 files changed, 8 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 84ab5c0e56..b623f3b644 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -221,12 +221,6 @@ RC_Channel::set_pwm_no_deadzone(int16_t pwm) } } -int16_t -RC_Channel::control_mix(float value) -{ - return (1 - abs(control_in / _high_in)) * value + control_in; -} - // returns just the PWM without the offset from radio_min void RC_Channel::calc_pwm(void) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index aac0937f94..217cce0db7 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -85,8 +85,6 @@ public: // value generated from PWM int16_t control_in; - int16_t control_mix(float value); - // current values to the servos - degrees * 100 (approx assuming servo is -45 to 45 degrees except [3] is 0 to 100 int16_t servo_out;