Go to the documentation of this file.
12 #if UAVCAN_KINETIS_NUTTX
13 # include <nuttx/arch.h>
14 # include <nuttx/irq.h>
15 # include <arch/board/board.h>
26 #if UAVCAN_KINETIS_NUM_IFACES > 1
27 static int can1_irq(
const int irq,
void*,
void*
args);
42 CanIface* ifaces[UAVCAN_KINETIS_NUM_IFACES] =
45 #if UAVCAN_KINETIS_NUM_IFACES > 1
58 can->handleTxInterrupt(iflags1,
utc_usec);
68 can->handleRxInterrupt(iflags1,
utc_usec);
100 if (
out_ >= capacity_)
115 if (
out_ >= capacity_)
141 if (target_bitrate < 1)
171 const int max_quanta_per_bit = 17;
181 if (prescaler > nbt_prescaler)
186 if ((0 == nbt_prescaler % prescaler) && (nbt_prescaler / prescaler) < max_quanta_per_bit)
207 return ((out_timings.
pseg1 <= 8) && (out_timings.
pseg2 <= 8) && (out_timings.
propseg <= 8)) ? 0 :
234 CriticalSectionLocker lock;
314 CriticalSectionLocker lock;
330 CriticalSectionLocker lock;
341 if (num_configs == 0)
387 filter.
w = 0xffffffff;
401 const unsigned Timeout = 1000;
402 for (
unsigned wait_ack = 0; wait_ack < Timeout; wait_ack++)
404 const bool state = (
can_->
MCR & mask) != 0;
405 if (state == target_state)
435 CriticalSectionLocker lock;
548 unsigned(timings.
pseg2));
626 if (moreAborts & bit)
635 tx_iflags &= ~aborts;
645 if (tx_iflags & mbBit)
758 pending_aborts |= iflag1;;
769 CriticalSectionLocker lock;
801 CriticalSectionLocker lock;
816 CriticalSectionLocker lock;
822 CriticalSectionLocker lock;
828 CriticalSectionLocker lock;
834 CriticalSectionLocker lock;
848 msk.
read = if0_.isRxBufferEmpty() ? 0 : 1;
852 msk.
write = if0_.canAcceptNewTxFrame(*pending_tx[0]) ? 1 : 0;
856 #if UAVCAN_KINETIS_NUM_IFACES > 1
857 if (!if1_.isRxBufferEmpty())
864 if (if1_.canAcceptNewTxFrame(*pending_tx[1]))
875 #if UAVCAN_KINETIS_NUM_IFACES == 1
876 return !if0_.isRxBufferEmpty();
877 #elif UAVCAN_KINETIS_NUM_IFACES == 2
878 return !if0_.isRxBufferEmpty() || !if1_.isRxBufferEmpty();
880 # error UAVCAN_KINETIS_NUM_IFACES
891 if0_.discardTimedOutTxMailboxes(time);
893 CriticalSectionLocker cs_locker;
894 if0_.pollErrorFlagsFromISR();
897 #if UAVCAN_KINETIS_NUM_IFACES > 1
898 if1_.discardTimedOutTxMailboxes(time);
900 CriticalSectionLocker cs_locker;
901 if1_.pollErrorFlagsFromISR();
905 inout_masks = makeSelectMasks(pending_tx);
906 if ((inout_masks.
read & in_masks.
read) != 0 ||
913 inout_masks = makeSelectMasks(pending_tx);
924 CriticalSectionLocker lock;
925 modifyreg32(KINETIS_SIM_SCGC6, 0, SIM_SCGC6_FLEXCAN0);
926 #if UAVCAN_KINETIS_NUM_IFACES > 1
927 modifyreg32(KINETIS_SIM_SCGC3, 0, SIM_SCGC3_FLEXCAN1);
934 #define IRQ_ATTACH(irq, handler) \
936 const int res = irq_attach(irq, handler, NULL); \
939 up_enable_irq(irq); \
942 #if UAVCAN_KINETIS_NUM_IFACES > 1
952 UAVCAN_KINETIS_LOG(
"Bitrate %lu mode %d",
static_cast<unsigned long>(bitrate),
static_cast<int>(mode));
954 static bool initialized_once =
false;
955 if (!initialized_once)
957 initialized_once =
true;
967 res = if0_.
init(bitrate, mode);
978 #if UAVCAN_KINETIS_NUM_IFACES > 1
981 res = if1_.
init(bitrate, mode);
1002 if (iface_index < UAVCAN_KINETIS_NUM_IFACES)
1004 return ifaces[iface_index];
1011 bool ret = if0_.hadActivity();
1012 #if UAVCAN_KINETIS_NUM_IFACES > 1
1013 ret |= if1_.hadActivity();
1040 flags = flex->
IFLAG1 & MB_IFLAG1;
1049 #if UAVCAN_KINETIS_NUM_IFACES > 1
1051 static int can1_irq(
const int irq,
void*,
void*)
1065 flags = flex->IFLAG1 & MB_IFLAG1;
static const uint32_t MaskStdID
volatile FilterType RXIMR[HWMaxMB]
const uavcan::uint32_t busclck
static const uint32_t FlagEFF
Extended frame format.
constexpr unsigned long CTRL1_RJW_SHIFT
CanType *const Can[UAVCAN_KINETIS_NUM_IFACES]
std::uint32_t overflow_cnt_
constexpr unsigned long MCR_MDIS
void discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time)
uavcan::uint8_t prescaler
constexpr unsigned long MCR_AEN
void pollErrorFlagsFromISR()
uavcan::uint64_t fifo_warn_cnt_
volatile uint32_t RX14MASK
constexpr unsigned long CAN_FIFO_WARN
constexpr unsigned long CTRL2_RFFN_16MB(1U<< CTRL2_RFFN_SHIFT)
virtual CanIface * getIface(uavcan::uint8_t iface_index)
constexpr unsigned long CTRL1_TWRNMSK
constexpr unsigned long ESR1_BIT0ERR
Implicitly convertible to/from uavcan.Timestamp.
constexpr unsigned long MCR_SOFTRST
constexpr unsigned long CTRL1_PSEG2_SHIFT
void setMCR(uavcan::uint32_t mask, bool target_state)
constexpr unsigned long MCR_WAKSRC
uavcan::uint32_t pending_aborts_
constexpr unsigned long ESR1_BIT1ERR
bool waitMCRChange(uavcan::uint32_t mask, bool target_state)
static const uavcan::int16_t ErrMcrSOFTRSTNotCleared
MCR_SOFTRST bit of the MCR register is not 0.
constexpr unsigned long MCR_LPMACK
volatile uint32_t RXMGMASK
constexpr unsigned long CAN_FIFO_OV
constexpr unsigned long CAN_FIFO_NE
bool waitFreezeAckChange(bool target_state)
constexpr unsigned long CTRL2_RRS
int init(const uavcan::uint32_t bitrate, const OperatingMode mode)
#define IRQ_ATTACH(irq, handler)
static const uavcan::int16_t ErrFilterNumConfigs
Number of filters is more than supported.
uint8_t dlc
Data Length Code.
static const CanIOFlags CanIOFlagLoopback
static int can0_irq(const int irq, void *, void *args)
const uavcan::uint32_t numberFIFOFilters
static const uavcan::int16_t ErrMcrLPMAckNotCleared
MCR_LPMACK bit of the MCR register is not 0.
constexpr unsigned long MCR_SUPV
uint32_t id
CAN ID with flags (above)
UAVCAN_EXPORT void fill_n(OutputIt first, std::size_t n, const T &value)
static const uavcan::int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
bool hasReadableInterfaces() const
constexpr unsigned long ESR1_FRMERR
constexpr unsigned long MCR_FRZACK
const uavcan::uint32_t canclk
void handleTxInterrupt(uavcan::uint32_t tx_iflags, uavcan::uint64_t utc_usec)
void handleTxMailboxInterrupt(uavcan::uint8_t mailbox_index, bool txok, uavcan::uint64_t utc_usec)
bool isErrorFrame() const
constexpr unsigned long CTRL2_TASD_MASK
union uavcan_kinetis::flexcan::CanType::@167 MB[HWMaxMB]
const uavcan::uint32_t FIFO_IFLAG1
constexpr unsigned long ESR1_ACKERR
uavcan::CanSelectMasks makeSelectMasks(const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces]) const
constexpr unsigned long ESR1_STFERR
static UtcTime fromUSec(uint64_t us)
uavcan::MonotonicTime deadline
constexpr unsigned long MCR_FRZ
static const uavcan::int16_t ErrInvalidBitRate
Bit rate not supported.
virtual uavcan::uint64_t getErrorCount() const
unsigned getLength() const
constexpr unsigned long ESR2_LPTM_MASK
constexpr unsigned long CTRL1_ERRMSK
constexpr unsigned long MCR_MAXMB_MASK
void setFreeze(bool freeze_true)
constexpr unsigned long CTRL1_ROPSEG_SHIFT
const UAVCAN_EXPORT T & max(const T &a, const T &b)
constexpr unsigned long ESR2_IMB
constexpr unsigned long ESR2_VPS
void handleRxInterrupt(uavcan::uint32_t rx_iflags, uavcan::uint64_t utc_usec)
constexpr unsigned long MCR_MAXMB_SHIFT
static const uint32_t MaskExtID
bool wait(uavcan::MonotonicDuration duration)
constexpr unsigned long CTRL1_PSEG1_SHIFT
int computeTimings(uavcan::uint32_t target_bitrate, Timings &out_timings)
uavcan::uint32_t getOverflowCount() const
constexpr unsigned long CTRL2_EACEN
bool isRemoteTransmissionRequest() const
constexpr unsigned long MCR_WRNEN
uavcan::int16_t doReset(Timings timings)
const uavcan::uint8_t useFIFO
const UAVCAN_EXPORT T & min(const T &a, const T &b)
constexpr unsigned long CTRL1_LOM
virtual uavcan::int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline)
uavcan::uint32_t overflow_cnt_
constexpr unsigned long MCR_RFEN
constexpr unsigned long MCR_HALT
uavcan::MonotonicTime getMonotonic()
virtual uavcan::int16_t configureFilters(const uavcan::CanFilterConfig *filter_configs, uavcan::uint16_t num_configs)
constexpr unsigned long CTRL1_PRESDIV_SHIFT
virtual uavcan::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags)
bool canAcceptNewTxFrame(const uavcan::CanFrame &frame) const
constexpr unsigned long CTRL1_RWRNMSK
uavcan::uint8_t peak_tx_mailbox_index_
enum uavcan_kinetis::CanIface::TxItem::@143 pending
constexpr unsigned long CTRL1_CLKSRC
static const uavcan::int16_t ErrMcrFRZACKAckNotCleared
MCR_FRZACK bit of the MCR register is not 0.
virtual uavcan::int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags)
uavcan::uint64_t getUtcUSecFromCanInterrupt()
unsigned getRxQueueLength() const
Item buf_[UAVCAN_LPC11C24_RX_QUEUE_LEN]
void push(const uavcan::CanFrame &frame, const uint64_t &utc_usec, uavcan::CanIOFlags flags)
CanIface(flexcan::CanType *can, BusEvent &update_event, uavcan::uint8_t self_index, CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
constexpr unsigned long MCR_IRMQ
const uavcan::uint8_t CLOCKSEL
bool setEnable(bool enable_true)
constexpr unsigned long MCR_SLFWAK
flexcan::CanType *const can_
int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode)
void pop(uavcan::CanFrame &out_frame, uavcan::uint64_t &out_utc_usec, uavcan::CanIOFlags &out_flags)
constexpr unsigned long ESR2_LPTM_SHIFT
bool priorityHigherThan(const CanFrame &rhs) const
const uavcan::uint32_t OSCERCLK
static const uavcan::int16_t ErrMcrLPMAckNotSet
MCR_LPMACK bit of the MCR register is not 1.
volatile uint32_t RXFGMASK
volatile uint32_t RX15MASK
bool isRxBufferEmpty() const
static const CanIOFlags CanIOFlagAbortOnError
uavcan::uint32_t served_aborts_cnt_
static const uavcan::int16_t ErrMcrFRZACKAckNotSet
MCR_FRZACK bit of the MCR register is not 1.
constexpr unsigned long MCR_SRXDIS
TxItem pending_tx_[NumTxMesgBuffers]
void signalFromInterrupt()
static const uint32_t FlagRTR
Remote transmission request.
#define UAVCAN_KINETIS_LOG(fmt,...)
constexpr unsigned long ESR1_CRCERR
uavcan::uint64_t error_cnt_
constexpr unsigned long CTRL2_TASD_SHIFT