Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/Parameters.cpp
9347 views
1
#include "Sub.h"
2
3
#include <AP_Gripper/AP_Gripper.h>
4
5
/*
6
This program is free software: you can redistribute it and/or modify
7
it under the terms of the GNU General Public License as published by
8
the Free Software Foundation, either version 3 of the License, or
9
(at your option) any later version.
10
11
This program is distributed in the hope that it will be useful,
12
but WITHOUT ANY WARRANTY; without even the implied warranty of
13
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14
GNU General Public License for more details.
15
16
You should have received a copy of the GNU General Public License
17
along with this program. If not, see <http://www.gnu.org/licenses/>.
18
*/
19
20
/*
21
* ArduSub parameter definitions
22
*
23
*/
24
25
const AP_Param::Info Sub::var_info[] = {
26
27
// @Param: SURFACE_DEPTH
28
// @DisplayName: Depth reading at surface
29
// @Description: The depth the external pressure sensor will read when the vehicle is considered at the surface (in centimeters)
30
// @Units: cm
31
// @Range: -100 0
32
// @User: Standard
33
GSCALAR(surface_depth, "SURFACE_DEPTH", SURFACE_DEPTH_DEFAULT),
34
35
// @Param: FORMAT_VERSION
36
// @DisplayName: Eeprom format version number
37
// @Description: This value is incremented when changes are made to the eeprom format
38
// @User: Advanced
39
GSCALAR(format_version, "FORMAT_VERSION", 0),
40
41
// SYSID_THISMAV was here
42
43
// SYSID_MYGCS was here
44
45
// @Param: PILOT_THR_FILT
46
// @DisplayName: Throttle filter cutoff
47
// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
48
// @User: Advanced
49
// @Units: Hz
50
// @Range: 0 10
51
// @Increment: 0.5
52
GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),
53
54
// AP_SerialManager was here
55
56
// @Param: GCS_PID_MASK
57
// @DisplayName: GCS PID tuning mask
58
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
59
// @User: Advanced
60
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
61
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
62
63
// @Param: FS_GCS_ENABLE
64
// @DisplayName: Ground Station Failsafe Enable
65
// @Description: Controls what action to take when GCS heartbeat is lost.
66
// @Values: 0:Disabled,1:Warn only,2:Disarm,3:Enter depth hold mode,4:Enter surface mode
67
// @User: Standard
68
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISARM),
69
70
// @Param: FS_GCS_TIMEOUT
71
// @DisplayName: GCS failsafe timeout
72
// @Description: Timeout before triggering the GCS failsafe
73
// @Units: s
74
// @Increment: 1
75
// @User: Standard
76
GSCALAR(failsafe_gcs_timeout, "FS_GCS_TIMEOUT", FS_GCS_TIMEOUT_S),
77
78
// @Param: FS_LEAK_ENABLE
79
// @DisplayName: Leak Failsafe Enable
80
// @Description: Controls what action to take if a leak is detected.
81
// @Values: 0:Disabled,1:Warn only,2:Enter surface mode
82
// @User: Standard
83
GSCALAR(failsafe_leak, "FS_LEAK_ENABLE", FS_LEAK_WARN_ONLY),
84
85
// @Param: FS_PRESS_ENABLE
86
// @DisplayName: Internal Pressure Failsafe Enable
87
// @Description: Controls what action to take if internal pressure exceeds FS_PRESS_MAX parameter.
88
// @Values: 0:Disabled,1:Warn only
89
// @User: Standard
90
GSCALAR(failsafe_pressure, "FS_PRESS_ENABLE", FS_PRESS_DISABLED),
91
92
// @Param: FS_TEMP_ENABLE
93
// @DisplayName: Internal Temperature Failsafe Enable
94
// @Description: Controls what action to take if internal temperature exceeds FS_TEMP_MAX parameter.
95
// @Values: 0:Disabled,1:Warn only
96
// @User: Standard
97
GSCALAR(failsafe_temperature, "FS_TEMP_ENABLE", FS_TEMP_DISABLED),
98
99
#if AP_SUB_RC_ENABLED
100
// @Param: FS_THR_ENABLE
101
// @DisplayName: Throttle Failsafe Enable
102
// @Description: The throttle failsafe allows you to configure a software RC failsafe activated by a setting on the throttle input channel. It also enables RC failsafe on absence of RC signals being recieved.
103
// @Values: 0:Disabled,1: Force effective control inputs to trim positions and prevent arming,2:Surface and hold on surface on failsafe
104
// @User: Standard
105
GSCALAR(failsafe_throttle, "FS_THR_ENABLE", 0),
106
107
// @Param: FS_THR_VALUE
108
// @DisplayName: Throttle Failsafe Value
109
// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers
110
// @Range: 910 1100
111
// @Units: PWM
112
// @Increment: 1
113
// @User: Standard
114
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
115
116
// @Param: FLTMODE1
117
// @DisplayName: Flight Mode 1
118
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230
119
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,7:Circle,9:Surface,16:PosHold,19:Manual,20:Motor Detect,21:SurfTrak
120
// @User: Standard
121
GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),
122
123
// @Param: FLTMODE2
124
// @CopyFieldsFrom: FLTMODE1
125
// @DisplayName: Flight Mode 2
126
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360
127
GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),
128
129
// @Param: FLTMODE3
130
// @CopyFieldsFrom: FLTMODE1
131
// @DisplayName: Flight Mode 3
132
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490
133
GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),
134
135
// @Param: FLTMODE4
136
// @CopyFieldsFrom: FLTMODE1
137
// @DisplayName: Flight Mode 4
138
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620
139
GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),
140
141
// @Param: FLTMODE5
142
// @CopyFieldsFrom: FLTMODE1
143
// @DisplayName: Flight Mode 5
144
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749
145
GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),
146
147
// @Param: FLTMODE6
148
// @CopyFieldsFrom: FLTMODE1
149
// @DisplayName: Flight Mode 6
150
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750
151
GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),
152
153
// @Param: FLTMODE_CH
154
// @DisplayName: Flightmode channel
155
// @Description: RC Channel to use for flight mode control
156
// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8,9:Channel9,10:Channel 10,11:Channel 11,12:Channel 12,13:Channel 13,14:Channel 14,15:Channel 15
157
// @User: Advanced
158
GSCALAR(flight_mode_chan, "FLTMODE_CH", 0),
159
160
// @Param: THR_ARM_POS
161
// @DisplayName: Throttle arming position
162
// @Description: Determines if throttle must be at min or within trim value to arm, if RC checks and RC_OPTION for "0" throttle are enabled.
163
// @User: Standard
164
// @Bitmask: 0:Throttle at or below min, 1: Throttle within a dead zone of RC trim value
165
GSCALAR(thr_arming_position, "THR_ARM_POS", 1),
166
#endif
167
// @Param: FS_PRESS_MAX
168
// @DisplayName: Internal Pressure Failsafe Threshold
169
// @Description: The maximum internal pressure allowed before triggering failsafe. Failsafe action is determined by FS_PRESS_ENABLE parameter
170
// @Units: Pa
171
// @User: Standard
172
GSCALAR(failsafe_pressure_max, "FS_PRESS_MAX", FS_PRESS_MAX_DEFAULT),
173
174
// @Param: FS_TEMP_MAX
175
// @DisplayName: Internal Temperature Failsafe Threshold
176
// @Description: The maximum internal temperature allowed before triggering failsafe. Failsafe action is determined by FS_TEMP_ENABLE parameter.
177
// @Units: degC
178
// @User: Standard
179
GSCALAR(failsafe_temperature_max, "FS_TEMP_MAX", FS_TEMP_MAX_DEFAULT),
180
181
// @Param: SURFACE_MAX_THR
182
// @DisplayName: Surface Maximum Throttle
183
// @Description: Maximum throttle value when the vehicle is at the surface. This value is used to scale throttle linearly from 1. (full) to min as the vehicle approaches the surface. The attenuation starts at 1 meter from surface. Only upwards throttle is limited.
184
// @Range: 0.0 1.0
185
// @User: Standard
186
// @Increment: 0.01
187
GSCALAR(surface_max_throttle, "SURFACE_MAX_THR", 0.1f),
188
189
// @Param: FS_TERRAIN_ENAB
190
// @DisplayName: Terrain Failsafe Enable
191
// @Description: Controls what action to take if terrain information is lost during AUTO mode
192
// @Values: 0:Disarm, 1:Hold Position, 2:Surface
193
// @User: Standard
194
GSCALAR(failsafe_terrain, "FS_TERRAIN_ENAB", FS_TERRAIN_DISARM),
195
196
// @Param: FS_PILOT_INPUT
197
// @DisplayName: Pilot input failsafe action
198
// @Description: Controls what action to take if no pilot input has been received after the timeout period specified by the FS_PILOT_TIMEOUT parameter
199
// @Values: 0:Disabled, 1:Warn Only, 2:Disarm
200
// @User: Standard
201
GSCALAR(failsafe_pilot_input, "FS_PILOT_INPUT", FS_PILOT_INPUT_DISARM),
202
203
// @Param: FS_PILOT_TIMEOUT
204
// @DisplayName: Timeout for activation of pilot input failsafe
205
// @Description: Controls the maximum interval between received pilot inputs before the failsafe action is triggered
206
// @Units: s
207
// @Range: 0.1 3.0
208
// @User: Standard
209
GSCALAR(failsafe_pilot_input_timeout, "FS_PILOT_TIMEOUT", 3.0f),
210
211
// @Param: XTRACK_ANG_LIM
212
// @DisplayName: Crosstrack correction angle limit
213
// @Description: Maximum allowed angle (in degrees) between current track and desired heading during waypoint navigation
214
// @Range: 10 90
215
// @User: Standard
216
GSCALAR(xtrack_angle_limit,"XTRACK_ANG_LIM", 45),
217
218
// @Param: WP_YAW_BEHAVIOR
219
// @DisplayName: Yaw behaviour during missions
220
// @Description: Determines how the autopilot controls the yaw during missions and RTL
221
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course, 4:Correct crosstrack error
222
// @User: Standard
223
GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),
224
225
// @Param: PILOT_SPEED_UP
226
// @DisplayName: Pilot maximum vertical ascending speed
227
// @Description: The maximum vertical ascending velocity the pilot may request in cm/s
228
// @Units: cm/s
229
// @Range: 20 500
230
// @Increment: 10
231
// @User: Standard
232
GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX),
233
234
// @Param: PILOT_SPEED_DN
235
// @DisplayName: Pilot maximum vertical descending speed
236
// @Description: The maximum vertical descending velocity the pilot may request in cm/s
237
// @Units: cm/s
238
// @Range: 20 500
239
// @Increment: 10
240
// @User: Standard
241
GSCALAR(pilot_speed_dn, "PILOT_SPEED_DN", 0),
242
243
// @Param: PILOT_SPEED
244
// @DisplayName: Pilot maximum horizontal speed
245
// @Description: The maximum horizontal velocity the pilot may request in cm/s
246
// @Units: cm/s
247
// @Range: 10 500
248
// @Increment: 10
249
// @User: Standard
250
GSCALAR(pilot_speed, "PILOT_SPEED", PILOT_SPEED_DEFAULT),
251
252
// @Param: PILOT_ACCEL_Z
253
// @DisplayName: Pilot vertical acceleration
254
// @Description: The vertical acceleration used when pilot is controlling the altitude
255
// @Units: cm/s/s
256
// @Range: 50 500
257
// @Increment: 10
258
// @User: Standard
259
GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),
260
261
// @Param: THR_DZ
262
// @DisplayName: Throttle deadzone
263
// @Description: The PWM deadzone in microseconds above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
264
// @User: Standard
265
// @Range: 0 300
266
// @Units: PWM
267
// @Increment: 1
268
GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),
269
270
// @Param: LOG_BITMASK
271
// @DisplayName: Log bitmask
272
// @Description: 4 byte bitmap of log types to enable
273
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW
274
// @User: Standard
275
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
276
277
// @Param: FS_EKF_ACTION
278
// @DisplayName: EKF Failsafe Action
279
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
280
// @Values: 0:Disabled, 1:Warn only, 2:Disarm
281
// @User: Advanced
282
GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),
283
284
// @Param: FS_EKF_THRESH
285
// @DisplayName: EKF failsafe variance threshold
286
// @Description: Allows setting the maximum acceptable compass and velocity variance
287
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
288
// @Range: 0.6 1.0
289
// @User: Advanced
290
GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),
291
292
// @Param: FS_CRASH_CHECK
293
// @DisplayName: Crash check enable
294
// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
295
// @Values: 0:Disabled,1:Warn only,2:Disarm
296
// @User: Advanced
297
GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLED),
298
299
// @Param: JS_GAIN_DEFAULT
300
// @DisplayName: Default gain at boot
301
// @Description: Default gain at boot, must be in range [JS_GAIN_MIN , JS_GAIN_MAX]. Current gain value is accessible via NAMED_VALUE_FLOAT MAVLink message with name 'PilotGain'.
302
// @User: Standard
303
// @Range: 0.1 1.0
304
GSCALAR(gain_default, "JS_GAIN_DEFAULT", 0.5),
305
306
// @Param: JS_GAIN_MAX
307
// @DisplayName: Maximum joystick gain
308
// @Description: Maximum joystick gain
309
// @User: Standard
310
// @Range: 0.2 1.0
311
GSCALAR(maxGain, "JS_GAIN_MAX", 1.0),
312
313
// @Param: JS_GAIN_MIN
314
// @DisplayName: Minimum joystick gain
315
// @Description: Minimum joystick gain
316
// @User: Standard
317
// @Range: 0.1 0.8
318
GSCALAR(minGain, "JS_GAIN_MIN", 0.25),
319
320
// @Param: JS_GAIN_STEPS
321
// @DisplayName: Gain steps
322
// @Description: Controls the number of steps between minimum and maximum joystick gain when the gain is adjusted using buttons. Set to 1 to always use JS_GAIN_DEFAULT.
323
// @User: Standard
324
// @Range: 1 10
325
GSCALAR(numGainSettings, "JS_GAIN_STEPS", 4),
326
327
// @Param: JS_LIGHTS_STEPS
328
// @DisplayName: Lights brightness steps
329
// @Description: Number of steps in brightness between minimum and maximum brightness
330
// @User: Standard
331
// @Range: 1 10
332
// @Units: PWM
333
GSCALAR(lights_steps, "JS_LIGHTS_STEPS", 8),
334
335
// @Param: JS_THR_GAIN
336
// @DisplayName: Throttle gain scalar
337
// @Description: Scalar for gain on the throttle channel. Gets scaled with the current JS gain
338
// @User: Standard
339
// @Range: 0.5 4.0
340
GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f),
341
342
// @Param: FRAME_CONFIG
343
// @DisplayName: Frame configuration
344
// @Description: Set this parameter according to your vehicle/motor configuration
345
// @User: Standard
346
// @RebootRequired: True
347
// @Values: 0:BlueROV1, 1:Vectored, 2:Vectored_6DOF, 3:Vectored_6DOF_90, 4:SimpleROV-3, 5:SimpleROV-4, 6:SimpleROV-5, 7:Custom
348
GSCALAR(frame_configuration, "FRAME_CONFIG", AP_Motors6DOF::SUB_FRAME_VECTORED),
349
350
// @Group: BTN0_
351
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
352
GGROUP(jbtn_0, "BTN0_", JSButton),
353
354
// @Group: BTN1_
355
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
356
GGROUP(jbtn_1, "BTN1_", JSButton),
357
358
// @Group: BTN2_
359
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
360
GGROUP(jbtn_2, "BTN2_", JSButton),
361
362
// @Group: BTN3_
363
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
364
GGROUP(jbtn_3, "BTN3_", JSButton),
365
366
// @Group: BTN4_
367
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
368
GGROUP(jbtn_4, "BTN4_", JSButton),
369
370
// @Group: BTN5_
371
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
372
GGROUP(jbtn_5, "BTN5_", JSButton),
373
374
// @Group: BTN6_
375
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
376
GGROUP(jbtn_6, "BTN6_", JSButton),
377
378
// @Group: BTN7_
379
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
380
GGROUP(jbtn_7, "BTN7_", JSButton),
381
382
// @Group: BTN8_
383
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
384
GGROUP(jbtn_8, "BTN8_", JSButton),
385
386
// @Group: BTN9_
387
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
388
GGROUP(jbtn_9, "BTN9_", JSButton),
389
390
// @Group: BTN10_
391
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
392
GGROUP(jbtn_10, "BTN10_", JSButton),
393
394
// @Group: BTN11_
395
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
396
GGROUP(jbtn_11, "BTN11_", JSButton),
397
398
// @Group: BTN12_
399
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
400
GGROUP(jbtn_12, "BTN12_", JSButton),
401
402
// @Group: BTN13_
403
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
404
GGROUP(jbtn_13, "BTN13_", JSButton),
405
406
// @Group: BTN14_
407
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
408
GGROUP(jbtn_14, "BTN14_", JSButton),
409
410
// @Group: BTN15_
411
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
412
GGROUP(jbtn_15, "BTN15_", JSButton),
413
414
// @Group: BTN16_
415
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
416
GGROUP(jbtn_16, "BTN16_", JSButton),
417
418
// @Group: BTN17_
419
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
420
GGROUP(jbtn_17, "BTN17_", JSButton),
421
422
// @Group: BTN18_
423
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
424
GGROUP(jbtn_18, "BTN18_", JSButton),
425
426
// @Group: BTN19_
427
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
428
GGROUP(jbtn_19, "BTN19_", JSButton),
429
430
// @Group: BTN20_
431
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
432
GGROUP(jbtn_20, "BTN20_", JSButton),
433
434
// @Group: BTN21_
435
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
436
GGROUP(jbtn_21, "BTN21_", JSButton),
437
438
// @Group: BTN22_
439
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
440
GGROUP(jbtn_22, "BTN22_", JSButton),
441
442
// @Group: BTN23_
443
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
444
GGROUP(jbtn_23, "BTN23_", JSButton),
445
446
// @Group: BTN24_
447
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
448
GGROUP(jbtn_24, "BTN24_", JSButton),
449
450
// @Group: BTN25_
451
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
452
GGROUP(jbtn_25, "BTN25_", JSButton),
453
454
// @Group: BTN26_
455
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
456
GGROUP(jbtn_26, "BTN26_", JSButton),
457
458
// @Group: BTN27_
459
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
460
GGROUP(jbtn_27, "BTN27_", JSButton),
461
462
// @Group: BTN28_
463
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
464
GGROUP(jbtn_28, "BTN28_", JSButton),
465
466
// @Group: BTN29_
467
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
468
GGROUP(jbtn_29, "BTN29_", JSButton),
469
470
// @Group: BTN30_
471
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
472
GGROUP(jbtn_30, "BTN30_", JSButton),
473
474
// @Group: BTN31_
475
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
476
GGROUP(jbtn_31, "BTN31_", JSButton),
477
478
// @Param: RC_SPEED
479
// @DisplayName: ESC Update Speed
480
// @Description: This is the speed in Hertz that your ESCs will receive updates
481
// @Units: Hz
482
// @Range: 50 490
483
// @Increment: 1
484
// @User: Advanced
485
GSCALAR(rc_speed, "RC_SPEED", RC_SPEED_DEFAULT),
486
487
// @Param: ACRO_RP_P
488
// @DisplayName: Acro Roll and Pitch P gain
489
// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
490
// @Range: 1 10
491
// @User: Standard
492
GSCALAR(acro_rp_p, "ACRO_RP_P", ACRO_RP_P),
493
494
// @Param: ACRO_YAW_P
495
// @DisplayName: Acro Yaw P gain
496
// @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.
497
// @Range: 1 10
498
// @User: Standard
499
GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),
500
501
// @Param: ACRO_BAL_ROLL
502
// @DisplayName: Acro Balance Roll
503
// @Description: rate at which roll angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
504
// @Range: 0 3
505
// @Increment: 0.1
506
// @User: Advanced
507
GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),
508
509
// @Param: ACRO_BAL_PITCH
510
// @DisplayName: Acro Balance Pitch
511
// @Description: rate at which pitch angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
512
// @Range: 0 3
513
// @Increment: 0.1
514
// @User: Advanced
515
GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
516
517
// @Param: ACRO_TRAINER
518
// @DisplayName: Acro Trainer
519
// @Description: Type of trainer used in acro mode
520
// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
521
// @User: Advanced
522
GSCALAR(acro_trainer, "ACRO_TRAINER", ACRO_TRAINER_LIMITED),
523
524
// @Param: ACRO_EXPO
525
// @DisplayName: Acro Expo
526
// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges
527
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
528
// @Range: -0.5 0.95
529
// @User: Advanced
530
GSCALAR(acro_expo, "ACRO_EXPO", ACRO_EXPO_DEFAULT),
531
532
// variables not in the g class which contain EEPROM saved variables
533
534
#if AP_CAMERA_ENABLED
535
// @Group: CAM
536
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
537
GOBJECT(camera, "CAM", AP_Camera),
538
#endif
539
540
#if AP_RELAY_ENABLED
541
// @Group: RELAY
542
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
543
GOBJECT(relay, "RELAY", AP_Relay),
544
#endif
545
546
// @Group: COMPASS_
547
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
548
GOBJECT(compass, "COMPASS_", Compass),
549
550
// @Group: INS
551
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
552
GOBJECT(ins, "INS", AP_InertialSensor),
553
554
// @Group: WPNAV_
555
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
556
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
557
558
// @Group: LOIT_
559
// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
560
GOBJECT(loiter_nav, "LOIT_", AC_Loiter),
561
562
#if CIRCLE_NAV_ENABLED
563
// @Group: CIRCLE_
564
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
565
GOBJECT(circle_nav, "CIRCLE_", AC_Circle),
566
#endif
567
568
// @Group: ATC_
569
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp
570
GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Sub),
571
572
// @Group: PSC
573
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
574
GOBJECT(pos_control, "PSC", AC_PosControl),
575
576
// @Group: AHRS_
577
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
578
GOBJECT(ahrs, "AHRS_", AP_AHRS),
579
580
#if HAL_MOUNT_ENABLED
581
// @Group: MNT
582
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
583
GOBJECT(camera_mount, "MNT", AP_Mount),
584
#endif
585
586
// @Group: BATT
587
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
588
GOBJECT(battery, "BATT", AP_BattMonitor),
589
590
// @Group: ARMING_
591
// @Path: AP_Arming_Sub.cpp,../libraries/AP_Arming/AP_Arming.cpp
592
GOBJECT(arming, "ARMING_", AP_Arming_Sub),
593
594
// @Group: BRD_
595
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
596
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
597
598
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
599
// @Group: CAN_
600
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
601
GOBJECT(can_mgr, "CAN_", AP_CANManager),
602
#endif
603
604
#if AP_SIM_ENABLED
605
// @Group: SIM_
606
// @Path: ../libraries/SITL/SITL.cpp
607
GOBJECT(sitl, "SIM_", SITL::SIM),
608
#endif
609
610
// @Group: BARO
611
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
612
GOBJECT(barometer, "BARO", AP_Baro),
613
614
// GPS driver
615
// @Group: GPS
616
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
617
GOBJECT(gps, "GPS", AP_GPS),
618
619
// Leak detector
620
// @Group: LEAK
621
// @Path: ../libraries/AP_LeakDetector/AP_LeakDetector.cpp
622
GOBJECT(leak_detector, "LEAK", AP_LeakDetector),
623
624
// @Group: SCHED_
625
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
626
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
627
628
#if AVOIDANCE_ENABLED
629
// @Group: AVOID_
630
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
631
GOBJECT(avoid, "AVOID_", AC_Avoid),
632
#endif
633
634
#if HAL_RALLY_ENABLED
635
// @Group: RALLY_
636
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
637
GOBJECT(rally, "RALLY_", AP_Rally),
638
#endif
639
640
// @Group: MOT_
641
// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp,../libraries/AP_Motors/AP_MotorsMulticopter.cpp
642
GOBJECT(motors, "MOT_", AP_Motors6DOF),
643
644
#if RCMAP_ENABLED
645
// @Group: RCMAP_
646
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
647
GOBJECT(rcmap, "RCMAP_", RCMapper),
648
#endif
649
650
#if HAL_NAVEKF2_AVAILABLE
651
// @Group: EK2_
652
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
653
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
654
#endif
655
656
#if HAL_NAVEKF3_AVAILABLE
657
// @Group: EK3_
658
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
659
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
660
#endif
661
662
// @Group: MIS_
663
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
664
GOBJECT(mission, "MIS_", AP_Mission),
665
666
#if AP_RANGEFINDER_ENABLED
667
// @Group: RNGFND
668
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
669
GOBJECT(rangefinder, "RNGFND", RangeFinder),
670
671
// @Param: RNGFND_SQ_MIN
672
// @DisplayName: Rangefinder signal quality minimum
673
// @Description: Minimum signal quality for good rangefinder readings
674
// @Range: 0 100
675
// @User: Advanced
676
GSCALAR(rangefinder_signal_min, "RNGFND_SQ_MIN", RANGEFINDER_SIGNAL_MIN_DEFAULT),
677
678
// @Param: SURFTRAK_DEPTH
679
// @DisplayName: SURFTRAK minimum depth
680
// @Description: Minimum depth to engage SURFTRAK mode
681
// @Units: cm
682
// @User: Standard
683
GSCALAR(surftrak_depth, "SURFTRAK_DEPTH", SURFTRAK_DEPTH_DEFAULT),
684
#endif
685
686
#if AP_TERRAIN_AVAILABLE
687
// @Group: TERRAIN_
688
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
689
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
690
#endif
691
692
#if AP_OPTICALFLOW_ENABLED
693
// @Group: FLOW
694
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
695
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
696
#endif
697
698
#if OSD_ENABLED || OSD_PARAM_ENABLED
699
// @Group: OSD
700
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
701
GOBJECT(osd, "OSD", AP_OSD),
702
#endif
703
704
#if AP_RSSI_ENABLED
705
// @Group: RSSI_
706
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
707
GOBJECT(rssi, "RSSI_", AP_RSSI),
708
#endif
709
710
// @Group: NTF_
711
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
712
GOBJECT(notify, "NTF_", AP_Notify),
713
714
// @Group:
715
// @Path: Parameters.cpp
716
GOBJECT(g2, "", ParametersG2),
717
718
// @Group:
719
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
720
PARAM_VEHICLE_INFO,
721
722
#if HAL_GCS_ENABLED
723
// @Group: MAV
724
// @Path: ../libraries/GCS_MAVLink/GCS.cpp
725
GOBJECT(_gcs, "MAV", GCS),
726
#endif
727
728
AP_VAREND
729
};
730
731
/*
732
2nd group of parameters
733
*/
734
const AP_Param::GroupInfo ParametersG2::var_info[] = {
735
736
// 1 was AP_Stats
737
738
#if HAL_PROXIMITY_ENABLED
739
// @Group: PRX
740
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
741
AP_SUBGROUPINFO(proximity, "PRX", 2, ParametersG2, AP_Proximity),
742
#endif
743
744
// 3 was AP_Gripper
745
746
// @Group: SERVO
747
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
748
AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),
749
750
// @Group: RC
751
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
752
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),
753
754
// 18 was scripting
755
// 19 was ORIGIN_LAT
756
// 20 was ORIGIN_LON
757
// 21 was ORIGIN_ALT
758
759
// @Param: SFC_NOBARO_THST
760
// @DisplayName: Surface mode throttle output when no barometer is available
761
// @Description: Surface mode throttle output when no borometer is available. 100% is full throttle. -100% is maximum throttle downwards
762
// @Units: %
763
// @User: Standard
764
// @Range: -100 100
765
AP_GROUPINFO("SFC_NOBARO_THST", 22, ParametersG2, surface_nobaro_thrust, 10),
766
767
// @Group: ACTUATOR
768
// @Path: ../ArduSub/actuators.cpp
769
AP_SUBGROUPINFO(actuators, "ACTUATOR", 23, ParametersG2, Actuators),
770
771
AP_GROUPEND
772
};
773
774
/*
775
constructor for g2 object
776
*/
777
ParametersG2::ParametersG2()
778
{
779
AP_Param::setup_object_defaults(this, var_info);
780
}
781
782
const AP_Param::ConversionInfo conversion_table[] = {
783
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" },
784
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" },
785
{ Parameters::k_param_failsafe_battery_enabled, 0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },
786
{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },
787
};
788
789
void Sub::load_parameters()
790
{
791
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
792
793
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
794
795
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB);
796
797
convert_old_parameters();
798
AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table));
799
// We should ignore this parameter since ROVs are neutral buoyancy
800
AP_Param::set_by_name("MOT_THST_HOVER", 0.5);
801
802
// PARAMETER_CONVERSION - Added: Mar-2022
803
#if AP_FENCE_ENABLED
804
AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true);
805
#endif
806
807
// PARAMETER_CONVERSION - Added: July-2025 for ArduPilot-4.7
808
#if AP_RPM_ENABLED
809
AP_Param::convert_class(g.k_param_rpm_sensor_old, &rpm_sensor, rpm_sensor.var_info, 0, true, true);
810
#endif
811
812
static const AP_Param::G2ObjectConversion g2_conversions[] {
813
#if AP_AIRSPEED_ENABLED
814
// PARAMETER_CONVERSION - Added: JAN-2022
815
{ &airspeed, airspeed.var_info, 19 },
816
#endif
817
#if AP_STATS_ENABLED
818
// PARAMETER_CONVERSION - Added: Jan-2024
819
{ &stats, stats.var_info, 1 },
820
#endif
821
#if AP_SCRIPTING_ENABLED
822
// PARAMETER_CONVERSION - Added: Jan-2024
823
{ &scripting, scripting.var_info, 18 },
824
#endif
825
#if AP_GRIPPER_ENABLED
826
// PARAMETER_CONVERSION - Added: Feb-2024
827
{ &gripper, gripper.var_info, 3 },
828
#endif
829
};
830
831
AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));
832
833
// PARAMETER_CONVERSION - Added: Feb-2024
834
#if HAL_LOGGING_ENABLED
835
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
836
#endif
837
838
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
839
#if AP_SERIALMANAGER_ENABLED
840
// PARAMETER_CONVERSION - Added: Feb-2024
841
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
842
#endif
843
};
844
845
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
846
847
#if HAL_GCS_ENABLED
848
// Move parameters into new MAV_ parameter namespace
849
// PARAMETER_CONVERSION - Added: Mar-2025
850
{
851
static const AP_Param::ConversionInfo gcs_conversion_info[] {
852
{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },
853
{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },
854
};
855
AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));
856
}
857
#endif // HAL_GCS_ENABLED
858
859
// upgrade attitude controller parameters
860
sub.attitude_control.convert_parameters();
861
862
// upgrade loiter navigation parameters
863
loiter_nav.convert_parameters();
864
865
#if CIRCLE_NAV_ENABLED
866
circle_nav.convert_parameters();
867
#endif
868
869
// PARAMETER_CONVERSION - Added: Jan-2026
870
// move ORIGIN_LAT, ORIGIN_LON, ORIGIN_ALT to AHRS
871
static const AP_Param::ConversionInfo gcs_conversion_info[] {
872
{ 2, 19, AP_PARAM_FLOAT, "AHRS_ORIGIN_LAT" }, // ORIGIN_LAT moved to AHRS_ORIGIN_LAT
873
{ 2, 20, AP_PARAM_FLOAT, "AHRS_ORIGIN_LON" }, // ORIGIN_LON moved to AHRS_ORIGIN_LON
874
{ 2, 21, AP_PARAM_FLOAT, "AHRS_ORIGIN_ALT" }, // ORIGIN_ALT moved to AHRS_ORIGIN_ALT
875
};
876
AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));
877
}
878
879
void Sub::convert_old_parameters()
880
{
881
// attitude control filter parameter changes from _FILT to FLTE or FLTD
882
const AP_Param::ConversionInfo filt_conversion_info[] = {
883
// move ATC_RAT_RLL/PIT_FILT to FLTD, move ATC_RAT_YAW_FILT to FLTE
884
{ Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" },
885
{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" },
886
{ Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" },
887
};
888
AP_Param::convert_old_parameters(&filt_conversion_info[0], ARRAY_SIZE(filt_conversion_info));
889
890
SRV_Channels::upgrade_parameters();
891
}
892
893
#if LEAKDETECTOR_MAX_INSTANCES > 0
894
// PARAMETER_CONVERSION - Added: Dec-2025
895
// Deals with leak detector getting misconfigured when updating from Sub 4.1
896
void Sub::update_leak_pins()
897
{
898
for (uint8_t instance = 0; instance < LEAKDETECTOR_MAX_INSTANCES; instance++) {
899
if (leak_detector.get_pin(instance) <= 0) {
900
// leak detector does not use pin
901
continue;
902
}
903
uint8_t servo_channel;
904
if (!hal.gpio->pin_to_servo_channel(leak_detector.get_pin(instance), servo_channel)) {
905
// leak detector pin does not map to a servo channel
906
continue;
907
}
908
if (SRV_Channels::is_GPIO(servo_channel)) {
909
// servo channel is already set to GPIO
910
continue;
911
}
912
if (SRV_Channels::channel_function(servo_channel) != SRV_Channel::Function::k_none) {
913
// servo channel is already set to a function
914
gcs().send_text(MAV_SEVERITY_WARNING, "Leak detector %u error. Please set SERVO%u_FUNCTION to GPIO", instance + 1, servo_channel + 1);
915
continue;
916
}
917
// servo channel is disabled, let's set it to GPIO for the user
918
gcs().send_text(MAV_SEVERITY_INFO, "Leak detector %u pin (servo %u) auto-set to GPIO", instance + 1, servo_channel + 1);
919
char param_name[20];
920
snprintf(param_name, sizeof(param_name), "SERVO%u_FUNCTION", servo_channel + 1);
921
AP_Param::set_and_save_by_name(param_name, static_cast<int>(SRV_Channel::Function::k_GPIO));
922
}
923
}
924
#endif
925
926
#if AP_RELAY_ENABLED
927
// PARAMETER_CONVERSION - Added: Dec-2025
928
// Deals with relay getting misconfigured when updating from Sub 4.1
929
void Sub::update_relay_pins()
930
{
931
for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) {
932
uint8_t servo_channel;
933
uint8_t pin;
934
if (!relay.get_pin_by_instance(instance, pin) || !hal.gpio->pin_to_servo_channel(pin, servo_channel)) {
935
// instance does not use pin or pin does not map to a servo channel
936
continue;
937
}
938
if (!relay.enabled(instance) || SRV_Channels::is_GPIO(servo_channel)) {
939
// instance is not enabled or servo channel is already set to GPIO
940
continue;
941
}
942
if (SRV_Channels::channel_function(servo_channel) != SRV_Channel::Function::k_none) {
943
// servo channel is already set to a function
944
gcs().send_text(MAV_SEVERITY_WARNING, "Relay %u error. Please set SERVO%u_FUNCTION to GPIO", instance + 1, servo_channel + 1);
945
continue;
946
}
947
// servo channel is disabled, let's set it to GPIO for the user
948
gcs().send_text(MAV_SEVERITY_INFO, "Relay %u pin (servo %u) auto-set to GPIO", instance + 1, servo_channel + 1);
949
char param_name[20];
950
snprintf(param_name, sizeof(param_name), "SERVO%u_FUNCTION", servo_channel + 1);
951
AP_Param::set_and_save_by_name(param_name, static_cast<int>(SRV_Channel::Function::k_GPIO));
952
}
953
}
954
#endif
955
956