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

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

#include <can.hpp>

Inheritance diagram for uavcan_stm32::CanDriver:
Collaboration diagram for uavcan_stm32::CanDriver:

Public Member Functions

template<unsigned RxQueueCapacity>
 CanDriver (CanRxItem(&rx_queue_storage)[UAVCAN_STM32_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...
 
BusEvent & updateEvent ()
 

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 230 of file can.hpp.

Constructor & Destructor Documentation

◆ CanDriver()

template<unsigned RxQueueCapacity>
uavcan_stm32::CanDriver::CanDriver ( CanRxItem(&)  rx_queue_storage[UAVCAN_STM32_NUM_IFACES][RxQueueCapacity])
inline

Definition at line 246 of file can.hpp.

References ToneAlarmInterface::init().

Here is the call graph for this function:

Member Function Documentation

◆ getIface()

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

Definition at line 973 of file uc_stm32_can.cpp.

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

Here is the caller graph for this function:

◆ getNumIfaces()

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

Definition at line 274 of file can.hpp.

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

Here is the caller graph for this function:

◆ hadActivity()

bool uavcan_stm32::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 982 of file uc_stm32_can.cpp.

References UAVCAN_STM32_IRQ_HANDLER().

Here is the call graph for this function:

◆ hasReadableInterfaces()

bool uavcan_stm32::CanDriver::hasReadableInterfaces ( ) const

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

Definition at line 824 of file uc_stm32_can.cpp.

◆ init()

int uavcan_stm32::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 920 of file uc_stm32_can.cpp.

References UAVCAN_STM32_LOG.

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

Here is the caller graph for this function:

◆ initOnce()

void uavcan_stm32::CanDriver::initOnce ( )
staticprivate

Definition at line 869 of file uc_stm32_can.cpp.

References IRQ_ATTACH, and MicroBenchHRT::lock().

Here is the call graph for this function:

◆ makeSelectMasks()

uavcan::CanSelectMasks uavcan_stm32::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 796 of file uc_stm32_can.cpp.

◆ select()

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

Definition at line 835 of file uc_stm32_can.cpp.

References uavcan_stm32::clock::getMonotonic(), and uavcan_stm32::CanIface::update_event_.

Here is the call graph for this function:

◆ updateEvent()

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

Definition at line 282 of file can.hpp.

Referenced by UavcanEsc::start().

Here is the caller graph for this function:

Member Data Documentation

◆ if0_

CanIface uavcan_stm32::CanDriver::if0_
private

Definition at line 233 of file can.hpp.

◆ update_event_

BusEvent uavcan_stm32::CanDriver::update_event_
private

Definition at line 232 of file can.hpp.


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