SRV_Channel: add methods to set defualt and save min/max values

This commit is contained in:
Iampete1 2024-08-03 13:27:54 +01:00 committed by Andrew Tridgell
parent 5a3fb37214
commit eee2d2f57e
2 changed files with 32 additions and 1 deletions

View File

@ -416,6 +416,12 @@ 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);

View File

@ -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<NUM_SERVO_CHANNELS; i++) {
if (channels[i].function == function) {
channels[i].servo_min.set_default(min_pwm);
channels[i].servo_max.set_default(max_pwm);
}
}
}
// Save MIN/MAX/REVERSED parameters for a function
void SRV_Channels::save_output_min_max(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm)
{
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
if (channels[i].function == function) {
// If min is larger than max swap and set reversed
const bool reversed = min_pwm > 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)
{