mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
SRV_Channel: call rcout->update_channel_masks() at 1Hz
This commit is contained in:
parent
6e35b458c5
commit
32b172669c
@ -191,6 +191,7 @@ void SRV_Channels::update_aux_servo_function(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/// Should be called after the the servo functions have been initialized
|
/// Should be called after the the servo functions have been initialized
|
||||||
|
/// called at 1Hz
|
||||||
void SRV_Channels::enable_aux_servos()
|
void SRV_Channels::enable_aux_servos()
|
||||||
{
|
{
|
||||||
hal.rcout->set_default_rate(uint16_t(_singleton->default_rate.get()));
|
hal.rcout->set_default_rate(uint16_t(_singleton->default_rate.get()));
|
||||||
@ -221,6 +222,9 @@ void SRV_Channels::enable_aux_servos()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// propagate channel masks to the ESCS
|
||||||
|
hal.rcout->update_channel_masks();
|
||||||
|
|
||||||
#if HAL_SUPPORT_RCOUT_SERIAL
|
#if HAL_SUPPORT_RCOUT_SERIAL
|
||||||
blheli_ptr->update();
|
blheli_ptr->update();
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user