11 #include <systemlib/perf_counter.h> 14 #include <semaphore.h> 19 #if defined(GPIO_CAN2_RX) && defined(GPIO_CAN2_TX) 20 #define CAN_STM32_NUM_IFACES 2 22 #define CAN_STM32_NUM_IFACES 1 25 #define CAN_STM32_RX_QUEUE_SIZE 64 80 bool wait(uavcan::MonotonicDuration duration);
81 static void signalFromCallOut(
BusEvent *sem);
83 void signalFromInterrupt();
96 prescaler(0), sjw(0), bs1(0), bs2(0)
112 pending(false), loopback(false), abort_on_error(false)
124 static const uint32_t TSR_ABRQx[NumTxMailboxes];
139 int computeTimings(uint32_t target_bitrate,
Timings& out_timings);
141 virtual int16_t send(
const uavcan::CanFrame&
frame, uavcan::MonotonicTime tx_deadline,
142 uavcan::CanIOFlags
flags)
override;
144 virtual int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
145 uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
override;
147 virtual int16_t configureFilters(
const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs)
override;
154 void handleTxMailboxInterrupt(uint8_t mailbox_index,
bool txok, uint64_t
utc_usec);
156 bool waitMsrINakBitStateChange(
bool target_state);
161 MaxRxQueueCapacity = 254
165 NormalMode, SilentMode
169 rx_queue_(rx_queue_capacity), can_(can), error_cnt_(0), served_aborts_cnt_(0), update_event_(
170 update_event), peak_tx_mailbox_index_(0), self_index_(self_index), had_activity_(false), bitrate_(
171 0), initialized_(false)
187 update_event_ = update_event;
190 void handleTxInterrupt(uint64_t utc_usec);
191 void handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec);
200 void pollErrorFlagsFromISR();
202 void discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time);
204 bool canAcceptNewTxFrame(
const uavcan::CanFrame&
frame)
const;
205 bool isRxBufferEmpty()
const;
211 virtual uint64_t getErrorCount()
const override;
220 return served_aborts_cnt_;
227 unsigned getRxQueueLength()
const;
242 return uint8_t(peak_tx_mailbox_index_ + 1);
245 bool begin(uint32_t bitrate)
override;
250 void reset()
override;
252 int32_t tx_pending()
override;
253 int32_t available()
override;
255 bool is_initialized()
override;
263 virtual int16_t select(uavcan::CanSelectMasks& inout_masks,
264 const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline)
override;
266 void initOnce(uint8_t can_number);
282 uavcan::CanSelectMasks makeSelectMasks(
const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces])
const;
287 bool hasReadableInterfaces()
const;
295 virtual VRBRAINCAN* getIface(uint8_t iface_index)
override;
296 VRBRAINCAN* getIface_out_to_in(uint8_t iface_index);
309 bool begin(uint32_t bitrate, uint8_t can_number)
override;
311 bool is_initialized()
override;
312 void initialized(
bool val)
override;
315 void set_UAVCAN(
AP_UAVCAN *uavcan)
override;
uint32_t getVoluntaryTxAbortCount() const
uint64_t getUtcUSecFromCanInterrupt()
static const int16_t ErrUnknown
Reserved for future use.
uint8_t peak_tx_mailbox_index_
VRBRAINCAN(bxcan::CanType *can, BusEvent *update_event, uint8_t self_index, uint8_t rx_queue_capacity)
static const int16_t ErrNotImplemented
Feature not implemented.
static const int16_t ErrFilterNumConfigs
Auto bit rate detection could not be finished.
#define CAN_STM32_NUM_IFACES
static const int16_t ErrBitRateNotDetected
Auto bit rate detection could not be finished.
static const int16_t ErrInvalidBitRate
Bit rate not supported.
volatile uint16_t _signal
void set_update_event(BusEvent *update_event)
static const int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
ObjectBuffer< CanRxItem > rx_queue_
static const int16_t ErrLogic
Internal logic error.
bxcan::CanType *const can_
uavcan::MonotonicTime getMonotonic()
uavcan::MonotonicTime deadline
uint32_t served_aborts_cnt_
static const int16_t ErrMsrInakNotSet
INAK bit of the MSR register is not 1.
static const int16_t ErrMsrInakNotCleared
INAK bit of the MSR register is not 0.
virtual uint16_t getNumFilters() const override
void init()
Generic board initialization function.
uint8_t getPeakNumTxMailboxesUsed() const
const uint8_t self_index_
virtual uint8_t getNumIfaces() const override