10 #include <uavcan/driver/can.hpp>    63         void registerOverflow();
    76         void push(
const uavcan::CanFrame &
frame, 
const uint64_t &
utc_usec, uavcan::CanIOFlags 
flags);
    77         void pop(uavcan::CanFrame &out_frame, uavcan::uint64_t &out_utc_usec, uavcan::CanIOFlags &out_flags);
   111         enum {free = 0, busy, abort } pending;
   118               abort_on_error(false)
   123     enum { NumTxMesgBuffers = 6 };
   124     enum { NumFilters = 16 };
   140     int computeTimings(uavcan::uint32_t target_bitrate, 
Timings &out_timings);
   142     virtual uavcan::int16_t 
send(
const uavcan::CanFrame &
frame, uavcan::MonotonicTime tx_deadline,
   143                      uavcan::CanIOFlags 
flags);
   145     virtual uavcan::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic,
   146                     uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags);
   148     virtual uavcan::int16_t configureFilters(
const uavcan::CanFilterConfig *filter_configs,
   149             uavcan::uint16_t num_configs);
   156     void handleTxMailboxInterrupt(uavcan::uint8_t mailbox_index, 
bool txok, uavcan::uint64_t 
utc_usec);
   158     bool waitMCRChange(uavcan::uint32_t mask, 
bool target_state);
   159     void setMCR(uavcan::uint32_t mask, 
bool target_state);
   161     bool setEnable(
bool enable_true);
   162     uavcan::int16_t doReset(
Timings timings);
   163     bool waitFreezeAckChange(
bool target_state);
   164     void setFreeze(
bool freeze_true);
   167     enum { MaxRxQueueCapacity = 254 };
   175          CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
   177           rx_queue_(rx_queue_buffer, rx_queue_capacity),
   182           served_aborts_cnt_(0),
   183           update_event_(update_event),
   184           peak_tx_mailbox_index_(0),
   185           self_index_(self_index),
   188         UAVCAN_ASSERT(self_index_ < UAVCAN_KINETIS_NUM_IFACES);
   200     void handleTxInterrupt(uavcan::uint32_t tx_iflags, uavcan::uint64_t utc_usec);
   201     void handleRxInterrupt(uavcan::uint32_t rx_iflags, uavcan::uint64_t utc_usec);
   210     void pollErrorFlagsFromISR();
   212     void discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time);
   214     bool canAcceptNewTxFrame(
const uavcan::CanFrame &
frame) 
const;
   215     bool isRxBufferEmpty() 
const;
   230     virtual uavcan::uint64_t getErrorCount() 
const;
   239         return served_aborts_cnt_;
   246     unsigned getRxQueueLength() 
const;
   261         return uavcan::uint8_t(peak_tx_mailbox_index_ + 1);
   270     , uavcan::Noncopyable
   274 #if UAVCAN_KINETIS_NUM_IFACES > 1   278     virtual uavcan::int16_t select(uavcan::CanSelectMasks &inout_masks,
   279                        const uavcan::CanFrame * (&pending_tx)[uavcan::MaxCanIfaces],
   280                        uavcan::MonotonicTime blocking_deadline);
   282     static void initOnce();
   285     template <
unsigned RxQueueCapacity>
   287         : update_event_(*this),
   288           if0_(flexcan::
Can[0], update_event_, 0, rx_queue_storage[0], RxQueueCapacity)
   289 #if UAVCAN_KINETIS_NUM_IFACES > 1
   290         , if1_(flexcan::
Can[1], update_event_, 1, rx_queue_storage[1], RxQueueCapacity)
   293         uavcan::StaticAssert < (RxQueueCapacity <= CanIface::MaxRxQueueCapacity) >::check();
   299     uavcan::CanSelectMasks makeSelectMasks(
const uavcan::CanFrame * (&pending_tx)[uavcan::MaxCanIfaces]) 
const;
   304     bool hasReadableInterfaces() 
const;
   312     virtual CanIface *getIface(uavcan::uint8_t iface_index);
   316         return UAVCAN_KINETIS_NUM_IFACES;
   333 template <
unsigned RxQueueCapacity = 128>
   336     CanRxItem queue_storage_[UAVCAN_KINETIS_NUM_IFACES][RxQueueCapacity];
   339     enum { BitRateAutoDetect = 0 };
   344         driver(queue_storage_)
   354     int init(uavcan::uint32_t bitrate)
   373     template <
typename DelayCallable>
   374     int init(DelayCallable delay_callable, uavcan::uint32_t &inout_bitrate = BitRateAutoDetect)
   376         if (inout_bitrate > 0) {
   380             static const uavcan::uint32_t StandardBitRates[] = {
   387             for (uavcan::uint8_t br = 0; br < 
sizeof(StandardBitRates) / 
sizeof(StandardBitRates[0]); br++) {
   388                 inout_bitrate = StandardBitRates[br];
   395                     for (uavcan::uint8_t iface = 0; iface < driver.
getNumIfaces(); iface++) {
   413         return uavcan::MonotonicDuration::fromMSec(1050);
 int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode)
Returns zero if OK. 
 
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...
 
virtual uavcan::uint8_t getNumIfaces() const
 
CanIface(flexcan::CanType *can, BusEvent &update_event, uavcan::uint8_t self_index, CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
 
static const uavcan::int16_t ErrMcrFRZACKAckNotSet
MCR_FRZACK bit of the MCR register is not 1. 
 
unsigned getLength() const
 
int init(uavcan::uint32_t bitrate)
This overload simply configures the provided bitrate. 
 
uavcan::uint8_t getPeakNumTxMailboxesUsed() const
Peak number of TX mailboxes used concurrently since initialization. 
 
static const uavcan::int16_t ErrNotImplemented
Driver error codes. 
 
uavcan::uint32_t served_aborts_cnt_
 
int reset(enum LPS22HB_BUS busid)
Reset the driver. 
 
static uavcan::MonotonicDuration getRecommendedListeningDelay()
Use this value for listening delay during automatic bit rate detection. 
 
constexpr unsigned long CAN_FIFO_NE
 
uavcan::uint32_t overflow_cnt_
 
uavcan::MonotonicTime deadline
 
uavcan::uint8_t prescaler
 
RxQueue(CanRxItem *buf, uavcan::uint8_t capacity)
 
flexcan::CanType *const can_
 
CAN driver, incorporates all available CAN ifaces. 
 
void init()
Activates/configures the hardware registers. 
 
uavcan::uint64_t fifo_warn_cnt_
 
uavcan::uint8_t peak_tx_mailbox_index_
 
CanDriver(CanRxItem(&rx_queue_storage)[UAVCAN_KINETIS_NUM_IFACES][RxQueueCapacity])
 
static const uavcan::int16_t ErrMcrSOFTRSTNotCleared
MCR_SOFTRST bit of the MCR register is not 0. 
 
virtual CanIface * getIface(uavcan::uint8_t iface_index)
 
const uavcan::uint8_t self_index_
 
uavcan::uint32_t pending_aborts_
 
static const uavcan::int16_t ErrBitRateNotDetected
Auto bit rate detection could not be finished. 
 
CanType *const Can[UAVCAN_KINETIS_NUM_IFACES]
CANx register sets. 
 
const uavcan::uint8_t capacity_
 
static const uavcan::int16_t ErrMcrLPMAckNotSet
MCR_LPMACK bit of the MCR register is not 1. 
 
static const uavcan::int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc) 
 
static const uavcan::int16_t ErrMcrFRZACKAckNotCleared
MCR_FRZACK bit of the MCR register is not 0. 
 
All bus events are reported as POLLIN. 
 
bool isRxBufferEmpty() const
 
uavcan::uint32_t getRxQueueOverflowCount() const
Number of RX frames lost due to queue overflow. 
 
static const uavcan::int16_t ErrInvalidBitRate
Bit rate not supported. 
 
constexpr unsigned long CAN_FIFO_WARN
 
static const uavcan::int16_t ErrFilterNumConfigs
Number of filters is more than supported. 
 
uavcan::uint32_t getOverflowCount() const
 
uavcan::uint64_t utc_usec
 
static const uavcan::int16_t ErrMcrLPMAckNotCleared
MCR_LPMACK bit of the MCR register is not 0. 
 
constexpr unsigned long CAN_FIFO_OV
 
uavcan::uint32_t getVoluntaryTxAbortCount() const
Number of times the driver exercised library's requirement to abort transmission on first error...
 
virtual uavcan::uint16_t getNumFilters() const
 
uavcan::uint64_t error_cnt_
 
static const uavcan::int16_t ErrLogic
Internal logic error.