mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
HAL_ChibiOS: remove singleton interface from slcan_router
This commit is contained in:
parent
28288a7329
commit
2f153a3577
@ -119,7 +119,9 @@ inline void handleInterrupt(uavcan::uint8_t iface_index, uavcan::uint8_t line_in
|
||||
} // namespace
|
||||
|
||||
uint32_t CanIface::FDCANMessageRAMOffset_ = 0;
|
||||
SLCANRouter *CanIface::_slcan_router = nullptr;
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
SLCANRouter CanIface::_slcan_router;
|
||||
#endif
|
||||
|
||||
CanIface::CanIface(fdcan::CanType* can, BusEvent& update_event, uavcan::uint8_t self_index,
|
||||
CanRxItem* rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
|
||||
@ -133,7 +135,6 @@ CanIface::CanIface(fdcan::CanType* can, BusEvent& update_event, uavcan::uint8_t
|
||||
, had_activity_(false)
|
||||
{
|
||||
UAVCAN_ASSERT(self_index_ < UAVCAN_STM32_NUM_IFACES);
|
||||
_slcan_router = SLCANRouter::get_singleton();
|
||||
}
|
||||
|
||||
/*
|
||||
@ -695,9 +696,7 @@ bool CanIface::readRxFIFO(uavcan::uint8_t fifo_index)
|
||||
*/
|
||||
rx_queue_.push(frame, utc_usec, 0);
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
if (_slcan_router != nullptr) {
|
||||
_slcan_router->route_frame_to_slcan(this, frame, utc_usec);
|
||||
}
|
||||
_slcan_router.route_frame_to_slcan(this, frame, utc_usec);
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
@ -85,8 +85,10 @@ struct CanRxItem {
|
||||
*/
|
||||
class CanIface : public uavcan::ICanIface, uavcan::Noncopyable
|
||||
{
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
friend class ::SLCANRouter;
|
||||
static SLCANRouter *_slcan_router;
|
||||
static SLCANRouter _slcan_router;
|
||||
#endif
|
||||
class RxQueue
|
||||
{
|
||||
CanRxItem* const buf_;
|
||||
@ -276,6 +278,10 @@ public:
|
||||
{
|
||||
return can_;
|
||||
}
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
static SLCANRouter &slcan_router() { return _slcan_router; }
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -86,7 +86,12 @@ struct CanRxItem {
|
||||
* The application shall not use this directly.
|
||||
*/
|
||||
class CanIface : public uavcan::ICanIface, uavcan::Noncopyable {
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
friend class ::SLCANRouter;
|
||||
static SLCANRouter _slcan_router;
|
||||
#endif
|
||||
|
||||
class RxQueue {
|
||||
CanRxItem* const buf_;
|
||||
const uavcan::uint8_t capacity_;
|
||||
@ -280,6 +285,9 @@ public:
|
||||
{
|
||||
return uavcan::uint8_t(peak_tx_mailbox_index_ + 1);
|
||||
}
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
static SLCANRouter &slcan_router() { return _slcan_router; }
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -20,14 +20,9 @@
|
||||
#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||
SLCANRouter* SLCANRouter::_singleton = nullptr;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
SLCANRouter &slcan_router()
|
||||
{
|
||||
return *SLCANRouter::get_singleton();
|
||||
}
|
||||
|
||||
void SLCANRouter::init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* update_event)
|
||||
{
|
||||
|
@ -42,7 +42,6 @@ class SLCANRouter {
|
||||
SLCAN::CAN _slcan_if;
|
||||
ObjectBuffer<CanRouteItem> _can_tx_queue;
|
||||
ObjectBuffer<CanRouteItem> _slcan_tx_queue;
|
||||
static SLCANRouter* _singleton;
|
||||
ChibiOS_CAN::BusEvent* _update_event;
|
||||
uint32_t _last_active_time = 0;
|
||||
uint32_t _slcan_rt_timeout = 0;
|
||||
@ -56,26 +55,14 @@ class SLCANRouter {
|
||||
|
||||
public:
|
||||
SLCANRouter() : _slcan_if(SLCAN_DRIVER_INDEX, SLCAN_RX_QUEUE_SIZE), _can_tx_queue(SLCAN_ROUTER_QUEUE_SIZE), _slcan_tx_queue(SLCAN_ROUTER_QUEUE_SIZE)
|
||||
{
|
||||
if (_singleton == nullptr) {
|
||||
_singleton = this;
|
||||
}
|
||||
}
|
||||
{}
|
||||
void init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* update_event);
|
||||
void route_frame_to_slcan(ChibiOS_CAN::CanIface* can_if, const uavcan::CanFrame& frame, uint64_t timestamp_usec);
|
||||
void route_frame_to_can(const uavcan::CanFrame& frame, uint64_t timestamp_usec);
|
||||
void slcan2can_router_trampoline(void);
|
||||
void can2slcan_router_trampoline(void);
|
||||
void run(void);
|
||||
static SLCANRouter* get_singleton()
|
||||
{
|
||||
if (_singleton == nullptr) {
|
||||
_singleton = new SLCANRouter;
|
||||
}
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
SLCANRouter &slcan_router();
|
||||
|
||||
#endif
|
||||
|
@ -138,7 +138,9 @@ inline void handleRxInterrupt(uavcan::uint8_t iface_index, uavcan::uint8_t fifo_
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
SLCANRouter CanIface::_slcan_router;
|
||||
#endif
|
||||
/*
|
||||
* CanIface::RxQueue
|
||||
*/
|
||||
@ -761,8 +763,8 @@ void CanIface::handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t ut
|
||||
* Store with timeout into the FIFO buffer and signal update event
|
||||
*/
|
||||
rx_queue_.push(frame, utc_usec, 0);
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
slcan_router().route_frame_to_slcan(this, frame, utc_usec);
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
_slcan_router.route_frame_to_slcan(this, frame, utc_usec);
|
||||
#endif
|
||||
had_activity_ = true;
|
||||
update_event_.signalFromInterrupt();
|
||||
|
Loading…
Reference in New Issue
Block a user