mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: added function based set_output_min_max
this is for a conversion of AP_Motors heli code to servo functions
This commit is contained in:
parent
86b85c569a
commit
e94177e469
@ -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);
|
||||
|
||||
|
@ -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<NUM_SERVO_CHANNELS; i++) {
|
||||
if (channels[i].function == function) {
|
||||
channels[i].set_output_min(min_pwm);
|
||||
channels[i].set_output_max(max_pwm);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// constrain to output min/max for function
|
||||
void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user