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/Rover/Parameters.cpp
Views: 1798
1
#include "Rover.h"
2
3
#include <AP_Gripper/AP_Gripper.h>
4
5
/*
6
Rover parameter definitions
7
*/
8
9
const AP_Param::Info Rover::var_info[] = {
10
// @Param: FORMAT_VERSION
11
// @DisplayName: Eeprom format version number
12
// @Description: This value is incremented when changes are made to the eeprom format
13
// @User: Advanced
14
GSCALAR(format_version, "FORMAT_VERSION", 1),
15
16
// @Param: LOG_BITMASK
17
// @DisplayName: Log bitmask
18
// @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535.
19
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Throttle,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Rangefinder,11:Compass,12:Camera,13:Steering,14:RC Input-Output,19:Raw IMU,20:Video Stabilization,21:Optical Flow
20
// @User: Advanced
21
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
22
23
// @Param: RST_SWITCH_CH
24
// @DisplayName: Reset Switch Channel
25
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
26
// @User: Advanced
27
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
28
29
// @Param: INITIAL_MODE
30
// @DisplayName: Initial driving mode
31
// @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART.
32
// @CopyValuesFrom: MODE1
33
// @User: Advanced
34
GSCALAR(initial_mode, "INITIAL_MODE", (int8_t)Mode::Number::MANUAL),
35
36
// @Param: SYSID_THISMAV
37
// @DisplayName: MAVLink system ID of this vehicle
38
// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
39
// @Range: 1 255
40
// @User: Advanced
41
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
42
43
// @Param: SYSID_MYGCS
44
// @DisplayName: MAVLink ground station ID
45
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
46
// @Range: 1 255
47
// @Increment: 1
48
// @User: Advanced
49
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
50
51
// @Param: TELEM_DELAY
52
// @DisplayName: Telemetry startup delay
53
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
54
// @User: Standard
55
// @Units: s
56
// @Range: 0 30
57
// @Increment: 1
58
GSCALAR(telem_delay, "TELEM_DELAY", 0),
59
60
// @Param: GCS_PID_MASK
61
// @DisplayName: GCS PID tuning mask
62
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
63
// @User: Advanced
64
// @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel,6:Velocity North,7:Velocity East
65
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
66
67
// @Param: AUTO_TRIGGER_PIN
68
// @DisplayName: Auto mode trigger pin
69
// @Description: pin number to use to enable the throttle in auto mode. If set to -1 then don't use a trigger, otherwise this is a pin number which if held low in auto mode will enable the motor to run. If the switch is released while in AUTO then the motor will stop again. This can be used in combination with INITIAL_MODE to give a 'press button to start' rover with no receiver.
70
// @Values: -1:Disabled,0:APM TriggerPin0,1:APM TriggerPin1,2:APM TriggerPin2,3:APM TriggerPin3,4:APM TriggerPin4,5:APM TriggerPin5,6:APM TriggerPin6,7:APM TriggerPin7,8:APM TriggerPin8,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
71
// @User: Standard
72
GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),
73
74
// @Param: AUTO_KICKSTART
75
// @DisplayName: Auto mode trigger kickstart acceleration
76
// @Description: X acceleration in meters/second/second to use to trigger the motor start in auto mode. If set to zero then auto throttle starts immediately when the mode switch happens, otherwise the rover waits for the X acceleration to go above this value before it will start the motor
77
// @Units: m/s/s
78
// @Range: 0 20
79
// @Increment: 0.1
80
// @User: Standard
81
GSCALAR(auto_kickstart, "AUTO_KICKSTART", 0.0f),
82
83
// @Param: CRUISE_SPEED
84
// @DisplayName: Target cruise speed in auto modes
85
// @Description: The target speed in auto missions.
86
// @Units: m/s
87
// @Range: 0 100
88
// @Increment: 0.1
89
// @User: Standard
90
GSCALAR(speed_cruise, "CRUISE_SPEED", CRUISE_SPEED),
91
92
93
// @Param: CRUISE_THROTTLE
94
// @DisplayName: Base throttle percentage in auto
95
// @Description: The base throttle percentage to use in auto mode. The CRUISE_SPEED parameter controls the target speed, but the rover starts with the CRUISE_THROTTLE setting as the initial estimate for how much throttle is needed to achieve that speed. It then adjusts the throttle based on how fast the rover is actually going.
96
// @Units: %
97
// @Range: 0 100
98
// @Increment: 1
99
// @User: Standard
100
GSCALAR(throttle_cruise, "CRUISE_THROTTLE", 50),
101
102
// @Param: PILOT_STEER_TYPE
103
// @DisplayName: Pilot input steering type
104
// @Description: Pilot RC input interpretation
105
// @Values: 0:Default,1:Two Paddles Input,2:Direction reversed when backing up,3:Direction unchanged when backing up
106
// @User: Standard
107
GSCALAR(pilot_steer_type, "PILOT_STEER_TYPE", 0),
108
109
// @Param: FS_ACTION
110
// @DisplayName: Failsafe Action
111
// @Description: What to do on a failsafe event
112
// @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold,5:Terminate
113
// @User: Standard
114
GSCALAR(fs_action, "FS_ACTION", (int8_t)FailsafeAction::Hold),
115
116
// @Param: FS_TIMEOUT
117
// @DisplayName: Failsafe timeout
118
// @Description: The time in seconds that a failsafe condition must persist before the failsafe action is triggered
119
// @Units: s
120
// @Range: 1 100
121
// @Increment: 0.5
122
// @User: Standard
123
GSCALAR(fs_timeout, "FS_TIMEOUT", 1.5),
124
125
// @Param: FS_THR_ENABLE
126
// @DisplayName: Throttle Failsafe Enable
127
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel to a low value. This can be used to detect the RC transmitter going out of range. Failsafe will be triggered when the throttle channel goes below the FS_THR_VALUE for FS_TIMEOUT seconds.
128
// @Values: 0:Disabled,1:Enabled,2:Enabled Continue with Mission in Auto
129
// @User: Standard
130
GSCALAR(fs_throttle_enabled, "FS_THR_ENABLE", FS_THR_ENABLED),
131
132
// @Param: FS_THR_VALUE
133
// @DisplayName: Throttle Failsafe Value
134
// @Description: The PWM level on the throttle channel below which throttle failsafe triggers.
135
// @Range: 910 1100
136
// @Increment: 1
137
// @User: Standard
138
GSCALAR(fs_throttle_value, "FS_THR_VALUE", 910),
139
140
// @Param: FS_GCS_ENABLE
141
// @DisplayName: GCS failsafe enable
142
// @Description: Enable ground control station telemetry failsafe. When enabled the Rover will execute the FS_ACTION when it fails to receive MAVLink heartbeat packets for FS_TIMEOUT seconds.
143
// @Values: 0:Disabled,1:Enabled,2:Enabled Continue with Mission in Auto
144
// @User: Standard
145
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", FS_GCS_DISABLED),
146
147
// @Param: FS_CRASH_CHECK
148
// @DisplayName: Crash check action
149
// @Description: What to do on a crash event. When enabled the rover will go to hold if a crash is detected.
150
// @Values: 0:Disabled,1:Hold,2:HoldAndDisarm
151
// @User: Standard
152
GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLE),
153
154
// @Param: FS_EKF_ACTION
155
// @DisplayName: EKF Failsafe Action
156
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
157
// @Values: 0:Disabled,1:Hold,2:ReportOnly
158
// @User: Advanced
159
GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_HOLD),
160
161
// @Param: FS_EKF_THRESH
162
// @DisplayName: EKF failsafe variance threshold
163
// @Description: Allows setting the maximum acceptable compass and velocity variance
164
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
165
// @User: Advanced
166
GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", 0.8f),
167
168
// @Param: MODE_CH
169
// @DisplayName: Mode channel
170
// @Description: RC Channel to use for driving mode control
171
// @User: Advanced
172
GSCALAR(mode_channel, "MODE_CH", MODE_CHANNEL),
173
174
// @Param: MODE1
175
// @DisplayName: Mode1
176
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,8:Dock,9:Circle,10:Auto,11:RTL,12:SmartRTL,15:Guided
177
// @User: Standard
178
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
179
GSCALAR(mode1, "MODE1", (int8_t)Mode::Number::MANUAL),
180
181
// @Param: MODE2
182
// @DisplayName: Mode2
183
// @Description: Driving mode for switch position 2 (1231 to 1360)
184
// @CopyValuesFrom: MODE1
185
// @User: Standard
186
GSCALAR(mode2, "MODE2", (int8_t)Mode::Number::MANUAL),
187
188
// @Param: MODE3
189
// @CopyFieldsFrom: MODE1
190
// @DisplayName: Mode3
191
// @Description: Driving mode for switch position 3 (1361 to 1490)
192
GSCALAR(mode3, "MODE3", (int8_t)Mode::Number::MANUAL),
193
194
// @Param: MODE4
195
// @CopyFieldsFrom: MODE1
196
// @DisplayName: Mode4
197
// @Description: Driving mode for switch position 4 (1491 to 1620)
198
GSCALAR(mode4, "MODE4", (int8_t)Mode::Number::MANUAL),
199
200
// @Param: MODE5
201
// @CopyFieldsFrom: MODE1
202
// @DisplayName: Mode5
203
// @Description: Driving mode for switch position 5 (1621 to 1749)
204
GSCALAR(mode5, "MODE5", (int8_t)Mode::Number::MANUAL),
205
206
// @Param: MODE6
207
// @CopyFieldsFrom: MODE1
208
// @DisplayName: Mode6
209
// @Description: Driving mode for switch position 6 (1750 to 2049)
210
GSCALAR(mode6, "MODE6", (int8_t)Mode::Number::MANUAL),
211
212
// variables not in the g class which contain EEPROM saved variables
213
214
// @Group: COMPASS_
215
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
216
GOBJECT(compass, "COMPASS_", Compass),
217
218
// @Group: SCHED_
219
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
220
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
221
222
// @Group: BARO
223
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
224
GOBJECT(barometer, "BARO", AP_Baro),
225
226
#if AP_RELAY_ENABLED
227
// @Group: RELAY
228
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
229
GOBJECT(relay, "RELAY", AP_Relay),
230
#endif
231
232
// @Group: RCMAP_
233
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
234
GOBJECT(rcmap, "RCMAP_", RCMapper),
235
236
// @Group: SR0_
237
// @Path: GCS_MAVLink_Rover.cpp
238
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
239
240
#if MAVLINK_COMM_NUM_BUFFERS >= 2
241
// @Group: SR1_
242
// @Path: GCS_MAVLink_Rover.cpp
243
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
244
#endif
245
246
#if MAVLINK_COMM_NUM_BUFFERS >= 3
247
// @Group: SR2_
248
// @Path: GCS_MAVLink_Rover.cpp
249
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
250
#endif
251
252
#if MAVLINK_COMM_NUM_BUFFERS >= 4
253
// @Group: SR3_
254
// @Path: GCS_MAVLink_Rover.cpp
255
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
256
#endif
257
258
#if MAVLINK_COMM_NUM_BUFFERS >= 5
259
// @Group: SR4_
260
// @Path: GCS_MAVLink_Rover.cpp
261
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
262
#endif
263
264
#if MAVLINK_COMM_NUM_BUFFERS >= 6
265
// @Group: SR5_
266
// @Path: GCS_MAVLink_Rover.cpp
267
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
268
#endif
269
270
#if MAVLINK_COMM_NUM_BUFFERS >= 7
271
// @Group: SR6_
272
// @Path: GCS_MAVLink_Rover.cpp
273
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
274
#endif
275
276
// AP_SerialManager was here
277
278
#if AP_RANGEFINDER_ENABLED
279
// @Group: RNGFND
280
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
281
GOBJECT(rangefinder, "RNGFND", RangeFinder),
282
#endif
283
284
// @Group: INS
285
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
286
GOBJECT(ins, "INS", AP_InertialSensor),
287
288
#if AP_SIM_ENABLED
289
// @Group: SIM_
290
// @Path: ../libraries/SITL/SITL.cpp
291
GOBJECT(sitl, "SIM_", SITL::SIM),
292
#endif
293
294
// @Group: AHRS_
295
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
296
GOBJECT(ahrs, "AHRS_", AP_AHRS),
297
298
#if AP_CAMERA_ENABLED
299
// @Group: CAM
300
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
301
GOBJECT(camera, "CAM", AP_Camera),
302
#endif
303
304
#if AC_PRECLAND_ENABLED
305
// @Group: PLND_
306
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
307
GOBJECT(precland, "PLND_", AC_PrecLand),
308
#endif
309
310
#if HAL_MOUNT_ENABLED
311
// @Group: MNT
312
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
313
GOBJECT(camera_mount, "MNT", AP_Mount),
314
#endif
315
316
// @Group: ARMING_
317
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
318
GOBJECT(arming, "ARMING_", AP_Arming),
319
320
// @Group: BATT
321
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
322
GOBJECT(battery, "BATT", AP_BattMonitor),
323
324
// @Group: BRD_
325
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
326
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
327
328
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
329
// @Group: CAN_
330
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
331
GOBJECT(can_mgr, "CAN_", AP_CANManager),
332
#endif
333
334
// GPS driver
335
// @Group: GPS
336
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
337
GOBJECT(gps, "GPS", AP_GPS),
338
339
#if HAL_NAVEKF2_AVAILABLE
340
// @Group: EK2_
341
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
342
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
343
#endif
344
345
#if HAL_NAVEKF3_AVAILABLE
346
// @Group: EK3_
347
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
348
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
349
#endif
350
351
#if AP_RPM_ENABLED
352
// @Group: RPM
353
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
354
GOBJECT(rpm_sensor, "RPM", AP_RPM),
355
#endif
356
357
// @Group: MIS_
358
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
359
GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
360
361
#if AP_RSSI_ENABLED
362
// @Group: RSSI_
363
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
364
GOBJECT(rssi, "RSSI_", AP_RSSI),
365
#endif
366
367
// @Group: NTF_
368
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
369
GOBJECT(notify, "NTF_", AP_Notify),
370
371
#if HAL_BUTTON_ENABLED
372
// @Group: BTN_
373
// @Path: ../libraries/AP_Button/AP_Button.cpp
374
GOBJECT(button, "BTN_", AP_Button),
375
#endif
376
377
// @Group:
378
// @Path: Parameters.cpp
379
GOBJECT(g2, "", ParametersG2),
380
381
#if OSD_ENABLED || OSD_PARAM_ENABLED
382
// @Group: OSD
383
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
384
GOBJECT(osd, "OSD", AP_OSD),
385
#endif
386
387
#if AP_OPTICALFLOW_ENABLED
388
// @Group: FLOW
389
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
390
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
391
#endif
392
393
// @Group:
394
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
395
PARAM_VEHICLE_INFO,
396
397
AP_VAREND
398
};
399
400
/*
401
2nd group of parameters
402
*/
403
const AP_Param::GroupInfo ParametersG2::var_info[] = {
404
// 1 was AP_Stats
405
406
// @Param: SYSID_ENFORCE
407
// @DisplayName: GCS sysid enforcement
408
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
409
// @Values: 0:NotEnforced,1:Enforced
410
// @User: Advanced
411
AP_GROUPINFO("SYSID_ENFORCE", 2, ParametersG2, sysid_enforce, 0),
412
413
// @Group: SERVO
414
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
415
AP_SUBGROUPINFO(servo_channels, "SERVO", 3, ParametersG2, SRV_Channels),
416
417
// @Group: RC
418
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
419
AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels_Rover),
420
421
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
422
// @Group: AFS_
423
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
424
AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe),
425
#endif
426
427
#if AP_BEACON_ENABLED
428
// @Group: BCN
429
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
430
AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon),
431
#endif
432
433
// 7 was used by AP_VisualOdometry
434
435
// @Group: MOT_
436
// @Path: ../libraries/AR_Motors/AP_MotorsUGV.cpp
437
AP_SUBGROUPINFO(motors, "MOT_", 8, ParametersG2, AP_MotorsUGV),
438
439
// @Group: WENC
440
// @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp
441
AP_SUBGROUPINFO(wheel_encoder, "WENC", 9, ParametersG2, AP_WheelEncoder),
442
443
// @Group: ATC
444
// @Path: ../libraries/APM_Control/AR_AttitudeControl.cpp
445
AP_SUBGROUPINFO(attitude_control, "ATC", 10, ParametersG2, AR_AttitudeControl),
446
447
// @Param: TURN_RADIUS
448
// @DisplayName: Turn radius of vehicle
449
// @Description: Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode
450
// @Units: m
451
// @Range: 0 10
452
// @Increment: 0.1
453
// @User: Standard
454
AP_GROUPINFO("TURN_RADIUS", 11, ParametersG2, turn_radius, 0.9),
455
456
// @Param: ACRO_TURN_RATE
457
// @DisplayName: Acro mode turn rate maximum
458
// @Description: Acro mode turn rate maximum
459
// @Units: deg/s
460
// @Range: 0 360
461
// @Increment: 1
462
// @User: Standard
463
AP_GROUPINFO("ACRO_TURN_RATE", 12, ParametersG2, acro_turn_rate, 180.0f),
464
465
// @Group: SRTL_
466
// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
467
AP_SUBGROUPINFO(smart_rtl, "SRTL_", 13, ParametersG2, AP_SmartRTL),
468
469
// 14 was WP_SPEED and should not be re-used
470
471
// @Param: RTL_SPEED
472
// @DisplayName: Return-to-Launch speed default
473
// @Description: Return-to-Launch speed default. If zero use WP_SPEED or CRUISE_SPEED.
474
// @Units: m/s
475
// @Range: 0 100
476
// @Increment: 0.1
477
// @User: Standard
478
AP_GROUPINFO("RTL_SPEED", 15, ParametersG2, rtl_speed, 0.0f),
479
480
// @Param: FRAME_CLASS
481
// @DisplayName: Frame Class
482
// @Description: Frame Class
483
// @Values: 0:Undefined,1:Rover,2:Boat,3:BalanceBot
484
// @User: Standard
485
AP_GROUPINFO("FRAME_CLASS", 16, ParametersG2, frame_class, 1),
486
487
#if HAL_PROXIMITY_ENABLED
488
// @Group: PRX
489
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
490
AP_SUBGROUPINFO(proximity, "PRX", 18, ParametersG2, AP_Proximity),
491
#endif
492
493
#if AP_AVOIDANCE_ENABLED
494
// @Group: AVOID_
495
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
496
AP_SUBGROUPINFO(avoid, "AVOID_", 19, ParametersG2, AC_Avoid),
497
#endif
498
499
// 20 was PIVOT_TURN_RATE and should not be re-used
500
501
// @Param: BAL_PITCH_MAX
502
// @DisplayName: BalanceBot Maximum Pitch
503
// @Description: Pitch angle in degrees at 100% throttle
504
// @Units: deg
505
// @Range: 0 15
506
// @Increment: 0.1
507
// @User: Standard
508
AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 10),
509
510
// @Param: CRASH_ANGLE
511
// @DisplayName: Crash Angle
512
// @Description: Pitch/Roll angle limit in degrees for crash check. Zero disables check
513
// @Units: deg
514
// @Range: 0 60
515
// @Increment: 1
516
// @User: Standard
517
AP_GROUPINFO("CRASH_ANGLE", 22, ParametersG2, crash_angle, 0),
518
519
#if AP_FOLLOW_ENABLED
520
// @Group: FOLL
521
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
522
AP_SUBGROUPINFO(follow, "FOLL", 23, ParametersG2, AP_Follow),
523
#endif
524
525
// @Param: FRAME_TYPE
526
// @DisplayName: Frame Type
527
// @Description: Frame Type
528
// @Values: 0:Undefined,1:Omni3,2:OmniX,3:OmniPlus,4:Omni3Mecanum
529
// @User: Standard
530
// @RebootRequired: True
531
AP_GROUPINFO("FRAME_TYPE", 24, ParametersG2, frame_type, 0),
532
533
// @Param: LOIT_TYPE
534
// @DisplayName: Loiter type
535
// @Description: Loiter behaviour when moving to the target point
536
// @Values: 0:Forward or reverse to target point,1:Always face bow towards target point,2:Always face stern towards target point
537
// @User: Standard
538
AP_GROUPINFO("LOIT_TYPE", 25, ParametersG2, loit_type, 0),
539
540
#if HAL_SPRAYER_ENABLED
541
// @Group: SPRAY_
542
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
543
AP_SUBGROUPINFO(sprayer, "SPRAY_", 26, ParametersG2, AC_Sprayer),
544
#endif
545
546
// @Group: WRC
547
// @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp
548
AP_SUBGROUPINFO(wheel_rate_control, "WRC", 27, ParametersG2, AP_WheelRateControl),
549
550
#if HAL_RALLY_ENABLED
551
// @Group: RALLY_
552
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
553
AP_SUBGROUPINFO(rally, "RALLY_", 28, ParametersG2, AP_Rally_Rover),
554
#endif
555
556
// @Param: SIMPLE_TYPE
557
// @DisplayName: Simple_Type
558
// @Description: Simple mode types
559
// @Values: 0:InitialHeading,1:CardinalDirections
560
// @User: Standard
561
// @RebootRequired: True
562
AP_GROUPINFO("SIMPLE_TYPE", 29, ParametersG2, simple_type, 0),
563
564
// @Param: LOIT_RADIUS
565
// @DisplayName: Loiter radius
566
// @Description: Vehicle will drift when within this distance of the target position
567
// @Units: m
568
// @Range: 0 20
569
// @Increment: 1
570
// @User: Standard
571
AP_GROUPINFO("LOIT_RADIUS", 30, ParametersG2, loit_radius, 2),
572
573
// @Group: WNDVN_
574
// @Path: ../libraries/AP_WindVane/AP_WindVane.cpp
575
AP_SUBGROUPINFO(windvane, "WNDVN_", 31, ParametersG2, AP_WindVane),
576
577
// 32 to 36 were old sailboat params
578
579
// 37 was airspeed
580
581
// @Param: MIS_DONE_BEHAVE
582
// @DisplayName: Mission done behave
583
// @Description: Behaviour after mission completes
584
// @Values: 0:Hold in Auto Mode,1:Loiter in Auto Mode,2:Acro Mode,3:Manual Mode
585
// @User: Standard
586
AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0),
587
588
// 39 was AP_Gripper
589
590
// @Param: BAL_PITCH_TRIM
591
// @DisplayName: Balance Bot pitch trim angle
592
// @Description: Balance Bot pitch trim for balancing. This offsets the tilt of the center of mass.
593
// @Units: deg
594
// @Range: -2 2
595
// @Increment: 0.1
596
// @User: Standard
597
AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0),
598
599
// 41 was Scripting
600
601
// @Param: STICK_MIXING
602
// @DisplayName: Stick Mixing
603
// @Description: When enabled, this adds steering user stick input in auto modes, allowing the user to have some degree of control without changing modes.
604
// @Values: 0:Disabled,1:Enabled
605
// @User: Advanced
606
AP_GROUPINFO("STICK_MIXING", 42, ParametersG2, stick_mixing, 0),
607
608
// @Group: WP_
609
// @Path: ../libraries/AR_WPNav/AR_WPNav.cpp
610
AP_SUBGROUPINFO(wp_nav, "WP_", 43, ParametersG2, AR_WPNav_OA),
611
612
// @Group: SAIL_
613
// @Path: sailboat.cpp
614
AP_SUBGROUPINFO(sailboat, "SAIL_", 44, ParametersG2, Sailboat),
615
616
#if AP_OAPATHPLANNER_ENABLED
617
// @Group: OA_
618
// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp
619
AP_SUBGROUPINFO(oa, "OA_", 45, ParametersG2, AP_OAPathPlanner),
620
#endif
621
622
// @Param: SPEED_MAX
623
// @DisplayName: Speed maximum
624
// @Description: Maximum speed vehicle can obtain at full throttle. If 0, it will be estimated based on CRUISE_SPEED and CRUISE_THROTTLE.
625
// @Units: m/s
626
// @Range: 0 30
627
// @Increment: 0.1
628
// @User: Advanced
629
AP_GROUPINFO("SPEED_MAX", 46, ParametersG2, speed_max, 0.0f),
630
631
// @Param: LOIT_SPEED_GAIN
632
// @DisplayName: Loiter speed gain
633
// @Description: Determines how agressively LOITER tries to correct for drift from loiter point. Higher is faster but default should be acceptable.
634
// @Range: 0 5
635
// @Increment: 0.01
636
// @User: Advanced
637
AP_GROUPINFO("LOIT_SPEED_GAIN", 47, ParametersG2, loiter_speed_gain, 0.5f),
638
639
// @Param: FS_OPTIONS
640
// @DisplayName: Failsafe Options
641
// @Description: Bitmask to enable failsafe options
642
// @Bitmask: 0:Failsafe enabled in Hold mode
643
// @User: Advanced
644
AP_GROUPINFO("FS_OPTIONS", 48, ParametersG2, fs_options, 0),
645
646
#if HAL_TORQEEDO_ENABLED
647
// @Group: TRQ
648
// @Path: ../libraries/AP_Torqeedo/AP_Torqeedo.cpp
649
AP_SUBGROUPINFO(torqeedo, "TRQ", 49, ParametersG2, AP_Torqeedo),
650
#endif
651
652
// @Group: PSC
653
// @Path: ../libraries/APM_Control/AR_PosControl.cpp
654
AP_SUBGROUPINFO(pos_control, "PSC", 51, ParametersG2, AR_PosControl),
655
656
// @Param: GUID_OPTIONS
657
// @DisplayName: Guided mode options
658
// @Description: Options that can be applied to change guided mode behaviour
659
// @Bitmask: 6:SCurves used for navigation
660
// @User: Advanced
661
AP_GROUPINFO("GUID_OPTIONS", 52, ParametersG2, guided_options, 0),
662
663
// @Param: MANUAL_OPTIONS
664
// @DisplayName: Manual mode options
665
// @Description: Manual mode specific options
666
// @Bitmask: 0:Enable steering speed scaling
667
// @User: Advanced
668
AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0),
669
670
#if MODE_DOCK_ENABLED
671
// @Group: DOCK
672
// @Path: mode_dock.cpp
673
AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock),
674
#endif
675
676
// @Param: MANUAL_STR_EXPO
677
// @DisplayName: Manual Steering Expo
678
// @Description: Manual steering expo to allow faster steering when stick at edges
679
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
680
// @Range: -0.5 0.95
681
// @User: Advanced
682
AP_GROUPINFO("MANUAL_STR_EXPO", 55, ParametersG2, manual_steering_expo, 0),
683
684
// @Param: FS_GCS_TIMEOUT
685
// @DisplayName: GCS failsafe timeout
686
// @Description: Timeout before triggering the GCS failsafe
687
// @Units: s
688
// @Range: 2 120
689
// @Increment: 1
690
// @User: Standard
691
AP_GROUPINFO("FS_GCS_TIMEOUT", 56, ParametersG2, fs_gcs_timeout, 5),
692
693
// @Group: CIRC
694
// @Path: mode_circle.cpp
695
AP_SUBGROUPINFO(mode_circle, "CIRC", 57, ParametersG2, ModeCircle),
696
697
AP_GROUPEND
698
};
699
700
// These auxiliary channel param descriptions are here so that users of beta Mission Planner (which uses the master branch as its source of descriptions)
701
// can get them. These lines can be removed once Rover-3.6-beta testing begins or we improve the source of descriptions for GCSs.
702
//
703
// @Param: CH7_OPTION
704
// @DisplayName: Channel 7 option
705
// @Description: What to do use channel 7 for
706
// @Values: 0:Nothing,1:SaveWaypoint,2:LearnCruiseSpeed,3:ArmDisarm,4:Manual,5:Acro,6:Steering,7:Hold,8:Auto,9:RTL,10:SmartRTL,11:Guided,12:Loiter
707
// @User: Standard
708
709
// @Param: AUX_CH
710
// @DisplayName: Auxiliary switch channel
711
// @Description: RC Channel to use for auxiliary functions including saving waypoints
712
// @User: Advanced
713
714
// @Param: PIVOT_TURN_ANGLE
715
// @DisplayName: Pivot turn angle
716
// @Description: Navigation angle threshold in degrees to switch to pivot steering. This allows you to setup a skid steering rover to turn on the spot in auto mode when the angle it needs to turn it greater than this angle. An angle of zero means to disable pivot turning. Note that you will probably also want to set a low value for WP_RADIUS to get neat turns.
717
// @Units: deg
718
// @Range: 0 360
719
// @Increment: 1
720
// @User: Standard
721
722
// @Param: PIVOT_TURN_RATE
723
// @DisplayName: Pivot turn rate
724
// @Description: Desired pivot turn rate in deg/s.
725
// @Units: deg/s
726
// @Range: 0 360
727
// @Increment: 1
728
// @User: Standard
729
730
ParametersG2::ParametersG2(void)
731
:
732
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
733
afs(),
734
#endif
735
#if AP_BEACON_ENABLED
736
beacon(),
737
#endif
738
wheel_rate_control(wheel_encoder),
739
motors(wheel_rate_control),
740
attitude_control(),
741
smart_rtl(),
742
#if HAL_PROXIMITY_ENABLED
743
proximity(),
744
#endif
745
#if MODE_DOCK_ENABLED
746
mode_dock_ptr(&rover.mode_dock),
747
#endif
748
#if AP_AVOIDANCE_ENABLED
749
avoid(),
750
#endif
751
#if AP_FOLLOW_ENABLED
752
follow(),
753
#endif
754
windvane(),
755
wp_nav(attitude_control, pos_control),
756
sailboat(),
757
pos_control(attitude_control)
758
{
759
AP_Param::setup_object_defaults(this, var_info);
760
}
761
762
763
/*
764
This is a conversion table from old parameter values to new
765
parameter names. The startup code looks for saved values of the old
766
parameters and will copy them across to the new parameters if the
767
new parameter does not yet have a saved value. It then saves the new
768
value.
769
770
Note that this works even if the old parameter has been removed. It
771
relies on the old k_param index not being removed
772
773
The second column below is the index in the var_info[] table for the
774
old object. This should be zero for top level parameters.
775
*/
776
const AP_Param::ConversionInfo conversion_table[] = {
777
{ Parameters::k_param_battery_monitoring, 0, AP_PARAM_INT8, "BATT_MONITOR" },
778
{ Parameters::k_param_battery_volt_pin, 0, AP_PARAM_INT8, "BATT_VOLT_PIN" },
779
{ Parameters::k_param_battery_curr_pin, 0, AP_PARAM_INT8, "BATT_CURR_PIN" },
780
{ Parameters::k_param_volt_div_ratio, 0, AP_PARAM_FLOAT, "BATT_VOLT_MULT" },
781
{ Parameters::k_param_curr_amp_per_volt, 0, AP_PARAM_FLOAT, "BATT_AMP_PERVOLT" },
782
{ Parameters::k_param_pack_capacity, 0, AP_PARAM_INT32, "BATT_CAPACITY" },
783
{ Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },
784
{ Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },
785
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
786
{ Parameters::k_param_throttle_min_old, 0, AP_PARAM_INT8, "MOT_THR_MIN" },
787
{ Parameters::k_param_throttle_max_old, 0, AP_PARAM_INT8, "MOT_THR_MAX" },
788
{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },
789
{ Parameters::k_param_waypoint_radius_old, 0, AP_PARAM_FLOAT, "WP_RADIUS" },
790
{ Parameters::k_param_g2, 299, AP_PARAM_INT16, "WP_PIVOT_ANGLE" },
791
{ Parameters::k_param_g2, 363, AP_PARAM_INT16, "WP_PIVOT_RATE" },
792
{ Parameters::k_param_g2, 491, AP_PARAM_FLOAT, "WP_PIVOT_DELAY" },
793
{ Parameters::k_param_g2, 32, AP_PARAM_FLOAT, "SAIL_ANGLE_MIN" },
794
{ Parameters::k_param_g2, 33, AP_PARAM_FLOAT, "SAIL_ANGLE_MAX" },
795
{ Parameters::k_param_g2, 34, AP_PARAM_FLOAT, "SAIL_ANGLE_IDEAL" },
796
{ Parameters::k_param_g2, 35, AP_PARAM_FLOAT, "SAIL_HEEL_MAX" },
797
{ Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" },
798
{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },
799
{ Parameters::k_param_turn_max_g_old, 0, AP_PARAM_FLOAT, "ATC_TURN_MAX_G" },
800
{ Parameters::k_param_g2, 82, AP_PARAM_INT8 , "PRX1_TYPE" },
801
{ Parameters::k_param_g2, 146, AP_PARAM_INT8 , "PRX1_ORIENT" },
802
{ Parameters::k_param_g2, 210, AP_PARAM_INT16, "PRX1_YAW_CORR" },
803
{ Parameters::k_param_g2, 274, AP_PARAM_INT16, "PRX1_IGN_ANG1" },
804
{ Parameters::k_param_g2, 338, AP_PARAM_INT8, "PRX1_IGN_WID1" },
805
{ Parameters::k_param_g2, 402, AP_PARAM_INT16, "PRX1_IGN_ANG2" },
806
{ Parameters::k_param_g2, 466, AP_PARAM_INT8, "PRX1_IGN_WID2" },
807
{ Parameters::k_param_g2, 530, AP_PARAM_INT16, "PRX1_IGN_ANG3" },
808
{ Parameters::k_param_g2, 594, AP_PARAM_INT8, "PRX1_IGN_WID3" },
809
{ Parameters::k_param_g2, 658, AP_PARAM_INT16, "PRX1_IGN_ANG4" },
810
{ Parameters::k_param_g2, 722, AP_PARAM_INT8, "PRX1_IGN_WID4" },
811
{ Parameters::k_param_g2, 1234, AP_PARAM_FLOAT, "PRX1_MIN" },
812
{ Parameters::k_param_g2, 1298, AP_PARAM_FLOAT, "PRX1_MAX" },
813
{ Parameters::k_param_g2, 113, AP_PARAM_INT8, "TRQ1_TYPE" },
814
{ Parameters::k_param_g2, 177, AP_PARAM_INT8, "TRQ1_ONOFF_PIN" },
815
{ Parameters::k_param_g2, 241, AP_PARAM_INT8, "TRQ1_DE_PIN" },
816
{ Parameters::k_param_g2, 305, AP_PARAM_INT16, "TRQ1_OPTIONS" },
817
{ Parameters::k_param_g2, 369, AP_PARAM_INT8, "TRQ1_POWER" },
818
{ Parameters::k_param_g2, 433, AP_PARAM_FLOAT, "TRQ1_SLEW_TIME" },
819
{ Parameters::k_param_g2, 497, AP_PARAM_FLOAT, "TRQ1_DIR_DELAY" },
820
};
821
822
823
void Rover::load_parameters(void)
824
{
825
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
826
827
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
828
829
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_ROVER);
830
831
SRV_Channels::set_default_function(CH_1, SRV_Channel::k_steering);
832
SRV_Channels::set_default_function(CH_3, SRV_Channel::k_throttle);
833
834
if (is_balancebot()) {
835
g2.crash_angle.set_default(30);
836
}
837
838
SRV_Channels::upgrade_parameters();
839
840
// convert CH7_OPTION to RC7_OPTION for Rover-3.4 to 3.5 upgrade
841
const AP_Param::ConversionInfo ch7_option_info = { Parameters::k_param_ch7_option, 0, AP_PARAM_INT8, "RC7_OPTION" };
842
AP_Int8 ch7_opt_old;
843
if (AP_Param::find_old_parameter(&ch7_option_info, &ch7_opt_old)) {
844
const uint8_t ch7_opt_map[] = {0,7,50,41,51,52,53,54,16,4,42,55,56};
845
const uint8_t ch7_opt_old_val = (uint8_t)ch7_opt_old.get();
846
if (ch7_opt_old_val < ARRAY_SIZE(ch7_opt_map)) {
847
AP_Param::set_default_by_name(ch7_option_info.new_name, ch7_opt_map[ch7_opt_old_val]);
848
}
849
}
850
851
// set AR_WPNav's WP_SPEED to be old WP_SPEED (if set) or CRUISE_SPEED (if set)
852
const AP_Param::ConversionInfo wp_speed_old_info = { Parameters::k_param_g2, 14, AP_PARAM_FLOAT, "WP_SPEED" };
853
const AP_Param::ConversionInfo cruise_speed_info = { Parameters::k_param_speed_cruise, 0, AP_PARAM_FLOAT, "WP_SPEED" };
854
AP_Float wp_speed_old;
855
if (AP_Param::find_old_parameter(&wp_speed_old_info, &wp_speed_old)) {
856
// old WP_SPEED parameter value was set so copy to new WP_SPEED
857
AP_Param::convert_old_parameter(&wp_speed_old_info, 1.0f);
858
} else {
859
// copy CRUISE_SPEED to new WP_SPEED
860
AP_Param::convert_old_parameter(&cruise_speed_info, 1.0f);
861
}
862
863
// attitude control FF and FILT parameter changes for Rover-3.6
864
const AP_Param::ConversionInfo ff_and_filt_conversion_info[] = {
865
{ Parameters::k_param_g2, 24650, AP_PARAM_FLOAT, "ATC_STR_RAT_FLTE" },
866
{ Parameters::k_param_g2, 28746, AP_PARAM_FLOAT, "ATC_STR_RAT_FF" },
867
{ Parameters::k_param_g2, 24714, AP_PARAM_FLOAT, "ATC_SPEED_FLTE" },
868
{ Parameters::k_param_g2, 28810, AP_PARAM_FLOAT, "ATC_SPEED_FF" },
869
{ Parameters::k_param_g2, 25226, AP_PARAM_FLOAT, "ATC_BAL_FLTE" },
870
{ Parameters::k_param_g2, 29322, AP_PARAM_FLOAT, "ATC_BAL_FF" },
871
{ Parameters::k_param_g2, 25354, AP_PARAM_FLOAT, "ATC_SAIL_FLTE" },
872
{ Parameters::k_param_g2, 29450, AP_PARAM_FLOAT, "ATC_SAIL_FF" },
873
};
874
AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[0], ARRAY_SIZE(ff_and_filt_conversion_info));
875
876
// configure safety switch to allow stopping the motors while armed
877
#if HAL_HAVE_SAFETY_SWITCH
878
AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|
879
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON|
880
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);
881
#endif
882
883
#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED | AP_FENCE_ENABLED
884
// Find G2's Top Level Key
885
AP_Param::ConversionInfo info;
886
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
887
return;
888
}
889
#endif
890
891
static const AP_Param::G2ObjectConversion g2_conversions[] {
892
#if AP_AIRSPEED_ENABLED
893
// PARAMETER_CONVERSION - Added: JAN-2022
894
{ &airspeed, airspeed.var_info, 37 },
895
#endif
896
#if AP_AIS_ENABLED
897
// PARAMETER_CONVERSION - Added: MAR-2022
898
{ &ais, ais.var_info, 50 },
899
#endif
900
#if AP_FENCE_ENABLED
901
// PARAMETER_CONVERSION - Added: Mar-2022
902
{ &fence, fence.var_info, 17 },
903
#endif
904
#if AP_STATS_ENABLED
905
// PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6
906
{ &stats, stats.var_info, 1 },
907
#endif
908
#if AP_SCRIPTING_ENABLED
909
// PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6
910
{ &scripting, scripting.var_info, 41 },
911
#endif
912
#if AP_GRIPPER_ENABLED
913
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
914
{ &gripper, gripper.var_info, 39 },
915
#endif
916
};
917
918
AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));
919
920
// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6
921
#if HAL_LOGGING_ENABLED
922
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
923
#endif
924
925
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
926
#if AP_SERIALMANAGER_ENABLED
927
// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6
928
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
929
#endif
930
};
931
932
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
933
934
}
935
936