Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/AP_Periph.h
9592 views
1
#pragma once
2
3
#include <AP_HAL/AP_HAL.h>
4
#include <canard.h>
5
#include <AP_Param/AP_Param.h>
6
#include <AP_GPS/AP_GPS.h>
7
#include <AP_Compass/AP_Compass.h>
8
#include <AP_Baro/AP_Baro.h>
9
#include <AP_InertialSensor/AP_InertialSensor.h>
10
#include "SRV_Channel/SRV_Channel.h"
11
#include <AP_Notify/AP_Notify.h>
12
#include <AP_Logger/AP_Logger.h>
13
#include <AP_BattMonitor/AP_BattMonitor.h>
14
#include <AP_Airspeed/AP_Airspeed.h>
15
#include <AP_RangeFinder/AP_RangeFinder.h>
16
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
17
#include <AP_Proximity/AP_Proximity.h>
18
#include <AP_EFI/AP_EFI.h>
19
#include <AP_KDECAN/AP_KDECAN.h>
20
#include <AP_MSP/AP_MSP.h>
21
#include <AP_MSP/msp.h>
22
#include <AP_TemperatureSensor/AP_TemperatureSensor.h>
23
#include "../AP_Bootloader/app_comms.h"
24
#include <AP_CheckFirmware/AP_CheckFirmware.h>
25
#include "hwing_esc.h"
26
#include <AP_CANManager/AP_CAN.h>
27
#include <AP_CANManager/AP_SLCANIface.h>
28
#include <AP_Scripting/AP_Scripting.h>
29
#include <AP_HAL/CANIface.h>
30
#include <AP_Stats/AP_Stats.h>
31
#include <AP_RPM/AP_RPM.h>
32
#include <AP_SerialManager/AP_SerialManager.h>
33
#include <AP_ESC_Telem/AP_ESC_Telem_config.h>
34
#if HAL_WITH_ESC_TELEM
35
#include <AP_ESC_Telem/AP_ESC_Telem.h>
36
#endif
37
#if AP_PERIPH_RTC_ENABLED
38
#include <AP_RTC/AP_RTC.h>
39
#endif
40
#include <AP_RCProtocol/AP_RCProtocol_config.h>
41
#include "rc_in.h"
42
#include "batt_balance.h"
43
#include "battery_tag.h"
44
#include "battery_bms.h"
45
#include "actuator_telem.h"
46
#include "networking.h"
47
#include "serial_options.h"
48
#if AP_SIM_ENABLED
49
#include <SITL/SITL.h>
50
#endif
51
#include <AP_AHRS/AP_AHRS.h>
52
#include <AP_DAC/AP_DAC.h>
53
54
#if AP_PERIPH_RELAY_ENABLED
55
#if AP_PERIPH_PWM_HARDPOINT_ENABLED
56
#error "Relay and PWM_HARDPOINT both use hardpoint message"
57
#endif
58
#include <AP_Relay/AP_Relay.h>
59
#if !AP_RELAY_ENABLED
60
#error "AP_PERIPH_RELAY_ENABLED requires AP_RELAY_ENABLED"
61
#endif
62
#endif
63
64
#if AP_PERIPH_DEVICE_TEMPERATURE_ENABLED && !AP_TEMPERATURE_SENSOR_ENABLED
65
#error "AP_PERIPH_DEVICE_TEMPERATURE_ENABLED requires AP_TEMPERATURE_SENSOR_ENABLED"
66
#endif
67
68
#include <AP_NMEA_Output/AP_NMEA_Output.h>
69
#if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && AP_PERIPH_GPS_ENABLED)
70
// Needs SerialManager + (AHRS or GPS)
71
#error "AP_NMEA_Output requires Serial/GCS and either AHRS or GPS. Needs HAL_GCS_ENABLED and AP_PERIPH_GPS_ENABLED"
72
#endif
73
74
#if HAL_GCS_ENABLED
75
#include "GCS_MAVLink.h"
76
#endif
77
78
#include "esc_apd_telem.h"
79
80
#define AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || AP_PERIPH_NCP5623_LED_WITHOUT_NOTIFY_ENABLED || AP_PERIPH_NCP5623_BGR_LED_WITHOUT_NOTIFY_ENABLED || AP_PERIPH_TOSHIBA_LED_WITHOUT_NOTIFY_ENABLED)
81
82
#if AP_PERIPH_NOTIFY_ENABLED
83
#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED
84
#error "You cannot enable AP_PERIPH_NOTIFY_ENABLED and AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED at the same time. Notify already includes it"
85
#endif
86
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
87
#error "You cannot enable AP_PERIPH_NOTIFY_ENABLED and any AP_PERIPH_<device>_LED_WITHOUT_NOTIFY_ENABLED at the same time. Notify already includes them all"
88
#endif
89
#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY
90
#error "You cannot use AP_PERIPH_NOTIFY_ENABLED and HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY at the same time. Notify already includes it. Set param OUTx_FUNCTION=120"
91
#endif
92
#endif
93
94
#if AP_PERIPH_RPM_STREAM_ENABLED && !AP_PERIPH_RPM_ENABLED
95
#error "AP_PERIPH_RPM_STREAM_ENABLED requires AP_PERIPH_RPM_ENABLED"
96
#endif
97
98
#ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED
99
#define AP_PERIPH_SAFETY_SWITCH_ENABLED AP_PERIPH_RC_OUT_ENABLED
100
#endif
101
102
#ifndef HAL_PERIPH_CAN_MIRROR
103
#define HAL_PERIPH_CAN_MIRROR 0
104
#endif
105
106
#ifndef AP_SIM_PARAM_ENABLED
107
#define AP_SIM_PARAM_ENABLED AP_SIM_ENABLED
108
#endif
109
110
#if defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT) && !defined(HAL_DEBUG_BUILD) && !defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG)
111
/* this checking for reboot can lose bytes on GPS modules and other
112
* serial devices. It is really only relevant on a debug build if you
113
* really want it for non-debug build then define
114
* HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG in hwdef.dat
115
*/
116
#undef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
117
#endif
118
119
#include "Parameters.h"
120
121
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
122
void stm32_watchdog_init();
123
void stm32_watchdog_pat();
124
#endif
125
/*
126
app descriptor for firmware checking
127
*/
128
extern const app_descriptor_t app_descriptor;
129
130
extern "C" {
131
void can_vprintf(uint8_t severity, const char *fmt, va_list arg);
132
void can_printf_severity(uint8_t severity, const char *fmt, ...) FMT_PRINTF(2,3);
133
void can_printf(const char *fmt, ...) FMT_PRINTF(1,2);
134
}
135
136
struct CanardInstance;
137
struct CanardRxTransfer;
138
139
#define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \
140
(((uint32_t)(data_type_id)) | (((uint32_t)(transfer_type)) << 16U) | \
141
(((uint32_t)(src_node_id)) << 18U) | (((uint32_t)(dst_node_id)) << 25U))
142
143
#ifndef HAL_CAN_POOL_SIZE
144
#if HAL_CANFD_SUPPORTED
145
#define HAL_CAN_POOL_SIZE 16000
146
#elif GPS_MOVING_BASELINE
147
#define HAL_CAN_POOL_SIZE 8000
148
#else
149
#define HAL_CAN_POOL_SIZE 4000
150
#endif
151
#endif
152
153
class AP_Periph_FW {
154
public:
155
AP_Periph_FW();
156
157
CLASS_NO_COPY(AP_Periph_FW);
158
159
static AP_Periph_FW* get_singleton()
160
{
161
if (_singleton == nullptr) {
162
AP_HAL::panic("AP_Periph_FW used before allocation.");
163
}
164
return _singleton;
165
}
166
167
void init();
168
void update();
169
170
Parameters g;
171
172
void can_start();
173
void can_update();
174
void can_mag_update();
175
void can_gps_update();
176
void send_moving_baseline_msg();
177
void send_relposheading_msg();
178
void can_baro_update();
179
void can_airspeed_update();
180
#if AP_PERIPH_IMU_ENABLED
181
void can_imu_update();
182
#endif
183
184
#if AP_PERIPH_RANGEFINDER_ENABLED
185
void can_rangefinder_update();
186
#endif
187
void can_battery_update();
188
void can_battery_send_cells(uint8_t instance);
189
void can_proximity_update();
190
void can_buzzer_update(void);
191
void can_safety_button_update(void);
192
void can_safety_LED_update(void);
193
194
void load_parameters();
195
void prepare_reboot();
196
bool canfdout() const { return (g.can_fdmode == 1); }
197
198
#if AP_PERIPH_EFI_ENABLED
199
void can_efi_update();
200
#endif
201
202
#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
203
void check_for_serial_reboot_cmd(const int8_t serial_index);
204
#endif
205
206
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
207
static ChibiOS::CANIface* can_iface_periph[HAL_NUM_CAN_IFACES];
208
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
209
static HALSITL::CANIface* can_iface_periph[HAL_NUM_CAN_IFACES];
210
#endif
211
212
#if AP_CAN_SLCAN_ENABLED
213
static SLCAN::CANIface slcan_interface;
214
#endif
215
216
AP_SerialManager serial_manager;
217
218
#if AP_STATS_ENABLED
219
AP_Stats node_stats;
220
#endif
221
222
#if AP_GPS_ENABLED
223
AP_GPS gps;
224
#if HAL_NUM_CAN_IFACES >= 2
225
int8_t gps_mb_can_port = -1;
226
#endif
227
#endif
228
229
#if HAL_NMEA_OUTPUT_ENABLED
230
AP_NMEA_Output nmea;
231
#endif
232
233
#if AP_PERIPH_MAG_ENABLED
234
Compass compass;
235
#endif
236
237
#if AP_PERIPH_BARO_ENABLED
238
AP_Baro baro;
239
#endif
240
241
#if AP_PERIPH_IMU_ENABLED
242
AP_InertialSensor imu;
243
#endif
244
245
#if AP_PERIPH_RPM_ENABLED
246
AP_RPM rpm_sensor;
247
uint32_t rpm_last_update_ms;
248
#if AP_PERIPH_RPM_STREAM_ENABLED
249
void rpm_sensor_send();
250
uint32_t rpm_last_send_ms;
251
uint8_t rpm_last_sent_index;
252
#endif
253
#endif // AP_PERIPH_RPM_ENABLED
254
255
#if AP_PERIPH_BATTERY_ENABLED
256
void handle_battery_failsafe(const char* type_str, const int8_t action) { }
257
AP_BattMonitor battery_lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::handle_battery_failsafe, void, const char*, const int8_t), nullptr};
258
struct {
259
uint32_t last_read_ms;
260
uint32_t last_can_send_ms;
261
} battery;
262
#endif
263
264
#if HAL_NUM_CAN_IFACES >= 2
265
// This allows you to change the protocol and it continues to use the one at boot.
266
// Without this, changing away from UAVCAN causes loss of comms and you can't
267
// change the rest of your params or verify it succeeded.
268
AP_CAN::Protocol can_protocol_cached[HAL_NUM_CAN_IFACES];
269
#endif
270
271
#if AP_PERIPH_MSP_ENABLED
272
struct {
273
AP_MSP msp;
274
MSP::msp_port_t port;
275
uint32_t last_gps_ms;
276
uint32_t last_baro_ms;
277
uint32_t last_mag_ms;
278
uint32_t last_airspeed_ms;
279
} msp;
280
void msp_init(AP_HAL::UARTDriver *_uart);
281
void msp_sensor_update(void);
282
void send_msp_packet(uint16_t cmd, void *p, uint16_t size);
283
void send_msp_GPS(void);
284
void send_msp_compass(void);
285
void send_msp_baro(void);
286
void send_msp_airspeed(void);
287
#endif
288
289
#if AP_PERIPH_ADSB_ENABLED
290
void adsb_init();
291
void adsb_update();
292
void can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg);
293
struct {
294
mavlink_message_t msg;
295
mavlink_status_t status;
296
uint32_t last_heartbeat_ms;
297
} adsb;
298
#endif
299
300
#if AP_PERIPH_AIRSPEED_ENABLED
301
AP_Airspeed airspeed;
302
#endif
303
304
#if AP_PERIPH_RANGEFINDER_ENABLED
305
RangeFinder rangefinder;
306
uint32_t last_rangefinder_update_ms;
307
uint32_t last_rangefinder_sample_ms[RANGEFINDER_MAX_INSTANCES];
308
#endif
309
310
#if AP_PERIPH_PROXIMITY_ENABLED
311
AP_Proximity proximity;
312
#endif
313
314
#if AP_PERIPH_PWM_HARDPOINT_ENABLED
315
void pwm_irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp);
316
void pwm_hardpoint_init();
317
void pwm_hardpoint_update();
318
struct {
319
uint8_t last_state;
320
uint32_t last_ts_us;
321
uint32_t last_send_ms;
322
uint16_t pwm_value;
323
uint16_t highest_pwm;
324
} pwm_hardpoint;
325
#endif
326
327
#if AP_PERIPH_HOBBYWING_ESC_ENABLED
328
HWESC_Telem hwesc_telem;
329
void hwesc_telem_update();
330
#endif
331
332
#if AP_PERIPH_EFI_ENABLED
333
AP_EFI efi;
334
uint32_t efi_update_ms;
335
#endif
336
337
#if AP_KDECAN_ENABLED
338
AP_KDECAN kdecan;
339
#endif
340
341
#if AP_PERIPH_ESC_APD_ENABLED
342
ESC_APD_Telem *apd_esc_telem[APD_ESC_INSTANCES];
343
void apd_esc_telem_update();
344
#endif
345
346
#if AP_PERIPH_RC_OUT_ENABLED
347
#if HAL_WITH_ESC_TELEM
348
AP_ESC_Telem esc_telem;
349
uint8_t get_motor_number(const uint8_t esc_number) const;
350
uint32_t last_esc_telem_update_ms;
351
void esc_telem_update();
352
uint32_t esc_telem_update_period_ms;
353
#if AP_EXTENDED_ESC_TELEM_ENABLED
354
void esc_telem_extended_update(const uint32_t &now_ms);
355
uint32_t last_esc_telem_extended_update;
356
uint8_t last_esc_telem_extended_sent_id;
357
#endif
358
#endif
359
360
SRV_Channels servo_channels;
361
bool rcout_has_new_data_to_update;
362
363
uint32_t last_esc_raw_command_ms;
364
uint8_t last_esc_num_channels;
365
366
// Track channels that have been output to by actuator commands
367
// Note there is a single timeout, channels are not tracked individually
368
struct {
369
uint32_t last_command_ms;
370
uint32_t mask;
371
} actuator;
372
373
void rcout_init();
374
void rcout_init_1Hz();
375
void rcout_esc(int16_t *rc, uint8_t num_channels);
376
void rcout_srv_unitless(const uint8_t actuator_id, const float command_value);
377
void rcout_srv_PWM(const uint8_t actuator_id, const float command_value);
378
void rcout_update();
379
void rcout_handle_safety_state(uint8_t safety_state);
380
#endif
381
382
#if AP_PERIPH_RCIN_ENABLED
383
void rcin_init();
384
void rcin_update();
385
void can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t nvalues, bool in_failsafe, bool quality_valid);
386
bool rcin_initialised;
387
uint32_t rcin_last_sent_RCInput_ms;
388
const char *rcin_rc_protocol; // protocol currently being decoded
389
Parameters_RCIN g_rcin;
390
#endif
391
392
#if AP_PERIPH_BATTERY_BALANCE_ENABLED
393
void batt_balance_update();
394
BattBalance battery_balance;
395
#endif
396
397
#if AP_PERIPH_BATTERY_TAG_ENABLED
398
BatteryTag battery_tag;
399
#endif
400
401
#if AP_PERIPH_BATTERY_BMS_ENABLED
402
BatteryBMS battery_bms;
403
#endif
404
405
#if AP_PERIPH_ACTUATOR_TELEM_ENABLED
406
ActuatorTelem actuator_telem;
407
#endif
408
409
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED
410
SerialOptions serial_options;
411
#endif
412
413
#if AP_TEMPERATURE_SENSOR_ENABLED
414
AP_TemperatureSensor temperature_sensor;
415
#if AP_PERIPH_DEVICE_TEMPERATURE_ENABLED
416
void temperature_sensor_update();
417
uint32_t temperature_last_send_ms;
418
uint8_t temperature_last_sent_index;
419
#endif
420
#endif
421
422
#if AP_PERIPH_NOTIFY_ENABLED || defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY)
423
void update_rainbow();
424
#endif
425
#if AP_PERIPH_NOTIFY_ENABLED
426
// notification object for LEDs, buzzers etc
427
AP_Notify notify;
428
uint64_t vehicle_state = 1; // default to initialisation
429
float yaw_earth;
430
uint32_t last_vehicle_state_ms;
431
432
// Handled under LUA script to control LEDs
433
float get_yaw_earth() { return yaw_earth; }
434
uint64_t get_vehicle_state() { return vehicle_state; }
435
#endif
436
437
#if AP_SCRIPTING_ENABLED
438
AP_Scripting scripting;
439
#endif
440
441
#if HAL_LOGGING_ENABLED
442
static const struct LogStructure log_structure[];
443
AP_Logger logger;
444
#endif
445
446
#if AP_PERIPH_NETWORKING_ENABLED
447
Networking_Periph networking_periph;
448
#endif
449
450
#if AP_PERIPH_RTC_ENABLED
451
AP_RTC rtc;
452
#endif
453
454
#if HAL_GCS_ENABLED
455
GCS_Periph _gcs;
456
#endif
457
458
#if AP_PERIPH_RELAY_ENABLED
459
AP_Relay relay;
460
#endif
461
462
// setup the var_info table
463
AP_Param param_loader{var_info};
464
465
static const AP_Param::Info var_info[];
466
467
#if AP_PERIPH_EFI_ENABLED
468
uint32_t last_efi_update_ms;
469
#endif
470
#if AP_PERIPH_MAG_ENABLED
471
uint32_t last_mag_update_ms;
472
#endif
473
#if AP_PERIPH_GPS_ENABLED
474
uint32_t last_gps_update_ms;
475
uint32_t last_gps_yaw_ms;
476
#endif
477
uint32_t last_relposheading_ms;
478
#if AP_PERIPH_BARO_ENABLED
479
uint32_t last_baro_update_ms;
480
#endif
481
#if AP_PERIPH_AIRSPEED_ENABLED
482
uint32_t last_airspeed_update_ms;
483
#endif
484
#if AP_PERIPH_GPS_ENABLED
485
bool saw_gps_lock_once;
486
#endif
487
488
static AP_Periph_FW *_singleton;
489
490
enum class DebugOptions {
491
SHOW_STACK = 0,
492
AUTOREBOOT = 1,
493
ENABLE_STATS = 2,
494
};
495
496
// check if an option is set
497
bool debug_option_is_set(const DebugOptions option) const {
498
return (uint8_t(g.debug.get()) & (1U<<uint8_t(option))) != 0;
499
}
500
501
enum class PeriphOptions {
502
PROBE_CONTINUOUS = 1U<<0,
503
};
504
505
// check if a periph option is set
506
bool option_is_set(const PeriphOptions opt) const {
507
return (uint32_t(g.options.get()) & uint32_t(opt)) != 0;
508
}
509
510
// show stack as DEBUG msgs
511
void show_stack_free();
512
513
static bool no_iface_finished_dna;
514
static constexpr auto can_printf = ::can_printf;
515
516
bool canard_broadcast(uint64_t data_type_signature,
517
uint16_t data_type_id,
518
uint8_t priority,
519
const void* payload,
520
uint16_t payload_len,
521
uint8_t iface_mask=0);
522
523
bool canard_respond(CanardInstance* canard_instance,
524
CanardRxTransfer* transfer,
525
uint64_t data_type_signature,
526
uint16_t data_type_id,
527
const uint8_t *payload,
528
uint16_t payload_len);
529
530
void onTransferReceived(CanardInstance* canard_instance,
531
CanardRxTransfer* transfer);
532
bool shouldAcceptTransfer(const CanardInstance* canard_instance,
533
uint64_t* out_data_type_signature,
534
uint16_t data_type_id,
535
CanardTransferType transfer_type,
536
uint8_t source_node_id);
537
538
// reboot the peripheral, optionally holding in bootloader
539
void reboot(bool hold_in_bootloader);
540
541
#if AP_UART_MONITOR_ENABLED
542
void handle_tunnel_Targetted(CanardInstance* canard_instance, CanardRxTransfer* transfer);
543
void send_serial_monitor_data();
544
int8_t get_default_tunnel_serial_port(void) const;
545
546
struct UARTMonitor {
547
ByteBuffer *buffer;
548
uint32_t last_request_ms;
549
AP_HAL::UARTDriver *uart;
550
int8_t uart_num;
551
uint8_t node_id;
552
uint8_t protocol;
553
uint32_t baudrate;
554
bool locked;
555
} uart_monitors[SERIALMANAGER_MAX_PORTS];
556
void send_serial_monitor_data_instance(UARTMonitor &monitor);
557
#endif
558
559
// handlers for incoming messages
560
void handle_get_node_info(CanardInstance* canard_instance, CanardRxTransfer* transfer);
561
void handle_param_getset(CanardInstance* canard_instance, CanardRxTransfer* transfer);
562
void handle_param_executeopcode(CanardInstance* canard_instance, CanardRxTransfer* transfer);
563
void handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer);
564
void handle_allocation_response(CanardInstance* canard_instance, CanardRxTransfer* transfer);
565
void handle_safety_state(CanardInstance* canard_instance, CanardRxTransfer* transfer);
566
void handle_arming_status(CanardInstance* canard_instance, CanardRxTransfer* transfer);
567
void handle_RTCMStream(CanardInstance* canard_instance, CanardRxTransfer* transfer);
568
void handle_MovingBaselineData(CanardInstance* canard_instance, CanardRxTransfer* transfer);
569
void handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer);
570
void handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer);
571
void handle_beep_command(CanardInstance* canard_instance, CanardRxTransfer* transfer);
572
void handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer);
573
void handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer);
574
void handle_hardpoint_command(CanardInstance* canard_instance, CanardRxTransfer* transfer);
575
void handle_globaltime(CanardInstance* canard_instance, CanardRxTransfer* transfer);
576
577
void process1HzTasks(uint64_t timestamp_usec);
578
void processTx(void);
579
void processRx(void);
580
#if HAL_PERIPH_CAN_MIRROR
581
void processMirror(void);
582
#endif // HAL_PERIPH_CAN_MIRROR
583
void cleanup_stale_transactions(uint64_t timestamp_usec);
584
void update_rx_protocol_stats(int16_t res);
585
void node_status_send(void);
586
bool can_do_dna();
587
uint8_t *get_tid_ptr(uint32_t transfer_desc);
588
uint16_t pool_peak_percent();
589
void set_rgb_led(uint8_t red, uint8_t green, uint8_t blue);
590
591
#if AP_SIM_ENABLED
592
// update simulation of servos
593
void sim_update_actuator(uint8_t actuator_id);
594
struct {
595
uint32_t mask;
596
uint32_t last_send_ms;
597
} sim_actuator;
598
#endif
599
600
struct dronecan_protocol_t {
601
CanardInstance canard;
602
uint32_t canard_memory_pool[HAL_CAN_POOL_SIZE/sizeof(uint32_t)];
603
struct tid_map {
604
uint32_t transfer_desc;
605
uint8_t tid;
606
tid_map *next;
607
} *tid_map_head;
608
/*
609
* Variables used for dynamic node ID allocation.
610
* RTFM at http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
611
*/
612
uint32_t send_next_node_id_allocation_request_at_ms; ///< When the next node ID allocation request should be sent
613
uint8_t node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request
614
uint8_t tx_fail_count;
615
uint8_t dna_interface = 1;
616
} dronecan;
617
618
#if AP_SIM_ENABLED
619
SITL::SIM sitl;
620
#endif
621
#if AP_AHRS_ENABLED
622
AP_AHRS ahrs;
623
#endif
624
625
#if AP_DAC_ENABLED
626
AP_DAC dac;
627
#endif
628
629
uint32_t reboot_request_ms = 0;
630
631
HAL_Semaphore canard_broadcast_semaphore;
632
};
633
634
#ifndef CAN_APP_NODE_NAME
635
#define CAN_APP_NODE_NAME "org.ardupilot." CHIBIOS_BOARD_NAME
636
#endif
637
638
namespace AP
639
{
640
AP_Periph_FW& periph();
641
}
642
643
extern AP_Periph_FW periph;
644
645