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/Parameters.cpp
Views: 1798
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 temination in this node
117
// @Description: Enable CAN software temination 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
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
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
#ifdef HAL_PERIPH_ENABLE_GPS
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
#ifdef HAL_PERIPH_ENABLE_BATTERY
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
#ifdef HAL_PERIPH_ENABLE_MAG
267
// @Group: COMPASS_
268
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
269
GOBJECT(compass, "COMPASS_", Compass),
270
#endif
271
272
#ifdef HAL_PERIPH_ENABLE_BARO
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
#ifdef 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
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
298
// Airspeed driver
299
// @Group: ARSPD
300
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
301
GOBJECT(airspeed, "ARSPD", AP_Airspeed),
302
#endif
303
304
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
305
// @Param: RNGFND_BAUDRATE
306
// @DisplayName: Rangefinder serial baudrate
307
// @Description: Rangefinder serial baudrate.
308
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
309
// @Increment: 1
310
// @User: Standard
311
// @RebootRequired: True
312
GARRAY(rangefinder_baud, 0, "RNGFND_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
313
314
// @Param: RNGFND_PORT
315
// @DisplayName: Rangefinder Serial Port
316
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.
317
// @Range: 0 10
318
// @Increment: 1
319
// @User: Advanced
320
// @RebootRequired: True
321
GARRAY(rangefinder_port, 0, "RNGFND_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),
322
323
#if RANGEFINDER_MAX_INSTANCES > 1
324
// @Param: RNGFND2_BAUDRATE
325
// @DisplayName: Rangefinder serial baudrate
326
// @Description: Rangefinder serial baudrate.
327
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
328
// @Increment: 1
329
// @User: Standard
330
// @RebootRequired: True
331
GARRAY(rangefinder_baud, 1, "RNGFND2_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
332
333
// @Param: RNGFND2_PORT
334
// @DisplayName: Rangefinder Serial Port
335
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.
336
// @Range: 0 10
337
// @Increment: 1
338
// @User: Advanced
339
// @RebootRequired: True
340
GARRAY(rangefinder_port, 1, "RNGFND2_PORT", -1),
341
#endif
342
343
// @Param: RNGFND_MAX_RATE
344
// @DisplayName: Rangefinder max rate
345
// @Description: This is the maximum rate we send rangefinder data in Hz. Zero means no limit
346
// @Units: Hz
347
// @Range: 0 200
348
// @Increment: 1
349
// @User: Advanced
350
GSCALAR(rangefinder_max_rate, "RNGFND_MAX_RATE", 50),
351
352
// Rangefinder driver
353
// @Group: RNGFND
354
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
355
GOBJECT(rangefinder, "RNGFND", RangeFinder),
356
#endif
357
358
#ifdef HAL_PERIPH_ENABLE_ADSB
359
// @Param: ADSB_BAUDRATE
360
// @DisplayName: ADSB serial baudrate
361
// @Description: ADSB serial baudrate.
362
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
363
// @Increment: 1
364
// @User: Standard
365
// @RebootRequired: True
366
GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", HAL_PERIPH_ADSB_BAUD_DEFAULT),
367
368
// @Param: ADSB_PORT
369
// @DisplayName: ADSB Serial Port
370
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ADSB.
371
// @Range: 0 10
372
// @Increment: 1
373
// @User: Advanced
374
// @RebootRequired: True
375
GSCALAR(adsb_port, "ADSB_PORT", HAL_PERIPH_ADSB_PORT_DEFAULT),
376
#endif
377
378
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
379
// @Param: HARDPOINT_ID
380
// @DisplayName: Hardpoint ID
381
// @Description: Hardpoint ID
382
// @User: Advanced
383
GSCALAR(hardpoint_id, "HARDPOINT_ID", HAL_PWM_HARDPOINT_ID_DEFAULT),
384
385
// @Param: HARDPOINT_RATE
386
// @DisplayName: Hardpoint PWM rate
387
// @Description: Hardpoint PWM rate
388
// @Range: 10 100
389
// @Units: Hz
390
// @Increment: 1
391
// @User: Advanced
392
GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),
393
#endif
394
395
#if defined(HAL_PERIPH_ENABLE_HWESC) || defined(HAL_PERIPH_ENABLE_ESC_APD)
396
// @Param: ESC_NUMBER
397
// @DisplayName: ESC number
398
// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.
399
// @Increment: 1
400
// @User: Advanced
401
GARRAY(esc_number, 0, "ESC_NUMBER", 0),
402
#endif
403
404
#ifdef HAL_PERIPH_ENABLE_RC_OUT
405
// Servo driver
406
// @Group: OUT
407
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
408
GOBJECT(servo_channels, "OUT", SRV_Channels),
409
410
// @Param: ESC_RATE
411
// @DisplayName: ESC Update Rate
412
// @Description: Rate in Hz that ESC PWM outputs (function is MotorN) will update at
413
// @Units: Hz
414
// @Range: 50 400
415
// @Increment: 1
416
// @User: Advanced
417
GSCALAR(esc_rate, "ESC_RATE", 400), // effective Copter and QuadPlane default after clamping
418
419
// @Param: ESC_PWM_TYPE
420
// @DisplayName: Output PWM type
421
// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output
422
// @Values: 1:Normal,2:OneShot,3:OneShot125,4:Brushed,5:DShot150,6:DShot300,7:DShot600,8:DShot1200
423
// @User: Advanced
424
// @RebootRequired: True
425
GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),
426
427
// @Param: ESC_CMD_TIMO
428
// @DisplayName: ESC Command Timeout
429
// @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.
430
// @Range: 0 10000
431
// @Units: ms
432
// @User: Advanced
433
GSCALAR(esc_command_timeout_ms, "ESC_CMD_TIMO", 200),
434
435
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
436
// @Param: ESC_TELEM_PORT
437
// @DisplayName: ESC Telemetry Serial Port
438
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ESC Telemetry
439
// @Range: 0 10
440
// @Increment: 1
441
// @User: Advanced
442
// @RebootRequired: True
443
GSCALAR(esc_telem_port, "ESC_TELEM_PORT", AP_PERIPH_ESC_TELEM_PORT_DEFAULT),
444
#endif
445
446
#if HAL_WITH_ESC_TELEM
447
// @Param: ESC_TELEM_RATE
448
// @DisplayName: ESC Telemetry update rate
449
// @Description: This is the rate at which ESC Telemetry will be sent across the CAN bus
450
// @Range: 0 1000
451
// @Increment: 1
452
// @User: Advanced
453
// @RebootRequired: True
454
GSCALAR(esc_telem_rate, "ESC_TELEM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT),
455
#endif
456
#endif
457
458
#if AP_TEMPERATURE_SENSOR_ENABLED
459
// @Group: TEMP
460
// @Path: ../libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp
461
GOBJECT(temperature_sensor, "TEMP", AP_TemperatureSensor),
462
#endif
463
464
#ifdef HAL_PERIPH_ENABLE_MSP
465
// @Param: MSP_PORT
466
// @DisplayName: MSP Serial Port
467
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to MSP
468
// @Range: 0 10
469
// @Increment: 1
470
// @User: Advanced
471
// @RebootRequired: True
472
GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),
473
#endif
474
475
#ifdef HAL_PERIPH_ENABLE_NOTIFY
476
// @Group: NTF_
477
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
478
GOBJECT(notify, "NTF_", AP_Notify),
479
#endif
480
481
#if HAL_LOGGING_ENABLED
482
// @Group: LOG
483
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
484
GOBJECT(logger, "LOG", AP_Logger),
485
486
// @Param: LOG_BITMASK
487
// @DisplayName: Log bitmask
488
// @Description: 4 byte bitmap of log types to enable
489
// @Bitmask: 2:GPS
490
// @User: Standard
491
GSCALAR(log_bitmask, "LOG_BITMASK", 4),
492
#endif
493
494
#if HAL_GCS_ENABLED
495
// @Param: SYSID_THISMAV
496
// @DisplayName: MAVLink system ID of this vehicle
497
// @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network
498
// @Range: 1 255
499
// @User: Advanced
500
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
501
#endif
502
503
#if HAL_GCS_ENABLED || defined(HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS)
504
// @Group: SERIAL
505
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
506
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
507
#endif
508
509
#if AP_SCRIPTING_ENABLED
510
// @Group: SCR_
511
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
512
GOBJECT(scripting, "SCR_", AP_Scripting),
513
#endif
514
515
#if AP_STATS_ENABLED
516
// @Group: Node
517
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
518
GOBJECT(node_stats, "STAT", AP_Stats),
519
#endif
520
521
#ifdef HAL_PERIPH_ENABLE_EFI
522
// @Param: EFI_BAUDRATE
523
// @DisplayName: EFI serial baudrate
524
// @Description: EFI serial baudrate.
525
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
526
// @Increment: 1
527
// @User: Standard
528
// @RebootRequired: True
529
GSCALAR(efi_baudrate, "EFI_BAUDRATE", HAL_PERIPH_EFI_BAUDRATE_DEFAULT),
530
531
// @Param: EFI_PORT
532
// @DisplayName: EFI Serial Port
533
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to EFI.
534
// @Range: 0 10
535
// @Increment: 1
536
// @User: Advanced
537
// @RebootRequired: True
538
GSCALAR(efi_port, "EFI_PORT", AP_PERIPH_EFI_PORT_DEFAULT),
539
540
// EFI driver
541
// @Group: EFI
542
// @Path: ../libraries/AP_EFI/AP_EFI.cpp
543
GOBJECT(efi, "EFI", AP_EFI),
544
#endif
545
546
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
547
// @Param: PRX_BAUDRATE
548
// @DisplayName: Proximity Sensor serial baudrate
549
// @Description: Proximity Sensor serial baudrate.
550
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
551
// @Increment: 1
552
// @User: Standard
553
// @RebootRequired: True
554
GSCALAR(proximity_baud, "PRX_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
555
556
// @Param: PRX_PORT
557
// @DisplayName: Proximity Sensor Serial Port
558
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Proximity Sensor.
559
// @Range: 0 10
560
// @Increment: 1
561
// @User: Advanced
562
// @RebootRequired: True
563
GSCALAR(proximity_port, "PRX_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),
564
565
// @Param: PRX_MAX_RATE
566
// @DisplayName: Proximity Sensor max rate
567
// @Description: This is the maximum rate we send Proximity Sensor data in Hz. Zero means no limit
568
// @Units: Hz
569
// @Range: 0 200
570
// @Increment: 1
571
// @User: Advanced
572
GSCALAR(proximity_max_rate, "PRX_MAX_RATE", 50),
573
574
// Proximity driver
575
// @Group: PRX
576
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
577
GOBJECT(proximity, "PRX", AP_Proximity),
578
#endif // HAL_PERIPH_ENABLE_PROXIMITY
579
580
#if HAL_NMEA_OUTPUT_ENABLED
581
// @Group: NMEA_
582
// @Path: ../libraries/AP_NMEA_Output/AP_NMEA_Output.cpp
583
GOBJECT(nmea, "NMEA_", AP_NMEA_Output),
584
#endif
585
586
#if AP_KDECAN_ENABLED
587
// @Group: KDE_
588
// @Path: ../libraries/AP_KDECAN/AP_KDECAN.cpp
589
GOBJECT(kdecan, "KDE_", AP_KDECAN),
590
#endif
591
592
#if defined(HAL_PERIPH_ENABLE_ESC_APD)
593
GARRAY(pole_count, 0, "ESC_NUM_POLES", 22),
594
#endif
595
596
#if defined(HAL_PERIPH_ENABLE_ESC_APD)
597
// @Param: ESC_APD_SERIAL_1
598
// @DisplayName: ESC APD Serial 1
599
// @Description: Which serial port to use for APD ESC data
600
// @Range: 0 6
601
// @Increment: 1
602
// @User: Advanced
603
// @RebootRequired: True
604
GARRAY(esc_serial_port, 0, "ESC_APD_SERIAL_1", APD_ESC_SERIAL_0),
605
606
#if APD_ESC_INSTANCES > 1
607
GARRAY(esc_number, 1, "ESC_NUMBER2", 1),
608
609
GARRAY(pole_count, 1, "ESC_NUM_POLES2", 22),
610
611
// @Param: ESC_APD_SERIAL_2
612
// @DisplayName: ESC APD Serial 2
613
// @Description: Which serial port to use for APD ESC data
614
// @Range: 0 6
615
// @Increment: 1
616
// @User: Advanced
617
// @RebootRequired: True
618
GARRAY(esc_serial_port, 1, "ESC_APD_SERIAL_2", APD_ESC_SERIAL_1),
619
#endif
620
#endif
621
622
#ifdef HAL_PERIPH_ENABLE_NETWORKING
623
// @Group: NET_
624
// @Path: networking.cpp
625
GOBJECT(networking_periph, "NET_", Networking_Periph),
626
#endif
627
628
#ifdef HAL_PERIPH_ENABLE_RPM
629
// @Group: RPM
630
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
631
GOBJECT(rpm_sensor, "RPM", AP_RPM),
632
#endif
633
634
#ifdef HAL_PERIPH_ENABLE_RCIN
635
// @Group: RC
636
// @Path: rc_in.cpp
637
GOBJECT(g_rcin, "RC", Parameters_RCIN),
638
#endif
639
640
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE
641
// @Group: BAL
642
// @Path: batt_balance.cpp
643
GOBJECT(battery_balance, "BAL", BattBalance),
644
#endif
645
646
#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS
647
// @Group: UART
648
// @Path: serial_options.cpp
649
GOBJECT(serial_options, "UART", SerialOptions),
650
#endif
651
652
// NOTE: sim parameters should go last
653
#if AP_SIM_ENABLED
654
// @Group: SIM_
655
// @Path: ../libraries/SITL/SITL.cpp
656
GOBJECT(sitl, "SIM_", SITL::SIM),
657
658
#if AP_AHRS_ENABLED
659
// @Group: AHRS_
660
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
661
GOBJECT(ahrs, "AHRS_", AP_AHRS),
662
#endif
663
#endif // AP_SIM_ENABLED
664
665
#if HAL_PERIPH_CAN_MIRROR
666
// @Param: CAN_MIRROR_PORTS
667
// @DisplayName: CAN ports to mirror traffic between
668
// @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.
669
// @Bitmask: 0:CAN1, 1:CAN2, 2:CAN3
670
// @User: Advanced
671
GSCALAR(can_mirror_ports, "CAN_MIRROR_PORTS", 0),
672
#endif // HAL_PERIPH_CAN_MIRROR
673
674
#ifdef HAL_PERIPH_ENABLE_RTC
675
// @Group: RTC
676
// @Path: ../libraries/AP_RTC/AP_RTC.cpp
677
GOBJECT(rtc, "RTC", AP_RTC),
678
#endif
679
680
#ifdef HAL_PERIPH_ENABLE_RELAY
681
// @Group: RELAY
682
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
683
GOBJECT(relay, "RELAY", AP_Relay),
684
#endif
685
686
#ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE
687
// @Param: TEMP_MSG_RATE
688
// @DisplayName: Temperature sensor message rate
689
// @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.
690
// @Units: Hz
691
// @Range: 0 200
692
// @Increment: 1
693
// @User: Standard
694
GSCALAR(temperature_msg_rate, "TEMP_MSG_RATE", 0),
695
#endif
696
697
// @Param: OPTIONS
698
// @DisplayName: AP Periph Options
699
// @Description: Bitmask of AP Periph Options
700
// @Bitmask: 0: Enable continuous sensor probe
701
// @User: Standard
702
GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS),
703
704
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
705
// @Param: RPM_MSG_RATE
706
// @DisplayName: RPM sensor message rate
707
// @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.
708
// @Units: Hz
709
// @Range: 0 200
710
// @Increment: 1
711
// @User: Standard
712
GSCALAR(rpm_msg_rate, "RPM_MSG_RATE", 0),
713
#endif
714
715
#if AP_EXTENDED_ESC_TELEM_ENABLED && HAL_WITH_ESC_TELEM
716
// @Param: ESC_EXT_TLM_RATE
717
// @DisplayName: ESC Extended telemetry message rate
718
// @Description: This is the rate at which extended ESC Telemetry will be sent across the CAN bus for each ESC
719
// @Units: Hz
720
// @Range: 0 50
721
// @Increment: 1
722
// @User: Advanced
723
GSCALAR(esc_extended_telem_rate, "ESC_EXT_TLM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT / 10),
724
#endif
725
726
727
#ifdef HAL_PERIPH_ENABLE_IMU
728
// @Param: IMU_SAMPLE_RATE
729
// @DisplayName: IMU Sample Rate
730
// @Description: IMU Sample Rate
731
// @Range: 0 1000
732
// @User: Standard
733
GSCALAR(imu_sample_rate, "INS_SAMPLE_RATE", 0),
734
735
// @Group: INS
736
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
737
GOBJECT(imu, "INS", AP_InertialSensor),
738
#endif
739
740
AP_VAREND
741
};
742
743
744
void AP_Periph_FW::load_parameters(void)
745
{
746
AP_Param::setup_sketch_defaults();
747
748
AP_Param::check_var_info();
749
750
if (!g.format_version.load() ||
751
g.format_version != Parameters::k_format_version) {
752
// erase all parameters
753
StorageManager::erase();
754
AP_Param::erase_all();
755
756
// save the current format version
757
g.format_version.set_and_save(Parameters::k_format_version);
758
}
759
g.format_version.set_default(Parameters::k_format_version);
760
761
// Load all auto-loaded EEPROM variables
762
AP_Param::load_all();
763
}
764
765