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