APM:Libraries
CAN.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017 Eugene Shamaev
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #pragma once
19 
20 #include <inttypes.h>
21 #include <string.h>
22 #include <assert.h>
23 #include <cmath>
24 
25 #if HAL_WITH_UAVCAN
26 
27 #include "AP_HAL_Namespace.h"
28 #include "utility/functor.h"
29 #include <uavcan/driver/can.hpp>
30 #include <uavcan/time.hpp>
31 
32 #define MAX_NUMBER_OF_CAN_INTERFACES 2
33 #define MAX_NUMBER_OF_CAN_DRIVERS 2
34 
35 class AP_UAVCAN;
36 
40 class AP_HAL::CAN: public uavcan::ICanIface {
41 public:
42  /* CAN port open method
43 
44  bitrate Selects the speed that the port will be configured to. If zero, the port speed is left unchanged.
45 
46  return false - CAN port open failed
47  true - CAN port open succeeded
48  */
49  virtual bool begin(uint32_t bitrate) = 0;
50 
51  /*
52  CAN port close
53  */
54  virtual void end() = 0;
55 
56  /*
57  Reset opened CAN port
58 
59  Pending messages to be transmitted are deleted and receive state and FIFO also reset.
60  All pending errors are cleared.
61  */
62  virtual void reset() = 0;
63 
64  /*
65  Test if CAN port is opened and initialized
66 
67  return false - CAN port not initialized
68  true - CAN port is initialized
69  */
70  virtual bool is_initialized() = 0;
71 
72  /*
73  Return if CAN port has some untransmitted pending messages
74 
75  return -1 - CAN port is not opened or initialized
76  0 - no messages are pending
77  positive - number of pending messages
78  */
79  virtual int32_t tx_pending() = 0;
80 
81  /*
82  Return if CAN port has received but yet read messages
83 
84  return -1 - CAN port is not opened or initialized
85  0 - no messages are pending for read
86  positive - number of pending messages for read
87  */
88  virtual int32_t available() = 0;
89 
90 };
91 
95 class AP_HAL::CANManager {
96 public:
97  CANManager(uavcan::ICanDriver* driver) : _driver(driver) {}
98 
99  /* CAN port open method
100  Opens port with specified bit rate
101  bitrate - selects the speed that the port will be configured to. If zero, the port speed is left
102  unchanged.
103  can_number - the index of can interface to be opened
104 
105  return false - CAN port open failed
106  true - CAN port open succeeded
107  */
108  virtual bool begin(uint32_t bitrate, uint8_t can_number) = 0;
109 
110  /*
111  Test if CAN manager is ready and initialized
112  return false - CAN manager not initialized
113  true - CAN manager is initialized
114  */
115  virtual bool is_initialized() = 0;
116  virtual void initialized(bool val) = 0;
117 
118  virtual AP_UAVCAN *get_UAVCAN(void) = 0;
119  virtual void set_UAVCAN(AP_UAVCAN *uavcan) = 0;
120  uavcan::ICanDriver* get_driver() { return _driver; }
121 private:
122  uavcan::ICanDriver* _driver;
123 };
124 
125 #endif
void reset()