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

CAN driver, incorporates all available CAN ifaces. More...

#include <can.hpp>

Inheritance diagram for uavcan_kinetis::CanDriver:
Collaboration diagram for uavcan_kinetis::CanDriver:

Public Member Functions

template<unsigned RxQueueCapacity>
 CanDriver (CanRxItem(&rx_queue_storage)[UAVCAN_KINETIS_NUM_IFACES][RxQueueCapacity])
 
uavcan::CanSelectMasks makeSelectMasks (const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces]) const
 This function returns select masks indicating which interfaces are available for read/write. More...
 
bool hasReadableInterfaces () const
 Whether there's at least one interface where receive() would return a frame. More...
 
int init (const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode)
 Returns zero if OK. More...
 
virtual CanIfacegetIface (uavcan::uint8_t iface_index)
 
virtual uavcan::uint8_t getNumIfaces () const
 
bool hadActivity ()
 Whether at least one iface had at least one successful IO since previous call of this method. More...
 
BusEventupdateEvent ()
 

Private Member Functions

virtual uavcan::int16_t select (uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline)
 

Static Private Member Functions

static void initOnce ()
 

Private Attributes

BusEvent update_event_
 
CanIface if0_
 

Detailed Description

CAN driver, incorporates all available CAN ifaces.

Please avoid direct use, prefer CanInitHelper instead.

Definition at line 269 of file can.hpp.

Constructor & Destructor Documentation

◆ CanDriver()

template<unsigned RxQueueCapacity>
uavcan_kinetis::CanDriver::CanDriver ( CanRxItem(&)  rx_queue_storage[UAVCAN_KINETIS_NUM_IFACES][RxQueueCapacity])
inline

Definition at line 286 of file can.hpp.

References ToneAlarmInterface::init().

Here is the call graph for this function:

Member Function Documentation

◆ getIface()

CanIface * uavcan_kinetis::CanDriver::getIface ( uavcan::uint8_t  iface_index)
virtual

Definition at line 972 of file uc_kinetis_flexcan.cpp.

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

Here is the caller graph for this function:

◆ getNumIfaces()

virtual uavcan::uint8_t uavcan_kinetis::CanDriver::getNumIfaces ( ) const
inlinevirtual

Definition at line 314 of file can.hpp.

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

Here is the caller graph for this function:

◆ hadActivity()

bool uavcan_kinetis::CanDriver::hadActivity ( )

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

This is designed for use with iface activity LEDs.

Definition at line 981 of file uc_kinetis_flexcan.cpp.

◆ hasReadableInterfaces()

bool uavcan_kinetis::CanDriver::hasReadableInterfaces ( ) const

Whether there's at least one interface where receive() would return a frame.

Definition at line 844 of file uc_kinetis_flexcan.cpp.

◆ init()

int uavcan_kinetis::CanDriver::init ( const uavcan::uint32_t  bitrate,
const CanIface::OperatingMode  mode 
)

Returns zero if OK.

Returns negative value if failed (e.g. invalid bitrate).

Definition at line 919 of file uc_kinetis_flexcan.cpp.

References UAVCAN_KINETIS_LOG.

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

Here is the caller graph for this function:

◆ initOnce()

void uavcan_kinetis::CanDriver::initOnce ( )
staticprivate

Definition at line 889 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::can0_irq(), IRQ_ATTACH, and MicroBenchHRT::lock().

Here is the call graph for this function:

◆ makeSelectMasks()

uavcan::CanSelectMasks uavcan_kinetis::CanDriver::makeSelectMasks ( const uavcan::CanFrame *(&)  pending_tx[uavcan::MaxCanIfaces]) const

This function returns select masks indicating which interfaces are available for read/write.

Definition at line 816 of file uc_kinetis_flexcan.cpp.

◆ select()

uavcan::int16_t uavcan_kinetis::CanDriver::select ( uavcan::CanSelectMasks &  inout_masks,
const uavcan::CanFrame *(&)  pending_tx[uavcan::MaxCanIfaces],
uavcan::MonotonicTime  blocking_deadline 
)
privatevirtual

Definition at line 855 of file uc_kinetis_flexcan.cpp.

References uavcan_kinetis::clock::getMonotonic().

Here is the call graph for this function:

◆ updateEvent()

BusEvent& uavcan_kinetis::CanDriver::updateEvent ( )
inline

Definition at line 325 of file can.hpp.

Member Data Documentation

◆ if0_

CanIface uavcan_kinetis::CanDriver::if0_
private

Definition at line 273 of file can.hpp.

◆ update_event_

BusEvent uavcan_kinetis::CanDriver::update_event_
private

Definition at line 272 of file can.hpp.


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