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