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_DroneCAN/AP_DroneCAN.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
* Author: Eugene Shamaev, Siddharth Bharat Purohit
16
*/
17
#pragma once
18
19
#include <AP_HAL/AP_HAL.h>
20
21
#if HAL_ENABLE_DRONECAN_DRIVERS
22
23
#include "AP_Canard_iface.h"
24
#include <AP_CANManager/AP_CANManager.h>
25
#include <AP_HAL/Semaphores.h>
26
#include <AP_Param/AP_Param.h>
27
#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>
28
#include <SRV_Channel/SRV_Channel_config.h>
29
#include <canard/publisher.h>
30
#include <canard/subscriber.h>
31
#include <canard/service_client.h>
32
#include <canard/service_server.h>
33
#include <stdio.h>
34
#include "AP_DroneCAN_DNA_Server.h"
35
#include <canard.h>
36
#include <dronecan_msgs.h>
37
#include <AP_SerialManager/AP_SerialManager_config.h>
38
#include <AP_Relay/AP_Relay_config.h>
39
#include <AP_Servo_Telem/AP_Servo_Telem_config.h>
40
41
#ifndef DRONECAN_SRV_NUMBER
42
#define DRONECAN_SRV_NUMBER NUM_SERVO_CHANNELS
43
#endif
44
45
#ifndef AP_DRONECAN_SEND_GPS
46
#define AP_DRONECAN_SEND_GPS (BOARD_FLASH_SIZE > 1024)
47
#endif
48
49
#define AP_DRONECAN_SW_VERS_MAJOR 1
50
#define AP_DRONECAN_SW_VERS_MINOR 0
51
52
#define AP_DRONECAN_HW_VERS_MAJOR 1
53
#define AP_DRONECAN_HW_VERS_MINOR 0
54
55
56
#ifndef AP_DRONECAN_HOBBYWING_ESC_SUPPORT
57
#define AP_DRONECAN_HOBBYWING_ESC_SUPPORT (BOARD_FLASH_SIZE>1024)
58
#endif
59
60
#ifndef AP_DRONECAN_HIMARK_SERVO_SUPPORT
61
#define AP_DRONECAN_HIMARK_SERVO_SUPPORT (BOARD_FLASH_SIZE>1024)
62
#endif
63
64
#ifndef AP_DRONECAN_SERIAL_ENABLED
65
#define AP_DRONECAN_SERIAL_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024)
66
#endif
67
68
#ifndef AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
69
#define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0
70
#endif
71
72
#if AP_DRONECAN_SERIAL_ENABLED
73
#include "AP_DroneCAN_serial.h"
74
#endif
75
76
// fwd-declare callback classes
77
class AP_DroneCAN_DNA_Server;
78
class CANSensor;
79
80
class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend {
81
friend class AP_DroneCAN_DNA_Server;
82
public:
83
AP_DroneCAN(const int driver_index);
84
~AP_DroneCAN();
85
86
static const struct AP_Param::GroupInfo var_info[];
87
88
// Return uavcan from @driver_index or nullptr if it's not ready or doesn't exist
89
static AP_DroneCAN *get_dronecan(uint8_t driver_index);
90
bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const;
91
92
void init(uint8_t driver_index, bool enable_filters) override;
93
bool add_interface(AP_HAL::CANIface* can_iface) override;
94
95
// add an 11 bit auxillary driver
96
bool add_11bit_driver(CANSensor *sensor) override;
97
98
// handler for outgoing frames for auxillary drivers
99
bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) override;
100
101
uint8_t get_driver_index() const { return _driver_index; }
102
103
// define string with length structure
104
struct string { uint8_t len; uint8_t data[128]; };
105
106
FUNCTOR_TYPEDEF(ParamGetSetIntCb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &);
107
FUNCTOR_TYPEDEF(ParamGetSetFloatCb, bool, AP_DroneCAN*, const uint8_t, const char*, float &);
108
FUNCTOR_TYPEDEF(ParamGetSetStringCb, bool, AP_DroneCAN*, const uint8_t, const char*, string &);
109
FUNCTOR_TYPEDEF(ParamSaveCb, void, AP_DroneCAN*, const uint8_t, bool);
110
111
void send_node_status();
112
113
///// SRV output /////
114
void SRV_push_servos(void);
115
116
///// LED /////
117
bool led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue);
118
119
// buzzer
120
void set_buzzer_tone(float frequency, float duration_s);
121
122
// Send Reboot command
123
// Note: Do not call this from outside UAVCAN thread context,
124
// you can call this from dronecan callbacks and handlers.
125
// THIS IS NOT A THREAD SAFE API!
126
void send_reboot_request(uint8_t node_id);
127
128
// get or set param value
129
// returns true on success, false on failure
130
// failures occur when waiting on node to respond to previous get or set request
131
bool set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb);
132
bool set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb);
133
bool set_parameter_on_node(uint8_t node_id, const char *name, const string &value, ParamGetSetStringCb *cb);
134
bool get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb);
135
bool get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetIntCb *cb);
136
bool get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetStringCb *cb);
137
138
// Save parameters
139
bool save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb);
140
141
// options bitmask
142
enum class Options : uint16_t {
143
DNA_CLEAR_DATABASE = (1U<<0),
144
DNA_IGNORE_DUPLICATE_NODE = (1U<<1),
145
CANFD_ENABLED = (1U<<2),
146
DNA_IGNORE_UNHEALTHY_NODE = (1U<<3),
147
USE_ACTUATOR_PWM = (1U<<4),
148
SEND_GNSS = (1U<<5),
149
USE_HIMARK_SERVO = (1U<<6),
150
USE_HOBBYWING_ESC = (1U<<7),
151
ENABLE_STATS = (1U<<8),
152
ENABLE_FLEX_DEBUG = (1U<<9),
153
};
154
155
// check if a option is set
156
bool option_is_set(Options option) const {
157
return (uint16_t(_options.get()) & uint16_t(option)) != 0;
158
}
159
160
// check if a option is set and if it is then reset it to
161
// 0. return true if it was set
162
bool check_and_reset_option(Options option);
163
164
CanardInterface& get_canard_iface() { return canard_iface; }
165
166
Canard::Publisher<uavcan_equipment_indication_LightsCommand> rgb_led{canard_iface};
167
Canard::Publisher<uavcan_equipment_indication_BeepCommand> buzzer{canard_iface};
168
Canard::Publisher<uavcan_equipment_gnss_RTCMStream> rtcm_stream{canard_iface};
169
170
// xacti specific publishers
171
Canard::Publisher<com_xacti_CopterAttStatus> xacti_copter_att_status{canard_iface};
172
Canard::Publisher<com_xacti_GimbalControlData> xacti_gimbal_control_data{canard_iface};
173
Canard::Publisher<com_xacti_GnssStatus> xacti_gnss_status{canard_iface};
174
175
#if AP_RELAY_DRONECAN_ENABLED
176
// Hardpoint for relay
177
// Needs to be public so relay can edge trigger as well as streaming
178
Canard::Publisher<uavcan_equipment_hardpoint_Command> relay_hardpoint{canard_iface};
179
#endif
180
181
#if AP_SCRIPTING_ENABLED
182
bool get_FlexDebug(uint8_t node_id, uint16_t msg_id, uint32_t &timestamp_us, dronecan_protocol_FlexDebug &msg) const;
183
#endif
184
185
private:
186
void loop(void);
187
188
///// SRV output /////
189
void SRV_send_actuator();
190
void SRV_send_esc();
191
#if AP_DRONECAN_HIMARK_SERVO_SUPPORT
192
void SRV_send_himark();
193
#endif
194
195
//scale servo output appropriately before sending
196
int16_t scale_esc_output(uint8_t idx);
197
198
// SafetyState
199
void safety_state_send();
200
201
// send notify vehicle state
202
void notify_state_send();
203
204
// check for parameter get/set response timeout
205
void check_parameter_callback_timeout();
206
207
// send queued parameter get/set request. called from loop
208
void send_parameter_request();
209
210
// send queued parameter save request. called from loop
211
void send_parameter_save_request();
212
213
// periodic logging
214
void logging();
215
216
// get parameter on a node
217
ParamGetSetIntCb *param_int_cb; // latest get param request callback function (for integers)
218
ParamGetSetFloatCb *param_float_cb; // latest get param request callback function (for floats)
219
ParamGetSetStringCb *param_string_cb; // latest get param request callback function (for strings)
220
bool param_request_sent = true; // true after a param request has been sent, false when queued to be sent
221
uint32_t param_request_sent_ms; // system time that get param request was sent
222
HAL_Semaphore _param_sem; // semaphore protecting this block of variables
223
uint8_t param_request_node_id; // node id of most recent get param request
224
225
// save parameters on a node
226
ParamSaveCb *save_param_cb; // latest save param request callback function
227
bool param_save_request_sent = true; // true after a save param request has been sent, false when queued to be sent
228
HAL_Semaphore _param_save_sem; // semaphore protecting this block of variables
229
uint8_t param_save_request_node_id; // node id of most recent save param request
230
231
// UAVCAN parameters
232
AP_Int8 _dronecan_node;
233
AP_Int32 _servo_bm;
234
AP_Int32 _esc_bm;
235
AP_Int8 _esc_offset;
236
AP_Int16 _servo_rate_hz;
237
AP_Int16 _options;
238
AP_Int16 _notify_state_hz;
239
AP_Int16 _pool_size;
240
AP_Int32 _esc_rv;
241
242
uint32_t *mem_pool;
243
244
uint8_t _driver_index;
245
246
CanardInterface canard_iface;
247
248
AP_DroneCAN_DNA_Server _dna_server;
249
250
char _thread_name[13];
251
bool _initialized;
252
///// SRV output /////
253
struct {
254
uint16_t pulse;
255
bool esc_pending;
256
bool servo_pending;
257
} _SRV_conf[DRONECAN_SRV_NUMBER];
258
259
uint32_t _esc_send_count;
260
uint32_t _srv_send_count;
261
uint32_t _fail_send_count;
262
263
uint32_t _SRV_armed_mask; // mask of servo outputs that are active
264
uint32_t _ESC_armed_mask; // mask of ESC outputs that are active
265
uint32_t _SRV_last_send_us;
266
HAL_Semaphore SRV_sem;
267
268
// last log time
269
uint32_t last_log_ms;
270
271
#if AP_DRONECAN_SEND_GPS
272
// send GNSS Fix and yaw, same thing AP_GPS_DroneCAN would receive
273
void gnss_send_fix();
274
void gnss_send_yaw();
275
276
// GNSS Fix and Status
277
struct {
278
uint32_t last_gps_lib_fix_ms;
279
uint32_t last_send_status_ms;
280
uint32_t last_lib_yaw_time_ms;
281
} _gnss;
282
#endif
283
284
// node status send
285
uint32_t _node_status_last_send_ms;
286
287
// safety status send state
288
uint32_t _last_safety_state_ms;
289
290
// notify vehicle state
291
uint32_t _last_notify_state_ms;
292
uavcan_protocol_NodeStatus node_status_msg;
293
294
#if AP_RELAY_DRONECAN_ENABLED
295
void relay_hardpoint_send();
296
struct {
297
AP_Int16 rate_hz;
298
uint32_t last_send_ms;
299
uint8_t last_index;
300
} _relay;
301
#endif
302
303
#if AP_DRONECAN_SERIAL_ENABLED
304
AP_DroneCAN_Serial serial;
305
#endif
306
307
Canard::Publisher<uavcan_protocol_NodeStatus> node_status{canard_iface};
308
Canard::Publisher<dronecan_protocol_CanStats> can_stats{canard_iface};
309
Canard::Publisher<dronecan_protocol_Stats> protocol_stats{canard_iface};
310
Canard::Publisher<uavcan_equipment_actuator_ArrayCommand> act_out_array{canard_iface};
311
Canard::Publisher<uavcan_equipment_esc_RawCommand> esc_raw{canard_iface};
312
Canard::Publisher<ardupilot_indication_SafetyState> safety_state{canard_iface};
313
Canard::Publisher<uavcan_equipment_safety_ArmingStatus> arming_status{canard_iface};
314
Canard::Publisher<ardupilot_indication_NotifyState> notify_state{canard_iface};
315
316
#if AP_DRONECAN_HIMARK_SERVO_SUPPORT
317
Canard::Publisher<com_himark_servo_ServoCmd> himark_out{canard_iface};
318
#endif
319
320
#if AP_DRONECAN_SEND_GPS
321
Canard::Publisher<uavcan_equipment_gnss_Fix2> gnss_fix2{canard_iface};
322
Canard::Publisher<uavcan_equipment_gnss_Auxiliary> gnss_auxiliary{canard_iface};
323
Canard::Publisher<ardupilot_gnss_Heading> gnss_heading{canard_iface};
324
Canard::Publisher<ardupilot_gnss_Status> gnss_status{canard_iface};
325
#endif
326
// incoming messages
327
Canard::ObjCallback<AP_DroneCAN, ardupilot_indication_Button> safety_button_cb{this, &AP_DroneCAN::handle_button};
328
Canard::Subscriber<ardupilot_indication_Button> safety_button_listener{safety_button_cb, _driver_index};
329
330
Canard::ObjCallback<AP_DroneCAN, ardupilot_equipment_trafficmonitor_TrafficReport> traffic_report_cb{this, &AP_DroneCAN::handle_traffic_report};
331
Canard::Subscriber<ardupilot_equipment_trafficmonitor_TrafficReport> traffic_report_listener{traffic_report_cb, _driver_index};
332
333
#if AP_SERVO_TELEM_ENABLED
334
Canard::ObjCallback<AP_DroneCAN, uavcan_equipment_actuator_Status> actuator_status_cb{this, &AP_DroneCAN::handle_actuator_status};
335
Canard::Subscriber<uavcan_equipment_actuator_Status> actuator_status_listener{actuator_status_cb, _driver_index};
336
#endif
337
338
Canard::ObjCallback<AP_DroneCAN, uavcan_equipment_esc_Status> esc_status_cb{this, &AP_DroneCAN::handle_ESC_status};
339
Canard::Subscriber<uavcan_equipment_esc_Status> esc_status_listener{esc_status_cb, _driver_index};
340
341
#if AP_EXTENDED_ESC_TELEM_ENABLED
342
Canard::ObjCallback<AP_DroneCAN, uavcan_equipment_esc_StatusExtended> esc_status_extended_cb{this, &AP_DroneCAN::handle_esc_ext_status};
343
Canard::Subscriber<uavcan_equipment_esc_StatusExtended> esc_status_extended_listener{esc_status_extended_cb, _driver_index};
344
#endif
345
346
Canard::ObjCallback<AP_DroneCAN, uavcan_protocol_debug_LogMessage> debug_cb{this, &AP_DroneCAN::handle_debug};
347
Canard::Subscriber<uavcan_protocol_debug_LogMessage> debug_listener{debug_cb, _driver_index};
348
349
#if AP_DRONECAN_HIMARK_SERVO_SUPPORT && AP_SERVO_TELEM_ENABLED
350
Canard::ObjCallback<AP_DroneCAN, com_himark_servo_ServoInfo> himark_servo_ServoInfo_cb{this, &AP_DroneCAN::handle_himark_servoinfo};
351
Canard::Subscriber<com_himark_servo_ServoInfo> himark_servo_ServoInfo_cb_listener{himark_servo_ServoInfo_cb, _driver_index};
352
#endif
353
#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
354
Canard::ObjCallback<AP_DroneCAN, com_volz_servo_ActuatorStatus> volz_servo_ActuatorStatus_cb{this, &AP_DroneCAN::handle_actuator_status_Volz};
355
Canard::Subscriber<com_volz_servo_ActuatorStatus> volz_servo_ActuatorStatus_listener{volz_servo_ActuatorStatus_cb, _driver_index};
356
#endif
357
358
// param client
359
Canard::ObjCallback<AP_DroneCAN, uavcan_protocol_param_GetSetResponse> param_get_set_res_cb{this, &AP_DroneCAN::handle_param_get_set_response};
360
Canard::Client<uavcan_protocol_param_GetSetResponse> param_get_set_client{canard_iface, param_get_set_res_cb};
361
362
Canard::ObjCallback<AP_DroneCAN, uavcan_protocol_param_ExecuteOpcodeResponse> param_save_res_cb{this, &AP_DroneCAN::handle_param_save_response};
363
Canard::Client<uavcan_protocol_param_ExecuteOpcodeResponse> param_save_client{canard_iface, param_save_res_cb};
364
365
// reboot client
366
void handle_restart_node_response(const CanardRxTransfer& transfer, const uavcan_protocol_RestartNodeResponse& msg) {}
367
Canard::ObjCallback<AP_DroneCAN, uavcan_protocol_RestartNodeResponse> restart_node_res_cb{this, &AP_DroneCAN::handle_restart_node_response};
368
Canard::Client<uavcan_protocol_RestartNodeResponse> restart_node_client{canard_iface, restart_node_res_cb};
369
370
uavcan_protocol_param_ExecuteOpcodeRequest param_save_req;
371
uavcan_protocol_param_GetSetRequest param_getset_req;
372
373
// Node Info Server
374
Canard::ObjCallback<AP_DroneCAN, uavcan_protocol_GetNodeInfoRequest> node_info_req_cb{this, &AP_DroneCAN::handle_node_info_request};
375
Canard::Server<uavcan_protocol_GetNodeInfoRequest> node_info_server{canard_iface, node_info_req_cb};
376
uavcan_protocol_GetNodeInfoResponse node_info_rsp;
377
378
#if AP_SCRIPTING_ENABLED
379
Canard::ObjCallback<AP_DroneCAN, dronecan_protocol_FlexDebug> FlexDebug_cb{this, &AP_DroneCAN::handle_FlexDebug};
380
Canard::Subscriber<dronecan_protocol_FlexDebug> FlexDebug_listener{FlexDebug_cb, _driver_index};
381
#endif
382
383
#if AP_DRONECAN_HOBBYWING_ESC_SUPPORT
384
/*
385
Hobbywing ESC support. Note that we need additional meta-data as
386
the status messages do not have an ESC ID in them, so we need a
387
mapping from node ID
388
*/
389
#define HOBBYWING_MAX_ESC 8
390
struct {
391
uint32_t last_GetId_send_ms;
392
uint8_t thr_chan[HOBBYWING_MAX_ESC];
393
} hobbywing;
394
void hobbywing_ESC_update();
395
396
void SRV_send_esc_hobbywing();
397
Canard::Publisher<com_hobbywing_esc_RawCommand> esc_hobbywing_raw{canard_iface};
398
Canard::Publisher<com_hobbywing_esc_GetEscID> esc_hobbywing_GetEscID{canard_iface};
399
Canard::ObjCallback<AP_DroneCAN, com_hobbywing_esc_GetEscID> esc_hobbywing_GetEscID_cb{this, &AP_DroneCAN::handle_hobbywing_GetEscID};
400
Canard::Subscriber<com_hobbywing_esc_GetEscID> esc_hobbywing_GetEscID_listener{esc_hobbywing_GetEscID_cb, _driver_index};
401
Canard::ObjCallback<AP_DroneCAN, com_hobbywing_esc_StatusMsg1> esc_hobbywing_StatusMSG1_cb{this, &AP_DroneCAN::handle_hobbywing_StatusMsg1};
402
Canard::Subscriber<com_hobbywing_esc_StatusMsg1> esc_hobbywing_StatusMSG1_listener{esc_hobbywing_StatusMSG1_cb, _driver_index};
403
Canard::ObjCallback<AP_DroneCAN, com_hobbywing_esc_StatusMsg2> esc_hobbywing_StatusMSG2_cb{this, &AP_DroneCAN::handle_hobbywing_StatusMsg2};
404
Canard::Subscriber<com_hobbywing_esc_StatusMsg2> esc_hobbywing_StatusMSG2_listener{esc_hobbywing_StatusMSG2_cb, _driver_index};
405
bool hobbywing_find_esc_index(uint8_t node_id, uint8_t &esc_index) const;
406
void handle_hobbywing_GetEscID(const CanardRxTransfer& transfer, const com_hobbywing_esc_GetEscID& msg);
407
void handle_hobbywing_StatusMsg1(const CanardRxTransfer& transfer, const com_hobbywing_esc_StatusMsg1& msg);
408
void handle_hobbywing_StatusMsg2(const CanardRxTransfer& transfer, const com_hobbywing_esc_StatusMsg2& msg);
409
#endif // AP_DRONECAN_HOBBYWING_ESC_SUPPORT
410
411
#if AP_DRONECAN_HIMARK_SERVO_SUPPORT && AP_SERVO_TELEM_ENABLED
412
void handle_himark_servoinfo(const CanardRxTransfer& transfer, const com_himark_servo_ServoInfo &msg);
413
#endif
414
415
// incoming button handling
416
void handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg);
417
void handle_traffic_report(const CanardRxTransfer& transfer, const ardupilot_equipment_trafficmonitor_TrafficReport& msg);
418
#if AP_SERVO_TELEM_ENABLED
419
void handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg);
420
#endif
421
#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
422
void handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg);
423
#endif
424
void handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg);
425
#if AP_EXTENDED_ESC_TELEM_ENABLED
426
void handle_esc_ext_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_StatusExtended& msg);
427
#endif
428
static bool is_esc_data_index_valid(const uint8_t index);
429
void handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg);
430
void handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp);
431
void handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp);
432
void handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req);
433
434
#if AP_SCRIPTING_ENABLED
435
void handle_FlexDebug(const CanardRxTransfer& transfer, const dronecan_protocol_FlexDebug& msg);
436
struct FlexDebug {
437
struct FlexDebug *next;
438
uint32_t timestamp_us;
439
uint8_t node_id;
440
dronecan_protocol_FlexDebug msg;
441
} *flexDebug_list;
442
#endif
443
};
444
445
#endif // #if HAL_ENABLE_DRONECAN_DRIVERS
446
447