From eee2d2f57ee076479bca2bf20ceb682bdc90d067 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 3 Aug 2024 13:27:54 +0100 Subject: [PATCH] SRV_Channel: add methods to set defualt and save min/max values --- libraries/SRV_Channel/SRV_Channel.h | 8 +++++++- libraries/SRV_Channel/SRV_Channel_aux.cpp | 25 +++++++++++++++++++++++ 2 files changed, 32 insertions(+), 1 deletion(-) diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 22bcc5f779..9e6d69b2b7 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -415,7 +415,13 @@ public: // 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); - + + // set MIN/MAX parameter defaults for a function + static void set_output_min_max_defaults(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm); + + // Save MIN/MAX/REVERSED parameters for a function + static void save_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 4c36ae332c..1412957202 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -844,6 +844,31 @@ void SRV_Channels::set_output_min_max(SRV_Channel::Aux_servo_function_t function } } +// set MIN/MAX parameter defaults for a function +void SRV_Channels::set_output_min_max_defaults(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm) +{ + for (uint8_t i=0; i max_pwm; + channels[i].servo_min.set_and_save(reversed ? max_pwm : min_pwm); + channels[i].servo_max.set_and_save(reversed ? min_pwm : max_pwm); + channels[i].reversed.set_and_save(reversed ? 1 : 0); + } + } +} + // constrain to output min/max for function void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function) {