libuav original

Dependents:   UAVCAN UAVCAN_Subscriber

Embed: (wiki syntax)

« Back to documentation index

CanDriver Class Reference

This class implements CAN driver interface for libuavcan. More...

#include <can.hpp>

Inherits uavcan::ICanDriver, uavcan::ICanIface, and uavcan::Noncopyable.

Public Member Functions

int init (uavcan::uint32_t bitrate)
 Returns negative value if the requested baudrate can't be used.
bool hadActivity ()
 This method will return true only if there was any CAN bus activity since previous call of this method.
uavcan::uint32_t getRxQueueOverflowCount () const
 Returns the number of times the RX queue was overrun.
bool isInBusOffState () const
 Whether the controller is currently in bus off state.
uavcan::int16_t send (const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override
 Non-blocking transmission.
uavcan::int16_t receive (uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
 Non-blocking reception.
uavcan::int16_t configureFilters (const uavcan::CanFilterConfig *filter_configs, uavcan::uint16_t num_configs) override
 Configure the hardware CAN filters.
uavcan::uint64_t getErrorCount () const override
 Continuously incrementing counter of hardware errors.
uavcan::uint16_t getNumFilters () const override
 Number of available hardware filters.
uavcan::ICanIfacegetIface (uavcan::uint8_t iface_index) override
 Returns an interface by index, or null pointer if the index is out of range.
uavcan::uint8_t getNumIfaces () const override
 Total number of available CAN interfaces.
virtual const ICanIface * getIface (uint8_t iface_index) const
 Default implementation of this method calls the non-const overload of getIface().
virtual int16_t select (CanSelectMasks &inout_masks, const CanFrame *(&pending_tx)[MaxCanIfaces], MonotonicTime blocking_deadline)=0
 Block until the deadline, or one of the specified interfaces becomes available for read or write.

Static Public Member Functions

static CanDriverinstance ()
 Returns the singleton reference.
static uavcan::uint32_t detectBitRate (void(*idle_callback)()=nullptr)
 Attempts to detect bit rate of the CAN bus.

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 drivers/lpc11c24/driver/include/uavcan_lpc11c24/can.hpp.


Member Function Documentation

uavcan::int16_t configureFilters ( const uavcan::CanFilterConfig filter_configs,
uavcan::uint16_t  num_configs 
) [override, virtual]

Configure the hardware CAN filters.

CanFilterConfig.

Returns:
0 = success, negative for error.

Implements ICanIface.

Definition at line 469 of file can.cpp.

uavcan::uint32_t 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.

uavcan::uint64_t getErrorCount (  ) const [override, virtual]

Continuously incrementing counter of hardware errors.

Arbitration lost should not be treated as a hardware error.

Implements ICanIface.

Definition at line 541 of file can.cpp.

virtual const ICanIface* getIface ( uint8_t  iface_index ) const [virtual, inherited]

Default implementation of this method calls the non-const overload of getIface().

Can be overriden by the application if necessary.

Definition at line 211 of file include/uavcan/driver/can.hpp.

uavcan::ICanIface * getIface ( uavcan::uint8_t  iface_index ) [override, virtual]

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

Implements ICanDriver.

Definition at line 552 of file can.cpp.

uavcan::uint16_t getNumFilters (  ) const [override, virtual]

Number of available hardware filters.

Implements ICanIface.

Definition at line 547 of file can.cpp.

uavcan::uint8_t getNumIfaces (  ) const [override, virtual]

Total number of available CAN interfaces.

This value shall not change after initialization.

Implements ICanDriver.

Definition at line 557 of file can.cpp.

uavcan::uint32_t getRxQueueOverflowCount (  ) const

Returns the number of times the RX queue was overrun.

Definition at line 350 of file can.cpp.

bool 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.

int 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.

static CanDriver& instance (  ) [static]

Returns the singleton reference.

No other copies can be created.

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

bool 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.

uavcan::int16_t receive ( uavcan::CanFrame out_frame,
uavcan::MonotonicTime &  out_ts_monotonic,
uavcan::UtcTime out_ts_utc,
uavcan::CanIOFlags &  out_flags 
) [override, virtual]

Non-blocking reception.

Timestamps should be provided by the CAN driver, ideally by the hardware CAN controller.

Monotonic timestamp is required and can be not precise since it is needed only for protocol timing validation (transfer timeouts and inter-transfer intervals).

UTC timestamp is optional, if available it will be used for precise time synchronization; must be set to zero if not available.

Refer to ISystemClock to learn more about timestamps.

Parameters:
[out]out_ts_monotonicMonotonic timestamp, mandatory.
[out]out_ts_utcUTC timestamp, optional, zero if unknown.
Returns:
1 = one frame received, 0 = RX buffer empty, negative for error.

Implements ICanIface.

Definition at line 405 of file can.cpp.

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

Block until the deadline, or one of the specified interfaces becomes available for read or write.

Iface masks will be modified by the driver to indicate which exactly interfaces are available for IO.

Bit position in the masks defines interface index.

Note that it is allowed to return from this method even if no requested events actually happened, or if there are events that were not requested by the library.

The pending TX argument contains an array of pointers to CAN frames that the library wants to transmit next, per interface. This is intended to allow the driver to properly prioritize transmissions; many drivers will not need to use it. If a write flag for the given interface is set to one in the select mask structure, then the corresponding pointer is guaranteed to be valid (not UAVCAN_NULLPTR).

Parameters:
[in,out]inout_masksMasks indicating which interfaces are needed/available for IO.
[in]pending_txArray of frames, per interface, that are likely to be transmitted next.
[in]blocking_deadlineZero means non-blocking operation.
Returns:
Positive number of ready interfaces or negative error code.
uavcan::int16_t send ( const uavcan::CanFrame frame,
uavcan::MonotonicTime  tx_deadline,
uavcan::CanIOFlags  flags 
) [override, virtual]

Non-blocking transmission.

If the frame wasn't transmitted upon TX deadline, the driver should discard it.

Note that it is LIKELY that the library will want to send the frames that were passed into the select() method as the next ones to transmit, but it is NOT guaranteed. The library can replace those with new frames between the calls.

Returns:
1 = one frame transmitted, 0 = TX buffer full, negative for error.

Implements ICanIface.

Definition at line 361 of file can.cpp.