AP_HAL_ChibiOS: unify singleton naming to _singleton and get_singleton()
This commit is contained in:
parent
b8ee535fb4
commit
548a579f18
@ -348,7 +348,7 @@ void setUtcSyncParams(const UtcSyncParams& params)
|
|||||||
|
|
||||||
} // namespace clock
|
} // namespace clock
|
||||||
|
|
||||||
SystemClock& SystemClock::instance()
|
SystemClock& SystemClock::get_singleton()
|
||||||
{
|
{
|
||||||
static union SystemClockStorage {
|
static union SystemClockStorage {
|
||||||
uavcan::uint8_t buffer[sizeof(SystemClock)];
|
uavcan::uint8_t buffer[sizeof(SystemClock)];
|
||||||
|
@ -158,7 +158,7 @@ public:
|
|||||||
* Calls clock::init() as needed.
|
* Calls clock::init() as needed.
|
||||||
* This function is thread safe.
|
* This function is thread safe.
|
||||||
*/
|
*/
|
||||||
static SystemClock& instance();
|
static SystemClock& get_singleton();
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
SLCANRouter &slcan_router()
|
SLCANRouter &slcan_router()
|
||||||
{
|
{
|
||||||
return *SLCANRouter::instance();
|
return *SLCANRouter::get_singleton();
|
||||||
}
|
}
|
||||||
|
|
||||||
void SLCANRouter::init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* update_event)
|
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()
|
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) {
|
if (_slcan_if.init(921600, SLCAN::CAN::OperatingMode::NormalMode, _port) < 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -67,7 +67,7 @@ public:
|
|||||||
void slcan2can_router_trampoline(void);
|
void slcan2can_router_trampoline(void);
|
||||||
void can2slcan_router_trampoline(void);
|
void can2slcan_router_trampoline(void);
|
||||||
void run(void);
|
void run(void);
|
||||||
static SLCANRouter* instance()
|
static SLCANRouter* get_singleton()
|
||||||
{
|
{
|
||||||
if (_singleton == nullptr) {
|
if (_singleton == nullptr) {
|
||||||
_singleton = new SLCANRouter;
|
_singleton = new SLCANRouter;
|
||||||
|
@ -66,7 +66,7 @@ bool RCInput::new_input()
|
|||||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||||
if (!_radio_init) {
|
if (!_radio_init) {
|
||||||
_radio_init = true;
|
_radio_init = true;
|
||||||
radio = AP_Radio::instance();
|
radio = AP_Radio::get_singleton();
|
||||||
if (radio) {
|
if (radio) {
|
||||||
radio->init();
|
radio->init();
|
||||||
}
|
}
|
||||||
|
@ -1445,7 +1445,7 @@ void RCOutput::safety_update(void)
|
|||||||
}
|
}
|
||||||
safety_update_ms = now;
|
safety_update_ms = now;
|
||||||
|
|
||||||
AP_BoardConfig *boardconfig = AP_BoardConfig::get_instance();
|
AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
|
||||||
|
|
||||||
if (boardconfig) {
|
if (boardconfig) {
|
||||||
// remember mask of channels to allow with safety on
|
// remember mask of channels to allow with safety on
|
||||||
|
@ -29,11 +29,11 @@ extern const AP_HAL::HAL& hal;
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// singleton instance
|
// singleton instance
|
||||||
SoftSigReaderInt *SoftSigReaderInt::_instance;
|
SoftSigReaderInt *SoftSigReaderInt::_singleton;
|
||||||
|
|
||||||
SoftSigReaderInt::SoftSigReaderInt()
|
SoftSigReaderInt::SoftSigReaderInt()
|
||||||
{
|
{
|
||||||
_instance = this;
|
_singleton = this;
|
||||||
}
|
}
|
||||||
|
|
||||||
eicuchannel_t SoftSigReaderInt::get_pair_channel(eicuchannel_t channel)
|
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.w0 = eicup->tim->CCR[channel];
|
||||||
pulse.w1 = eicup->tim->CCR[aux_channel];
|
pulse.w1 = eicup->tim->CCR[aux_channel];
|
||||||
|
|
||||||
_instance->sigbuf.push(pulse);
|
_singleton->sigbuf.push(pulse);
|
||||||
|
|
||||||
//check for missed interrupt
|
//check for missed interrupt
|
||||||
uint32_t mask = (STM32_TIM_SR_CC1OF << channel) | (STM32_TIM_SR_CC1OF << aux_channel);
|
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)
|
//try to reset RCProtocol parser by returning invalid value (i.e. 0 width pulse)
|
||||||
pulse.w0 = 0;
|
pulse.w0 = 0;
|
||||||
pulse.w1 = 0;
|
pulse.w1 = 0;
|
||||||
_instance->sigbuf.push(pulse);
|
_singleton->sigbuf.push(pulse);
|
||||||
//reset overcapture mask
|
//reset overcapture mask
|
||||||
eicup->tim->SR &= ~mask;
|
eicup->tim->SR &= ~mask;
|
||||||
}
|
}
|
||||||
|
@ -35,16 +35,16 @@ public:
|
|||||||
SoftSigReaderInt &operator=(const SoftSigReaderInt&) = delete;
|
SoftSigReaderInt &operator=(const SoftSigReaderInt&) = delete;
|
||||||
|
|
||||||
// get singleton
|
// get singleton
|
||||||
static SoftSigReaderInt *get_instance(void)
|
static SoftSigReaderInt *get_singleton(void)
|
||||||
{
|
{
|
||||||
return _instance;
|
return _singleton;
|
||||||
}
|
}
|
||||||
|
|
||||||
void init(EICUDriver* icu_drv, eicuchannel_t chan);
|
void init(EICUDriver* icu_drv, eicuchannel_t chan);
|
||||||
bool read(uint32_t &widths0, uint32_t &widths1);
|
bool read(uint32_t &widths0, uint32_t &widths1);
|
||||||
private:
|
private:
|
||||||
// singleton
|
// singleton
|
||||||
static SoftSigReaderInt *_instance;
|
static SoftSigReaderInt *_singleton;
|
||||||
|
|
||||||
static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel);
|
static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user