mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: create and use a singleton for SRV_Channels
This commit is contained in:
parent
ccd12e3e12
commit
573b02fc23
|
@ -71,7 +71,7 @@ void AP_Periph_FW::rcout_init()
|
|||
hal.rcout->set_freq(esc_mask, g.esc_rate.get());
|
||||
|
||||
// setup ESCs with the desired PWM type, allowing for DShot
|
||||
SRV_Channels::init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());
|
||||
AP::srv().init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());
|
||||
|
||||
// run DShot at 1kHz
|
||||
hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), 400);
|
||||
|
@ -83,7 +83,7 @@ void AP_Periph_FW::rcout_init()
|
|||
void AP_Periph_FW::rcout_init_1Hz()
|
||||
{
|
||||
// this runs at 1Hz to allow for run-time param changes
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
|
||||
servo_channels.set_esc_scaling_for(SRV_Channels::get_motor_function(i));
|
||||
|
@ -159,7 +159,7 @@ void AP_Periph_FW::rcout_update()
|
|||
SRV_Channels::calc_pwm();
|
||||
SRV_Channels::cork();
|
||||
SRV_Channels::output_ch_all();
|
||||
SRV_Channels::push();
|
||||
AP::srv().push();
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
if (now_ms - last_esc_telem_update_ms >= esc_telem_update_period_ms) {
|
||||
last_esc_telem_update_ms = now_ms;
|
||||
|
|
Loading…
Reference in New Issue