mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
SRV_Channel: add and use RC_Channel_config.h
This commit is contained in:
parent
9b6aedb9e6
commit
ea26154088
@ -369,6 +369,7 @@ SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t functi
|
||||
}
|
||||
}
|
||||
|
||||
#if AP_RC_CHANNEL_ENABLED
|
||||
/*
|
||||
copy radio_in to radio_out for a given function
|
||||
*/
|
||||
@ -409,6 +410,7 @@ SRV_Channels::copy_radio_in_out_mask(uint32_t mask)
|
||||
}
|
||||
|
||||
}
|
||||
#endif // AP_RC_CHANNEL_ENABLED
|
||||
|
||||
/*
|
||||
setup failsafe value for an auxiliary function type to a Limit
|
||||
@ -459,6 +461,7 @@ SRV_Channels::set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_C
|
||||
if (c.function == function) {
|
||||
uint16_t pwm = c.get_limit_pwm(limit);
|
||||
c.set_output_pwm(pwm);
|
||||
#if AP_RC_CHANNEL_ENABLED
|
||||
if (c.function == SRV_Channel::k_manual) {
|
||||
RC_Channel *cin = rc().channel(c.ch_num);
|
||||
if (cin != nullptr) {
|
||||
@ -467,6 +470,7 @@ SRV_Channels::set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_C
|
||||
cin->set_radio_in(pwm);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user