From e94177e469d4b897ec9e3a392d2dac35fa8c1824 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 May 2018 12:58:12 +1000 Subject: [PATCH] SRV_Channel: added function based set_output_min_max this is for a conversion of AP_Motors heli code to servo functions --- libraries/SRV_Channel/SRV_Channel.h | 3 +++ libraries/SRV_Channel/SRV_Channel_aux.cpp | 11 +++++++++++ 2 files changed, 14 insertions(+) diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index e66681c760..06242aafb4 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -301,6 +301,9 @@ public: // adjust trim of a channel by a small increment void adjust_trim(SRV_Channel::Aux_servo_function_t function, float v); + // set MIN/MAX parameters for a function + static void set_output_min_max(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm); + // save trims void save_trim(void); diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index bae8bc08d7..760340088d 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -654,6 +654,17 @@ void SRV_Channels::set_range(SRV_Channel::Aux_servo_function_t function, uint16_ } } +// set MIN parameter for a function +void SRV_Channels::set_output_min_max(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm) +{ + for (uint8_t i=0; i