Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/Parameters.cpp
9379 views
1
2
#include <AP_HAL/AP_HAL_Boards.h>
3
#include "AP_Periph.h"
4
5
extern const AP_HAL::HAL &hal;
6
7
#ifndef HAL_PERIPH_LED_BRIGHT_DEFAULT
8
#define HAL_PERIPH_LED_BRIGHT_DEFAULT 100
9
#endif
10
11
#ifndef HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT
12
#define HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 115200
13
#endif
14
15
#ifndef AP_PERIPH_RANGEFINDER_PORT_DEFAULT
16
#define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 3
17
#endif
18
19
#ifndef HAL_PERIPH_GPS_PORT_DEFAULT
20
#define HAL_PERIPH_GPS_PORT_DEFAULT 3
21
#endif
22
23
#ifndef HAL_PERIPH_ADSB_BAUD_DEFAULT
24
#define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600
25
#endif
26
#ifndef HAL_PERIPH_ADSB_PORT_DEFAULT
27
#define HAL_PERIPH_ADSB_PORT_DEFAULT 1
28
#endif
29
30
#ifndef AP_PERIPH_MSP_PORT_DEFAULT
31
#define AP_PERIPH_MSP_PORT_DEFAULT 1
32
#endif
33
34
#ifndef AP_PERIPH_ESC_TELEM_PORT_DEFAULT
35
#define AP_PERIPH_ESC_TELEM_PORT_DEFAULT -1
36
#endif
37
38
#ifndef AP_PERIPH_ESC_TELEM_RATE_DEFAULT
39
#define AP_PERIPH_ESC_TELEM_RATE_DEFAULT 50
40
#endif
41
42
#ifndef AP_PERIPH_BARO_ENABLE_DEFAULT
43
#define AP_PERIPH_BARO_ENABLE_DEFAULT 1
44
#endif
45
46
#ifndef HAL_PERIPH_BATT_HIDE_MASK_DEFAULT
47
#define HAL_PERIPH_BATT_HIDE_MASK_DEFAULT 0
48
#endif
49
50
#ifndef AP_PERIPH_EFI_PORT_DEFAULT
51
#define AP_PERIPH_EFI_PORT_DEFAULT 3
52
#endif
53
54
#ifndef HAL_PERIPH_EFI_BAUDRATE_DEFAULT
55
#define HAL_PERIPH_EFI_BAUDRATE_DEFAULT 115200
56
#endif
57
58
#ifndef HAL_DEFAULT_MAV_SYSTEM_ID
59
#define MAV_SYSTEM_ID 3
60
#else
61
#define MAV_SYSTEM_ID HAL_DEFAULT_MAV_SYSTEM_ID
62
#endif
63
64
#ifndef APD_ESC_SERIAL_0
65
#define APD_ESC_SERIAL_0 -1
66
#endif
67
68
#ifndef APD_ESC_SERIAL_1
69
#define APD_ESC_SERIAL_1 -1
70
#endif
71
72
#ifndef AP_PERIPH_PROBE_CONTINUOUS
73
#define AP_PERIPH_PROBE_CONTINUOUS 0
74
#endif
75
76
/*
77
* AP_Periph parameter definitions
78
*
79
*/
80
81
const AP_Param::Info AP_Periph_FW::var_info[] = {
82
// @Param: FORMAT_VERSION
83
// @DisplayName: Eeprom format version number
84
// @Description: This value is incremented when changes are made to the eeprom format
85
// @User: Advanced
86
GSCALAR(format_version, "FORMAT_VERSION", 0),
87
88
// @Param: CAN_NODE
89
// @DisplayName: DroneCAN node ID used by this node on all networks
90
// @Description: Value of 0 requests any ID from a DNA server, any other value sets that ID ignoring DNA
91
// @Range: 0 127
92
// @User: Advanced
93
// @RebootRequired: True
94
GSCALAR(can_node, "CAN_NODE", HAL_CAN_DEFAULT_NODE_ID),
95
96
// @Param: CAN_BAUDRATE
97
// @DisplayName: Bitrate of CAN interface
98
// @Description: Bit rate can be set up to from 10000 to 1000000
99
// @Range: 10000 1000000
100
// @User: Advanced
101
// @RebootRequired: True
102
GARRAY(can_baudrate, 0, "CAN_BAUDRATE", 1000000),
103
104
#if AP_CAN_SLCAN_ENABLED
105
// @Param: CAN_SLCAN_CPORT
106
// @DisplayName: SLCAN Route
107
// @Description: CAN Interface ID to be routed to SLCAN, 0 means no routing
108
// @Values: 0:Disabled,1:First interface,2:Second interface
109
// @User: Standard
110
// @RebootRequired: True
111
GSCALAR(can_slcan_cport, "CAN_SLCAN_CPORT", 1),
112
#endif
113
114
#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM
115
// @Param: CAN_TERMINATE
116
// @DisplayName: Enable CAN software termination in this node
117
// @Description: Enable CAN software termination in this node
118
// @Values: 0:Disabled,1:Enabled
119
// @User: Advanced
120
// @RebootRequired: True
121
GARRAY(can_terminate, 0, "CAN_TERMINATE", 0),
122
#endif
123
124
#if HAL_NUM_CAN_IFACES >= 2
125
// @Param: CAN_PROTOCOL
126
// @DisplayName: Enable use of specific protocol to be used on this port
127
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
128
// @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,6:EFI_NWPMU,7:USD1,8:KDECAN
129
// @User: Advanced
130
// @RebootRequired: True
131
GARRAY(can_protocol, 0, "CAN_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),
132
133
// @Param: CAN2_BAUDRATE
134
// @CopyFieldsFrom: CAN_BAUDRATE
135
// @DisplayName: Bitrate of CAN2 interface
136
GARRAY(can_baudrate, 1, "CAN2_BAUDRATE", 1000000),
137
138
// @Param: CAN2_PROTOCOL
139
// @CopyFieldsFrom: CAN_PROTOCOL
140
GARRAY(can_protocol, 1, "CAN2_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),
141
142
#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM
143
// @Param: CAN2_TERMINATE
144
// @CopyFieldsFrom: CAN_TERMINATE
145
GARRAY(can_terminate, 1, "CAN2_TERMINATE", 0),
146
#endif
147
#endif
148
149
#if HAL_NUM_CAN_IFACES >= 3
150
// @Param: CAN3_BAUDRATE
151
// @DisplayName: Bitrate of CAN3 interface
152
// @CopyFieldsFrom: CAN_BAUDRATE
153
GARRAY(can_baudrate, 2, "CAN3_BAUDRATE", 1000000),
154
155
// @Param: CAN3_PROTOCOL
156
// @CopyFieldsFrom: CAN_PROTOCOL
157
GARRAY(can_protocol, 2, "CAN3_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),
158
159
#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM
160
// @Param: CAN3_TERMINATE
161
// @CopyFieldsFrom: CAN_TERMINATE
162
GARRAY(can_terminate, 2, "CAN3_TERMINATE", 0),
163
#endif
164
#endif
165
166
#if HAL_CANFD_SUPPORTED
167
// @Param: CAN_FDMODE
168
// @DisplayName: Enable CANFD mode
169
// @Description: Enabling this option sets the CAN bus to be in CANFD mode with BRS.
170
// @Values: 0:Disabled,1:Enabled
171
// @User: Advanced
172
// @RebootRequired: True
173
GSCALAR(can_fdmode, "CAN_FDMODE", 0),
174
175
// @Param: CAN_FDBAUDRATE
176
// @DisplayName: Set up bitrate for data section on CAN1
177
// @Description: This sets the bitrate for the data section of CAN1.
178
// @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M
179
// @User: Advanced
180
// @RebootRequired: True
181
GARRAY(can_fdbaudrate, 0, "CAN_FDBAUDRATE", HAL_CANFD_SUPPORTED),
182
183
#if HAL_NUM_CAN_IFACES >= 2
184
// @Param: CAN2_FDBAUDRATE
185
// @CopyFieldsFrom: CAN_FDBAUDRATE
186
// @DisplayName: Set up bitrate for data section on CAN2
187
// @Description: This sets the bitrate for the data section of CAN2.
188
GARRAY(can_fdbaudrate, 1, "CAN2_FDBAUDRATE", HAL_CANFD_SUPPORTED),
189
#endif
190
#endif
191
192
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
193
// @Param: FLASH_BOOTLOADER
194
// @DisplayName: Trigger bootloader update
195
// @Description: DANGER! When enabled, the App will perform a bootloader update by copying the embedded bootloader over the existing bootloader. This may take a few seconds to perform and should only be done if you know what you're doing.
196
// @Range: 0 1
197
// @User: Advanced
198
GSCALAR(flash_bootloader, "FLASH_BOOTLOADER", 0),
199
#endif
200
201
// @Param: DEBUG
202
// @DisplayName: Debug
203
// @Description: Debug
204
// @Bitmask: 0:Show free stack space, 1:Auto Reboot after 15sec, 2:Enable sending stats
205
// @User: Advanced
206
GSCALAR(debug, "DEBUG", 0),
207
208
209
// @Param: BRD_SERIAL_NUM
210
// @DisplayName: Serial number of device
211
// @Description: Non-zero positive values will be shown on the CAN App Name string
212
// @Range: 0 2147483648
213
// @User: Advanced
214
GSCALAR(serial_number, "BRD_SERIAL_NUM", 0),
215
216
#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED
217
// @Param: BUZZER_VOLUME
218
// @DisplayName: Buzzer volume
219
// @Description: Control the volume of the buzzer
220
// @Range: 0 100
221
// @Units: %
222
// @Increment: 1
223
// @User: Advanced
224
GSCALAR(buzz_volume, "BUZZER_VOLUME", 100),
225
#endif
226
227
#if AP_PERIPH_GPS_ENABLED
228
// GPS driver
229
// @Group: GPS
230
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
231
GOBJECT(gps, "GPS", AP_GPS),
232
233
// @Param: GPS_PORT
234
// @DisplayName: GPS Serial Port
235
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to GPS.
236
// @Range: 0 10
237
// @Increment: 1
238
// @User: Advanced
239
// @RebootRequired: True
240
GSCALAR(gps_port, "GPS_PORT", HAL_PERIPH_GPS_PORT_DEFAULT),
241
242
#if GPS_MOVING_BASELINE
243
// @Param: MB_CAN_PORT
244
// @DisplayName: Moving Baseline CAN Port option
245
// @Description: Autoselect dedicated CAN port on which moving baseline data will be transmitted.
246
// @Values: 0:Sends moving baseline data on all ports,1:auto select remaining port for transmitting Moving baseline Data
247
// @User: Advanced
248
// @RebootRequired: True
249
GSCALAR(gps_mb_only_can_port, "GPS_MB_ONLY_PORT", 0),
250
#endif
251
#endif
252
253
#if AP_PERIPH_BATTERY_ENABLED
254
// @Group: BATT
255
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
256
GOBJECT(battery_lib, "BATT", AP_BattMonitor),
257
258
// @Param: BATT_HIDE_MASK
259
// @DisplayName: Battery hide mask
260
// @Description: Instance mask of local battery index(es) to prevent transmitting their status over CAN. This is useful for hiding a "battery" instance that is used locally in the peripheral but don't want them to be treated as a battery source(s) to the autopilot. For example, an AP_Periph battery monitor with multiple batteries that monitors each locally for diagnostic or other purposes, but only reports as a single SUM battery monitor to the autopilot.
261
// @Bitmask: 0:BATT, 1:BATT2, 2:BATT3, 3:BATT4, 4:BATT5, 5:BATT6, 6:BATT7, 7:BATT8, 8:BATT9, 9:BATTA, 10:BATTB, 11:BATTC, 12:BATTD, 13:BATTE, 14:BATTF, 15:BATTG
262
// @User: Advanced
263
GSCALAR(battery_hide_mask, "BATT_HIDE_MASK", HAL_PERIPH_BATT_HIDE_MASK_DEFAULT),
264
#endif
265
266
#if AP_PERIPH_MAG_ENABLED
267
// @Group: COMPASS_
268
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
269
GOBJECT(compass, "COMPASS_", Compass),
270
#endif
271
272
#if AP_PERIPH_BARO_ENABLED
273
// Baro driver
274
// @Group: BARO
275
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
276
GOBJECT(baro, "BARO", AP_Baro),
277
278
// @Param: BARO_ENABLE
279
// @DisplayName: Barometer Enable
280
// @Description: Barometer Enable
281
// @Values: 0:Disabled, 1:Enabled
282
// @User: Standard
283
GSCALAR(baro_enable, "BARO_ENABLE", AP_PERIPH_BARO_ENABLE_DEFAULT),
284
#endif
285
286
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
287
// @Param: LED_BRIGHTNESS
288
// @DisplayName: LED Brightness
289
// @Description: Select the RGB LED brightness level.
290
// @Range: 0 100
291
// @Units: %
292
// @Increment: 1
293
// @User: Standard
294
GSCALAR(led_brightness, "LED_BRIGHTNESS", HAL_PERIPH_LED_BRIGHT_DEFAULT),
295
#endif
296
297
#if AP_PERIPH_AIRSPEED_ENABLED
298
// Airspeed driver
299
// @Group: ARSPD
300
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
301
GOBJECT(airspeed, "ARSPD", AP_Airspeed),
302
#endif
303
304
#if AP_PERIPH_RANGEFINDER_ENABLED
305
// @Param: RNGFND_BAUDRATE
306
// @DisplayName: Rangefinder serial baudrate
307
// @Description: Rangefinder serial baudrate.
308
// @Values: 1200:1200,2400:2400,4800:4800,9600:9600,19200:19200,38400:38400,57600:57600,111100:111100,115200:115200,230400:230400,256000:256000,460800:460800,500000:500000,921600:921600,1500000:1500000
309
// @Range: 1200 20000000
310
// @Increment: 1
311
// @User: Standard
312
// @RebootRequired: True
313
GARRAY(rangefinder_baud, 0, "RNGFND_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
314
315
// @Param: RNGFND_PORT
316
// @DisplayName: Rangefinder Serial Port
317
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.
318
// @Range: 0 10
319
// @Increment: 1
320
// @User: Advanced
321
// @RebootRequired: True
322
GARRAY(rangefinder_port, 0, "RNGFND_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),
323
324
#if RANGEFINDER_MAX_INSTANCES > 1
325
// @Param: RNGFND2_BAUDRATE
326
// @CopyFieldsFrom: RNGFND_BAUDRATE
327
GARRAY(rangefinder_baud, 1, "RNGFND2_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
328
329
// @Param: RNGFND2_PORT
330
// @DisplayName: Rangefinder Serial Port
331
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.
332
// @Range: 0 10
333
// @Increment: 1
334
// @User: Advanced
335
// @RebootRequired: True
336
GARRAY(rangefinder_port, 1, "RNGFND2_PORT", -1),
337
#endif
338
339
// @Param: RNGFND_MAX_RATE
340
// @DisplayName: Rangefinder max rate
341
// @Description: This is the maximum rate we send rangefinder data in Hz. Zero means no limit
342
// @Units: Hz
343
// @Range: 0 200
344
// @Increment: 1
345
// @User: Advanced
346
GSCALAR(rangefinder_max_rate, "RNGFND_MAX_RATE", 50),
347
348
// Rangefinder driver
349
// @Group: RNGFND
350
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
351
GOBJECT(rangefinder, "RNGFND", RangeFinder),
352
#endif
353
354
#if AP_PERIPH_ADSB_ENABLED
355
// @Param: ADSB_BAUDRATE
356
// @CopyFieldsFrom: RNGFND_BAUDRATE
357
// @DisplayName: ADSB serial baudrate
358
// @Description: ADSB serial baudrate.
359
GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", HAL_PERIPH_ADSB_BAUD_DEFAULT),
360
361
// @Param: ADSB_PORT
362
// @DisplayName: ADSB Serial Port
363
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ADSB.
364
// @Range: 0 10
365
// @Increment: 1
366
// @User: Advanced
367
// @RebootRequired: True
368
GSCALAR(adsb_port, "ADSB_PORT", HAL_PERIPH_ADSB_PORT_DEFAULT),
369
#endif
370
371
#if AP_PERIPH_PWM_HARDPOINT_ENABLED
372
// @Param: HARDPOINT_ID
373
// @DisplayName: Hardpoint ID
374
// @Description: Hardpoint ID
375
// @User: Advanced
376
GSCALAR(hardpoint_id, "HARDPOINT_ID", HAL_PWM_HARDPOINT_ID_DEFAULT),
377
378
// @Param: HARDPOINT_RATE
379
// @DisplayName: Hardpoint PWM rate
380
// @Description: Hardpoint PWM rate
381
// @Range: 10 100
382
// @Units: Hz
383
// @Increment: 1
384
// @User: Advanced
385
GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),
386
#endif
387
388
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || AP_PERIPH_ESC_APD_ENABLED
389
// @Param: ESC_NUMBER
390
// @DisplayName: ESC number
391
// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.
392
// @Increment: 1
393
// @User: Advanced
394
GARRAY(esc_number, 0, "ESC_NUMBER", 0),
395
#endif
396
397
#if AP_PERIPH_RC_OUT_ENABLED
398
// Servo driver
399
// @Group: OUT
400
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
401
GOBJECT(servo_channels, "OUT", SRV_Channels),
402
403
// @Param: ESC_RATE
404
// @DisplayName: ESC Update Rate
405
// @Description: Rate in Hz that ESC PWM outputs (function is MotorN) will update at
406
// @Units: Hz
407
// @Range: 50 400
408
// @Increment: 1
409
// @User: Advanced
410
GSCALAR(esc_rate, "ESC_RATE", 400), // effective Copter and QuadPlane default after clamping
411
412
// @Param: ESC_PWM_TYPE
413
// @DisplayName: Output PWM type
414
// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output
415
// @Values: 1:Normal,2:OneShot,3:OneShot125,4:Brushed,5:DShot150,6:DShot300,7:DShot600,8:DShot1200
416
// @User: Advanced
417
// @RebootRequired: True
418
GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),
419
420
// @Param: ESC_CMD_TIMO
421
// @DisplayName: ESC Command Timeout
422
// @Description: This is the duration (ms) with which to hold the last driven ESC command before timing out and zeroing the ESC outputs. To disable zeroing of outputs in event of CAN loss, use 0. Use values greater than the expected duration between two CAN frames to ensure Periph is not starved of ESC Raw Commands.
423
// @Range: 0 10000
424
// @Units: ms
425
// @User: Advanced
426
GSCALAR(esc_command_timeout_ms, "ESC_CMD_TIMO", 200),
427
428
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
429
// @Param: ESC_TELEM_PORT
430
// @DisplayName: ESC Telemetry Serial Port
431
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ESC Telemetry
432
// @Range: 0 10
433
// @Increment: 1
434
// @User: Advanced
435
// @RebootRequired: True
436
GSCALAR(esc_telem_port, "ESC_TELEM_PORT", AP_PERIPH_ESC_TELEM_PORT_DEFAULT),
437
#endif
438
439
#if HAL_WITH_ESC_TELEM
440
// @Param: ESC_TELEM_RATE
441
// @DisplayName: ESC Telemetry update rate
442
// @Description: This is the rate at which ESC Telemetry will be sent across the CAN bus
443
// @Range: 0 1000
444
// @Increment: 1
445
// @User: Advanced
446
// @RebootRequired: True
447
GSCALAR(esc_telem_rate, "ESC_TELEM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT),
448
#endif
449
#endif
450
451
#if AP_TEMPERATURE_SENSOR_ENABLED
452
// @Group: TEMP
453
// @Path: ../libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp
454
GOBJECT(temperature_sensor, "TEMP", AP_TemperatureSensor),
455
#endif
456
457
#if AP_PERIPH_MSP_ENABLED
458
// @Param: MSP_PORT
459
// @DisplayName: MSP Serial Port
460
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to MSP
461
// @Range: 0 10
462
// @Increment: 1
463
// @User: Advanced
464
// @RebootRequired: True
465
GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),
466
#endif
467
468
#if AP_PERIPH_NOTIFY_ENABLED
469
// @Group: NTF_
470
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
471
GOBJECT(notify, "NTF_", AP_Notify),
472
#endif
473
474
#if HAL_LOGGING_ENABLED
475
// @Group: LOG
476
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
477
GOBJECT(logger, "LOG", AP_Logger),
478
479
// @Param: LOG_BITMASK
480
// @DisplayName: Log bitmask
481
// @Description: 4 byte bitmap of log types to enable
482
// @Bitmask: 2:GPS
483
// @User: Standard
484
GSCALAR(log_bitmask, "LOG_BITMASK", 4),
485
#endif
486
487
// SYSID_THISMAV was here
488
489
#if HAL_GCS_ENABLED || defined(HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS)
490
// @Group: SERIAL
491
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
492
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
493
#endif
494
495
#if AP_SCRIPTING_ENABLED
496
// @Group: SCR_
497
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
498
GOBJECT(scripting, "SCR_", AP_Scripting),
499
#endif
500
501
#if AP_STATS_ENABLED
502
// @Group: Node
503
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
504
GOBJECT(node_stats, "STAT", AP_Stats),
505
#endif
506
507
#if AP_PERIPH_EFI_ENABLED
508
// @Param: EFI_BAUDRATE
509
// @CopyFieldsFrom: RNGFND_BAUDRATE
510
// @DisplayName: EFI serial baudrate
511
// @Description: EFI serial baudrate.
512
GSCALAR(efi_baudrate, "EFI_BAUDRATE", HAL_PERIPH_EFI_BAUDRATE_DEFAULT),
513
514
// @Param: EFI_PORT
515
// @DisplayName: EFI Serial Port
516
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to EFI.
517
// @Range: 0 10
518
// @Increment: 1
519
// @User: Advanced
520
// @RebootRequired: True
521
GSCALAR(efi_port, "EFI_PORT", AP_PERIPH_EFI_PORT_DEFAULT),
522
523
// EFI driver
524
// @Group: EFI
525
// @Path: ../libraries/AP_EFI/AP_EFI.cpp
526
GOBJECT(efi, "EFI", AP_EFI),
527
#endif
528
529
#if AP_PERIPH_PROXIMITY_ENABLED
530
// @Param: PRX_BAUDRATE
531
// @CopyFieldsFrom: RNGFND_BAUDRATE
532
// @DisplayName: Proximity Sensor serial baudrate
533
// @Description: Proximity Sensor serial baudrate.
534
GSCALAR(proximity_baud, "PRX_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
535
536
// @Param: PRX_PORT
537
// @DisplayName: Proximity Sensor Serial Port
538
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Proximity Sensor.
539
// @Range: 0 10
540
// @Increment: 1
541
// @User: Advanced
542
// @RebootRequired: True
543
GSCALAR(proximity_port, "PRX_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),
544
545
// @Param: PRX_MAX_RATE
546
// @DisplayName: Proximity Sensor max rate
547
// @Description: This is the maximum rate we send Proximity Sensor data in Hz. Zero means no limit
548
// @Units: Hz
549
// @Range: 0 200
550
// @Increment: 1
551
// @User: Advanced
552
GSCALAR(proximity_max_rate, "PRX_MAX_RATE", 50),
553
554
// Proximity driver
555
// @Group: PRX
556
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
557
GOBJECT(proximity, "PRX", AP_Proximity),
558
#endif // AP_PERIPH_PROXIMITY_ENABLED
559
560
#if HAL_NMEA_OUTPUT_ENABLED
561
// @Group: NMEA_
562
// @Path: ../libraries/AP_NMEA_Output/AP_NMEA_Output.cpp
563
GOBJECT(nmea, "NMEA_", AP_NMEA_Output),
564
#endif
565
566
#if AP_KDECAN_ENABLED
567
// @Group: KDE_
568
// @Path: ../libraries/AP_KDECAN/AP_KDECAN.cpp
569
GOBJECT(kdecan, "KDE_", AP_KDECAN),
570
#endif
571
572
#if AP_PERIPH_ESC_APD_ENABLED
573
GARRAY(pole_count, 0, "ESC_NUM_POLES", 22),
574
#endif
575
576
#if AP_PERIPH_ESC_APD_ENABLED
577
// @Param: ESC_APD_SERIAL_1
578
// @DisplayName: ESC APD Serial 1
579
// @Description: Which serial port to use for APD ESC data
580
// @Range: 0 6
581
// @Increment: 1
582
// @User: Advanced
583
// @RebootRequired: True
584
GARRAY(esc_serial_port, 0, "ESC_APD_SERIAL_1", APD_ESC_SERIAL_0),
585
586
#if APD_ESC_INSTANCES > 1
587
GARRAY(esc_number, 1, "ESC_NUMBER2", 1),
588
589
GARRAY(pole_count, 1, "ESC_NUM_POLES2", 22),
590
591
// @Param: ESC_APD_SERIAL_2
592
// @DisplayName: ESC APD Serial 2
593
// @Description: Which serial port to use for APD ESC data
594
// @Range: 0 6
595
// @Increment: 1
596
// @User: Advanced
597
// @RebootRequired: True
598
GARRAY(esc_serial_port, 1, "ESC_APD_SERIAL_2", APD_ESC_SERIAL_1),
599
#endif
600
#endif
601
602
#if AP_PERIPH_NETWORKING_ENABLED
603
// @Group: NET_
604
// @Path: networking.cpp
605
GOBJECT(networking_periph, "NET_", Networking_Periph),
606
#endif
607
608
#if AP_PERIPH_RPM_ENABLED
609
// @Group: RPM
610
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
611
GOBJECT(rpm_sensor, "RPM", AP_RPM),
612
#endif
613
614
#if AP_PERIPH_RCIN_ENABLED
615
// @Group: RC
616
// @Path: rc_in.cpp
617
GOBJECT(g_rcin, "RC", Parameters_RCIN),
618
#endif
619
620
#if AP_PERIPH_ACTUATOR_TELEM_ENABLED
621
// @Group: ACT
622
// @Path: actuator_telem.cpp
623
GOBJECT(actuator_telem, "ACT", ActuatorTelem),
624
#endif
625
626
#if AP_PERIPH_BATTERY_BALANCE_ENABLED
627
// @Group: BAL
628
// @Path: batt_balance.cpp
629
GOBJECT(battery_balance, "BAL", BattBalance),
630
#endif
631
632
#if AP_PERIPH_BATTERY_TAG_ENABLED
633
// @Group: BTAG
634
// @Path: battery_tag.cpp
635
GOBJECT(battery_tag, "BTAG", BatteryTag),
636
#endif
637
638
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED
639
// @Group: UART
640
// @Path: serial_options.cpp
641
GOBJECT(serial_options, "UART", SerialOptions),
642
#endif
643
644
// NOTE: sim parameters should go last
645
#if AP_SIM_PARAM_ENABLED
646
// @Group: SIM_
647
// @Path: ../libraries/SITL/SITL.cpp
648
GOBJECT(sitl, "SIM_", SITL::SIM),
649
650
#if AP_AHRS_ENABLED
651
// @Group: AHRS_
652
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
653
GOBJECT(ahrs, "AHRS_", AP_AHRS),
654
#endif
655
#endif // AP_SIM_ENABLED
656
657
#if HAL_PERIPH_CAN_MIRROR
658
// @Param: CAN_MIRROR_PORTS
659
// @DisplayName: CAN ports to mirror traffic between
660
// @Description: Any set ports will participate in blindly mirroring traffic from one port to the other. It is the users responsibility to ensure that no loops exist that cause traffic to be infinitly repeated, and both ports must be running the same baud rates.
661
// @Bitmask: 0:CAN1, 1:CAN2, 2:CAN3
662
// @User: Advanced
663
GSCALAR(can_mirror_ports, "CAN_MIRROR_PORTS", 0),
664
#endif // HAL_PERIPH_CAN_MIRROR
665
666
#if AP_PERIPH_RTC_ENABLED
667
// @Group: RTC
668
// @Path: ../libraries/AP_RTC/AP_RTC.cpp
669
GOBJECT(rtc, "RTC", AP_RTC),
670
#endif
671
672
#if AP_PERIPH_RELAY_ENABLED
673
// @Group: RELAY
674
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
675
GOBJECT(relay, "RELAY", AP_Relay),
676
#endif
677
678
#if AP_PERIPH_DEVICE_TEMPERATURE_ENABLED
679
// @Param: TEMP_MSG_RATE
680
// @DisplayName: Temperature sensor message rate
681
// @Description: This is the rate Temperature sensor data is sent in Hz. Zero means no send. Each sensor with source DroneCAN is sent in turn.
682
// @Units: Hz
683
// @Range: 0 200
684
// @Increment: 1
685
// @User: Standard
686
GSCALAR(temperature_msg_rate, "TEMP_MSG_RATE", 0),
687
#endif
688
689
// @Param: OPTIONS
690
// @DisplayName: AP Periph Options
691
// @Description: Bitmask of AP Periph Options
692
// @Bitmask: 0: Enable continuous sensor probe
693
// @User: Standard
694
GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS),
695
696
#if AP_PERIPH_RPM_STREAM_ENABLED
697
// @Param: RPM_MSG_RATE
698
// @DisplayName: RPM sensor message rate
699
// @Description: This is the rate RPM sensor data is sent in Hz. Zero means no send. Each sensor with a set ID is sent in turn.
700
// @Units: Hz
701
// @Range: 0 200
702
// @Increment: 1
703
// @User: Standard
704
GSCALAR(rpm_msg_rate, "RPM_MSG_RATE", 0),
705
#endif
706
707
#if AP_EXTENDED_ESC_TELEM_ENABLED && HAL_WITH_ESC_TELEM
708
// @Param: ESC_EXT_TLM_RATE
709
// @DisplayName: ESC Extended telemetry message rate
710
// @Description: This is the rate at which extended ESC Telemetry will be sent across the CAN bus for each ESC
711
// @Units: Hz
712
// @Range: 0 50
713
// @Increment: 1
714
// @User: Advanced
715
GSCALAR(esc_extended_telem_rate, "ESC_EXT_TLM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT / 10),
716
#endif
717
718
719
#if AP_PERIPH_IMU_ENABLED
720
// @Param: IMU_SAMPLE_RATE
721
// @DisplayName: IMU Sample Rate
722
// @Description: IMU Sample Rate
723
// @Range: 0 1000
724
// @User: Standard
725
GSCALAR(imu_sample_rate, "INS_SAMPLE_RATE", 0),
726
727
// @Group: INS
728
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
729
GOBJECT(imu, "INS", AP_InertialSensor),
730
#endif
731
732
#if AP_DAC_ENABLED
733
// @Group: DAC
734
// @Path: ../libraries/AP_DAC/AP_DAC.cpp
735
GOBJECT(dac, "DAC", AP_DAC),
736
#endif
737
738
#if HAL_GCS_ENABLED
739
// @Group: MAV
740
// @Path: ../libraries/GCS_MAVLink/GCS.cpp
741
GOBJECT(_gcs, "MAV", GCS),
742
#endif
743
744
#if AP_PERIPH_RC_OUT_ENABLED
745
// @Param: SRV_CMD_TIME_OUT
746
// @DisplayName: Servo Command Timeout
747
// @Description: This is the duration (ms) with which to hold the last driven servo command before timing out and zeroing the servo outputs. To disable zeroing of outputs in event of CAN loss, use 0. Use values greater than the expected duration between two CAN frames to ensure Periph is not starved of ESC Raw Commands.
748
// @Range: 0 10000
749
// @Units: ms
750
// @User: Advanced
751
GSCALAR(servo_command_timeout_ms, "SRV_CMD_TIME_OUT", 200),
752
#endif
753
754
AP_VAREND
755
};
756
757
758
void AP_Periph_FW::load_parameters(void)
759
{
760
AP_Param::setup_sketch_defaults();
761
762
AP_Param::check_var_info();
763
764
if (!g.format_version.load() ||
765
g.format_version != Parameters::k_format_version) {
766
// erase all parameters
767
StorageManager::erase();
768
AP_Param::erase_all();
769
770
// save the current format version
771
g.format_version.set_and_save(Parameters::k_format_version);
772
}
773
g.format_version.set_default(Parameters::k_format_version);
774
775
// Load all auto-loaded EEPROM variables
776
AP_Param::load_all();
777
}
778
779