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/ArduSub/Parameters.cpp
Views: 1798
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
// @Param: SYSID_THISMAV
42
// @DisplayName: MAVLink system ID of this vehicle
43
// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
44
// @Range: 1 255
45
// @User: Advanced
46
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
47
48
// @Param: SYSID_MYGCS
49
// @DisplayName: My ground station number
50
// @Description: Allows restricting radio overrides to only come from my ground station
51
// @Range: 1 255
52
// @Increment: 1
53
// @User: Advanced
54
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
55
56
// @Param: PILOT_THR_FILT
57
// @DisplayName: Throttle filter cutoff
58
// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
59
// @User: Advanced
60
// @Units: Hz
61
// @Range: 0 10
62
// @Increment: 0.5
63
GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),
64
65
// AP_SerialManager was here
66
67
// @Param: GCS_PID_MASK
68
// @DisplayName: GCS PID tuning mask
69
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
70
// @User: Advanced
71
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
72
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
73
74
// @Param: FS_GCS_ENABLE
75
// @DisplayName: Ground Station Failsafe Enable
76
// @Description: Controls what action to take when GCS heartbeat is lost.
77
// @Values: 0:Disabled,1:Warn only,2:Disarm,3:Enter depth hold mode,4:Enter surface mode
78
// @User: Standard
79
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISARM),
80
81
// @Param: FS_GCS_TIMEOUT
82
// @DisplayName: GCS failsafe timeout
83
// @Description: Timeout before triggering the GCS failsafe
84
// @Units: s
85
// @Increment: 1
86
// @User: Standard
87
GSCALAR(failsafe_gcs_timeout, "FS_GCS_TIMEOUT", FS_GCS_TIMEOUT_S),
88
89
// @Param: FS_LEAK_ENABLE
90
// @DisplayName: Leak Failsafe Enable
91
// @Description: Controls what action to take if a leak is detected.
92
// @Values: 0:Disabled,1:Warn only,2:Enter surface mode
93
// @User: Standard
94
GSCALAR(failsafe_leak, "FS_LEAK_ENABLE", FS_LEAK_WARN_ONLY),
95
96
// @Param: FS_PRESS_ENABLE
97
// @DisplayName: Internal Pressure Failsafe Enable
98
// @Description: Controls what action to take if internal pressure exceeds FS_PRESS_MAX parameter.
99
// @Values: 0:Disabled,1:Warn only
100
// @User: Standard
101
GSCALAR(failsafe_pressure, "FS_PRESS_ENABLE", FS_PRESS_DISABLED),
102
103
// @Param: FS_TEMP_ENABLE
104
// @DisplayName: Internal Temperature Failsafe Enable
105
// @Description: Controls what action to take if internal temperature exceeds FS_TEMP_MAX parameter.
106
// @Values: 0:Disabled,1:Warn only
107
// @User: Standard
108
GSCALAR(failsafe_temperature, "FS_TEMP_ENABLE", FS_TEMP_DISABLED),
109
110
// @Param: FS_PRESS_MAX
111
// @DisplayName: Internal Pressure Failsafe Threshold
112
// @Description: The maximum internal pressure allowed before triggering failsafe. Failsafe action is determined by FS_PRESS_ENABLE parameter
113
// @Units: Pa
114
// @User: Standard
115
GSCALAR(failsafe_pressure_max, "FS_PRESS_MAX", FS_PRESS_MAX_DEFAULT),
116
117
// @Param: FS_TEMP_MAX
118
// @DisplayName: Internal Temperature Failsafe Threshold
119
// @Description: The maximum internal temperature allowed before triggering failsafe. Failsafe action is determined by FS_TEMP_ENABLE parameter.
120
// @Units: degC
121
// @User: Standard
122
GSCALAR(failsafe_temperature_max, "FS_TEMP_MAX", FS_TEMP_MAX_DEFAULT),
123
124
// @Param: FS_TERRAIN_ENAB
125
// @DisplayName: Terrain Failsafe Enable
126
// @Description: Controls what action to take if terrain information is lost during AUTO mode
127
// @Values: 0:Disarm, 1:Hold Position, 2:Surface
128
// @User: Standard
129
GSCALAR(failsafe_terrain, "FS_TERRAIN_ENAB", FS_TERRAIN_DISARM),
130
131
// @Param: FS_PILOT_INPUT
132
// @DisplayName: Pilot input failsafe action
133
// @Description: Controls what action to take if no pilot input has been received after the timeout period specified by the FS_PILOT_TIMEOUT parameter
134
// @Values: 0:Disabled, 1:Warn Only, 2:Disarm
135
// @User: Standard
136
GSCALAR(failsafe_pilot_input, "FS_PILOT_INPUT", FS_PILOT_INPUT_DISARM),
137
138
// @Param: FS_PILOT_TIMEOUT
139
// @DisplayName: Timeout for activation of pilot input failsafe
140
// @Description: Controls the maximum interval between received pilot inputs before the failsafe action is triggered
141
// @Units: s
142
// @Range: 0.1 3.0
143
// @User: Standard
144
GSCALAR(failsafe_pilot_input_timeout, "FS_PILOT_TIMEOUT", 3.0f),
145
146
// @Param: XTRACK_ANG_LIM
147
// @DisplayName: Crosstrack correction angle limit
148
// @Description: Maximum allowed angle (in degrees) between current track and desired heading during waypoint navigation
149
// @Range: 10 90
150
// @User: Standard
151
GSCALAR(xtrack_angle_limit,"XTRACK_ANG_LIM", 45),
152
153
// @Param: WP_YAW_BEHAVIOR
154
// @DisplayName: Yaw behaviour during missions
155
// @Description: Determines how the autopilot controls the yaw during missions and RTL
156
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course, 4:Correct crosstrack error
157
// @User: Standard
158
GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),
159
160
// @Param: PILOT_SPEED_UP
161
// @DisplayName: Pilot maximum vertical ascending speed
162
// @Description: The maximum vertical ascending velocity the pilot may request in cm/s
163
// @Units: cm/s
164
// @Range: 20 500
165
// @Increment: 10
166
// @User: Standard
167
GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX),
168
169
// @Param: PILOT_SPEED_DN
170
// @DisplayName: Pilot maximum vertical descending speed
171
// @Description: The maximum vertical descending velocity the pilot may request in cm/s
172
// @Units: cm/s
173
// @Range: 20 500
174
// @Increment: 10
175
// @User: Standard
176
GSCALAR(pilot_speed_dn, "PILOT_SPEED_DN", 0),
177
178
// @Param: PILOT_ACCEL_Z
179
// @DisplayName: Pilot vertical acceleration
180
// @Description: The vertical acceleration used when pilot is controlling the altitude
181
// @Units: cm/s/s
182
// @Range: 50 500
183
// @Increment: 10
184
// @User: Standard
185
GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),
186
187
// @Param: THR_DZ
188
// @DisplayName: Throttle deadzone
189
// @Description: The PWM deadzone in microseconds above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
190
// @User: Standard
191
// @Range: 0 300
192
// @Units: PWM
193
// @Increment: 1
194
GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),
195
196
// @Param: LOG_BITMASK
197
// @DisplayName: Log bitmask
198
// @Description: 4 byte bitmap of log types to enable
199
// @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
200
// @User: Standard
201
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
202
203
// @Param: ANGLE_MAX
204
// @DisplayName: Angle Max
205
// @Description: Maximum lean angle in all flight modes
206
// @Units: cdeg
207
// @Increment: 10
208
// @Range: 1000 8000
209
// @User: Advanced
210
ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),
211
212
// @Param: FS_EKF_ACTION
213
// @DisplayName: EKF Failsafe Action
214
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
215
// @Values: 0:Disabled, 1:Warn only, 2:Disarm
216
// @User: Advanced
217
GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),
218
219
// @Param: FS_EKF_THRESH
220
// @DisplayName: EKF failsafe variance threshold
221
// @Description: Allows setting the maximum acceptable compass and velocity variance
222
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
223
// @User: Advanced
224
GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),
225
226
// @Param: FS_CRASH_CHECK
227
// @DisplayName: Crash check enable
228
// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
229
// @Values: 0:Disabled,1:Warn only,2:Disarm
230
// @User: Advanced
231
GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLED),
232
233
// @Param: JS_GAIN_DEFAULT
234
// @DisplayName: Default gain at boot
235
// @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'.
236
// @User: Standard
237
// @Range: 0.1 1.0
238
GSCALAR(gain_default, "JS_GAIN_DEFAULT", 0.5),
239
240
// @Param: JS_GAIN_MAX
241
// @DisplayName: Maximum joystick gain
242
// @Description: Maximum joystick gain
243
// @User: Standard
244
// @Range: 0.2 1.0
245
GSCALAR(maxGain, "JS_GAIN_MAX", 1.0),
246
247
// @Param: JS_GAIN_MIN
248
// @DisplayName: Minimum joystick gain
249
// @Description: Minimum joystick gain
250
// @User: Standard
251
// @Range: 0.1 0.8
252
GSCALAR(minGain, "JS_GAIN_MIN", 0.25),
253
254
// @Param: JS_GAIN_STEPS
255
// @DisplayName: Gain steps
256
// @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.
257
// @User: Standard
258
// @Range: 1 10
259
GSCALAR(numGainSettings, "JS_GAIN_STEPS", 4),
260
261
// @Param: JS_LIGHTS_STEPS
262
// @DisplayName: Lights brightness steps
263
// @Description: Number of steps in brightness between minimum and maximum brightness
264
// @User: Standard
265
// @Range: 1 10
266
// @Units: PWM
267
GSCALAR(lights_steps, "JS_LIGHTS_STEPS", 8),
268
269
// @Param: JS_THR_GAIN
270
// @DisplayName: Throttle gain scalar
271
// @Description: Scalar for gain on the throttle channel. Gets scaled with the current JS gain
272
// @User: Standard
273
// @Range: 0.5 4.0
274
GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f),
275
276
// @Param: FRAME_CONFIG
277
// @DisplayName: Frame configuration
278
// @Description: Set this parameter according to your vehicle/motor configuration
279
// @User: Standard
280
// @RebootRequired: True
281
// @Values: 0:BlueROV1, 1:Vectored, 2:Vectored_6DOF, 3:Vectored_6DOF_90, 4:SimpleROV-3, 5:SimpleROV-4, 6:SimpleROV-5, 7:Custom
282
GSCALAR(frame_configuration, "FRAME_CONFIG", AP_Motors6DOF::SUB_FRAME_VECTORED),
283
284
// @Group: BTN0_
285
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
286
GGROUP(jbtn_0, "BTN0_", JSButton),
287
288
// @Group: BTN1_
289
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
290
GGROUP(jbtn_1, "BTN1_", JSButton),
291
292
// @Group: BTN2_
293
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
294
GGROUP(jbtn_2, "BTN2_", JSButton),
295
296
// @Group: BTN3_
297
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
298
GGROUP(jbtn_3, "BTN3_", JSButton),
299
300
// @Group: BTN4_
301
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
302
GGROUP(jbtn_4, "BTN4_", JSButton),
303
304
// @Group: BTN5_
305
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
306
GGROUP(jbtn_5, "BTN5_", JSButton),
307
308
// @Group: BTN6_
309
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
310
GGROUP(jbtn_6, "BTN6_", JSButton),
311
312
// @Group: BTN7_
313
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
314
GGROUP(jbtn_7, "BTN7_", JSButton),
315
316
// @Group: BTN8_
317
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
318
GGROUP(jbtn_8, "BTN8_", JSButton),
319
320
// @Group: BTN9_
321
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
322
GGROUP(jbtn_9, "BTN9_", JSButton),
323
324
// @Group: BTN10_
325
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
326
GGROUP(jbtn_10, "BTN10_", JSButton),
327
328
// @Group: BTN11_
329
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
330
GGROUP(jbtn_11, "BTN11_", JSButton),
331
332
// @Group: BTN12_
333
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
334
GGROUP(jbtn_12, "BTN12_", JSButton),
335
336
// @Group: BTN13_
337
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
338
GGROUP(jbtn_13, "BTN13_", JSButton),
339
340
// @Group: BTN14_
341
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
342
GGROUP(jbtn_14, "BTN14_", JSButton),
343
344
// @Group: BTN15_
345
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
346
GGROUP(jbtn_15, "BTN15_", JSButton),
347
348
// @Group: BTN16_
349
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
350
GGROUP(jbtn_16, "BTN16_", JSButton),
351
352
// @Group: BTN17_
353
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
354
GGROUP(jbtn_17, "BTN17_", JSButton),
355
356
// @Group: BTN18_
357
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
358
GGROUP(jbtn_18, "BTN18_", JSButton),
359
360
// @Group: BTN19_
361
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
362
GGROUP(jbtn_19, "BTN19_", JSButton),
363
364
// @Group: BTN20_
365
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
366
GGROUP(jbtn_20, "BTN20_", JSButton),
367
368
// @Group: BTN21_
369
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
370
GGROUP(jbtn_21, "BTN21_", JSButton),
371
372
// @Group: BTN22_
373
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
374
GGROUP(jbtn_22, "BTN22_", JSButton),
375
376
// @Group: BTN23_
377
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
378
GGROUP(jbtn_23, "BTN23_", JSButton),
379
380
// @Group: BTN24_
381
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
382
GGROUP(jbtn_24, "BTN24_", JSButton),
383
384
// @Group: BTN25_
385
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
386
GGROUP(jbtn_25, "BTN25_", JSButton),
387
388
// @Group: BTN26_
389
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
390
GGROUP(jbtn_26, "BTN26_", JSButton),
391
392
// @Group: BTN27_
393
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
394
GGROUP(jbtn_27, "BTN27_", JSButton),
395
396
// @Group: BTN28_
397
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
398
GGROUP(jbtn_28, "BTN28_", JSButton),
399
400
// @Group: BTN29_
401
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
402
GGROUP(jbtn_29, "BTN29_", JSButton),
403
404
// @Group: BTN30_
405
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
406
GGROUP(jbtn_30, "BTN30_", JSButton),
407
408
// @Group: BTN31_
409
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
410
GGROUP(jbtn_31, "BTN31_", JSButton),
411
412
// @Param: RC_SPEED
413
// @DisplayName: ESC Update Speed
414
// @Description: This is the speed in Hertz that your ESCs will receive updates
415
// @Units: Hz
416
// @Range: 50 490
417
// @Increment: 1
418
// @User: Advanced
419
GSCALAR(rc_speed, "RC_SPEED", RC_SPEED_DEFAULT),
420
421
// @Param: ACRO_RP_P
422
// @DisplayName: Acro Roll and Pitch P gain
423
// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
424
// @Range: 1 10
425
// @User: Standard
426
GSCALAR(acro_rp_p, "ACRO_RP_P", ACRO_RP_P),
427
428
// @Param: ACRO_YAW_P
429
// @DisplayName: Acro Yaw P gain
430
// @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.
431
// @Range: 1 10
432
// @User: Standard
433
GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),
434
435
// @Param: ACRO_BAL_ROLL
436
// @DisplayName: Acro Balance Roll
437
// @Description: rate at which roll angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
438
// @Range: 0 3
439
// @Increment: 0.1
440
// @User: Advanced
441
GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),
442
443
// @Param: ACRO_BAL_PITCH
444
// @DisplayName: Acro Balance Pitch
445
// @Description: rate at which pitch angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
446
// @Range: 0 3
447
// @Increment: 0.1
448
// @User: Advanced
449
GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
450
451
// @Param: ACRO_TRAINER
452
// @DisplayName: Acro Trainer
453
// @Description: Type of trainer used in acro mode
454
// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
455
// @User: Advanced
456
GSCALAR(acro_trainer, "ACRO_TRAINER", ACRO_TRAINER_LIMITED),
457
458
// @Param: ACRO_EXPO
459
// @DisplayName: Acro Expo
460
// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges
461
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
462
// @User: Advanced
463
GSCALAR(acro_expo, "ACRO_EXPO", ACRO_EXPO_DEFAULT),
464
465
// variables not in the g class which contain EEPROM saved variables
466
467
#if AP_CAMERA_ENABLED
468
// @Group: CAM
469
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
470
GOBJECT(camera, "CAM", AP_Camera),
471
#endif
472
473
#if AP_RELAY_ENABLED
474
// @Group: RELAY
475
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
476
GOBJECT(relay, "RELAY", AP_Relay),
477
#endif
478
479
// @Group: COMPASS_
480
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
481
GOBJECT(compass, "COMPASS_", Compass),
482
483
// @Group: INS
484
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
485
GOBJECT(ins, "INS", AP_InertialSensor),
486
487
// @Group: WPNAV_
488
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
489
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
490
491
// @Group: LOIT_
492
// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
493
GOBJECT(loiter_nav, "LOIT_", AC_Loiter),
494
495
#if CIRCLE_NAV_ENABLED
496
// @Group: CIRCLE_
497
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
498
GOBJECT(circle_nav, "CIRCLE_", AC_Circle),
499
#endif
500
501
// @Group: ATC_
502
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp
503
GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Sub),
504
505
// @Group: PSC
506
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
507
GOBJECT(pos_control, "PSC", AC_PosControl),
508
509
// @Group: SR0_
510
// @Path: GCS_MAVLink_Sub.cpp
511
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
512
513
#if MAVLINK_COMM_NUM_BUFFERS >= 2
514
// @Group: SR1_
515
// @Path: GCS_MAVLink_Sub.cpp
516
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
517
#endif
518
519
#if MAVLINK_COMM_NUM_BUFFERS >= 3
520
// @Group: SR2_
521
// @Path: GCS_MAVLink_Sub.cpp
522
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
523
#endif
524
525
#if MAVLINK_COMM_NUM_BUFFERS >= 4
526
// @Group: SR3_
527
// @Path: GCS_MAVLink_Sub.cpp
528
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
529
#endif
530
531
#if MAVLINK_COMM_NUM_BUFFERS >= 5
532
// @Group: SR4_
533
// @Path: GCS_MAVLink_Sub.cpp
534
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
535
#endif
536
537
#if MAVLINK_COMM_NUM_BUFFERS >= 6
538
// @Group: SR5_
539
// @Path: GCS_MAVLink_Sub.cpp
540
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
541
#endif
542
543
#if MAVLINK_COMM_NUM_BUFFERS >= 7
544
// @Group: SR6_
545
// @Path: GCS_MAVLink_Sub.cpp
546
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
547
#endif
548
549
// @Group: AHRS_
550
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
551
GOBJECT(ahrs, "AHRS_", AP_AHRS),
552
553
#if HAL_MOUNT_ENABLED
554
// @Group: MNT
555
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
556
GOBJECT(camera_mount, "MNT", AP_Mount),
557
#endif
558
559
// @Group: BATT
560
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
561
GOBJECT(battery, "BATT", AP_BattMonitor),
562
563
// @Group: ARMING_
564
// @Path: AP_Arming_Sub.cpp,../libraries/AP_Arming/AP_Arming.cpp
565
GOBJECT(arming, "ARMING_", AP_Arming_Sub),
566
567
// @Group: BRD_
568
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
569
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
570
571
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
572
// @Group: CAN_
573
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
574
GOBJECT(can_mgr, "CAN_", AP_CANManager),
575
#endif
576
577
#if AP_SIM_ENABLED
578
// @Group: SIM_
579
// @Path: ../libraries/SITL/SITL.cpp
580
GOBJECT(sitl, "SIM_", SITL::SIM),
581
#endif
582
583
// @Group: BARO
584
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
585
GOBJECT(barometer, "BARO", AP_Baro),
586
587
// GPS driver
588
// @Group: GPS
589
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
590
GOBJECT(gps, "GPS", AP_GPS),
591
592
// Leak detector
593
// @Group: LEAK
594
// @Path: ../libraries/AP_LeakDetector/AP_LeakDetector.cpp
595
GOBJECT(leak_detector, "LEAK", AP_LeakDetector),
596
597
// @Group: SCHED_
598
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
599
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
600
601
#if AVOIDANCE_ENABLED
602
// @Group: AVOID_
603
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
604
GOBJECT(avoid, "AVOID_", AC_Avoid),
605
#endif
606
607
#if HAL_RALLY_ENABLED
608
// @Group: RALLY_
609
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
610
GOBJECT(rally, "RALLY_", AP_Rally),
611
#endif
612
613
// @Group: MOT_
614
// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp,../libraries/AP_Motors/AP_MotorsMulticopter.cpp
615
GOBJECT(motors, "MOT_", AP_Motors6DOF),
616
617
#if RCMAP_ENABLED
618
// @Group: RCMAP_
619
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
620
GOBJECT(rcmap, "RCMAP_", RCMapper),
621
#endif
622
623
#if HAL_NAVEKF2_AVAILABLE
624
// @Group: EK2_
625
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
626
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
627
#endif
628
629
#if HAL_NAVEKF3_AVAILABLE
630
// @Group: EK3_
631
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
632
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
633
#endif
634
635
// @Group: MIS_
636
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
637
GOBJECT(mission, "MIS_", AP_Mission),
638
639
#if AP_RANGEFINDER_ENABLED
640
// @Group: RNGFND
641
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
642
GOBJECT(rangefinder, "RNGFND", RangeFinder),
643
644
// @Param: RNGFND_SQ_MIN
645
// @DisplayName: Rangefinder signal quality minimum
646
// @Description: Minimum signal quality for good rangefinder readings
647
// @Range: 0 100
648
// @User: Advanced
649
GSCALAR(rangefinder_signal_min, "RNGFND_SQ_MIN", RANGEFINDER_SIGNAL_MIN_DEFAULT),
650
651
// @Param: SURFTRAK_DEPTH
652
// @DisplayName: SURFTRAK minimum depth
653
// @Description: Minimum depth to engage SURFTRAK mode
654
// @Units: cm
655
// @User: Standard
656
GSCALAR(surftrak_depth, "SURFTRAK_DEPTH", SURFTRAK_DEPTH_DEFAULT),
657
#endif
658
659
#if AP_TERRAIN_AVAILABLE
660
// @Group: TERRAIN_
661
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
662
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
663
#endif
664
665
#if AP_OPTICALFLOW_ENABLED
666
// @Group: FLOW
667
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
668
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
669
#endif
670
671
#if AP_RPM_ENABLED
672
// @Group: RPM
673
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
674
GOBJECT(rpm_sensor, "RPM", AP_RPM),
675
#endif
676
677
// @Group: NTF_
678
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
679
GOBJECT(notify, "NTF_", AP_Notify),
680
681
// @Group:
682
// @Path: Parameters.cpp
683
GOBJECT(g2, "", ParametersG2),
684
685
// @Group:
686
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
687
PARAM_VEHICLE_INFO,
688
689
AP_VAREND
690
};
691
692
/*
693
2nd group of parameters
694
*/
695
const AP_Param::GroupInfo ParametersG2::var_info[] = {
696
697
// 1 was AP_Stats
698
699
#if HAL_PROXIMITY_ENABLED
700
// @Group: PRX
701
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
702
AP_SUBGROUPINFO(proximity, "PRX", 2, ParametersG2, AP_Proximity),
703
#endif
704
705
// 3 was AP_Gripper
706
707
// @Group: SERVO
708
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
709
AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),
710
711
// @Group: RC
712
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
713
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),
714
715
// 18 was scripting
716
717
// @Param: ORIGIN_LAT
718
// @DisplayName: Backup latitude for EKF origin
719
// @Description: Backup EKF origin latitude used when not using a positioning system.
720
// @Units: deg
721
// @User: Standard
722
AP_GROUPINFO("ORIGIN_LAT", 19, ParametersG2, backup_origin_lat, 0),
723
724
// @Param: ORIGIN_LON
725
// @DisplayName: Backup longitude for EKF origin
726
// @Description: Backup EKF origin longitude used when not using a positioning system.
727
// @Units: deg
728
// @User: Standard
729
AP_GROUPINFO("ORIGIN_LON", 20, ParametersG2, backup_origin_lon, 0),
730
731
// @Param: ORIGIN_ALT
732
// @DisplayName: Backup altitude (MSL) for EKF origin
733
// @Description: Backup EKF origin altitude (MSL) used when not using a positioning system.
734
// @Units: m
735
// @User: Standard
736
AP_GROUPINFO("ORIGIN_ALT", 21, ParametersG2, backup_origin_alt, 0),
737
738
AP_GROUPEND
739
};
740
741
/*
742
constructor for g2 object
743
*/
744
ParametersG2::ParametersG2()
745
{
746
AP_Param::setup_object_defaults(this, var_info);
747
}
748
749
const AP_Param::ConversionInfo conversion_table[] = {
750
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" },
751
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" },
752
{ Parameters::k_param_failsafe_battery_enabled, 0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },
753
{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },
754
{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },
755
};
756
757
void Sub::load_parameters()
758
{
759
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
760
761
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
762
763
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB);
764
765
convert_old_parameters();
766
AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table));
767
// We should ignore this parameter since ROVs are neutral buoyancy
768
AP_Param::set_by_name("MOT_THST_HOVER", 0.5);
769
770
// PARAMETER_CONVERSION - Added: Mar-2022
771
#if AP_FENCE_ENABLED
772
AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true);
773
#endif
774
775
static const AP_Param::G2ObjectConversion g2_conversions[] {
776
#if AP_AIRSPEED_ENABLED
777
// PARAMETER_CONVERSION - Added: JAN-2022
778
{ &airspeed, airspeed.var_info, 19 },
779
#endif
780
#if AP_STATS_ENABLED
781
// PARAMETER_CONVERSION - Added: Jan-2024
782
{ &stats, stats.var_info, 1 },
783
#endif
784
#if AP_SCRIPTING_ENABLED
785
// PARAMETER_CONVERSION - Added: Jan-2024
786
{ &scripting, scripting.var_info, 18 },
787
#endif
788
#if AP_GRIPPER_ENABLED
789
// PARAMETER_CONVERSION - Added: Feb-2024
790
{ &gripper, gripper.var_info, 3 },
791
#endif
792
};
793
794
AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));
795
796
// PARAMETER_CONVERSION - Added: Feb-2024
797
#if HAL_LOGGING_ENABLED
798
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
799
#endif
800
801
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
802
#if AP_SERIALMANAGER_ENABLED
803
// PARAMETER_CONVERSION - Added: Feb-2024
804
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
805
#endif
806
};
807
808
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
809
}
810
811
void Sub::convert_old_parameters()
812
{
813
// attitude control filter parameter changes from _FILT to FLTE or FLTD
814
const AP_Param::ConversionInfo filt_conversion_info[] = {
815
// move ATC_RAT_RLL/PIT_FILT to FLTD, move ATC_RAT_YAW_FILT to FLTE
816
{ Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" },
817
{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" },
818
{ Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" },
819
};
820
AP_Param::convert_old_parameters(&filt_conversion_info[0], ARRAY_SIZE(filt_conversion_info));
821
822
SRV_Channels::upgrade_parameters();
823
}
824
825