SRV_Channel: added set_rc_frequency

this allows for setting RC output rate of named channel types
This commit is contained in:
Andrew Tridgell 2017-04-10 14:50:40 +10:00
parent 328541769d
commit 1db3b31686
2 changed files with 18 additions and 0 deletions

View File

@ -334,6 +334,9 @@ public:
// call set_range() on matching channels
static void set_range(SRV_Channel::Aux_servo_function_t function, uint16_t range);
// set output refresh frequency on a servo function
static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency);
// control pass-thru of channels
void disable_passthrough(bool disable) {

View File

@ -789,3 +789,18 @@ void SRV_Channels::upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors
}
}
// set RC output frequency on a function output
void SRV_Channels::set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency_hz)
{
uint16_t mask = 0;
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
SRV_Channel &ch = channels[i];
if (ch.function == function) {
mask |= (1U<<ch.ch_num);
}
}
if (mask != 0) {
hal.rcout->set_freq(mask, frequency_hz);
}
}