PX4 Firmware
PX4 Autopilot Software http://px4.io
uavcan_kinetis::CanIface Class Reference

Single CAN iface. More...

#include <can.hpp>

Inheritance diagram for uavcan_kinetis::CanIface:
Collaboration diagram for uavcan_kinetis::CanIface:

Classes

class  RxQueue
 
struct  Timings
 
struct  TxItem
 

Public Types

enum  { MaxRxQueueCapacity = 254 }
 
enum  OperatingMode { NormalMode, SilentMode }
 

Public Member Functions

 CanIface (flexcan::CanType *can, BusEvent &update_event, uavcan::uint8_t self_index, CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
 
int init (const uavcan::uint32_t bitrate, const OperatingMode mode)
 Initializes the hardware CAN controller. More...
 
void handleTxInterrupt (uavcan::uint32_t tx_iflags, uavcan::uint64_t utc_usec)
 
void handleRxInterrupt (uavcan::uint32_t rx_iflags, uavcan::uint64_t utc_usec)
 
void pollErrorFlagsFromISR ()
 This method is used to count errors and abort transmission on error if necessary. More...
 
void discardTimedOutTxMailboxes (uavcan::MonotonicTime current_time)
 
bool canAcceptNewTxFrame (const uavcan::CanFrame &frame) const
 
bool isRxBufferEmpty () const
 
uavcan::uint32_t getRxQueueOverflowCount () const
 Number of RX frames lost due to queue overflow. More...
 
virtual uavcan::uint64_t getErrorCount () const
 Total number of hardware failures and other kinds of errors (e.g. More...
 
uavcan::uint32_t getVoluntaryTxAbortCount () const
 Number of times the driver exercised library's requirement to abort transmission on first error. More...
 
unsigned getRxQueueLength () const
 Returns the number of frames pending in the RX queue. More...
 
bool hadActivity ()
 Whether this iface had at least one successful IO since the previous call of this method. More...
 
uavcan::uint8_t getPeakNumTxMailboxesUsed () const
 Peak number of TX mailboxes used concurrently since initialization. More...
 

Private Types

enum  { NumTxMesgBuffers = 6 }
 
enum  { NumFilters = 16 }
 

Private Member Functions

int computeTimings (uavcan::uint32_t target_bitrate, Timings &out_timings)
 
virtual uavcan::int16_t send (const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags)
 
virtual uavcan::int16_t receive (uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags)
 
virtual uavcan::int16_t configureFilters (const uavcan::CanFilterConfig *filter_configs, uavcan::uint16_t num_configs)
 
virtual uavcan::uint16_t getNumFilters () const
 
void handleTxMailboxInterrupt (uavcan::uint8_t mailbox_index, bool txok, uavcan::uint64_t utc_usec)
 
bool waitMCRChange (uavcan::uint32_t mask, bool target_state)
 
void setMCR (uavcan::uint32_t mask, bool target_state)
 
bool setEnable (bool enable_true)
 
uavcan::int16_t doReset (Timings timings)
 
bool waitFreezeAckChange (bool target_state)
 
void setFreeze (bool freeze_true)
 

Private Attributes

const uavcan::uint32_t FIFO_IFLAG1 = flexcan::CAN_FIFO_NE | flexcan::CAN_FIFO_WARN | flexcan::CAN_FIFO_OV
 
uavcan::uint8_t MaxMB
 
RxQueue rx_queue_
 
flexcan::CanType *const can_
 
uavcan::uint64_t error_cnt_
 
uavcan::uint64_t fifo_warn_cnt_
 
uavcan::uint32_t pending_aborts_
 
uavcan::uint32_t served_aborts_cnt_
 
BusEventupdate_event_
 
TxItem pending_tx_ [NumTxMesgBuffers]
 
uavcan::uint8_t peak_tx_mailbox_index_
 
const uavcan::uint8_t self_index_
 
bool had_activity_
 

Detailed Description

Single CAN iface.

The application shall not use this directly.

Definition at line 50 of file can.hpp.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
private
Enumerator
NumTxMesgBuffers 

Definition at line 123 of file can.hpp.

◆ anonymous enum

anonymous enum
private
Enumerator
NumFilters 

Definition at line 124 of file can.hpp.

◆ anonymous enum

anonymous enum
Enumerator
MaxRxQueueCapacity 

Definition at line 167 of file can.hpp.

◆ OperatingMode

Enumerator
NormalMode 
SilentMode 

Definition at line 169 of file can.hpp.

Constructor & Destructor Documentation

◆ CanIface()

uavcan_kinetis::CanIface::CanIface ( flexcan::CanType can,
BusEvent update_event,
uavcan::uint8_t  self_index,
CanRxItem rx_queue_buffer,
uavcan::uint8_t  rx_queue_capacity 
)
inline

Definition at line 174 of file can.hpp.

References uavcan_kinetis::CanRxItem::frame, and ToneAlarmInterface::init().

Here is the call graph for this function:

Member Function Documentation

◆ canAcceptNewTxFrame()

bool uavcan_kinetis::CanIface::canAcceptNewTxFrame ( const uavcan::CanFrame &  frame) const

Definition at line 758 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::flexcan::ESR2_IMB, uavcan_kinetis::flexcan::ESR2_VPS, and MicroBenchHRT::lock().

Here is the call graph for this function:

◆ computeTimings()

int uavcan_kinetis::CanIface::computeTimings ( uavcan::uint32_t  target_bitrate,
Timings out_timings 
)
private

Definition at line 138 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::flexcan::canclk, uavcan_kinetis::ErrInvalidBitRate, math::min(), uavcan_kinetis::CanIface::Timings::prescaler, uavcan_kinetis::CanIface::Timings::propseg, uavcan_kinetis::CanIface::Timings::pseg1, uavcan_kinetis::CanIface::Timings::pseg2, and uavcan_kinetis::CanIface::Timings::rjw.

Here is the call graph for this function:

◆ configureFilters()

uavcan::int16_t uavcan_kinetis::CanIface::configureFilters ( const uavcan::CanFilterConfig *  filter_configs,
uavcan::uint16_t  num_configs 
)
privatevirtual

◆ discardTimedOutTxMailboxes()

void uavcan_kinetis::CanIface::discardTimedOutTxMailboxes ( uavcan::MonotonicTime  current_time)

Definition at line 743 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::CanIface::TxItem::deadline, MicroBenchHRT::lock(), uavcan_kinetis::flexcan::NumMBinFiFoAndFilters, uavcan_kinetis::CanIface::TxItem::pending, and uavcan_kinetis::flexcan::TxMbAbort.

Here is the call graph for this function:

◆ doReset()

◆ getErrorCount()

uavcan::uint64_t uavcan_kinetis::CanIface::getErrorCount ( ) const
virtual

Total number of hardware failures and other kinds of errors (e.g.

queue overruns). May increase continuously if the interface is not connected to the bus.

Definition at line 793 of file uc_kinetis_flexcan.cpp.

References MicroBenchHRT::lock().

Here is the call graph for this function:

◆ getNumFilters()

virtual uavcan::uint16_t uavcan_kinetis::CanIface::getNumFilters ( ) const
inlineprivatevirtual

Definition at line 151 of file can.hpp.

References uavcan_kinetis::CanRxItem::utc_usec.

◆ getPeakNumTxMailboxesUsed()

uavcan::uint8_t uavcan_kinetis::CanIface::getPeakNumTxMailboxesUsed ( ) const
inline

Peak number of TX mailboxes used concurrently since initialization.

Range is [1, 3]. Value of 3 suggests that priority inversion could be taking place.

Definition at line 259 of file can.hpp.

◆ getRxQueueLength()

unsigned uavcan_kinetis::CanIface::getRxQueueLength ( ) const

Returns the number of frames pending in the RX queue.

This is intended for debug use only.

Definition at line 799 of file uc_kinetis_flexcan.cpp.

References MicroBenchHRT::lock().

Here is the call graph for this function:

◆ getRxQueueOverflowCount()

uavcan::uint32_t uavcan_kinetis::CanIface::getRxQueueOverflowCount ( ) const
inline

Number of RX frames lost due to queue overflow.

This is an atomic read, it doesn't require a critical section.

Definition at line 221 of file can.hpp.

References uavcan_kinetis::CanIface::RxQueue::getOverflowCount().

Here is the call graph for this function:

◆ getVoluntaryTxAbortCount()

uavcan::uint32_t uavcan_kinetis::CanIface::getVoluntaryTxAbortCount ( ) const
inline

Number of times the driver exercised library's requirement to abort transmission on first error.

This is an atomic read, it doesn't require a critical section. See uavcan::CanIOFlagAbortOnError.

Definition at line 237 of file can.hpp.

◆ hadActivity()

bool uavcan_kinetis::CanIface::hadActivity ( )

Whether this iface had at least one successful IO since the previous call of this method.

This is designed for use with iface activity LEDs.

Definition at line 805 of file uc_kinetis_flexcan.cpp.

References MicroBenchHRT::lock().

Here is the call graph for this function:

◆ handleRxInterrupt()

◆ handleTxInterrupt()

void uavcan_kinetis::CanIface::handleTxInterrupt ( uavcan::uint32_t  tx_iflags,
uavcan::uint64_t  utc_usec 
)

◆ handleTxMailboxInterrupt()

void uavcan_kinetis::CanIface::handleTxMailboxInterrupt ( uavcan::uint8_t  mailbox_index,
bool  txok,
uavcan::uint64_t  utc_usec 
)
private

◆ init()

◆ isRxBufferEmpty()

bool uavcan_kinetis::CanIface::isRxBufferEmpty ( ) const

Definition at line 787 of file uc_kinetis_flexcan.cpp.

References MicroBenchHRT::lock().

Referenced by uavcan_kinetis::CanInitHelper< RxQueueCapacity >::init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pollErrorFlagsFromISR()

void uavcan_kinetis::CanIface::pollErrorFlagsFromISR ( )

This method is used to count errors and abort transmission on error if necessary.

This functionality used to be implemented in the SCE interrupt handler, but that approach was generating too much processing overhead, especially on disconnected interfaces.

Should be called from RX ISR, TX ISR, and select(); interrupts must be enabled.

Definition at line 712 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::CanIface::TxItem::abort_on_error, uavcan_kinetis::flexcan::ESR1_ACKERR, uavcan_kinetis::flexcan::ESR1_BIT0ERR, uavcan_kinetis::flexcan::ESR1_BIT1ERR, uavcan_kinetis::flexcan::ESR1_CRCERR, uavcan_kinetis::flexcan::ESR1_FRMERR, uavcan_kinetis::flexcan::ESR1_STFERR, uavcan_kinetis::flexcan::NumMBinFiFoAndFilters, uavcan_kinetis::CanIface::TxItem::pending, and uavcan_kinetis::flexcan::TxMbAbort.

◆ receive()

uavcan::int16_t uavcan_kinetis::CanIface::receive ( uavcan::CanFrame &  out_frame,
uavcan::MonotonicTime &  out_ts_monotonic,
uavcan::UtcTime &  out_ts_utc,
uavcan::CanIOFlags &  out_flags 
)
privatevirtual

Definition at line 300 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::clock::getMonotonic(), and MicroBenchHRT::lock().

Here is the call graph for this function:

◆ send()

uavcan::int16_t uavcan_kinetis::CanIface::send ( const uavcan::CanFrame &  frame,
uavcan::MonotonicTime  tx_deadline,
uavcan::CanIOFlags  flags 
)
privatevirtual

◆ setEnable()

bool uavcan_kinetis::CanIface::setEnable ( bool  enable_true)
private

◆ setFreeze()

void uavcan_kinetis::CanIface::setFreeze ( bool  freeze_true)
private

Definition at line 418 of file uc_kinetis_flexcan.cpp.

References MicroBenchHRT::lock(), uavcan_kinetis::flexcan::MCR_FRZ, and uavcan_kinetis::flexcan::MCR_HALT.

Here is the call graph for this function:

◆ setMCR()

void uavcan_kinetis::CanIface::setMCR ( uavcan::uint32_t  mask,
bool  target_state 
)
private

Definition at line 402 of file uc_kinetis_flexcan.cpp.

◆ waitFreezeAckChange()

bool uavcan_kinetis::CanIface::waitFreezeAckChange ( bool  target_state)
private

Definition at line 413 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::flexcan::MCR_FRZACK.

◆ waitMCRChange()

bool uavcan_kinetis::CanIface::waitMCRChange ( uavcan::uint32_t  mask,
bool  target_state 
)
private

Definition at line 385 of file uc_kinetis_flexcan.cpp.

References state.

Member Data Documentation

◆ can_

flexcan::CanType* const uavcan_kinetis::CanIface::can_
private

Definition at line 129 of file can.hpp.

◆ error_cnt_

uavcan::uint64_t uavcan_kinetis::CanIface::error_cnt_
private

Definition at line 130 of file can.hpp.

◆ FIFO_IFLAG1

const uavcan::uint32_t uavcan_kinetis::CanIface::FIFO_IFLAG1 = flexcan::CAN_FIFO_NE | flexcan::CAN_FIFO_WARN | flexcan::CAN_FIFO_OV
private

Definition at line 53 of file can.hpp.

◆ fifo_warn_cnt_

uavcan::uint64_t uavcan_kinetis::CanIface::fifo_warn_cnt_
private

Definition at line 131 of file can.hpp.

◆ had_activity_

bool uavcan_kinetis::CanIface::had_activity_
private

Definition at line 138 of file can.hpp.

◆ MaxMB

uavcan::uint8_t uavcan_kinetis::CanIface::MaxMB
private

Definition at line 126 of file can.hpp.

◆ peak_tx_mailbox_index_

uavcan::uint8_t uavcan_kinetis::CanIface::peak_tx_mailbox_index_
private

Definition at line 136 of file can.hpp.

◆ pending_aborts_

uavcan::uint32_t uavcan_kinetis::CanIface::pending_aborts_
private

Definition at line 132 of file can.hpp.

◆ pending_tx_

TxItem uavcan_kinetis::CanIface::pending_tx_[NumTxMesgBuffers]
private

Definition at line 135 of file can.hpp.

◆ rx_queue_

RxQueue uavcan_kinetis::CanIface::rx_queue_
private

Definition at line 128 of file can.hpp.

◆ self_index_

const uavcan::uint8_t uavcan_kinetis::CanIface::self_index_
private

Definition at line 137 of file can.hpp.

◆ served_aborts_cnt_

uavcan::uint32_t uavcan_kinetis::CanIface::served_aborts_cnt_
private

Definition at line 133 of file can.hpp.

◆ update_event_

BusEvent& uavcan_kinetis::CanIface::update_event_
private

Definition at line 134 of file can.hpp.


The documentation for this class was generated from the following files: