Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Attributes | List of all members
uavcan_lpc11c24::CanDriver Class Reference

#include <can.hpp>

Inheritance diagram for uavcan_lpc11c24::CanDriver:
Inheritance graph
[legend]

Public Member Functions

uavcan::int16_t configureFilters (const uavcan::CanFilterConfig *filter_configs, uavcan::uint16_t num_configs) override
 
uavcan::uint64_t getErrorCount () const override
 
uavcan::ICanIfacegetIface (uavcan::uint8_t iface_index) override
 
uavcan::uint16_t getNumFilters () const override
 
uavcan::uint8_t getNumIfaces () const override
 
uavcan::uint32_t getRxQueueOverflowCount () const
 
bool hadActivity ()
 
bool hasEmptyTx () const
 
bool hasReadyRx () const
 
int init (uavcan::uint32_t bitrate)
 
bool isInBusOffState () const
 
uavcan::int16_t receive (uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
 
uavcan::int16_t select (uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
 
uavcan::int16_t send (const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override
 
- Public Member Functions inherited from uavcan::ICanDriver
virtual const ICanIfacegetIface (uint8_t iface_index) const
 
virtual int16_t select (CanSelectMasks &inout_masks, const CanFrame *(&pending_tx)[MaxCanIfaces], MonotonicTime blocking_deadline)=0
 
virtual ~ICanDriver ()
 
- Public Member Functions inherited from uavcan::ICanIface
virtual int16_t receive (CanFrame &out_frame, MonotonicTime &out_ts_monotonic, UtcTime &out_ts_utc, CanIOFlags &out_flags)=0
 
virtual int16_t send (const CanFrame &frame, MonotonicTime tx_deadline, CanIOFlags flags)=0
 
virtual ~ICanIface ()
 

Static Public Member Functions

static uavcan::uint32_t detectBitRate (void(*idle_callback)()=nullptr)
 
static CanDriverinstance ()
 

Private Member Functions

 CanDriver ()
 
- Private Member Functions inherited from uavcan::Noncopyable
 Noncopyable ()
 
 ~Noncopyable ()
 

Static Private Attributes

static CanDriver self
 

Detailed Description

This class implements CAN driver interface for libuavcan. No configuration needed other than CAN baudrate. This class is a singleton.

Definition at line 16 of file platform_specific_components/lpc11c24/libuavcan/driver/include/uavcan_lpc11c24/can.hpp.

Constructor & Destructor Documentation

◆ CanDriver()

uavcan_lpc11c24::CanDriver::CanDriver ( )
inlineprivate

Member Function Documentation

◆ configureFilters()

uavcan::int16_t uavcan_lpc11c24::CanDriver::configureFilters ( const uavcan::CanFilterConfig filter_configs,
uavcan::uint16_t  num_configs 
)
overridevirtual

Configure the hardware CAN filters. CanFilterConfig.

Returns
0 = success, negative for error.

Implements uavcan::ICanIface.

Definition at line 469 of file can.cpp.

◆ detectBitRate()

uavcan::uint32_t uavcan_lpc11c24::CanDriver::detectBitRate ( void(*)()  idle_callback = nullptr)
static

Attempts to detect bit rate of the CAN bus. This function may block for up to X seconds, where X is the number of bit rates to try. This function is NOT guaranteed to reset the CAN controller upon return.

Returns
On success: detected bit rate, in bits per second. On failure: zero.

Definition at line 171 of file can.cpp.

◆ getErrorCount()

uavcan::uint64_t uavcan_lpc11c24::CanDriver::getErrorCount ( ) const
overridevirtual

Continuously incrementing counter of hardware errors. Arbitration lost should not be treated as a hardware error.

Implements uavcan::ICanIface.

Definition at line 541 of file can.cpp.

◆ getIface()

uavcan::ICanIface * uavcan_lpc11c24::CanDriver::getIface ( uavcan::uint8_t  iface_index)
overridevirtual

Returns an interface by index, or null pointer if the index is out of range.

Implements uavcan::ICanDriver.

Definition at line 552 of file can.cpp.

◆ getNumFilters()

uavcan::uint16_t uavcan_lpc11c24::CanDriver::getNumFilters ( ) const
overridevirtual

Number of available hardware filters.

Implements uavcan::ICanIface.

Definition at line 547 of file can.cpp.

◆ getNumIfaces()

uavcan::uint8_t uavcan_lpc11c24::CanDriver::getNumIfaces ( ) const
overridevirtual

Total number of available CAN interfaces. This value shall not change after initialization.

Implements uavcan::ICanDriver.

Definition at line 557 of file can.cpp.

◆ getRxQueueOverflowCount()

uavcan::uint32_t uavcan_lpc11c24::CanDriver::getRxQueueOverflowCount ( ) const

Returns the number of times the RX queue was overrun.

Definition at line 350 of file can.cpp.

◆ hadActivity()

bool uavcan_lpc11c24::CanDriver::hadActivity ( )

This method will return true only if there was any CAN bus activity since previous call of this method. This is intended to be used for LED iface activity indicators.

Definition at line 342 of file can.cpp.

◆ hasEmptyTx()

bool uavcan_lpc11c24::CanDriver::hasEmptyTx ( ) const

Definition at line 336 of file can.cpp.

◆ hasReadyRx()

bool uavcan_lpc11c24::CanDriver::hasReadyRx ( ) const

Definition at line 330 of file can.cpp.

◆ init()

int uavcan_lpc11c24::CanDriver::init ( uavcan::uint32_t  bitrate)

Returns negative value if the requested baudrate can't be used. Returns zero if OK.

Definition at line 274 of file can.cpp.

◆ instance()

static CanDriver& uavcan_lpc11c24::CanDriver::instance ( )
inlinestatic

Returns the singleton reference. No other copies can be created.

Definition at line 30 of file platform_specific_components/lpc11c24/libuavcan/driver/include/uavcan_lpc11c24/can.hpp.

◆ isInBusOffState()

bool uavcan_lpc11c24::CanDriver::isInBusOffState ( ) const

Whether the controller is currently in bus off state. Note that the driver recovers the CAN controller from the bus off state automatically! Therefore, this method serves only monitoring purposes and is not necessary to use.

Definition at line 356 of file can.cpp.

◆ receive()

uavcan::int16_t uavcan_lpc11c24::CanDriver::receive ( uavcan::CanFrame out_frame,
uavcan::MonotonicTime out_ts_monotonic,
uavcan::UtcTime out_ts_utc,
uavcan::CanIOFlags out_flags 
)
override

Definition at line 405 of file can.cpp.

◆ select()

uavcan::int16_t uavcan_lpc11c24::CanDriver::select ( uavcan::CanSelectMasks inout_masks,
const uavcan::CanFrame (&)[uavcan::MaxCanIfaces],
uavcan::MonotonicTime  blocking_deadline 
)
override

Definition at line 422 of file can.cpp.

◆ send()

uavcan::int16_t uavcan_lpc11c24::CanDriver::send ( const uavcan::CanFrame frame,
uavcan::MonotonicTime  tx_deadline,
uavcan::CanIOFlags  flags 
)
override

Definition at line 361 of file can.cpp.

Member Data Documentation

◆ self

CanDriver uavcan_lpc11c24::CanDriver::self
staticprivate

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


uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:05