24 class HALSITL::HALSITLCAN :
public AP_HAL::CAN {
28 int16_t send(
const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags)
override;
29 int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic, uavcan::UtcTime& out_ts_utc,
30 uavcan::CanIOFlags& out_flags)
override;
31 int16_t configureFilters(
const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs)
override;
32 uint16_t getNumFilters()
const override;
33 uint64_t getErrorCount()
const override;
35 bool begin(uint32_t bitrate)
override;
37 void reset()
override;
38 bool is_initialized()
override;
39 int32_t tx_pending()
override;
40 int32_t available()
override;
45 volatile bool _initialised;
46 volatile bool _in_timer;
49 class HALSITL::HALSITLCANDriver :
public AP_HAL::CANManager
52 HALSITLCANDriver() { }
53 ~HALSITLCANDriver() { }
54 uavcan::ICanIface* getIface(uint8_t iface_index)
override;
55 const uavcan::ICanIface* getIface(uint8_t iface_index)
const override;
56 uint8_t getNumIfaces()
const override;
57 int16_t select(uavcan::CanSelectMasks& inout_masks,
58 const uavcan::CanFrame* (& pending_tx)[uavcan::MaxCanIfaces],
59 uavcan::MonotonicTime blocking_deadline)
override;