9 #include <uavcan/driver/can.hpp> 46 class CanIface :
public uavcan::ICanIface, uavcan::Noncopyable
57 void registerOverflow();
69 void push(
const uavcan::CanFrame &
frame,
const uint64_t &
utc_usec, uavcan::CanIOFlags
flags);
70 void pop(uavcan::CanFrame &out_frame, uavcan::uint64_t &out_utc_usec, uavcan::CanIOFlags &out_flags);
103 , abort_on_error(false)
107 enum { NumTxMailboxes = 3 };
108 enum { NumFilters = 14 };
110 static const uavcan::uint32_t TSR_ABRQx[NumTxMailboxes];
122 int computeTimings(uavcan::uint32_t target_bitrate,
Timings &out_timings);
124 virtual uavcan::int16_t
send(
const uavcan::CanFrame &
frame, uavcan::MonotonicTime tx_deadline,
125 uavcan::CanIOFlags
flags);
127 virtual uavcan::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic,
128 uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags);
130 virtual uavcan::int16_t configureFilters(
const uavcan::CanFilterConfig *filter_configs,
131 uavcan::uint16_t num_configs);
135 void handleTxMailboxInterrupt(uavcan::uint8_t mailbox_index,
bool txok, uavcan::uint64_t
utc_usec);
137 bool waitMsrINakBitStateChange(
bool target_state);
140 enum { MaxRxQueueCapacity = 254 };
148 CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
149 : rx_queue_(rx_queue_buffer, rx_queue_capacity)
152 , served_aborts_cnt_(0)
153 , update_event_(update_event)
154 , peak_tx_mailbox_index_(0)
155 , self_index_(self_index)
156 , had_activity_(false)
158 UAVCAN_ASSERT(self_index_ < UAVCAN_STM32_NUM_IFACES);
170 void handleTxInterrupt(uavcan::uint64_t utc_usec);
171 void handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t utc_usec);
180 void pollErrorFlagsFromISR();
182 void discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time);
184 bool canAcceptNewTxFrame(
const uavcan::CanFrame &
frame)
const;
185 bool isRxBufferEmpty()
const;
197 virtual uavcan::uint64_t getErrorCount()
const;
210 unsigned getRxQueueLength()
const;
230 class CanDriver :
public uavcan::ICanDriver, uavcan::Noncopyable
234 #if UAVCAN_STM32_NUM_IFACES > 1 238 virtual uavcan::int16_t select(uavcan::CanSelectMasks &inout_masks,
239 const uavcan::CanFrame * (& pending_tx)[uavcan::MaxCanIfaces],
240 uavcan::MonotonicTime blocking_deadline);
242 static void initOnce();
245 template <
unsigned RxQueueCapacity>
247 : update_event_(*this)
248 , if0_(bxcan::
Can[0], update_event_, 0, rx_queue_storage[0], RxQueueCapacity)
249 #if UAVCAN_STM32_NUM_IFACES > 1
250 , if1_(bxcan::
Can[1], update_event_, 1, rx_queue_storage[1], RxQueueCapacity)
253 uavcan::StaticAssert < (RxQueueCapacity <= CanIface::MaxRxQueueCapacity) >::check();
259 uavcan::CanSelectMasks makeSelectMasks(
const uavcan::CanFrame * (& pending_tx)[uavcan::MaxCanIfaces])
const;
264 bool hasReadableInterfaces()
const;
272 virtual CanIface *getIface(uavcan::uint8_t iface_index);
274 virtual uavcan::uint8_t
getNumIfaces()
const {
return UAVCAN_STM32_NUM_IFACES; }
290 template <
unsigned RxQueueCapacity = 128>
293 CanRxItem queue_storage_[UAVCAN_STM32_NUM_IFACES][RxQueueCapacity];
296 enum { BitRateAutoDetect = 0 };
301 driver(queue_storage_)
310 int init(uavcan::uint32_t bitrate)
329 template <
typename DelayCallable>
330 int init(DelayCallable delay_callable, uavcan::uint32_t &inout_bitrate = BitRateAutoDetect)
332 if (inout_bitrate > 0) {
336 static const uavcan::uint32_t StandardBitRates[] = {
343 for (uavcan::uint8_t br = 0; br <
sizeof(StandardBitRates) /
sizeof(StandardBitRates[0]); br++) {
344 inout_bitrate = StandardBitRates[br];
351 for (uavcan::uint8_t iface = 0; iface < driver.
getNumIfaces(); iface++) {
369 return uavcan::MonotonicDuration::fromMSec(1050);
uavcan::uint64_t utc_usec
uavcan::uint32_t served_aborts_cnt_
virtual uavcan::uint8_t getNumIfaces() const
uavcan::uint8_t getPeakNumTxMailboxesUsed() const
Peak number of TX mailboxes used concurrently since initialization.
static const uavcan::int16_t ErrInvalidBitRate
Bit rate not supported.
static const uavcan::int16_t ErrMsrInakNotCleared
INAK bit of the MSR register is not 0.
int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode)
Returns zero if OK.
uavcan::uint64_t error_cnt_
uavcan::uint16_t prescaler
static const uavcan::int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
int reset(enum LPS22HB_BUS busid)
Reset the driver.
static uavcan::MonotonicDuration getRecommendedListeningDelay()
Use this value for listening delay during automatic bit rate detection.
int init(uavcan::uint32_t bitrate)
This overload simply configures the provided bitrate.
int init(DelayCallable delay_callable, uavcan::uint32_t &inout_bitrate=BitRateAutoDetect)
This function can either initialize the driver at a fixed bit rate, or it can perform automatic bit r...
static const uavcan::int16_t ErrMsrInakNotSet
INAK bit of the MSR register is not 1.
virtual uavcan::uint16_t getNumFilters() const
static const uavcan::int16_t ErrLogic
Internal logic error.
virtual CanIface * getIface(uavcan::uint8_t iface_index)
bool isRxBufferEmpty() const
static const uavcan::int16_t ErrNotImplemented
Driver error codes.
void init()
Activates/configures the hardware registers.
uavcan::MonotonicTime deadline
bxcan::CanType *const can_
uavcan::uint32_t overflow_cnt_
static const uavcan::int16_t ErrBitRateNotDetected
Auto bit rate detection could not be finished.
CanIface(bxcan::CanType *can, BusEvent &update_event, uavcan::uint8_t self_index, CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
uavcan::uint32_t getVoluntaryTxAbortCount() const
Number of times the driver exercised library's requirement to abort transmission on first error...
const uavcan::uint8_t capacity_
CanDriver(CanRxItem(&rx_queue_storage)[UAVCAN_STM32_NUM_IFACES][RxQueueCapacity])
CanType *const Can[UAVCAN_KINETIS_NUM_IFACES]
CANx register sets.
uavcan::uint8_t peak_tx_mailbox_index_
unsigned getLength() const
RxQueue(CanRxItem *buf, uavcan::uint8_t capacity)
uavcan::uint32_t getOverflowCount() const
CAN driver, incorporates all available CAN ifaces.
static const uavcan::int16_t ErrFilterNumConfigs
Number of filters is more than supported.
uavcan::uint32_t getRxQueueOverflowCount() const
Number of RX frames lost due to queue overflow.
const uavcan::uint8_t self_index_