APM:Libraries
CAN.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
3  *
4  * With modifications for Ardupilot CAN driver
5  * Copyright (C) 2017 Eugene Shamaev
6  */
7 
8 #pragma once
9 
10 #include "AP_HAL_VRBRAIN.h"
11 #include <systemlib/perf_counter.h>
12 #include <AP_HAL/CAN.h>
13 #include <pthread.h>
14 #include <semaphore.h>
15 
16 #include "bxcan.h"
18 
19 #if defined(GPIO_CAN2_RX) && defined(GPIO_CAN2_TX)
20 #define CAN_STM32_NUM_IFACES 2
21 #else
22 #define CAN_STM32_NUM_IFACES 1
23 #endif
24 
25 #define CAN_STM32_RX_QUEUE_SIZE 64
26 
27 namespace VRBRAIN {
32 static const int16_t ErrUnknown = 1000;
33 static const int16_t ErrNotImplemented = 1001;
34 static const int16_t ErrInvalidBitRate = 1002;
35 static const int16_t ErrLogic = 1003;
36 static const int16_t ErrUnsupportedFrame = 1004;
37 static const int16_t ErrMsrInakNotSet = 1005;
38 static const int16_t ErrMsrInakNotCleared = 1006;
39 static const int16_t ErrBitRateNotDetected = 1007;
40 static const int16_t ErrFilterNumConfigs = 1008;
41 
46 struct CanRxItem {
47  uint64_t utc_usec;
48  uavcan::CanFrame frame;
49  uavcan::CanIOFlags flags;
51  utc_usec(0), flags(0)
52  {
53  }
54 };
55 
57  const irqstate_t flags_;
58 
60  flags_(irqsave())
61  {
62  }
63 
65  {
66  irqrestore(flags_);
67  }
68 };
69 
70 namespace clock {
72 uavcan::MonotonicTime getMonotonic();
73 }
74 
75 class BusEvent: uavcan::Noncopyable {
76 public:
77  BusEvent(VRBRAINCANManager& can_driver);
78  ~BusEvent();
79 
80  bool wait(uavcan::MonotonicDuration duration);
81  static void signalFromCallOut(BusEvent *sem);
82 
83  void signalFromInterrupt();
85  volatile uint16_t _signal;
86 };
87 
88 class VRBRAINCAN: public AP_HAL::CAN {
89  struct Timings {
90  uint16_t prescaler;
91  uint8_t sjw;
92  uint8_t bs1;
93  uint8_t bs2;
94 
95  Timings() :
96  prescaler(0), sjw(0), bs1(0), bs2(0)
97  {
98  }
99  };
100 
101  struct TxItem {
102  uavcan::MonotonicTime deadline;
103  uavcan::CanFrame frame;
104 
105  bool pending;
106 
107  bool loopback;
108 
110 
111  TxItem() :
112  pending(false), loopback(false), abort_on_error(false)
113  {
114  }
115  };
116 
117  enum {
118  NumTxMailboxes = 3
119  };
120  enum {
121  NumFilters = 14
122  };
123 
124  static const uint32_t TSR_ABRQx[NumTxMailboxes];
125 
128  uint64_t error_cnt_;
131  TxItem pending_tx_[NumTxMailboxes];
133  const uint8_t self_index_;
134 
136 
137  uint32_t bitrate_;
138 
139  int computeTimings(uint32_t target_bitrate, Timings& out_timings);
140 
141  virtual int16_t send(const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline,
142  uavcan::CanIOFlags flags) override;
143 
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;
146 
147  virtual int16_t configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs) override;
148 
149  virtual uint16_t getNumFilters() const override
150  {
151  return NumFilters;
152  }
153 
154  void handleTxMailboxInterrupt(uint8_t mailbox_index, bool txok, uint64_t utc_usec);
155 
156  bool waitMsrINakBitStateChange(bool target_state);
157 
159 public:
160  enum {
161  MaxRxQueueCapacity = 254
162  };
163 
165  NormalMode, SilentMode
166  };
167 
168  VRBRAINCAN(bxcan::CanType* can, BusEvent* update_event, uint8_t self_index, uint8_t rx_queue_capacity) :
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)
172  {
173  UAVCAN_ASSERT(self_index_ < CAN_STM32_NUM_IFACES);
174  }
175 
183  int init(const uint32_t bitrate, const OperatingMode mode);
184 
185  void set_update_event(BusEvent* update_event)
186  {
187  update_event_ = update_event;
188  }
189 
190  void handleTxInterrupt(uint64_t utc_usec);
191  void handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec);
192 
200  void pollErrorFlagsFromISR();
201 
202  void discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time);
203 
204  bool canAcceptNewTxFrame(const uavcan::CanFrame& frame) const;
205  bool isRxBufferEmpty() const;
206 
211  virtual uint64_t getErrorCount() const override;
212 
218  uint32_t getVoluntaryTxAbortCount() const
219  {
220  return served_aborts_cnt_;
221  }
222 
227  unsigned getRxQueueLength() const;
228 
233  bool hadActivity();
234 
241  {
242  return uint8_t(peak_tx_mailbox_index_ + 1);
243  }
244 
245  bool begin(uint32_t bitrate) override;
246  void end() override
247  {
248  }
249 
250  void reset() override;
251 
252  int32_t tx_pending() override;
253  int32_t available() override;
254 
255  bool is_initialized() override;
256 };
257 
258 class VRBRAINCANManager: public AP_HAL::CANManager {
262 
263  virtual int16_t select(uavcan::CanSelectMasks& inout_masks,
264  const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override;
265 
266  void initOnce(uint8_t can_number);
267 
269 
271  uint8_t _ifaces_num;
272  uint8_t _ifaces_out_to_in[CAN_STM32_NUM_IFACES];
273 
275 
276 public:
278 
282  uavcan::CanSelectMasks makeSelectMasks(const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces]) const;
283 
287  bool hasReadableInterfaces() const;
288 
293  int init(const uint32_t bitrate, const VRBRAINCAN::OperatingMode mode, uint8_t can_number);
294 
295  virtual VRBRAINCAN* getIface(uint8_t iface_index) override;
296  VRBRAINCAN* getIface_out_to_in(uint8_t iface_index);
297 
298  virtual uint8_t getNumIfaces() const override
299  {
300  return _ifaces_num;
301  }
302 
307  bool hadActivity();
308 
309  bool begin(uint32_t bitrate, uint8_t can_number) override;
310 
311  bool is_initialized() override;
312  void initialized(bool val) override;
313 
314  AP_UAVCAN *get_UAVCAN(void) override;
315  void set_UAVCAN(AP_UAVCAN *uavcan) override;
316 };
317 }
uint32_t getVoluntaryTxAbortCount() const
Definition: CAN.h:218
uint64_t error_cnt_
Definition: CAN.h:128
uint64_t getUtcUSecFromCanInterrupt()
bool initialized_
Definition: CAN.h:158
static const int16_t ErrUnknown
Reserved for future use.
Definition: CAN.h:32
AP_UAVCAN * p_uavcan
Definition: CAN.h:274
uavcan::CanIOFlags flags
Definition: CAN.h:49
uint8_t peak_tx_mailbox_index_
Definition: CAN.h:132
VRBRAINCAN(bxcan::CanType *can, BusEvent *update_event, uint8_t self_index, uint8_t rx_queue_capacity)
Definition: CAN.h:168
void reset()
uint32_t bitrate_
Definition: CAN.h:137
static const int16_t ErrNotImplemented
Feature not implemented.
Definition: CAN.h:33
static const int16_t ErrFilterNumConfigs
Auto bit rate detection could not be finished.
Definition: CAN.h:40
uint64_t utc_usec
Definition: CAN.h:47
#define CAN_STM32_NUM_IFACES
Definition: CAN.h:22
static const int16_t ErrBitRateNotDetected
Auto bit rate detection could not be finished.
Definition: CAN.h:39
static const int16_t ErrInvalidBitRate
Bit rate not supported.
Definition: CAN.h:34
volatile uint16_t _signal
Definition: CAN.h:85
void set_update_event(BusEvent *update_event)
Definition: CAN.h:185
static const int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
Definition: CAN.h:36
bool had_activity_
Definition: CAN.h:135
ObjectBuffer< CanRxItem > rx_queue_
Definition: CAN.h:126
static const int16_t ErrLogic
Internal logic error.
Definition: CAN.h:35
bxcan::CanType *const can_
Definition: CAN.h:127
BusEvent update_event_
Definition: CAN.h:259
uavcan::MonotonicTime getMonotonic()
uavcan::MonotonicTime deadline
Definition: CAN.h:102
uint32_t served_aborts_cnt_
Definition: CAN.h:129
static const int16_t ErrMsrInakNotSet
INAK bit of the MSR register is not 1.
Definition: CAN.h:37
static const int16_t ErrMsrInakNotCleared
INAK bit of the MSR register is not 0.
Definition: CAN.h:38
uavcan::CanFrame frame
Definition: CAN.h:48
virtual uint16_t getNumFilters() const override
Definition: CAN.h:149
const irqstate_t flags_
Definition: CAN.h:57
void init()
Generic board initialization function.
Definition: system.cpp:136
uint8_t getPeakNumTxMailboxesUsed() const
Definition: CAN.h:240
void end() override
Definition: CAN.h:246
uavcan::CanFrame frame
Definition: CAN.h:103
const uint8_t self_index_
Definition: CAN.h:133
virtual uint8_t getNumIfaces() const override
Definition: CAN.h:298
BusEvent * update_event_
Definition: CAN.h:130
sem_t _wait_semaphore
Definition: CAN.h:84