mirror of https://github.com/ArduPilot/ardupilot
SRV_Channels: move fetteconewire out of AP_Periph #if
This commit is contained in:
parent
2bfd2f1c32
commit
fd97d79cb4
|
@ -568,11 +568,12 @@ private:
|
|||
static AP_BLHeli *blheli_ptr;
|
||||
#endif
|
||||
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
#if AP_FETTEC_ONEWIRE_ENABLED
|
||||
AP_FETtecOneWire fetteconwire;
|
||||
static AP_FETtecOneWire *fetteconwire_ptr;
|
||||
#endif // AP_FETTEC_ONEWIRE_ENABLED
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
static uint16_t disabled_mask;
|
||||
|
||||
|
|
|
@ -47,10 +47,11 @@ SRV_Channels *SRV_Channels::_singleton;
|
|||
AP_Volz_Protocol *SRV_Channels::volz_ptr;
|
||||
AP_SBusOut *SRV_Channels::sbus_ptr;
|
||||
AP_RobotisServo *SRV_Channels::robotis_ptr;
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
#if AP_FETTEC_ONEWIRE_ENABLED
|
||||
AP_FETtecOneWire *SRV_Channels::fetteconwire_ptr;
|
||||
#endif
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
uint16_t SRV_Channels::override_counter[NUM_SERVO_CHANNELS];
|
||||
|
||||
|
@ -250,13 +251,14 @@ SRV_Channels::SRV_Channels(void)
|
|||
channels[i].ch_num = i;
|
||||
}
|
||||
|
||||
#if AP_FETTEC_ONEWIRE_ENABLED
|
||||
fetteconwire_ptr = &fetteconwire;
|
||||
#endif
|
||||
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
volz_ptr = &volz;
|
||||
sbus_ptr = &sbus;
|
||||
robotis_ptr = &robotis;
|
||||
#if AP_FETTEC_ONEWIRE_ENABLED
|
||||
fetteconwire_ptr = &fetteconwire;
|
||||
#endif
|
||||
#if HAL_SUPPORT_RCOUT_SERIAL
|
||||
blheli_ptr = &blheli;
|
||||
#endif
|
||||
|
@ -374,16 +376,16 @@ void SRV_Channels::push()
|
|||
// give robotis library a chance to update
|
||||
robotis_ptr->update();
|
||||
|
||||
#if AP_FETTEC_ONEWIRE_ENABLED
|
||||
fetteconwire_ptr->update();
|
||||
#endif
|
||||
|
||||
#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();
|
||||
#endif
|
||||
|
||||
#if HAL_CANMANAGER_ENABLED
|
||||
// push outputs to CAN
|
||||
uint8_t can_num_drivers = AP::can().get_num_drivers();
|
||||
|
|
Loading…
Reference in New Issue