diff --git a/libraries/AP_HAL_ChibiOS/CANClock.cpp b/libraries/AP_HAL_ChibiOS/CANClock.cpp index 8b7c547aec..4507e827f9 100644 --- a/libraries/AP_HAL_ChibiOS/CANClock.cpp +++ b/libraries/AP_HAL_ChibiOS/CANClock.cpp @@ -348,7 +348,7 @@ void setUtcSyncParams(const UtcSyncParams& params) } // namespace clock -SystemClock& SystemClock::instance() +SystemClock& SystemClock::get_singleton() { static union SystemClockStorage { uavcan::uint8_t buffer[sizeof(SystemClock)]; diff --git a/libraries/AP_HAL_ChibiOS/CANClock.h b/libraries/AP_HAL_ChibiOS/CANClock.h index 3e20f41b6e..f5fa32c985 100644 --- a/libraries/AP_HAL_ChibiOS/CANClock.h +++ b/libraries/AP_HAL_ChibiOS/CANClock.h @@ -158,7 +158,7 @@ public: * Calls clock::init() as needed. * This function is thread safe. */ - static SystemClock& instance(); + static SystemClock& get_singleton(); }; } diff --git a/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp b/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp index 2dac476a1f..8e394f58b9 100644 --- a/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp +++ b/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; SLCANRouter &slcan_router() { - return *SLCANRouter::instance(); + return *SLCANRouter::get_singleton(); } void SLCANRouter::init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* update_event) @@ -38,7 +38,7 @@ void SLCANRouter::init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* upd void SLCANRouter::run() { - _port = AP_SerialManager::get_instance()->get_serial_by_id(AP::can().get_slcan_serial()); + _port = AP_SerialManager::get_singleton()->get_serial_by_id(AP::can().get_slcan_serial()); if (_slcan_if.init(921600, SLCAN::CAN::OperatingMode::NormalMode, _port) < 0) { return; } diff --git a/libraries/AP_HAL_ChibiOS/CANSerialRouter.h b/libraries/AP_HAL_ChibiOS/CANSerialRouter.h index 6ee2622c8f..66c1541ecc 100644 --- a/libraries/AP_HAL_ChibiOS/CANSerialRouter.h +++ b/libraries/AP_HAL_ChibiOS/CANSerialRouter.h @@ -67,7 +67,7 @@ public: void slcan2can_router_trampoline(void); void can2slcan_router_trampoline(void); void run(void); - static SLCANRouter* instance() + static SLCANRouter* get_singleton() { if (_singleton == nullptr) { _singleton = new SLCANRouter; diff --git a/libraries/AP_HAL_ChibiOS/RCInput.cpp b/libraries/AP_HAL_ChibiOS/RCInput.cpp index c85d97f7b8..fc5cfe9622 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCInput.cpp @@ -66,7 +66,7 @@ bool RCInput::new_input() #if HAL_RCINPUT_WITH_AP_RADIO if (!_radio_init) { _radio_init = true; - radio = AP_Radio::instance(); + radio = AP_Radio::get_singleton(); if (radio) { radio->init(); } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 8efa1199e8..8346afd725 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -1445,7 +1445,7 @@ void RCOutput::safety_update(void) } safety_update_ms = now; - AP_BoardConfig *boardconfig = AP_BoardConfig::get_instance(); + AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton(); if (boardconfig) { // remember mask of channels to allow with safety on diff --git a/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.cpp b/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.cpp index 439526137e..72bd169d61 100644 --- a/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.cpp +++ b/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.cpp @@ -29,11 +29,11 @@ extern const AP_HAL::HAL& hal; #endif // singleton instance -SoftSigReaderInt *SoftSigReaderInt::_instance; +SoftSigReaderInt *SoftSigReaderInt::_singleton; SoftSigReaderInt::SoftSigReaderInt() { - _instance = this; + _singleton = this; } eicuchannel_t SoftSigReaderInt::get_pair_channel(eicuchannel_t channel) @@ -97,7 +97,7 @@ void SoftSigReaderInt::_irq_handler(EICUDriver *eicup, eicuchannel_t aux_channel pulse.w0 = eicup->tim->CCR[channel]; pulse.w1 = eicup->tim->CCR[aux_channel]; - _instance->sigbuf.push(pulse); + _singleton->sigbuf.push(pulse); //check for missed interrupt uint32_t mask = (STM32_TIM_SR_CC1OF << channel) | (STM32_TIM_SR_CC1OF << aux_channel); @@ -106,7 +106,7 @@ void SoftSigReaderInt::_irq_handler(EICUDriver *eicup, eicuchannel_t aux_channel //try to reset RCProtocol parser by returning invalid value (i.e. 0 width pulse) pulse.w0 = 0; pulse.w1 = 0; - _instance->sigbuf.push(pulse); + _singleton->sigbuf.push(pulse); //reset overcapture mask eicup->tim->SR &= ~mask; } diff --git a/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.h b/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.h index 1293fd0a49..9b344f9a9a 100644 --- a/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.h +++ b/libraries/AP_HAL_ChibiOS/SoftSigReaderInt.h @@ -35,16 +35,16 @@ public: SoftSigReaderInt &operator=(const SoftSigReaderInt&) = delete; // get singleton - static SoftSigReaderInt *get_instance(void) + static SoftSigReaderInt *get_singleton(void) { - return _instance; + return _singleton; } void init(EICUDriver* icu_drv, eicuchannel_t chan); bool read(uint32_t &widths0, uint32_t &widths1); private: // singleton - static SoftSigReaderInt *_instance; + static SoftSigReaderInt *_singleton; static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel);