diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index a3786a94bc..6d739596c9 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -203,6 +203,8 @@ private: */ class SRV_Channels { public: + friend class SRV_Channel; + // constructor SRV_Channels(void); @@ -232,7 +234,7 @@ public: static float get_output_norm(SRV_Channel::Aux_servo_function_t function); // limit slew rate to given limit in percent per second - static void limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate); + static void limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt); // call output_ch() on all channels static void output_ch_all(void); diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 2bf4ddff05..697b808639 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -542,11 +542,27 @@ float SRV_Channels::get_output_norm(SRV_Channel::Aux_servo_function_t function) } /* - limit slew rate for an output function to given rate in percent per second + limit slew rate for an output function to given rate in percent per + second. This assumes output has not yet done to the hal */ -void SRV_Channels::limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate) +void SRV_Channels::limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt) { - // NOT IMPLEMENTED YET + for (uint8_t i=0; iread(ch.ch_num); + if (last_pwm == ch.output_pwm) { + continue; + } + uint16_t max_change = (ch.get_output_max() - ch.get_output_min()) * slew_rate * dt * 0.01f; + if (max_change == 0) { + // always allow some change + max_change = 1; + } + ch.output_pwm = constrain_int16(ch.output_pwm, last_pwm-max_change, last_pwm+max_change); + } + } } // call set_angle() on matching channels