mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: allow for AP_Periph ESC telemetry
This commit is contained in:
parent
91424c1f03
commit
9359f39e30
|
@ -261,10 +261,10 @@ SRV_Channels::SRV_Channels(void)
|
|||
volz_ptr = &volz;
|
||||
sbus_ptr = &sbus;
|
||||
robotis_ptr = &robotis;
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
#if HAL_SUPPORT_RCOUT_SERIAL
|
||||
blheli_ptr = &blheli;
|
||||
#endif
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
}
|
||||
|
||||
// SRV_Channels initialization
|
||||
|
@ -274,7 +274,9 @@ void SRV_Channels::init(void)
|
|||
#if HAL_SUPPORT_RCOUT_SERIAL
|
||||
blheli_ptr->init();
|
||||
#endif
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
hal.rcout->set_dshot_rate(_singleton->dshot_rate, AP::scheduler().get_loop_rate_hz());
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -378,11 +380,12 @@ void SRV_Channels::push()
|
|||
// give robotis library a chance to update
|
||||
robotis_ptr->update();
|
||||
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
#if HAL_SUPPORT_RCOUT_SERIAL
|
||||
// give blheli telemetry a chance to update
|
||||
blheli_ptr->update_telemetry();
|
||||
#endif
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
#if AP_FETTEC_ONEWIRE_ENABLED
|
||||
fetteconwire_ptr->update();
|
||||
|
|
Loading…
Reference in New Issue