CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CANManager/AP_CANManager.h
Views: 1798
1
/*
2
* This file is free software: you can redistribute it and/or modify it
3
* under the terms of the GNU General Public License as published by the
4
* Free Software Foundation, either version 3 of the License, or
5
* (at your option) any later version.
6
*
7
* This file is distributed in the hope that it will be useful, but
8
* WITHOUT ANY WARRANTY; without even the implied warranty of
9
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10
* See the GNU General Public License for more details.
11
*
12
* You should have received a copy of the GNU General Public License along
13
* with this program. If not, see <http://www.gnu.org/licenses/>.
14
*
15
* Code by Siddharth Bharat Purohit
16
*/
17
18
#pragma once
19
20
#include "AP_CANManager_config.h"
21
22
#if HAL_CANMANAGER_ENABLED
23
24
#include <AP_HAL/AP_HAL.h>
25
26
#include <AP_Param/AP_Param.h>
27
#include "AP_SLCANIface.h"
28
#include "AP_CANDriver.h"
29
#include <GCS_MAVLink/GCS_config.h>
30
#if HAL_GCS_ENABLED
31
#include <GCS_MAVLink/GCS_MAVLink.h>
32
#include <AP_HAL/utility/RingBuffer.h>
33
#endif
34
35
#include "AP_CAN.h"
36
37
class CANSensor;
38
39
class AP_CANManager
40
{
41
public:
42
AP_CANManager();
43
44
/* Do not allow copies */
45
CLASS_NO_COPY(AP_CANManager);
46
47
static AP_CANManager* get_singleton()
48
{
49
if (_singleton == nullptr) {
50
AP_HAL::panic("CANManager used before allocation.");
51
}
52
return _singleton;
53
}
54
55
enum LogLevel : uint8_t {
56
LOG_NONE,
57
LOG_ERROR,
58
LOG_WARNING,
59
LOG_INFO,
60
LOG_DEBUG,
61
};
62
63
void init(void);
64
65
// register a new driver
66
bool register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver);
67
68
// register a new auxillary sensor driver for 11 bit address frames
69
bool register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index);
70
71
// returns number of active CAN Drivers
72
uint8_t get_num_drivers(void) const
73
{
74
return HAL_MAX_CAN_PROTOCOL_DRIVERS;
75
}
76
77
// return driver for index i
78
AP_CANDriver* get_driver(uint8_t i) const
79
{
80
if (i < ARRAY_SIZE(_drivers)) {
81
return _drivers[i];
82
}
83
return nullptr;
84
}
85
86
// returns current log level
87
LogLevel get_log_level(void) const
88
{
89
return LogLevel(_loglevel.get());
90
}
91
92
// Method to log status and debug information for review while debugging
93
void log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...) FMT_PRINTF(4,5);
94
95
void log_retrieve(ExpandingString &str) const;
96
97
// return driver type index i
98
AP_CAN::Protocol get_driver_type(uint8_t i) const
99
{
100
if (i < ARRAY_SIZE(_driver_type_cache)) {
101
return _driver_type_cache[i];
102
}
103
return AP_CAN::Protocol::None;
104
}
105
106
static const struct AP_Param::GroupInfo var_info[];
107
108
#if HAL_GCS_ENABLED
109
bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg);
110
void handle_can_frame(const mavlink_message_t &msg);
111
void handle_can_filter_modify(const mavlink_message_t &msg);
112
#endif
113
114
private:
115
116
// Parameter interface for CANIfaces
117
class CANIface_Params
118
{
119
friend class AP_CANManager;
120
121
public:
122
CANIface_Params()
123
{
124
AP_Param::setup_object_defaults(this, var_info);
125
}
126
127
static const struct AP_Param::GroupInfo var_info[];
128
129
enum class Options : uint32_t {
130
LOG_ALL_FRAMES = (1U<<0),
131
};
132
133
bool option_is_set(Options option) const {
134
return (_options & uint32_t(option)) != 0;
135
}
136
137
private:
138
AP_Int8 _driver_number;
139
AP_Int32 _bitrate;
140
AP_Int32 _fdbitrate;
141
AP_Int32 _options;
142
143
#if AP_CAN_LOGGING_ENABLED && HAL_LOGGING_ENABLED
144
uint8_t logging_id;
145
#endif
146
};
147
148
//Parameter Interface for CANDrivers
149
class CANDriver_Params
150
{
151
friend class AP_CANManager;
152
153
public:
154
CANDriver_Params()
155
{
156
AP_Param::setup_object_defaults(this, var_info);
157
}
158
static const struct AP_Param::GroupInfo var_info[];
159
160
private:
161
AP_Int8 _driver_type;
162
AP_Int8 _driver_type_11bit;
163
AP_CANDriver* _uavcan;
164
AP_CANDriver* _piccolocan;
165
};
166
167
CANIface_Params _interfaces[HAL_NUM_CAN_IFACES];
168
AP_CANDriver* _drivers[HAL_MAX_CAN_PROTOCOL_DRIVERS];
169
CANDriver_Params _drv_param[HAL_MAX_CAN_PROTOCOL_DRIVERS];
170
AP_CAN::Protocol _driver_type_cache[HAL_MAX_CAN_PROTOCOL_DRIVERS];
171
172
AP_Int8 _loglevel;
173
uint8_t _num_drivers;
174
#if AP_CAN_SLCAN_ENABLED
175
SLCAN::CANIface _slcan_interface;
176
#endif
177
178
static AP_CANManager *_singleton;
179
180
char* _log_buf;
181
uint32_t _log_pos;
182
183
HAL_Semaphore _sem;
184
185
#if HAL_GCS_ENABLED
186
/*
187
handler for CAN frames from the registered callback, sending frames
188
out as CAN_FRAME messages
189
*/
190
void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame);
191
192
struct {
193
mavlink_channel_t chan;
194
uint8_t system_id;
195
uint8_t component_id;
196
uint8_t frame_counter;
197
uint32_t last_callback_enable_ms;
198
HAL_Semaphore sem;
199
uint16_t num_filter_ids;
200
uint16_t *filter_ids;
201
uint8_t callback_id;
202
uint8_t callback_bus;
203
} can_forward;
204
205
// buffer for MAVCAN frames
206
struct BufferFrame {
207
uint8_t bus;
208
AP_HAL::CANFrame frame;
209
};
210
ObjectBuffer<BufferFrame> *frame_buffer;
211
212
void process_frame_buffer(void);
213
#endif // HAL_GCS_ENABLED
214
215
#if AP_CAN_LOGGING_ENABLED && HAL_LOGGING_ENABLED
216
/*
217
handler for CAN frames for logging
218
*/
219
void can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame);
220
void check_logging_enable(void);
221
#endif
222
};
223
224
namespace AP
225
{
226
AP_CANManager& can();
227
}
228
229
#endif // HAL_CANMANAGER_ENABLED
230
231