|
|
|
@ -33,6 +33,7 @@ SRV_Channel *SRV_Channels::channels;
@@ -33,6 +33,7 @@ SRV_Channel *SRV_Channels::channels;
|
|
|
|
|
SRV_Channels *SRV_Channels::instance; |
|
|
|
|
AP_Volz_Protocol *SRV_Channels::volz_ptr; |
|
|
|
|
AP_SBusOut *SRV_Channels::sbus_ptr; |
|
|
|
|
AP_RobotisServo *SRV_Channels::robotis_ptr; |
|
|
|
|
|
|
|
|
|
#if HAL_SUPPORT_RCOUT_SERIAL |
|
|
|
|
AP_BLHeli *SRV_Channels::blheli_ptr; |
|
|
|
@ -141,6 +142,10 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
@@ -141,6 +142,10 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
|
|
|
|
|
AP_SUBGROUPINFO(blheli, "_BLH_", 21, SRV_Channels, AP_BLHeli), |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// @Group: _ROB_
|
|
|
|
|
// @Path: ../AP_RobotisServo/AP_RobotisServo.cpp
|
|
|
|
|
AP_SUBGROUPINFO(robotis, "_ROB_", 22, SRV_Channels, AP_RobotisServo), |
|
|
|
|
|
|
|
|
|
AP_GROUPEND |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
@ -162,6 +167,7 @@ SRV_Channels::SRV_Channels(void)
@@ -162,6 +167,7 @@ SRV_Channels::SRV_Channels(void)
|
|
|
|
|
|
|
|
|
|
volz_ptr = &volz; |
|
|
|
|
sbus_ptr = &sbus; |
|
|
|
|
robotis_ptr = &robotis; |
|
|
|
|
#if HAL_SUPPORT_RCOUT_SERIAL |
|
|
|
|
blheli_ptr = &blheli; |
|
|
|
|
#endif |
|
|
|
@ -228,6 +234,9 @@ void SRV_Channels::push()
@@ -228,6 +234,9 @@ void SRV_Channels::push()
|
|
|
|
|
// give sbus library a chance to update
|
|
|
|
|
sbus_ptr->update(); |
|
|
|
|
|
|
|
|
|
// give robotis library a chance to update
|
|
|
|
|
robotis_ptr->update(); |
|
|
|
|
|
|
|
|
|
#if HAL_SUPPORT_RCOUT_SERIAL |
|
|
|
|
// give blheli telemetry a chance to update
|
|
|
|
|
blheli_ptr->update_telemetry(); |
|
|
|
|