Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/AntennaTracker/Parameters.cpp
9322 views
1
#include "Tracker.h"
2
3
/*
4
* AntennaTracker parameter definitions
5
*
6
*/
7
8
const AP_Param::Info Tracker::var_info[] = {
9
// @Param: FORMAT_VERSION
10
// @DisplayName: Eeprom format version number
11
// @Description: This value is incremented when changes are made to the eeprom format
12
// @User: Advanced
13
GSCALAR(format_version, "FORMAT_VERSION", 0),
14
15
// SYSID_THISMAV was here
16
17
// SYSID_MYGCS was here
18
19
// @Param: SYSID_TARGET
20
// @DisplayName: Target vehicle's MAVLink system ID
21
// @Description: The identifier of the vehicle being tracked. This should be zero (to auto detect) or be the same as the MAV_SYSID parameter of the vehicle being tracked.
22
// @Range: 1 255
23
// @User: Advanced
24
GSCALAR(sysid_target, "SYSID_TARGET", 0),
25
26
// @Param: YAW_SLEW_TIME
27
// @DisplayName: Time for yaw to slew through its full range
28
// @Description: This controls how rapidly the tracker will change the servo output for yaw. It is set as the number of seconds to do a full rotation. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
29
// @Units: s
30
// @Increment: 0.1
31
// @Range: 0 20
32
// @User: Standard
33
GSCALAR(yaw_slew_time, "YAW_SLEW_TIME", 2),
34
35
// @Param: PITCH_SLEW_TIME
36
// @DisplayName: Time for pitch to slew through its full range
37
// @Description: This controls how rapidly the tracker will change the servo output for pitch. It is set as the number of seconds to do a full range of pitch movement. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
38
// @Units: s
39
// @Increment: 0.1
40
// @Range: 0 20
41
// @User: Standard
42
GSCALAR(pitch_slew_time, "PITCH_SLEW_TIME", 2),
43
44
// @Param: MIN_REVERSE_TIME
45
// @DisplayName: Minimum time to apply a yaw reversal
46
// @Description: When the tracker detects it has reached the limit of servo movement in yaw it will reverse and try moving to the other extreme of yaw. This parameter controls the minimum time it should reverse for. It is used to cope with trackers that have a significant lag in movement to ensure they do move all the way around.
47
// @Units: s
48
// @Increment: 1
49
// @Range: 0 20
50
// @User: Standard
51
GSCALAR(min_reverse_time, "MIN_REVERSE_TIME", 1),
52
53
// @Param: START_LATITUDE
54
// @DisplayName: Initial Latitude before GPS lock
55
// @Description: Combined with START_LONGITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
56
// @Units: deg
57
// @Increment: 0.000001
58
// @Range: -90 90
59
// @User: Standard
60
GSCALAR(start_latitude, "START_LATITUDE", 0),
61
62
// @Param: START_LONGITUDE
63
// @DisplayName: Initial Longitude before GPS lock
64
// @Description: Combined with START_LATITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
65
// @Units: deg
66
// @Increment: 0.000001
67
// @Range: -180 180
68
// @User: Standard
69
GSCALAR(start_longitude, "START_LONGITUDE", 0),
70
71
// @Param: STARTUP_DELAY
72
// @DisplayName: Delay before first servo movement from trim
73
// @Description: This parameter can be used to force the servos to their trim value for a time on startup. This can help with some servo types
74
// @Units: s
75
// @Increment: 0.1
76
// @Range: 0 10
77
// @User: Standard
78
GSCALAR(startup_delay, "STARTUP_DELAY", 0),
79
80
// @Param: SERVO_PITCH_TYPE
81
// @DisplayName: Type of servo system being used for pitch
82
// @Description: This allows selection of position servos or on/off servos for pitch
83
// @Values: 0:Position,1:OnOff,2:ContinuousRotation
84
// @User: Standard
85
GSCALAR(servo_pitch_type, "SERVO_PITCH_TYPE", SERVO_TYPE_POSITION),
86
87
// @Param: SERVO_YAW_TYPE
88
// @DisplayName: Type of servo system being used for yaw
89
// @Description: This allows selection of position servos or on/off servos for yaw
90
// @Values: 0:Position,1:OnOff,2:ContinuousRotation
91
// @User: Standard
92
GSCALAR(servo_yaw_type, "SERVO_YAW_TYPE", SERVO_TYPE_POSITION),
93
94
// @Param: ONOFF_YAW_RATE
95
// @DisplayName: Yaw rate for on/off servos
96
// @Description: Rate of change of yaw in degrees/second for on/off servos
97
// @Units: deg/s
98
// @Increment: 0.1
99
// @Range: 0 50
100
// @User: Standard
101
GSCALAR(onoff_yaw_rate, "ONOFF_YAW_RATE", 9.0f),
102
103
// @Param: ONOFF_PITCH_RATE
104
// @DisplayName: Pitch rate for on/off servos
105
// @Description: Rate of change of pitch in degrees/second for on/off servos
106
// @Units: deg/s
107
// @Increment: 0.1
108
// @Range: 0 50
109
// @User: Standard
110
GSCALAR(onoff_pitch_rate, "ONOFF_PITCH_RATE", 1.0f),
111
112
// @Param: ONOFF_YAW_MINT
113
// @DisplayName: Yaw minimum movement time
114
// @Description: Minimum amount of time in seconds to move in yaw
115
// @Units: s
116
// @Increment: 0.01
117
// @Range: 0 2
118
// @User: Standard
119
GSCALAR(onoff_yaw_mintime, "ONOFF_YAW_MINT", 0.1f),
120
121
// @Param: ONOFF_PITCH_MINT
122
// @DisplayName: Pitch minimum movement time
123
// @Description: Minimum amount of time in seconds to move in pitch
124
// @Units: s
125
// @Increment: 0.01
126
// @Range: 0 2
127
// @User: Standard
128
GSCALAR(onoff_pitch_mintime, "ONOFF_PITCH_MINT", 0.1f),
129
130
// @Param: YAW_TRIM
131
// @DisplayName: Yaw trim
132
// @Description: Amount of extra yaw to add when tracking. This allows for small adjustments for an out of trim compass.
133
// @Units: deg
134
// @Increment: 0.1
135
// @Range: -10 10
136
// @User: Standard
137
GSCALAR(yaw_trim, "YAW_TRIM", 0),
138
139
// @Param: PITCH_TRIM
140
// @DisplayName: Pitch trim
141
// @Description: Amount of extra pitch to add when tracking. This allows for small adjustments for a badly calibrated barometer.
142
// @Units: deg
143
// @Increment: 0.1
144
// @Range: -10 10
145
// @User: Standard
146
GSCALAR(pitch_trim, "PITCH_TRIM", 0),
147
148
// @Param: YAW_RANGE
149
// @DisplayName: Yaw Angle Range
150
// @Description: Yaw axis total range of motion in degrees
151
// @Units: deg
152
// @Increment: 0.1
153
// @Range: 0 360
154
// @User: Standard
155
GSCALAR(yaw_range, "YAW_RANGE", YAW_RANGE_DEFAULT),
156
157
// @Param: DISTANCE_MIN
158
// @DisplayName: Distance minimum to target
159
// @Description: Tracker will track targets at least this distance away
160
// @Units: m
161
// @Increment: 1
162
// @Range: 0 100
163
// @User: Standard
164
GSCALAR(distance_min, "DISTANCE_MIN", DISTANCE_MIN_DEFAULT),
165
166
// @Param: ALT_SOURCE
167
// @DisplayName: Altitude Source
168
// @Description: What provides altitude information for vehicle. Vehicle only assumes tracker has same altitude as vehicle's home
169
// @Values: 0:Barometer,1:GPS,2:GPS vehicle only
170
// @User: Standard
171
GSCALAR(alt_source, "ALT_SOURCE", 0),
172
173
// @Param: MAV_UPDATE_RATE
174
// @DisplayName: Mavlink Update Rate
175
// @Description: The rate at which Mavlink updates position and baro data
176
// @Units: Hz
177
// @Increment: 1
178
// @Range: 1 10
179
// @User: Standard
180
GSCALAR(mavlink_update_rate, "MAV_UPDATE_RATE", 1),
181
182
// @Param: PITCH_MIN
183
// @DisplayName: Minimum Pitch Angle
184
// @Description: The lowest angle the pitch can reach
185
// @Units: deg
186
// @Increment: 1
187
// @Range: -90 0
188
// @User: Standard
189
GSCALAR(pitch_min, "PITCH_MIN", PITCH_MIN_DEFAULT),
190
191
// @Param: PITCH_MAX
192
// @DisplayName: Maximum Pitch Angle
193
// @Description: The highest angle the pitch can reach
194
// @Units: deg
195
// @Increment: 1
196
// @Range: 0 90
197
// @User: Standard
198
GSCALAR(pitch_max, "PITCH_MAX", PITCH_MAX_DEFAULT),
199
200
// barometer library
201
// @Group: BARO
202
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
203
GOBJECT(barometer, "BARO", AP_Baro),
204
205
// @Group: COMPASS_
206
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
207
GOBJECT(compass, "COMPASS_", Compass),
208
209
// @Group: SCHED_
210
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
211
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
212
213
// @Param: LOG_BITMASK
214
// @DisplayName: Log bitmask
215
// @Description: 4 byte bitmap of log types to enable
216
// @Bitmask: 0:ATTITUDE,1:GPS,2:RCIN,3:IMU,4:RCOUT,5:COMPASS,6:Battery
217
// @User: Standard
218
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
219
220
// @Group: INS
221
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
222
GOBJECT(ins, "INS", AP_InertialSensor),
223
224
// @Group: AHRS_
225
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
226
GOBJECT(ahrs, "AHRS_", AP_AHRS),
227
228
#if AP_SIM_ENABLED
229
// @Group: SIM_
230
// @Path: ../libraries/SITL/SITL.cpp
231
GOBJECT(sitl, "SIM_", SITL::SIM),
232
#endif
233
234
// @Group: BRD_
235
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
236
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
237
238
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
239
// @Group: CAN_
240
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
241
GOBJECT(can_mgr, "CAN_", AP_CANManager),
242
#endif
243
244
// GPS driver
245
// @Group: GPS
246
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
247
GOBJECT(gps, "GPS", AP_GPS),
248
249
// @Group: NTF_
250
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
251
GOBJECT(notify, "NTF_", AP_Notify),
252
253
// @Group: RC
254
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
255
GOBJECT(rc_channels, "RC", RC_Channels_Tracker),
256
257
// @Group: SERVO
258
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
259
GOBJECT(servo_channels, "SERVO", SRV_Channels),
260
261
// AP_SerialManager was here
262
263
// @Param: PITCH2SRV_P
264
// @DisplayName: Pitch axis controller P gain
265
// @Description: Pitch axis controller P gain. Converts the difference between desired pitch angle and actual pitch angle into a pitch servo pwm change
266
// @Range: 0.0 3.0
267
// @Increment: 0.01
268
// @User: Standard
269
270
// @Param: PITCH2SRV_I
271
// @DisplayName: Pitch axis controller I gain
272
// @Description: Pitch axis controller I gain. Corrects long-term difference in desired pitch angle vs actual pitch angle
273
// @Range: 0.0 3.0
274
// @Increment: 0.01
275
// @User: Standard
276
277
// @Param: PITCH2SRV_IMAX
278
// @DisplayName: Pitch axis controller I gain maximum
279
// @Description: Pitch axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output
280
// @Range: 0 4000
281
// @Increment: 10
282
// @Units: d%
283
// @User: Standard
284
285
// @Param: PITCH2SRV_D
286
// @DisplayName: Pitch axis controller D gain
287
// @Description: Pitch axis controller D gain. Compensates for short-term change in desired pitch angle vs actual pitch angle
288
// @Range: 0.001 0.1
289
// @Increment: 0.001
290
// @User: Standard
291
292
// @Param: PITCH2SRV_FF
293
// @DisplayName: Pitch axis controller feed forward
294
// @Description: Pitch axis controller feed forward
295
// @Range: 0 0.5
296
// @Increment: 0.001
297
// @User: Standard
298
299
// @Param: PITCH2SRV_FLTT
300
// @DisplayName: Pitch axis controller target frequency in Hz
301
// @Description: Pitch axis controller target frequency in Hz
302
// @Range: 1 50
303
// @Increment: 1
304
// @Units: Hz
305
// @User: Standard
306
307
// @Param: PITCH2SRV_FLTE
308
// @DisplayName: Pitch axis controller error frequency in Hz
309
// @Description: Pitch axis controller error frequency in Hz
310
// @Range: 1 100
311
// @Increment: 1
312
// @Units: Hz
313
// @User: Standard
314
315
// @Param: PITCH2SRV_FLTD
316
// @DisplayName: Pitch axis controller derivative frequency in Hz
317
// @Description: Pitch axis controller derivative frequency in Hz
318
// @Range: 1 100
319
// @Increment: 1
320
// @Units: Hz
321
// @User: Standard
322
323
// @Param: PITCH2SRV_SMAX
324
// @DisplayName: Pitch slew rate limit
325
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
326
// @Range: 0 200
327
// @Increment: 0.5
328
// @User: Advanced
329
330
// @Param: PITCH2SRV_PDMX
331
// @DisplayName: Pitch axis controller PD sum maximum
332
// @Description: Pitch axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
333
// @Range: 0 4000
334
// @Increment: 10
335
// @Units: d%
336
// @User: Advanced
337
338
// @Param: PITCH2SRV_D_FF
339
// @DisplayName: Pitch Derivative FeedForward Gain
340
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
341
// @Range: 0 0.1
342
// @Increment: 0.001
343
// @User: Advanced
344
345
// @Param: PITCH2SRV_NTF
346
// @DisplayName: Pitch Target notch filter index
347
// @Description: Pitch Target notch filter index
348
// @Range: 1 8
349
// @User: Advanced
350
351
// @Param: PITCH2SRV_NEF
352
// @DisplayName: Pitch Error notch filter index
353
// @Description: Pitch Error notch filter index
354
// @Range: 1 8
355
// @User: Advanced
356
357
GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),
358
359
// @Param: YAW2SRV_P
360
// @DisplayName: Yaw axis controller P gain
361
// @Description: Yaw axis controller P gain. Converts the difference between desired yaw angle (heading) and actual yaw angle into a yaw servo pwm change
362
// @Range: 0.0 3.0
363
// @Increment: 0.01
364
// @User: Standard
365
366
// @Param: YAW2SRV_I
367
// @DisplayName: Yaw axis controller I gain
368
// @Description: Yaw axis controller I gain. Corrects long-term difference in desired yaw angle (heading) vs actual yaw angle
369
// @Range: 0.0 3.0
370
// @Increment: 0.01
371
// @User: Standard
372
373
// @Param: YAW2SRV_IMAX
374
// @DisplayName: Yaw axis controller I gain maximum
375
// @Description: Yaw axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output
376
// @Range: 0 4000
377
// @Increment: 10
378
// @Units: d%
379
// @User: Standard
380
381
// @Param: YAW2SRV_D
382
// @DisplayName: Yaw axis controller D gain
383
// @Description: Yaw axis controller D gain. Compensates for short-term change in desired yaw angle (heading) vs actual yaw angle
384
// @Range: 0.001 0.1
385
// @Increment: 0.001
386
// @User: Standard
387
388
// @Param: YAW2SRV_FF
389
// @DisplayName: Yaw axis controller feed forward
390
// @Description: Yaw axis controller feed forward
391
// @Range: 0 0.5
392
// @Increment: 0.001
393
// @User: Standard
394
395
// @Param: YAW2SRV_FLTT
396
// @DisplayName: Yaw axis controller target frequency in Hz
397
// @Description: Yaw axis controller target frequency in Hz
398
// @Range: 1 50
399
// @Increment: 1
400
// @Units: Hz
401
// @User: Standard
402
403
// @Param: YAW2SRV_FLTE
404
// @DisplayName: Yaw axis controller error frequency in Hz
405
// @Description: Yaw axis controller error frequency in Hz
406
// @Range: 1 100
407
// @Increment: 1
408
// @Units: Hz
409
// @User: Standard
410
411
// @Param: YAW2SRV_FLTD
412
// @DisplayName: Yaw axis controller derivative frequency in Hz
413
// @Description: Yaw axis controller derivative frequency in Hz
414
// @Range: 1 100
415
// @Increment: 1
416
// @Units: Hz
417
// @User: Standard
418
419
// @Param: YAW2SRV_SMAX
420
// @DisplayName: Yaw slew rate limit
421
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
422
// @Range: 0 200
423
// @Increment: 0.5
424
// @User: Advanced
425
426
// @Param: YAW2SRV_PDMX
427
// @DisplayName: Yaw axis controller PD sum maximum
428
// @Description: Yaw axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
429
// @Range: 0 4000
430
// @Increment: 10
431
// @Units: d%
432
// @User: Advanced
433
434
// @Param: YAW2SRV_D_FF
435
// @DisplayName: Yaw Derivative FeedForward Gain
436
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
437
// @Range: 0 0.1
438
// @Increment: 0.001
439
// @User: Advanced
440
441
// @Param: YAW2SRV_NTF
442
// @DisplayName: Yaw Target notch filter index
443
// @Description: Yaw Target notch filter index
444
// @Range: 1 8
445
// @User: Advanced
446
447
// @Param: YAW2SRV_NEF
448
// @DisplayName: Yaw Error notch filter index
449
// @Description: Yaw Error notch filter index
450
// @Range: 1 8
451
// @User: Advanced
452
453
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),
454
455
// @Param: CMD_TOTAL
456
// @DisplayName: Number of loaded mission items
457
// @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.
458
// @Range: 1 255
459
// @User: Advanced
460
GSCALAR(command_total, "CMD_TOTAL", 0),
461
462
// @Group: BATT
463
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
464
GOBJECT(battery, "BATT", AP_BattMonitor),
465
466
// @Param: GCS_PID_MASK
467
// @DisplayName: GCS PID tuning mask
468
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
469
// @User: Advanced
470
// @Bitmask: 0:Pitch,1:Yaw
471
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
472
473
// @Param: SCAN_SPEED_YAW
474
// @DisplayName: Speed at which to rotate the yaw axis in scan mode
475
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
476
// @Units: deg/s
477
// @Increment: 1
478
// @Range: 0 100
479
// @User: Standard
480
GSCALAR(scan_speed_yaw, "SCAN_SPEED_YAW", 2),
481
482
// @Param: SCAN_SPEED_PIT
483
// @DisplayName: Speed at which to rotate pitch axis in scan mode
484
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
485
// @Units: deg/s
486
// @Increment: 1
487
// @Range: 0 100
488
// @User: Standard
489
GSCALAR(scan_speed_pitch, "SCAN_SPEED_PIT", 5),
490
491
// @Param: INITIAL_MODE
492
// @DisplayName: Mode tracker will switch into after initialization
493
// @Description: 0:MANUAL, 1:STOP, 2:SCAN, 10:AUTO
494
// @User: Standard
495
GSCALAR(initial_mode, "INITIAL_MODE", 10),
496
497
// @Param: SAFE_DISARM_PWM
498
// @DisplayName: PWM that will be output when disarmed or in stop mode
499
// @Description: 0:zero pwm, 1:trim pwm
500
// @User: Standard
501
GSCALAR(disarm_pwm, "SAFE_DISARM_PWM", 0),
502
503
// @Param: AUTO_OPTIONS
504
// @DisplayName: Auto mode options
505
// @Description: 1: Scan for unknown target
506
// @User: Standard
507
// @Bitmask: 0:Scan for unknown target
508
GSCALAR(auto_opts, "AUTO_OPTIONS", 0),
509
510
// @Group:
511
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
512
PARAM_VEHICLE_INFO,
513
514
#if HAL_NAVEKF2_AVAILABLE
515
// @Group: EK2_
516
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
517
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
518
#endif
519
520
#if HAL_NAVEKF3_AVAILABLE
521
// @Group: EK3_
522
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
523
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
524
#endif
525
526
#if HAL_GCS_ENABLED
527
// @Group: MAV
528
// @Path: ../libraries/GCS_MAVLink/GCS.cpp
529
GOBJECT(_gcs, "MAV", GCS),
530
#endif
531
532
AP_VAREND
533
};
534
535
536
void Tracker::load_parameters(void)
537
{
538
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
539
540
#if AP_STATS_ENABLED
541
// PARAMETER_CONVERSION - Added: Jan-2024
542
AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, true);
543
#endif
544
545
#if AP_SCRIPTING_ENABLED
546
// PARAMETER_CONVERSION - Added: Jan-2024
547
AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, true);
548
#endif
549
550
// PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-4.6
551
#if HAL_LOGGING_ENABLED
552
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
553
#endif
554
555
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
556
#if AP_SERIALMANAGER_ENABLED
557
// PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-4.6
558
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
559
#endif
560
};
561
562
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
563
564
#if HAL_HAVE_SAFETY_SWITCH
565
// configure safety switch to allow stopping the motors while armed
566
AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|
567
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON|
568
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);
569
#endif
570
571
#if HAL_GCS_ENABLED
572
// Move parameters into new MAV_ parameter namespace
573
// PARAMETER_CONVERSION - Added: Mar-2025
574
{
575
static const AP_Param::ConversionInfo gcs_conversion_info[] {
576
{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },
577
{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },
578
};
579
AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));
580
}
581
#endif // HAL_GCS_ENABLED
582
583
}
584
585