Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/Parameters.cpp
9546 views
1
#include "Plane.h"
2
3
#include <AP_Gripper/AP_Gripper.h>
4
5
/*
6
* ArduPlane parameter definitions
7
*
8
*/
9
10
const AP_Param::Info Plane::var_info[] = {
11
// @Param: FORMAT_VERSION
12
// @DisplayName: Eeprom format version number
13
// @Description: This value is incremented when changes are made to the eeprom format
14
// @User: Advanced
15
GSCALAR(format_version, "FORMAT_VERSION", 0),
16
17
// SYSID_THISMAV was here
18
19
// SYSID_MYGCS was here
20
21
// AP_SerialManager was here
22
23
// @Param: AUTOTUNE_LEVEL
24
// @DisplayName: Autotune level
25
// @Description: Level of aggressiveness of pitch and roll PID gains. Lower values result in a 'softer' tune. Level 6 recommended for most planes. A value of 0 means to keep the current values of RMAX and TCONST for the controllers, tuning only the PID values
26
// @Range: 0 10
27
// @Increment: 1
28
// @User: Standard
29
ASCALAR(autotune_level, "AUTOTUNE_LEVEL", 6),
30
31
// @Param: AUTOTUNE_OPTIONS
32
// @DisplayName: Autotune options bitmask
33
// @Description: Fixed Wing Autotune specific options. Useful on QuadPlanes with higher INS_GYRO_FILTER settings to prevent these filter values from being set too aggressively during Fixed Wing Autotune.
34
// @Bitmask: 0: Disable FLTD update by Autotune
35
// @Bitmask: 1: Disable FLTT update by Autotune
36
// @User: Advanced
37
ASCALAR(autotune_options, "AUTOTUNE_OPTIONS", 0),
38
39
// TELEM_DELAY was here
40
41
// @Param: GCS_PID_MASK
42
// @DisplayName: GCS PID tuning mask
43
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
44
// @User: Advanced
45
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ
46
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
47
48
// @Param: KFF_RDDRMIX
49
// @DisplayName: Rudder Mix
50
// @Description: Amount of rudder to add during aileron movement. Increase if nose initially yaws away from roll. Reduces adverse yaw.
51
// @Range: 0 1
52
// @Increment: 0.01
53
// @User: Standard
54
GSCALAR(kff_rudder_mix, "KFF_RDDRMIX", RUDDER_MIX),
55
56
// @Param: KFF_THR2PTCH
57
// @DisplayName: Throttle to Pitch Mix
58
// @Description: Pitch up to add in proportion to throttle. 100% throttle will add this number of degrees to the pitch target.
59
// @Range: -5 5
60
// @Increment: 0.01
61
// @User: Advanced
62
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", 0),
63
64
// @Param: STAB_PITCH_DOWN
65
// @DisplayName: Low throttle pitch down trim
66
// @Description: Degrees of down pitch added when throttle is below TRIM_THROTTLE in FBWA and AUTOTUNE modes. Scales linearly so full value is added when THR_MIN is reached. Helps to keep airspeed higher in glides or landing approaches and prevents accidental stalls. 2 degrees recommended for most planes.
67
// @Range: 0 15
68
// @Increment: 0.1
69
// @Units: deg
70
// @User: Advanced
71
GSCALAR(stab_pitch_down, "STAB_PITCH_DOWN", 2.0f),
72
73
// @Param: ALT_SLOPE_MIN
74
// @DisplayName: Altitude slope minimum
75
// @Description: This controls the minimum altitude change for a waypoint before an altitude slope will be used instead of an immediate altitude change. The default value is 15 meters, which helps to smooth out waypoint missions where small altitude changes happen near waypoints. If you don't want altitude slopes to be used in missions then you can set this to zero, which will disable altitude slope calculations. Otherwise you can set it to a minimum number of meters of altitude error to the destination waypoint before an altitude slope will be used to change altitude.
76
// @Range: 0 1000
77
// @Increment: 1
78
// @Units: m
79
// @User: Advanced
80
GSCALAR(alt_slope_min, "ALT_SLOPE_MIN", 15),
81
82
// @Param: ALT_SLOPE_MAXHGT
83
// @DisplayName: Altitude slope maximum height
84
// @Description: This controls the height above the altitude slope the plane may be before rebuilding it. This is useful for smoothing out an auto-takeoff.
85
// @Range: 0 100
86
// @Increment: 1
87
// @Units: m
88
// @User: Advanced
89
GSCALAR(alt_slope_max_height, "ALT_SLOPE_MAXHGT", 5.0),
90
91
// @Param: STICK_MIXING
92
// @DisplayName: Stick Mixing
93
// @Description: When enabled, this adds user stick input to the control surfaces in auto modes, allowing the user to have some degree of flight control without changing modes. There are 3 types of stick mixing available. If you set STICK_MIXING to 1 or 4 then it will use "fly by wire" mixing. 4 will provide roll and yaw control, while 1 also provides FBW-A style pitch control. If you set STICK_MIXING to 3 then it will apply to the yaw while in quadplane modes only, such as while doing an automatic VTOL takeoff or landing. WARNING: FBW-A pitch control does not offer flight envelope protections. Prolonged pitch inputs in mode 1 can result in a stall or overspeed condition, and should be avoided.
94
// @Values: 0:Disabled,1:FBW style,3:VTOL Yaw only,4:FBW style (no pitch)
95
// @User: Advanced
96
GSCALAR(stick_mixing, "STICK_MIXING", uint8_t(StickMixing::FBW)),
97
98
// @Param: TKOFF_THR_MINSPD
99
// @DisplayName: Takeoff throttle min speed
100
// @Description: Minimum GPS ground speed in m/s used by the speed check that un-suppresses throttle in auto-takeoff. This can be be used for catapult launches where you want the motor to engage only after the plane leaves the catapult, but it is preferable to use the TKOFF_THR_MINACC and TKOFF_THR_DELAY parameters for catapult launches due to the errors associated with GPS measurements. For hand launches with a pusher prop it is strongly advised that this parameter be set to a value no less than 4 m/s to provide additional protection against premature motor start. Note that the GPS velocity will lag the real velocity by about 0.5 seconds. The ground speed check is delayed by the TKOFF_THR_DELAY parameter.
101
// @Units: m/s
102
// @Range: 0 30
103
// @Increment: 0.1
104
// @User: Standard
105
GSCALAR(takeoff_throttle_min_speed, "TKOFF_THR_MINSPD", 0),
106
107
// @Param: TKOFF_THR_MINACC
108
// @DisplayName: Takeoff throttle min acceleration
109
// @Description: Minimum forward acceleration in m/s/s before arming the ground speed check in auto-takeoff. This is meant to be used for hand launches. Setting this value to 0 disables the acceleration test which means the ground speed check will always be armed which could allow GPS velocity jumps to start the engine. For hand launches and bungee launches this should be set to around 15. Also see TKOFF_ACCEL_CNT parameter for control of full "shake to arm".
110
// @Units: m/s/s
111
// @Range: 0 30
112
// @Increment: 0.1
113
// @User: Standard
114
GSCALAR(takeoff_throttle_min_accel, "TKOFF_THR_MINACC", 0),
115
116
// @Param: TKOFF_THR_DELAY
117
// @DisplayName: Takeoff throttle delay
118
// @Description: This parameter sets the time delay (in 1/10ths of a second) that the ground speed check is delayed after the forward acceleration check controlled by TKOFF_THR_MINACC has passed. For hand launches with pusher propellers it is essential that this is set to a value of no less than 2 (0.2 seconds) to ensure that the aircraft is safely clear of the throwers arm before the motor can start. For bungee launches a larger value can be used (such as 30) to give time for the bungee to release from the aircraft before the motor is started.
119
// @Units: ds
120
// @Range: 0 127
121
// @Increment: 1
122
// @User: Standard
123
GSCALAR(takeoff_throttle_delay, "TKOFF_THR_DELAY", 2),
124
125
// @Param: TKOFF_THR_MAX_T
126
// @DisplayName: Takeoff throttle maximum time
127
// @Description: This sets the time that maximum throttle will be forced during a fixed wing takeoff.
128
// @Units: s
129
// @Range: 0 10
130
// @Increment: 0.5
131
// @User: Standard
132
ASCALAR(takeoff_throttle_max_t, "TKOFF_THR_MAX_T", 4),
133
134
// @Param: TKOFF_THR_MIN
135
// @DisplayName: Takeoff minimum throttle
136
// @Description: The minimum throttle to use in takeoffs in AUTO and TAKEOFF flight modes, when TKOFF_OPTIONS bit 0 is set. Also, the minimum throttle to use in a quadpane forward transition. This can be useful to ensure faster takeoffs or transitions on aircraft where the normal throttle control leads to a slow takeoff or transition. It is used when it is larger than THR_MIN, otherwise THR_MIN is used instead.
137
// @Units: %
138
// @Range: 0 100
139
// @Increment: 1
140
// @User: Standard
141
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),
142
143
// @Param: TKOFF_THR_IDLE
144
// @DisplayName: Takeoff idle throttle
145
// @Description: The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes.
146
// @Units: %
147
// @Range: 0 100
148
// @Increment: 1
149
// @User: Standard
150
ASCALAR(takeoff_throttle_idle, "TKOFF_THR_IDLE", 0),
151
152
// @Param: TKOFF_OPTIONS
153
// @DisplayName: Takeoff options
154
// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.
155
// @Bitmask: 0: When unset the maximum allowed throttle is always used (THR_MAX or TKOFF_THR_MAX) during takeoff. When set TECS is allowed to operate between a minimum (THR_MIN or TKOFF_THR_MIN) and a maximum (THR_MAX or TKOFF_THR_MAX) limit. Applicable only when using an airspeed sensor.
156
// @User: Advanced
157
ASCALAR(takeoff_options, "TKOFF_OPTIONS", 0),
158
159
// @Param: TKOFF_TDRAG_ELEV
160
// @DisplayName: Takeoff tail dragger elevator
161
// @Description: This parameter sets the amount of elevator to apply during the initial stage of a takeoff. It is used to hold the tail wheel of a taildragger on the ground during the initial takeoff stage to give maximum steering. This option should be combined with the TKOFF_TDRAG_SPD1 option and the GROUND_STEER_ALT option along with tuning of the ground steering controller. A value of zero means to bypass the initial "tail hold" stage of takeoff. Set to zero for hand and catapult launch. For tail-draggers you should normally set this to 100, meaning full up elevator during the initial stage of takeoff. For most tricycle undercarriage aircraft a value of zero will work well, but for some tricycle aircraft a small negative value (say around -20 to -30) will apply down elevator which will hold the nose wheel firmly on the ground during initial acceleration. Only use a negative value if you find that the nosewheel doesn't grip well during takeoff. Too much down elevator on a tricycle undercarriage may cause instability in steering as the plane pivots around the nosewheel. Add down elevator 10 percent at a time.
162
// @Units: %
163
// @Range: -100 100
164
// @Increment: 1
165
// @User: Standard
166
GSCALAR(takeoff_tdrag_elevator, "TKOFF_TDRAG_ELEV", 0),
167
168
// @Param: TKOFF_TDRAG_SPD1
169
// @DisplayName: Takeoff tail dragger speed1
170
// @Description: This parameter sets the airspeed at which to stop holding the tail down and transition to rudder control of steering on the ground. When TKOFF_TDRAG_SPD1 is reached the pitch of the aircraft will be held level until TKOFF_ROTATE_SPD is reached, at which point the takeoff pitch specified in the mission will be used to "rotate" the pitch for takeoff climb. Set TKOFF_TDRAG_SPD1 to zero to go straight to rotation. This should be set to zero for hand launch and catapult launch. It should also be set to zero for tricycle undercarriages unless you are using the method above to gently hold the nose wheel down. For tail dragger aircraft it should be set just below the stall speed.
171
// @Units: m/s
172
// @Range: 0 30
173
// @Increment: 0.1
174
// @User: Standard
175
GSCALAR(takeoff_tdrag_speed1, "TKOFF_TDRAG_SPD1", 0),
176
177
// @Param: TKOFF_ROTATE_SPD
178
// @DisplayName: Takeoff rotate speed
179
// @Description: This parameter sets the airspeed at which the aircraft will "rotate", setting climb pitch specified in the mission. If TKOFF_ROTATE_SPD is zero then the climb pitch will be used as soon as takeoff is started. For hand launch and catapult launches a TKOFF_ROTATE_SPD of zero should be set. For all ground launches TKOFF_ROTATE_SPD should be set above the stall speed, usually by about 10 to 30 percent. During the run, use TKOFF_GND_PITCH to keep the aircraft on the runway while below this airspeed.
180
// @Units: m/s
181
// @Range: 0 30
182
// @Increment: 0.1
183
// @User: Standard
184
GSCALAR(takeoff_rotate_speed, "TKOFF_ROTATE_SPD", 0),
185
186
// @Param: TKOFF_THR_SLEW
187
// @DisplayName: Takeoff throttle slew rate
188
// @Description: This parameter sets the slew rate for the throttle during auto takeoff. When this is zero the THR_SLEWRATE parameter is used during takeoff. For rolling takeoffs it can be a good idea to set a lower slewrate for takeoff to give a slower acceleration which can improve ground steering control. The value is a percentage throttle change per second, so a value of 20 means to advance the throttle over 5 seconds on takeoff. Values below 20 are not recommended as they may cause the plane to try to climb out with too little throttle. A value of -1 means no limit on slew rate in takeoff.
189
// @Units: %/s
190
// @Range: -1 127
191
// @Increment: 1
192
// @User: Standard
193
GSCALAR(takeoff_throttle_slewrate, "TKOFF_THR_SLEW", 0),
194
195
// @Param: TKOFF_PLIM_SEC
196
// @DisplayName: Takeoff pitch limit reduction
197
// @Description: This parameter reduces the pitch minimum limit of an auto-takeoff just a few seconds before it reaches the target altitude. This reduces overshoot by allowing the flight controller to start leveling off a few seconds before reaching the target height. When set to zero, the mission pitch min is enforced all the way to and through the target altitude, otherwise the pitch min slowly reduces to zero in the final segment. This is the pitch_min, not the demand. The flight controller should still be commanding to gain altitude to finish the takeoff but with this param it is not forcing it higher than it wants to be.
198
// @Units: s
199
// @Range: 0 10
200
// @Increment: 0.5
201
// @User: Advanced
202
GSCALAR(takeoff_pitch_limit_reduction_sec, "TKOFF_PLIM_SEC", 2),
203
204
// @Param: TKOFF_FLAP_PCNT
205
// @DisplayName: Takeoff flap percentage
206
// @Description: The amount of flaps (as a percentage) to apply in automatic takeoff
207
// @Range: 0 100
208
// @Units: %
209
// @Increment: 1
210
// @User: Advanced
211
GSCALAR(takeoff_flap_percent, "TKOFF_FLAP_PCNT", 0),
212
213
// @Param: LEVEL_ROLL_LIMIT
214
// @DisplayName: Level flight roll limit
215
// @Description: This controls the maximum bank angle in degrees during flight modes where level flight is desired, such as in the final stages of landing, and during auto takeoff. This should be a small angle (such as 5 degrees) to prevent a wing hitting the runway during takeoff or landing. Setting this to zero will completely disable heading hold on auto takeoff while below 5 meters and during the flare portion of a final landing approach.
216
// @Units: deg
217
// @Range: 0 45
218
// @Increment: 1
219
// @User: Standard
220
GSCALAR(level_roll_limit, "LEVEL_ROLL_LIMIT", 5),
221
222
// @Param: USE_REV_THRUST
223
// @DisplayName: Bitmask for when to allow negative reverse thrust
224
// @Description: This controls when to use reverse thrust. If set to a non-zero value then the bits correspond to flight stages where reverse thrust may be used. The most commonly used value for USE_REV_THRUST is 2, which means AUTO_LAND only. That enables reverse thrust in the landing stage of AUTO mode. Another common choice is 1, which means to use reverse thrust in all auto flight stages. Reverse thrust is always used in MANUAL mode if enabled with THR_MIN < 0. In non-autothrottle controlled modes, if reverse thrust is not used, then THR_MIN is effectively set to 0 for that mode.
225
// @Bitmask: 0:AUTO_ALWAYS,1:AUTO_LAND,2:AUTO_LOITER_TO_ALT,3:AUTO_LOITER_ALL,4:AUTO_WAYPOINTS,5:LOITER,6:RTL,7:CIRCLE,8:CRUISE,9:FBWB,10:GUIDED,11:AUTO_LANDING_PATTERN,12:FBWA,13:ACRO,14:STABILIZE,15:THERMAL
226
// @User: Advanced
227
GSCALAR(use_reverse_thrust, "USE_REV_THRUST", float(UseReverseThrust::AUTO_LAND_APPROACH)),
228
229
// @Param: ALT_OFFSET
230
// @DisplayName: Altitude offset
231
// @Description: This is added to the target altitude in automatic flight. It can be used to add a global altitude offset to a mission
232
// @Units: m
233
// @Range: -32767 32767
234
// @Increment: 1
235
// @User: Advanced
236
GSCALAR(alt_offset, "ALT_OFFSET", 0),
237
238
// @Param: WP_RADIUS
239
// @DisplayName: Waypoint Radius
240
// @Description: Defines the maximum distance from a waypoint that when crossed indicates the waypoint may be complete. To avoid the aircraft looping around the waypoint in case it misses by more than the WP_RADIUS an additional check is made to see if the aircraft has crossed a "finish line" passing through the waypoint and perpendicular to the flight path from the previous waypoint. If that finish line is crossed then the waypoint is considered complete. Note that the navigation controller may decide to turn later than WP_RADIUS before a waypoint, based on how sharp the turn is and the speed of the aircraft. It is safe to set WP_RADIUS much larger than the usual turn radius of your aircraft and the navigation controller will work out when to turn. If you set WP_RADIUS too small then you will tend to overshoot the turns.
241
// @Units: m
242
// @Range: 1 32767
243
// @Increment: 1
244
// @User: Standard
245
GSCALAR(waypoint_radius, "WP_RADIUS", WP_RADIUS_DEFAULT),
246
247
// @Param: WP_MAX_RADIUS
248
// @DisplayName: Waypoint Maximum Radius
249
// @Description: Sets the maximum distance to a waypoint for the waypoint to be considered complete. This overrides the "cross the finish line" logic that is normally used to consider a waypoint complete. For normal AUTO behaviour this parameter should be set to zero. Using a non-zero value is only recommended when it is critical that the aircraft does approach within the given radius, and should loop around until it has done so. This can cause the aircraft to loop forever if its turn radius is greater than the maximum radius set.
250
// @Units: m
251
// @Range: 0 32767
252
// @Increment: 1
253
// @User: Standard
254
GSCALAR(waypoint_max_radius, "WP_MAX_RADIUS", 0),
255
256
// @Param: WP_LOITER_RAD
257
// @DisplayName: Waypoint Loiter Radius
258
// @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter. If you set this value to a negative number then the default loiter direction will be counter-clockwise instead of clockwise. If this value is too close to zero, the achieved loiter radius will be determined by ROLL_LIMIT_DEG.
259
// @Units: m
260
// @Range: -32767 32767
261
// @Increment: 1
262
// @User: Standard
263
ASCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),
264
265
// @Param: RTL_RADIUS
266
// @DisplayName: RTL loiter radius
267
// @Description: Defines the radius of the loiter circle when in RTL mode. If this is zero then WP_LOITER_RAD is used. If the radius is negative then a counter-clockwise is used. If positive then a clockwise loiter is used. For quadplanes with Q_RTL_MODE set to 1 (Enabled), this value is used to set the minimum radius at which the plane will transition from fixed-wing to VTOL mode for landing.
268
// @Units: m
269
// @Range: -32767 32767
270
// @Increment: 1
271
// @User: Standard
272
GSCALAR(rtl_radius, "RTL_RADIUS", 0),
273
274
// @Param: STALL_PREVENTION
275
// @DisplayName: Enable stall prevention
276
// @Description: Enables roll limits at low airspeed in roll limiting flight modes. Roll limits based on aerodynamic load factor in turns and scale on AIRSPEED_MIN that must be set correctly. Without airspeed sensor, uses synthetic airspeed from wind speed estimate that may both be inaccurate.
277
// @Values: 0:Disabled,1:Enabled
278
// @User: Standard
279
ASCALAR(stall_prevention, "STALL_PREVENTION", 1),
280
281
// @Param: AIRSPEED_CRUISE
282
// @DisplayName: Target cruise airspeed
283
// @Description: Target cruise airspeed in m/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
284
// @Units: m/s
285
// @User: Standard
286
ASCALAR(airspeed_cruise, "AIRSPEED_CRUISE", AIRSPEED_CRUISE),
287
288
// @Param: AIRSPEED_MIN
289
// @DisplayName: Minimum Airspeed
290
// @Description: Minimum airspeed demanded in automatic throttle modes. Should be set to 20% higher than level flight stall speed.
291
// @Units: m/s
292
// @Range: 5 100
293
// @Increment: 1
294
// @User: Standard
295
ASCALAR(airspeed_min, "AIRSPEED_MIN", AIRSPEED_FBW_MIN),
296
297
// @Param: AIRSPEED_MAX
298
// @DisplayName: Maximum Airspeed
299
// @Description: Maximum airspeed demanded in automatic throttle modes. Should be set slightly less than level flight speed at THR_MAX and also at least 50% above AIRSPEED_MIN to allow for accurate TECS altitude control.
300
// @Units: m/s
301
// @Range: 5 100
302
// @Increment: 1
303
// @User: Standard
304
ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX),
305
306
// @Param: AIRSPEED_STALL
307
// @DisplayName: Stall airspeed
308
// @Description: If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. It is also used during landing final as the minimum airspeed that can be demanded by the TECS, which allows using TECS_LAND_ARSPD or LAND_PF_ARSPD to achieve landings slower than AIRSPEED_MIN. If this is set to 0 then the stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed.
309
// @Units: m/s
310
// @Range: 5 75
311
// @User: Standard
312
ASCALAR(airspeed_stall, "AIRSPEED_STALL", 0),
313
314
// @Param: FBWB_ELEV_REV
315
// @DisplayName: Fly By Wire elevator reverse
316
// @Description: Reverse sense of elevator in FBWB and CRUISE modes. When set to 0 up elevator (pulling back on the stick) means to raise altitude. When set to 1, up elevator means to lower altitude.
317
// @Values: 0:Disabled,1:Enabled
318
// @User: Standard
319
GSCALAR(flybywire_elev_reverse, "FBWB_ELEV_REV", 0),
320
321
#if AP_TERRAIN_AVAILABLE
322
// @Param: TERRAIN_FOLLOW
323
// @DisplayName: Use terrain following
324
// @Description: This enables terrain following for CRUISE mode, FBWB mode, RTL and for rally points. To use this option you also need to set TERRAIN_ENABLE to 1, which enables terrain data fetching from the GCS, and you need to have a GCS that supports sending terrain data to the aircraft. When terrain following is enabled then CRUISE and FBWB mode will hold height above terrain rather than height above home. In RTL the return to launch altitude will be considered to be a height above the terrain. Rally point altitudes will be taken as height above the terrain. This option does not affect mission items, which have a per-waypoint flag for whether they are height above home or height above the terrain. To use terrain following missions you need a ground station which can set the waypoint type to be a terrain height waypoint when creating the mission.
325
// @Bitmask: 0: Enable all modes, 1:FBWB, 2:Cruise, 3:Auto, 4:RTL, 5:Avoid_ADSB, 6:Guided, 7:Loiter, 8:Circle, 9:QRTL, 10:QLand, 11:Qloiter, 12:AUTOLAND
326
// @User: Standard
327
GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),
328
329
// @Param: TERRAIN_LOOKAHD
330
// @DisplayName: Terrain lookahead
331
// @Description: This controls how far ahead the terrain following code looks to ensure it stays above upcoming terrain. A value of zero means no lookahead, so the controller will track only the terrain directly below the aircraft. The lookahead will never extend beyond the next waypoint when in AUTO mode.
332
// @Range: 0 10000
333
// @Units: m
334
// @User: Standard
335
GSCALAR(terrain_lookahead, "TERRAIN_LOOKAHD", 2000),
336
#endif
337
338
// @Param: FBWB_CLIMB_RATE
339
// @DisplayName: Fly By Wire B altitude change rate
340
// @Description: This sets the rate in m/s at which FBWB and CRUISE modes will change its target altitude for full elevator deflection. Note that the actual climb rate of the aircraft can be lower than this, depending on your airspeed and throttle control settings. If you have this parameter set to the default value of 2.0, then holding the elevator at maximum deflection for 10 seconds would change the target altitude by 20 meters.
341
// @Range: 1 10
342
// @Units: m/s
343
// @Increment: 0.1
344
// @User: Standard
345
GSCALAR(flybywire_climb_rate, "FBWB_CLIMB_RATE", 2.0f),
346
347
// @Param: THR_MIN
348
// @DisplayName: Minimum Throttle
349
// @Description: Minimum throttle percentage used in all modes except manual, provided THR_PASS_STAB is not set. Negative values allow reverse thrust if hardware supports it.
350
// @Units: %
351
// @Range: -100 100
352
// @Increment: 1
353
// @User: Standard
354
ASCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
355
356
// @Param: THR_MAX
357
// @DisplayName: Maximum Throttle
358
// @Description: Maximum throttle percentage used in all modes except manual, provided THR_PASS_STAB is not set.
359
// @Units: %
360
// @Range: 0 100
361
// @Increment: 1
362
// @User: Standard
363
ASCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
364
365
// @Param: TKOFF_THR_MAX
366
// @DisplayName: Maximum Throttle for takeoff
367
// @Description: The maximum throttle setting during automatic takeoff. If this is zero then THR_MAX is used for takeoff as well.
368
// @Units: %
369
// @Range: 0 100
370
// @Increment: 1
371
// @User: Advanced
372
ASCALAR(takeoff_throttle_max, "TKOFF_THR_MAX", 0),
373
374
// @Param: THR_SLEWRATE
375
// @DisplayName: Throttle slew rate
376
// @Description: Maximum change in throttle percentage per second. Lower limit based on 1 microsend of servo increase per loop. Divide SCHED_LOOP_RATE by approximately 10 to determine minimum achievable value.
377
// @Units: %/s
378
// @Range: 0 127
379
// @Increment: 1
380
// @User: Standard
381
ASCALAR(throttle_slewrate, "THR_SLEWRATE", 100),
382
383
// @Param: FLAP_SLEWRATE
384
// @DisplayName: Flap slew rate
385
// @Description: maximum percentage change in flap output per second. A setting of 25 means to not change the flap by more than 25% of the full flap range in one second. A value of 0 means no rate limiting.
386
// @Units: %/s
387
// @Range: 0 100
388
// @Increment: 1
389
// @User: Advanced
390
GSCALAR(flap_slewrate, "FLAP_SLEWRATE", 75),
391
392
// @Param: THR_SUPP_MAN
393
// @DisplayName: Throttle suppress manual passthru
394
// @Description: When throttle is suppressed in auto mode it is normally forced to zero. If you enable this option, then while suppressed it will be manual throttle. This is useful on petrol engines to hold the idle throttle manually while waiting for takeoff
395
// @Values: 0:Disabled,1:Enabled
396
// @User: Advanced
397
GSCALAR(throttle_suppress_manual,"THR_SUPP_MAN", 0),
398
399
// @Param: THR_PASS_STAB
400
// @DisplayName: Throttle passthru in stabilize
401
// @Description: If this is set then when in STABILIZE, FBWA or ACRO modes the throttle is a direct passthru from the transmitter. This means the THR_MIN and THR_MAX settings are not used in these modes. This is useful for petrol engines where you setup a throttle cut switch that suppresses the throttle below the normal minimum.
402
// @Values: 0:Disabled,1:Enabled
403
// @User: Advanced
404
GSCALAR(throttle_passthru_stabilize,"THR_PASS_STAB", 0),
405
406
// @Param: THR_FAILSAFE
407
// @DisplayName: Throttle and RC Failsafe Enable
408
// @Description: 0 disables the failsafe. 1 enables failsafe on loss of RC input. This is detected either by throttle values below THR_FS_VALUE, loss of receiver valid pulses/data, or by the FS bit in receivers that provide it, like SBUS. A programmable failsafe action will occur and RC inputs, if present, will be ignored. A value of 2 means that the RC inputs won't be used when RC failsafe is detected by any of the above methods, but it won't trigger an RC failsafe action.
409
// @Values: 0:Disabled,1:Enabled,2:EnabledNoFailsafe
410
// @User: Standard
411
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", int(ThrFailsafe::Enabled)),
412
413
414
// @Param: THR_FS_VALUE
415
// @DisplayName: Throttle Failsafe Value
416
// @Description: The PWM level on the throttle input channel below which throttle failsafe triggers. Note that this should be well below the normal minimum for your throttle channel.
417
// @Range: 925 2200
418
// @Increment: 1
419
// @User: Standard
420
GSCALAR(throttle_fs_value, "THR_FS_VALUE", 950),
421
422
// @Param: TRIM_THROTTLE
423
// @DisplayName: Throttle cruise percentage
424
// @Description: Target percentage of throttle to apply for flight in automatic throttle modes and throttle percentage that maintains AIRSPEED_CRUISE. Caution: low battery voltages at the end of flights may require higher throttle to maintain airspeed.
425
// @Units: %
426
// @Range: 0 100
427
// @Increment: 1
428
// @User: Standard
429
ASCALAR(throttle_cruise, "TRIM_THROTTLE", AP_PLANE_TRIM_THROTTLE_DEFAULT),
430
431
// @Param: THROTTLE_NUDGE
432
// @DisplayName: Throttle nudge enable
433
// @Description: When enabled, this uses the throttle input in auto-throttle modes to 'nudge' the throttle or airspeed to higher or lower values. When you have an airspeed sensor the nudge affects the target airspeed, so that throttle inputs above 50% will increase the target airspeed from AIRSPEED_CRUISE up to a maximum of AIRSPEED_MAX. When no airspeed sensor is enabled the throttle nudge will push up the target throttle for throttle inputs above 50%.
434
// @Values: 0:Disabled,1:Enabled
435
// @User: Standard
436
GSCALAR(throttle_nudge, "THROTTLE_NUDGE", 1),
437
438
// @Param: FS_SHORT_ACTN
439
// @DisplayName: Short failsafe action
440
// @Description: The action to take on a short failsafe event. A short failsafe event can be triggered instantly by loss of RC control or by throttle value (see THR_FS_VALUE). If in CIRCLE or RTL mode this parameter is ignored. A short failsafe event in stabilization and manual modes will cause a change to CIRCLE mode if FS_SHORT_ACTN is 0 or 1, a change to FBWA mode with zero throttle if FS_SHORT_ACTN is 2, and a change to FBWB mode if FS_SHORT_ACTN is 4. In all other modes (AUTO, GUIDED and LOITER) a short failsafe event will cause no mode change if FS_SHORT_ACTN is set to 0, will cause a change to CIRCLE mode if set to 1, will change to FBWA mode with zero throttle if set to 2, or will change to FBWB if set to 4. Please see the documentation for FS_LONG_ACTN for the behaviour after FS_LONG_TIMEOUT seconds of failsafe. This parameter only applies to failsafes during fixed wing modes. Quadplane modes will switch to QLAND unless Q_OPTIONS bit 5(QRTL) or 20(RTL) are set.
441
// @Values: 0:CIRCLE/no change(if already in AUTO|GUIDED|LOITER),1:CIRCLE,2:FBWA at zero throttle,3:Disable,4:FBWB
442
// @User: Standard
443
GSCALAR(fs_action_short, "FS_SHORT_ACTN", FS_ACTION_SHORT_BESTGUESS),
444
445
// @Param: FS_LONG_ACTN
446
// @DisplayName: Long failsafe action
447
// @Description: The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTN is set to 3, the parachute will be deployed (make sure the chute is configured and enabled). If FS_LONG_ACTN is set to 4 the aircraft will switch to mode AUTO with the current waypoint if it is not already in mode AUTO, unless it is in the middle of a landing sequence. If FS_LONG_ACTN is set to 5, will switch to AUTOLAND mode if possible, otherwise RTL mode. This parameter only applies to failsafes during fixed wing modes. Quadplane modes will switch to QLAND unless Q_OPTIONS bit 5 (QRTL) or 20(RTL) are set.
448
// @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute,4:Auto,5:AUTOLAND
449
// @User: Standard
450
GSCALAR(fs_action_long, "FS_LONG_ACTN", FS_ACTION_LONG_CONTINUE),
451
452
// @Param: FS_LONG_TIMEOUT
453
// @DisplayName: Long failsafe timeout
454
// @Description: The time in seconds that a failsafe condition has to persist before a long failsafe event will occur. This defaults to 5 seconds.
455
// @Units: s
456
// @Range: 1 300
457
// @Increment: 0.5
458
// @User: Standard
459
GSCALAR(fs_timeout_long, "FS_LONG_TIMEOUT", 5),
460
461
// @Param: FS_GCS_ENABL
462
// @DisplayName: GCS failsafe enable
463
// @Description: Enable ground control station telemetry failsafe. Failsafe will trigger after FS_LONG_TIMEOUT seconds of no MAVLink heartbeat messages. There are three possible enabled settings. Setting FS_GCS_ENABL to 1 means that GCS failsafe will be triggered when the aircraft has not received a MAVLink HEARTBEAT message. Note that heartbeat tracking only becomes active after having received the first heartbeat from the MAV_GCS_SYSID primary GCS system. Setting FS_GCS_ENABL to 2 means that GCS failsafe will be triggered on either a loss of HEARTBEAT messages, or a RADIO_STATUS message from a MAVLink enabled telemetry adio indicating that the primary ground station is not receiving status updates from the aircraft, which is indicated by the RADIO_STATUS.remrssi field being zero (this may happen if you have a one way link due to asymmetric noise on the ground station and aircraft radios).Setting FS_GCS_ENABL to 3 means that GCS failsafe will be triggered by Heartbeat(like option one), but only in AUTO mode. WARNING: Enabling this option opens up the possibility of your plane going into failsafe mode and running the motor on the ground it it loses contact with your ground station. If this option is enabled on an electric plane then you should enable ARMING_REQUIRED.
464
// @Values: 0:Disabled,1:Heartbeat,2:HeartbeatAndREMRSSI,3:HeartbeatAndAUTO
465
// @User: Standard
466
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL", GCS_FAILSAFE_OFF),
467
468
// @Param: FLTMODE_CH
469
// @DisplayName: Flightmode channel
470
// @Description: RC Channel to use for flight mode control
471
// @Values: 0:Disabled,1:Channel 1,2:Channel 2,3:Channel 3,4:Channel 4,5:Channel 5,6:Channel 6,7:Channel 7,8:Channel 8,9:Channel 9,10:Channel 10,11:Channel 11,12:Channel 12,13:Channel 13,14:Channel 14,15:Channel 15,16:Channel 16
472
// @User: Advanced
473
GSCALAR(flight_mode_channel, "FLTMODE_CH", FLIGHT_MODE_CHANNEL),
474
475
// @Param: FLTMODE1
476
// @DisplayName: FlightMode1
477
// @Description: Flight mode for switch position 1 (910 to 1230 and above 2049)
478
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,7:CRUISE,8:AUTOTUNE,10:Auto,11:RTL,12:Loiter,13:TAKEOFF,14:AVOID_ADSB,15:Guided,17:QSTABILIZE,18:QHOVER,19:QLOITER,20:QLAND,21:QRTL,22:QAUTOTUNE,23:QACRO,24:THERMAL,25:Loiter to QLand,26:AUTOLAND
479
// @User: Standard
480
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
481
482
// @Param: FLTMODE2
483
// @CopyFieldsFrom: FLTMODE1
484
// @DisplayName: FlightMode2
485
// @Description: Flight mode for switch position 2 (1231 to 1360)
486
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
487
488
// @Param: FLTMODE3
489
// @CopyFieldsFrom: FLTMODE1
490
// @DisplayName: FlightMode3
491
// @Description: Flight mode for switch position 3 (1361 to 1490)
492
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
493
494
// @Param: FLTMODE4
495
// @CopyFieldsFrom: FLTMODE1
496
// @DisplayName: FlightMode4
497
// @Description: Flight mode for switch position 4 (1491 to 1620)
498
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
499
500
// @Param: FLTMODE5
501
// @CopyFieldsFrom: FLTMODE1
502
// @DisplayName: FlightMode5
503
// @Description: Flight mode for switch position 5 (1621 to 1749)
504
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
505
506
// @Param: FLTMODE6
507
// @CopyFieldsFrom: FLTMODE1
508
// @DisplayName: FlightMode6
509
// @Description: Flight mode for switch position 6 (1750 to 2049)
510
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
511
512
// @Param: INITIAL_MODE
513
// @DisplayName: Initial flight mode
514
// @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.
515
// @CopyValuesFrom: FLTMODE1
516
// @User: Advanced
517
GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL),
518
519
// @Param: ROLL_LIMIT_DEG
520
// @DisplayName: Maximum Bank Angle
521
// @Description: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls.
522
// @Units: deg
523
// @Range: 0 90
524
// @Increment: 1
525
// @User: Standard
526
ASCALAR(roll_limit, "ROLL_LIMIT_DEG", ROLL_LIMIT_DEG),
527
528
// @Param: PTCH_LIM_MAX_DEG
529
// @DisplayName: Maximum Pitch Angle
530
// @Description: Maximum pitch up angle commanded in modes with stabilized limits.
531
// @Units: deg
532
// @Range: 0 90
533
// @Increment: 1
534
// @User: Standard
535
ASCALAR(pitch_limit_max, "PTCH_LIM_MAX_DEG", PITCH_MAX),
536
537
// @Param: PTCH_LIM_MIN_DEG
538
// @DisplayName: Minimum Pitch Angle
539
// @Description: Maximum pitch down angle commanded in modes with stabilized limits
540
// @Units: deg
541
// @Range: -90 0
542
// @Increment: 1
543
// @User: Standard
544
ASCALAR(pitch_limit_min, "PTCH_LIM_MIN_DEG", PITCH_MIN),
545
546
// @Param: ACRO_ROLL_RATE
547
// @DisplayName: ACRO mode roll rate
548
// @Description: The maximum roll rate at full stick deflection in ACRO mode
549
// @Units: deg/s
550
// @Range: 10 500
551
// @Increment: 1
552
// @User: Standard
553
GSCALAR(acro_roll_rate, "ACRO_ROLL_RATE", 180),
554
555
// @Param: ACRO_PITCH_RATE
556
// @DisplayName: ACRO mode pitch rate
557
// @Description: The maximum pitch rate at full stick deflection in ACRO mode
558
// @Units: deg/s
559
// @Range: 10 500
560
// @Increment: 1
561
// @User: Standard
562
GSCALAR(acro_pitch_rate, "ACRO_PITCH_RATE", 180),
563
564
// @Param: ACRO_YAW_RATE
565
// @DisplayName: ACRO mode yaw rate
566
// @Description: The maximum yaw rate at full stick deflection in ACRO mode. If this is zero then rudder is directly controlled by rudder stick input. This option is only available if you also set YAW_RATE_ENABLE to 1.
567
// @Units: deg/s
568
// @Range: 0 500
569
// @Increment: 1
570
// @User: Standard
571
GSCALAR(acro_yaw_rate, "ACRO_YAW_RATE", 0),
572
573
// @Param: ACRO_LOCKING
574
// @DisplayName: ACRO mode attitude locking
575
// @Description: Enable attitude locking when sticks are released. If set to 2 then quaternion based locking is used if the yaw rate controller is enabled. Quaternion based locking will hold any attitude
576
// @Values: 0:Disabled,1:Enabled,2:Quaternion
577
// @User: Standard
578
GSCALAR(acro_locking, "ACRO_LOCKING", 0),
579
580
// @Param: GROUND_STEER_ALT
581
// @DisplayName: Ground steer altitude
582
// @Description: Altitude at which to use the ground steering controller on the rudder. If non-zero then the STEER2SRV controller will be used to control the rudder for altitudes within this limit of the home altitude.
583
// @Units: m
584
// @Range: -100 100
585
// @Increment: 0.1
586
// @User: Standard
587
GSCALAR(ground_steer_alt, "GROUND_STEER_ALT", 0),
588
589
// @Param: GROUND_STEER_DPS
590
// @DisplayName: Ground steer rate
591
// @Description: Ground steering rate in degrees per second for full rudder stick deflection
592
// @Units: deg/s
593
// @Range: 10 360
594
// @Increment: 1
595
// @User: Advanced
596
GSCALAR(ground_steer_dps, "GROUND_STEER_DPS", 90),
597
598
// @Param: MIXING_GAIN
599
// @DisplayName: Mixing Gain
600
// @Description: The gain for the Vtail and elevon output mixers. The default is 0.5, which ensures that the mixer doesn't saturate, allowing both input channels to go to extremes while retaining control over the output. Hardware mixers often have a 1.0 gain, which gives more servo throw, but can saturate. If you don't have enough throw on your servos with VTAIL_OUTPUT or ELEVON_OUTPUT enabled then you can raise the gain using MIXING_GAIN. The mixer allows outputs in the range 900 to 2100 microseconds.
601
// @Range: 0.5 1.2
602
// @User: Standard
603
GSCALAR(mixing_gain, "MIXING_GAIN", 0.5f),
604
605
// @Param: RUDDER_ONLY
606
// @DisplayName: Rudder only aircraft
607
// @Description: Enable rudder only mode. The rudder will control attitude in attitude controlled modes (such as FBWA). You should setup your transmitter to send roll stick inputs to the RCMAP_YAW channel (normally channel 4). The rudder servo should be attached to the RCMAP_YAW channel as well. Note that automatic ground steering will be disabled for rudder only aircraft. You should also set KFF_RDDRMIX to 1.0. You will also need to setup the YAW2SRV_DAMP yaw damping appropriately for your aircraft. A value of 0.5 for YAW2SRV_DAMP is a good starting point.
608
// @Values: 0:Disabled,1:Enabled
609
// @User: Standard
610
GSCALAR(rudder_only, "RUDDER_ONLY", 0),
611
612
// @Param: MIXING_OFFSET
613
// @DisplayName: Mixing Offset
614
// @Description: The offset for the Vtail and elevon output mixers, as a percentage. This can be used in combination with MIXING_GAIN to configure how the control surfaces respond to input. The response to aileron or elevator input can be increased by setting this parameter to a positive or negative value. A common usage is to enter a positive value to increase the aileron response of the elevons of a flying wing. The default value of zero will leave the aileron-input response equal to the elevator-input response.
615
// @Units: d%
616
// @Range: -1000 1000
617
// @User: Standard
618
GSCALAR(mixing_offset, "MIXING_OFFSET", 0),
619
620
// @Param: DSPOILR_RUD_RATE
621
// @DisplayName: Differential spoilers rudder rate
622
// @Description: Sets the amount of deflection that the rudder output will apply to the differential spoilers, as a percentage. The default value of 100 results in full rudder applying full deflection. A value of 0 will result in the differential spoilers exactly following the elevons (no rudder effect).
623
// @Units: %
624
// @Range: -100 100
625
// @User: Standard
626
GSCALAR(dspoiler_rud_rate, "DSPOILR_RUD_RATE", DSPOILR_RUD_RATE_DEFAULT),
627
628
// @Param: LOG_BITMASK
629
// @DisplayName: Log bitmask
630
// @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basic log types by setting this to 65535.
631
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:Performance,4:Control Tuning,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Compass,11:TECS,12:Camera,13:RC Input-Output,14:Rangefinder,19:Raw IMU,20:Fullrate Attitude,21:Video Stabilization,22:Fullrate Notch
632
// @User: Advanced
633
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
634
635
// @Param: SCALING_SPEED
636
// @DisplayName: speed used for speed scaling calculations
637
// @Description: Airspeed in m/s to use when calculating surface speed scaling. Note that changing this value will affect all PID values
638
// @Units: m/s
639
// @Range: 0 50
640
// @Increment: 0.1
641
// @User: Advanced
642
GSCALAR(scaling_speed, "SCALING_SPEED", SCALING_SPEED),
643
644
// @Param: MIN_GROUNDSPEED
645
// @DisplayName: Minimum ground speed
646
// @Description: Minimum ground speed when under airspeed control
647
// @Units: m/s
648
// @User: Advanced
649
ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED),
650
651
// @Param: PTCH_TRIM_DEG
652
// @DisplayName: Pitch angle offset
653
// @Description: Offset in degrees used for in-flight pitch trimming for level flight. Correct ground leveling is an alternative to changing this parameter.
654
// @Units: deg
655
// @Range: -45 45
656
// @User: Standard
657
GSCALAR(pitch_trim, "PTCH_TRIM_DEG", 0.0f),
658
659
// @Param: RTL_ALTITUDE
660
// @DisplayName: RTL altitude
661
// @Description: Target altitude above home for RTL mode. Maintains current altitude if set to -1. Rally point altitudes are used if plane does not return to home.
662
// @Units: m
663
// @User: Standard
664
GSCALAR(RTL_altitude, "RTL_ALTITUDE", ALT_HOLD_HOME),
665
666
// @Param: CRUISE_ALT_FLOOR
667
// @DisplayName: Minimum altitude for FBWB and CRUISE mode
668
// @Description: This is the minimum altitude in meters (above home) that FBWB and CRUISE modes will allow. If you attempt to descend below this altitude then the plane will level off. It will also force a climb to this altitude if below in these modes. A value of zero means no limit.
669
// @Units: m
670
// @User: Standard
671
GSCALAR(cruise_alt_floor, "CRUISE_ALT_FLOOR", CRUISE_ALT_FLOOR),
672
673
// @Param: FLAP_1_PERCNT
674
// @DisplayName: Flap 1 percentage
675
// @Description: The percentage change in flap position when FLAP_1_SPEED is reached. Use zero to disable flaps
676
// @Range: 0 100
677
// @Increment: 1
678
// @Units: %
679
// @User: Advanced
680
GSCALAR(flap_1_percent, "FLAP_1_PERCNT", FLAP_1_PERCENT),
681
682
// @Param: FLAP_1_SPEED
683
// @DisplayName: Flap 1 speed
684
// @Description: The speed in meters per second at which to engage FLAP_1_PERCENT of flaps. Note that FLAP_1_SPEED should be greater than or equal to FLAP_2_SPEED
685
// @Range: 0 100
686
// @Increment: 1
687
// @Units: m/s
688
// @User: Advanced
689
GSCALAR(flap_1_speed, "FLAP_1_SPEED", FLAP_1_SPEED),
690
691
// @Param: FLAP_2_PERCNT
692
// @DisplayName: Flap 2 percentage
693
// @Description: The percentage change in flap position when FLAP_2_SPEED is reached. Use zero to disable flaps
694
// @Range: 0 100
695
// @Units: %
696
// @Increment: 1
697
// @User: Advanced
698
GSCALAR(flap_2_percent, "FLAP_2_PERCNT", FLAP_2_PERCENT),
699
700
// @Param: FLAP_2_SPEED
701
// @DisplayName: Flap 2 speed
702
// @Description: The speed in meters per second at which to engage FLAP_2_PERCENT of flaps. Note that FLAP_1_SPEED should be greater than or equal to FLAP_2_SPEED
703
// @Range: 0 100
704
// @Units: m/s
705
// @Increment: 1
706
// @User: Advanced
707
GSCALAR(flap_2_speed, "FLAP_2_SPEED", FLAP_2_SPEED),
708
709
#if HAL_WITH_IO_MCU
710
// @Param: OVERRIDE_CHAN
711
// @DisplayName: IO override channel
712
// @Description: If set to a non-zero value then this is an RC input channel number to use for giving IO manual control in case the main FMU microcontroller on a board with a IO co-processor fails. When this RC input channel goes above 1750 the FMU microcontroller will no longer be involved in controlling the servos and instead the IO microcontroller will directly control the servos. Note that IO manual control will be automatically activated if the FMU crashes for any reason. This parameter allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is can be set to a non-zero value either for ground testing purposes or for giving the effect of an external override control board. Note that you may set OVERRIDE_CHAN to the same channel as FLTMODE_CH to get IO based override when in flight mode 6. Note that when override is triggered due to a FMU crash the 6 auxiliary output channels on the FMU will no longer be updated, so all the flight controls you need must be assigned to the first 8 channels on boards with an IOMCU.
713
// @Range: 0 16
714
// @Increment: 1
715
// @User: Advanced
716
GSCALAR(override_channel, "OVERRIDE_CHAN", 0),
717
#endif
718
719
// @Param: RTL_AUTOLAND
720
// @DisplayName: RTL auto land
721
// @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location For a value of 1 a rally point will be used instead of HOME if in range (see rally point documentation).If this is set to 0 and there is a DO_LAND_START or DO_RETURN_PATH_START mission item then you will get an arming check failure. You can set to a value of 3 to avoid the arming check failure and use the DO_LAND_START for go-around (see wiki for aborting autolandings) without it changing RTL behaviour.
722
// @Values: 0:Disable,1:Fly HOME then land via DO_LAND_START mission item, 2:Go directly to landing sequence via DO_LAND_START mission item, 3:OnlyForGoAround, 4:Go directly to landing sequence via DO_RETURN_PATH_START mission item
723
// @User: Standard
724
GSCALAR(rtl_autoland, "RTL_AUTOLAND", float(RtlAutoland::RTL_DISABLE)),
725
726
// @Param: CRASH_ACC_THRESH
727
// @DisplayName: Crash Deceleration Threshold
728
// @Description: X-Axis deceleration threshold to notify the crash detector that there was a possible impact which helps disarm the motor quickly after a crash. This value should be much higher than normal negative x-axis forces during normal flight, check flight log files to determine the average IMU.x values for your aircraft and motor type. Higher value means less sensitive (triggers on higher impact). For electric planes that don't vibrate much during fight a value of 25 is good (that's about 2.5G). For petrol/nitro planes you'll want a higher value. Set to 0 to disable the collision detector.
729
// @Units: m/s/s
730
// @Range: 10 127
731
// @Increment: 1
732
// @User: Advanced
733
GSCALAR(crash_accel_threshold, "CRASH_ACC_THRESH", 0),
734
735
// @Param: CRASH_DETECT
736
// @DisplayName: Crash Detection
737
// @Description: Automatically detect a crash during AUTO flight and perform the bitmask selected action(s). Disarm will turn off motor for safety and to help against burning out ESC and motor. Set to 0 to disable crash detection.
738
// @Bitmask: 0:Disarm
739
// @User: Advanced
740
ASCALAR(crash_detection_enable, "CRASH_DETECT", 0),
741
742
// @Group: BARO
743
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
744
GOBJECT(barometer, "BARO", AP_Baro),
745
746
// GPS driver
747
// @Group: GPS
748
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
749
GOBJECT(gps, "GPS", AP_GPS),
750
751
#if AP_CAMERA_ENABLED
752
// @Group: CAM
753
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
754
GOBJECT(camera, "CAM", AP_Camera),
755
#endif
756
757
// @Group: ARMING_
758
// @Path: AP_Arming_Plane.cpp,../libraries/AP_Arming/AP_Arming.cpp
759
GOBJECT(arming, "ARMING_", AP_Arming_Plane),
760
761
#if AP_RELAY_ENABLED
762
// @Group: RELAY
763
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
764
GOBJECT(relay, "RELAY", AP_Relay),
765
#endif
766
767
#if HAL_PARACHUTE_ENABLED
768
// @Group: CHUTE_
769
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
770
GOBJECT(parachute, "CHUTE_", AP_Parachute),
771
#endif
772
773
#if AP_RANGEFINDER_ENABLED
774
// @Group: RNGFND
775
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
776
GOBJECT(rangefinder, "RNGFND", RangeFinder),
777
778
// @Param: RNGFND_LANDING
779
// @DisplayName: Enable use of rangefinder
780
// @Description: Sets the use of a rangefinder for automatic landing and other use cases. When enabled for landing and takeoff the rangefinder will be used both on the landing approach and for final flare as well as as VTOL landing and for takeoffs and throttle suppression when close to the ground. When enabled for assist the rangefinder will be used for VTOL assistance. When enabled for climb the rangefinder will be used for the initial climb in QRTL and AUTO. Set to 0 to disable use of the rangefinder.
781
// @Bitmask: 0:All, 1:TakeoffAndLanding, 2:Assist, 3:InitialClimb
782
// @User: Standard
783
GSCALAR(rangefinder_landing, "RNGFND_LANDING", 0),
784
#endif
785
786
#if AP_TERRAIN_AVAILABLE
787
// @Group: TERRAIN_
788
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
789
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
790
#endif
791
792
#if HAL_ADSB_ENABLED
793
// @Group: ADSB_
794
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
795
GOBJECT(adsb, "ADSB_", AP_ADSB),
796
#endif // HAL_ADSB_ENABLED
797
798
#if AP_ADSB_AVOIDANCE_ENABLED
799
// @Group: AVD_
800
// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp
801
GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Plane),
802
#endif // AP_ADSB_AVOIDANCE_ENABLED
803
804
#if HAL_QUADPLANE_ENABLED
805
// @Group: Q_
806
// @Path: quadplane.cpp
807
GOBJECT(quadplane, "Q_", QuadPlane),
808
#endif
809
810
#if AP_TUNING_ENABLED
811
// @Group: TUNE_
812
// @Path: tuning.cpp,../libraries/AP_Tuning/AP_Tuning.cpp
813
GOBJECT(tuning, "TUNE_", AP_Tuning_Plane),
814
#endif
815
816
#if HAL_QUADPLANE_ENABLED
817
// @Group: Q_A_
818
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
819
{ "Q_A_", (const void *)&plane.quadplane.attitude_control,
820
{group_info : AC_AttitudeControl_Multi::var_info}, AP_PARAM_FLAG_POINTER,
821
Parameters::k_param_q_attitude_control, AP_PARAM_GROUP },
822
#endif
823
824
// @Group: RLL
825
// @Path: ../libraries/APM_Control/AP_RollController.cpp
826
GOBJECT(rollController, "RLL", AP_RollController),
827
828
// @Group: PTCH
829
// @Path: ../libraries/APM_Control/AP_PitchController.cpp
830
GOBJECT(pitchController, "PTCH", AP_PitchController),
831
832
// @Group: YAW
833
// @Path: ../libraries/APM_Control/AP_YawController.cpp
834
GOBJECT(yawController, "YAW", AP_YawController),
835
836
// @Group: STEER2SRV_
837
// @Path: ../libraries/APM_Control/AP_SteerController.cpp
838
GOBJECT(steerController, "STEER2SRV_", AP_SteerController),
839
840
// variables not in the g class which contain EEPROM saved variables
841
842
// @Group: COMPASS_
843
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
844
GOBJECT(compass, "COMPASS_", Compass),
845
846
// @Group: SCHED_
847
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
848
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
849
850
// @Group: RCMAP_
851
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
852
GOBJECT(rcmap, "RCMAP_", RCMapper),
853
854
// SR0 through SR6 were here
855
856
// @Group: INS
857
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
858
GOBJECT(ins, "INS", AP_InertialSensor),
859
860
// @Group: AHRS_
861
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
862
GOBJECT(ahrs, "AHRS_", AP_AHRS),
863
864
// Airspeed was here
865
866
// @Group: NAVL1_
867
// @Path: ../libraries/AP_L1_Control/AP_L1_Control.cpp
868
GOBJECT(L1_controller, "NAVL1_", AP_L1_Control),
869
870
// @Group: TECS_
871
// @Path: ../libraries/AP_TECS/AP_TECS.cpp
872
GOBJECT(TECS_controller, "TECS_", AP_TECS),
873
874
#if HAL_MOUNT_ENABLED
875
// @Group: MNT
876
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
877
GOBJECT(camera_mount, "MNT", AP_Mount),
878
#endif
879
880
// @Group: BATT
881
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
882
GOBJECT(battery, "BATT", AP_BattMonitor),
883
884
// @Group: BRD_
885
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
886
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
887
888
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
889
// @Group: CAN_
890
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
891
GOBJECT(can_mgr, "CAN_", AP_CANManager),
892
#endif
893
894
#if AP_SIM_ENABLED
895
// @Group: SIM_
896
// @Path: ../libraries/SITL/SITL.cpp
897
GOBJECT(sitl, "SIM_", SITL::SIM),
898
#endif
899
900
#if AP_ADVANCEDFAILSAFE_ENABLED
901
// @Group: AFS_
902
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
903
GOBJECT(afs, "AFS_", AP_AdvancedFailsafe),
904
#endif
905
906
#if AP_OPTICALFLOW_ENABLED
907
// @Group: FLOW
908
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
909
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
910
#endif
911
912
// @Group: MIS_
913
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
914
GOBJECT(mission, "MIS_", AP_Mission),
915
916
#if HAL_RALLY_ENABLED
917
// @Group: RALLY_
918
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
919
GOBJECT(rally, "RALLY_", AP_Rally),
920
#endif
921
922
#if HAL_NAVEKF2_AVAILABLE
923
// @Group: EK2_
924
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
925
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
926
#endif
927
928
#if HAL_NAVEKF3_AVAILABLE
929
// @Group: EK3_
930
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
931
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
932
#endif
933
934
#if AP_RSSI_ENABLED
935
// @Group: RSSI_
936
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
937
GOBJECT(rssi, "RSSI_", AP_RSSI),
938
#endif
939
940
// @Group: NTF_
941
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
942
GOBJECT(notify, "NTF_", AP_Notify),
943
944
// @Group:
945
// @Path: Parameters.cpp
946
GOBJECT(g2, "", ParametersG2),
947
948
// @Group: LAND_
949
// @Path: ../libraries/AP_Landing/AP_Landing.cpp
950
GOBJECT(landing, "LAND_", AP_Landing),
951
952
#if OSD_ENABLED || OSD_PARAM_ENABLED
953
// @Group: OSD
954
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
955
GOBJECT(osd, "OSD", AP_OSD),
956
#endif
957
958
// @Group: TKOFF_
959
// @Path: mode_takeoff.cpp
960
GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff),
961
962
#if MODE_AUTOLAND_ENABLED
963
// @Group: AUTOLAND_
964
// @Path: mode_autoland.cpp
965
GOBJECT(mode_autoland, "AUTOLAND_", ModeAutoLand),
966
#endif
967
968
#if AP_PLANE_GLIDER_PULLUP_ENABLED
969
// @Group: PUP_
970
// @Path: pullup.cpp
971
GOBJECTN(mode_auto.pullup, pullup, "PUP_", GliderPullup),
972
#endif
973
974
// @Group:
975
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
976
PARAM_VEHICLE_INFO,
977
978
#if AP_QUICKTUNE_ENABLED
979
// @Group: QWIK_
980
// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp
981
GOBJECT(quicktune, "QWIK_", AP_Quicktune),
982
#endif
983
984
#if HAL_GCS_ENABLED
985
// @Group: MAV
986
// @Path: ../libraries/GCS_MAVLink/GCS.cpp
987
GOBJECT(_gcs, "MAV", GCS),
988
#endif
989
990
AP_VAREND
991
};
992
993
/*
994
2nd group of parameters
995
*/
996
const AP_Param::GroupInfo ParametersG2::var_info[] = {
997
998
#if HAL_BUTTON_ENABLED
999
// @Group: BTN_
1000
// @Path: ../libraries/AP_Button/AP_Button.cpp
1001
AP_SUBGROUPPTR(button_ptr, "BTN_", 1, ParametersG2, AP_Button),
1002
#endif
1003
1004
#if AP_ICENGINE_ENABLED
1005
// @Group: ICE_
1006
// @Path: ../libraries/AP_ICEngine/AP_ICEngine.cpp
1007
AP_SUBGROUPINFO(ice_control, "ICE_", 2, ParametersG2, AP_ICEngine),
1008
#endif
1009
1010
// 3 was used by prototype for servo_channels
1011
1012
// 4 was used by SYSID_ENFORCE
1013
1014
// AP_Stats was 5
1015
1016
// @Group: SERVO
1017
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
1018
AP_SUBGROUPINFO(servo_channels, "SERVO", 6, ParametersG2, SRV_Channels),
1019
1020
// @Group: RC
1021
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
1022
AP_SUBGROUPINFO(rc_channels, "RC", 7, ParametersG2, RC_Channels_Plane),
1023
1024
#if HAL_SOARING_ENABLED
1025
// @Group: SOAR_
1026
// @Path: ../libraries/AP_Soaring/AP_Soaring.cpp
1027
AP_SUBGROUPINFO(soaring_controller, "SOAR_", 8, ParametersG2, SoaringController),
1028
#endif
1029
1030
// @Param: RUDD_DT_GAIN
1031
// @DisplayName: rudder differential thrust gain
1032
// @Description: gain control from rudder to differential thrust
1033
// @Range: 0 100
1034
// @Units: %
1035
// @Increment: 1
1036
// @User: Standard
1037
AP_GROUPINFO("RUDD_DT_GAIN", 9, ParametersG2, rudd_dt_gain, 10),
1038
1039
// @Param: MANUAL_RCMASK
1040
// @DisplayName: Manual R/C pass-through mask
1041
// @Description: Mask of R/C channels to pass directly to corresponding output channel when in MANUAL mode. When in any mode except MANUAL the channels selected with this option behave normally. This parameter is designed to allow for complex mixing strategies to be used for MANUAL flight using transmitter based mixing. Note that when this option is used you need to be very careful with pre-flight checks to ensure that the output is correct both in MANUAL and non-MANUAL modes.
1042
// @Bitmask: 0:Chan1,1:Chan2,2:Chan3,3:Chan4,4:Chan5,5:Chan6,6:Chan7,7:Chan8,8:Chan9,9:Chan10,10:Chan11,11:Chan12,12:Chan13,13:Chan14,14:Chan15,15:Chan16
1043
// @User: Advanced
1044
AP_GROUPINFO("MANUAL_RCMASK", 10, ParametersG2, manual_rc_mask, 0),
1045
1046
// @Param: HOME_RESET_ALT
1047
// @DisplayName: Home reset altitude threshold
1048
// @Description: When the aircraft is within this altitude of the home waypoint, while disarmed it will automatically update the home position. Set to 0 to continuously reset it.
1049
// @Values: -1:Never reset,0:Always reset
1050
// @Range: -1 127
1051
// @Units: m
1052
// @User: Advanced
1053
AP_GROUPINFO("HOME_RESET_ALT", 11, ParametersG2, home_reset_threshold, 0),
1054
1055
// 12 was AP_Gripper
1056
1057
// @Param: FLIGHT_OPTIONS
1058
// @DisplayName: Flight mode options
1059
// @Description: Flight mode specific options
1060
// @Bitmask: 0: Rudder mixing in direct flight modes only (Manual/Stabilize/Acro)
1061
// @Bitmask: 1: Use centered throttle in Cruise or FBWB to indicate trim airspeed
1062
// @Bitmask: 2: Disable attitude check for takeoff arming
1063
// @Bitmask: 3: Force target airspeed to trim airspeed in Cruise or FBWB
1064
// @Bitmask: 4: Climb to RTL_ALTITUDE before turning for RTL
1065
// @Bitmask: 5: Enable yaw damper in acro mode
1066
// @Bitmask: 6: Suppress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airspeed sensor.
1067
// @Bitmask: 7: EnableDefaultAirspeed for takeoff
1068
// @Bitmask: 8: Remove the PTCH_TRIM_DEG on the GCS horizon
1069
// @Bitmask: 9: Remove the PTCH_TRIM_DEG on the OSD horizon
1070
// @Bitmask: 10: Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL
1071
// @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode
1072
// @Bitmask: 12: Enable FBWB style loiter altitude control
1073
// @Bitmask: 13: Indicate takeoff waiting for neutral rudder with flight control surfaces
1074
// @Bitmask: 14: In AUTO - climb to next waypoint altitude immediately instead of linear climb
1075
// @Bitmask: 15: Enable autoflap in manual modes and use minimum of target and actual speed for flap setting
1076
// @Bitmask: 16: Enable full aerodynamic load factor-based roll limits when an airspeed sensor is enabled and AIRSPEED_STALL is set
1077
// @User: Advanced
1078
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
1079
1080
// 14 was AP_Scripting
1081
1082
// @Param: TKOFF_ACCEL_CNT
1083
// @DisplayName: Takeoff throttle acceleration count
1084
// @Description: This is the number of acceleration events to require for arming with TKOFF_THR_MINACC. The default is 1, which means a single forward acceleration above TKOFF_THR_MINACC will arm. By setting this higher than 1 you can require more forward/backward movements to arm.
1085
// @Range: 1 10
1086
// @User: Standard
1087
AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1),
1088
1089
#if AP_LANDINGGEAR_ENABLED
1090
// @Group: LGR_
1091
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
1092
AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),
1093
#endif
1094
1095
// @Param: DSPOILER_CROW_W1
1096
// @DisplayName: Differential spoiler crow flaps outer weight
1097
// @Description: This is amount of deflection applied to the two outer surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 25.
1098
// @Range: 0 100
1099
// @Units: %
1100
// @Increment: 1
1101
// @User: Advanced
1102
AP_GROUPINFO("DSPOILER_CROW_W1", 17, ParametersG2, crow_flap_weight_outer, 0),
1103
1104
// @Param: DSPOILER_CROW_W2
1105
// @DisplayName: Differential spoiler crow flaps inner weight
1106
// @Description: This is amount of deflection applied to the two inner surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 45.
1107
// @Range: 0 100
1108
// @Units: %
1109
// @Increment: 1
1110
// @User: Advanced
1111
AP_GROUPINFO("DSPOILER_CROW_W2", 18, ParametersG2, crow_flap_weight_inner, 0),
1112
1113
// @Param: TKOFF_TIMEOUT
1114
// @DisplayName: Takeoff timeout
1115
// @Description: This is the timeout for an automatic takeoff. If this is non-zero and the aircraft does not reach a ground speed of at least 4 m/s within this number of seconds then the takeoff is aborted and the vehicle disarmed. If the value is zero then no timeout applies.
1116
// @Range: 0 120
1117
// @Increment: 1
1118
// @Units: s
1119
// @User: Standard
1120
AP_GROUPINFO("TKOFF_TIMEOUT", 19, ParametersG2, takeoff_timeout, 0),
1121
1122
// @Param: DSPOILER_OPTS
1123
// @DisplayName: Differential spoiler and crow flaps options
1124
// @Description: Differential spoiler and crow flaps options. Progressive crow flaps only first (0-50% flap in) then crow flaps (50 - 100% flap in).
1125
// @Bitmask: 0:Pitch input, 1:use both control surfaces on each wing for roll, 2:Progressive crow flaps
1126
// @User: Advanced
1127
AP_GROUPINFO("DSPOILER_OPTS", 20, ParametersG2, crow_flap_options, 3),
1128
1129
// @Param: DSPOILER_AILMTCH
1130
// @DisplayName: Differential spoiler aileron matching
1131
// @Description: This scales down the inner flaps so less than full downwards range can be used for differential spoiler and full span ailerons, 100 is use full range, upwards travel is unaffected
1132
// @Range: 0 100
1133
// @Units: %
1134
// @Increment: 1
1135
// @User: Advanced
1136
AP_GROUPINFO("DSPOILER_AILMTCH", 21, ParametersG2, crow_flap_aileron_matching, 100),
1137
1138
1139
// 22 was EFI
1140
1141
// @Param: FWD_BAT_VOLT_MAX
1142
// @DisplayName: Forward throttle battery voltage compensation maximum voltage
1143
// @Description: Forward throttle battery voltage compensation maximum voltage (voltage above this will have no additional scaling effect on thrust). Recommend 4.2 * cell count, 0 = Disabled. Recommend THR_MAX is set to no more than 100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX, THR_MIN is set to no less than -100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX and climb descent rate limits are set accordingly.
1144
// @Range: 6 35
1145
// @Units: V
1146
// @Increment: 0.1
1147
// @User: Advanced
1148
AP_GROUPINFO("FWD_BAT_VOLT_MAX", 23, ParametersG2, fwd_batt_cmp.batt_voltage_max, 0.0f),
1149
1150
// @Param: FWD_BAT_VOLT_MIN
1151
// @DisplayName: Forward throttle battery voltage compensation minimum voltage
1152
// @Description: Forward throttle battery voltage compensation minimum voltage (voltage below this will have no additional scaling effect on thrust). Recommend 3.5 * cell count, 0 = Disabled. Recommend THR_MAX is set to no more than 100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX, THR_MIN is set to no less than -100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX and climb descent rate limits are set accordingly.
1153
// @Range: 6 35
1154
// @Units: V
1155
// @Increment: 0.1
1156
// @User: Advanced
1157
AP_GROUPINFO("FWD_BAT_VOLT_MIN", 24, ParametersG2, fwd_batt_cmp.batt_voltage_min, 0.0f),
1158
1159
// @Param: FWD_BAT_IDX
1160
// @DisplayName: Forward throttle battery compensation index
1161
// @Description: Which battery monitor should be used for doing compensation for the forward throttle
1162
// @Values: 0:First battery, 1:Second battery
1163
// @Range: 0 15
1164
// @User: Advanced
1165
AP_GROUPINFO("FWD_BAT_IDX", 25, ParametersG2, fwd_batt_cmp.batt_idx, 0),
1166
1167
// @Param: FS_EKF_THRESH
1168
// @DisplayName: EKF failsafe variance threshold
1169
// @Description: Allows setting the maximum acceptable compass and velocity variance used to check navigation health in VTOL modes
1170
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
1171
// @Range: 0.6 1.0
1172
// @User: Advanced
1173
AP_GROUPINFO("FS_EKF_THRESH", 26, ParametersG2, fs_ekf_thresh, FS_EKF_THRESHOLD_DEFAULT),
1174
1175
// @Param: RTL_CLIMB_MIN
1176
// @DisplayName: RTL minimum climb
1177
// @Description: The vehicle will climb this many m during the initial climb portion of the RTL. During this time the roll will be limited to LEVEL_ROLL_LIMIT degrees.
1178
// @Units: m
1179
// @Range: 0 30
1180
// @Increment: 1
1181
// @User: Standard
1182
AP_GROUPINFO("RTL_CLIMB_MIN", 27, ParametersG2, rtl_climb_min, 0),
1183
1184
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
1185
// @Group: GUIDED_
1186
// @Path: ../libraries/AC_PID/AC_PID.cpp
1187
AP_SUBGROUPINFO(guidedHeading, "GUIDED_", 28, ParametersG2, AC_PID),
1188
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
1189
1190
// @Param: MAN_EXPO_ROLL
1191
// @DisplayName: Manual control expo for roll
1192
// @Description: Percentage exponential for roll input in MANUAL, ACRO and TRAINING modes
1193
// @Range: 0 100
1194
// @Increment: 1
1195
// @User: Standard
1196
AP_GROUPINFO("MAN_EXPO_ROLL", 29, ParametersG2, man_expo_roll, 0),
1197
1198
// @Param: MAN_EXPO_PITCH
1199
// @DisplayName: Manual input expo for pitch
1200
// @Description: Percentage exponential for pitch input in MANUAL, ACRO and TRAINING modes
1201
// @Range: 0 100
1202
// @Increment: 1
1203
// @User: Standard
1204
AP_GROUPINFO("MAN_EXPO_PITCH", 30, ParametersG2, man_expo_pitch, 0),
1205
1206
// @Param: MAN_EXPO_RUDDER
1207
// @DisplayName: Manual input expo for rudder
1208
// @Description: Percentage exponential for rudder input in MANUAL, ACRO and TRAINING modes
1209
// @Range: 0 100
1210
// @Increment: 1
1211
// @User: Standard
1212
AP_GROUPINFO("MAN_EXPO_RUDDER", 31, ParametersG2, man_expo_rudder, 0),
1213
1214
// @Param: ONESHOT_MASK
1215
// @DisplayName: Oneshot output mask
1216
// @Description: Mask of output channels to use oneshot on
1217
// @User: Advanced
1218
// @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15, 15: Servo 16, 16: Servo 17, 17: Servo 18, 18: Servo 19, 19: Servo 20, 20: Servo 21, 21: Servo 22, 22: Servo 23, 23: Servo 24, 24: Servo 25, 25: Servo 26, 26: Servo 27, 27: Servo 28, 28: Servo 29, 29: Servo 30, 30: Servo 31, 31: Servo 32
1219
AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0),
1220
1221
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
1222
// @Group: FOLL
1223
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
1224
AP_SUBGROUPINFO(follow, "FOLL", 33, ParametersG2, AP_Follow),
1225
#endif
1226
1227
// @Param: AUTOTUNE_AXES
1228
// @DisplayName: Autotune axis bitmask
1229
// @Description: 1-byte bitmap of axes to autotune
1230
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
1231
// @User: Standard
1232
AP_GROUPINFO("AUTOTUNE_AXES", 34, ParametersG2, axis_bitmask, 7),
1233
1234
#if AC_PRECLAND_ENABLED
1235
// @Group: PLND_
1236
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
1237
AP_SUBGROUPINFO(precland, "PLND_", 35, ParametersG2, AC_PrecLand),
1238
#endif
1239
1240
#if AP_RANGEFINDER_ENABLED
1241
// @Param: RNGFND_LND_ORNT
1242
// @DisplayName: rangefinder landing orientation
1243
// @Description: The orientation of rangefinder to use for landing detection. Should be set to Down for normal downward facing rangefinder and Back for rearward facing rangefinder for quadplane tailsitters. Custom orientation can be used with Custom1 or Custom2. The orientation must match at least one of the available rangefinders.
1244
// @Values: 4:Back, 25:Down, 101:Custom1, 102:Custom2
1245
// @User: Standard
1246
AP_GROUPINFO("RNGFND_LND_ORNT", 36, ParametersG2, rangefinder_land_orient, ROTATION_PITCH_270),
1247
#endif
1248
1249
// @Param: FWD_BAT_THR_CUT
1250
// @DisplayName: Forward throttle cutoff battery voltage
1251
// @Description: The estimated battery resting voltage below which the throttle is cut in auto-throttle modes. Measured on the battery used for forward throttle compensation (FWD_BAT_IDX). If set to zero, the throttle will not be cut due to low voltage, allowing the motor(s) to continue running until the battery is depleted. This should be set to the minimum operating voltage of you motor(s) or to a voltage level where minimal thrust is produced, to conserve the remaining battery power for the electronics and actuators.
1252
// @Range: 0 35
1253
// @Units: V
1254
// @Increment: 0.1
1255
// @User: Standard
1256
AP_GROUPINFO("FWD_BAT_THR_CUT", 37, ParametersG2, fwd_batt_cmp.batt_voltage_throttle_cutoff, 0.0f),
1257
1258
#if AP_PLANE_SYSTEMID_ENABLED
1259
// @Group: SID
1260
// @Path: systemid.cpp
1261
AP_SUBGROUPINFO(systemid, "SID", 38, ParametersG2, AP_SystemID),
1262
#endif
1263
1264
// @Param: CLIMB_SLOPE_HGT
1265
// @DisplayName: Climb slope minimum height
1266
// @Description: Sets the minimum height above home at which the aircraft will apply a climb slope between waypoints. Below it, the aircraft will ascend immediately, and will only resume the requested trajectory upon reaching this height. This prevents unsafe behavior such as attempting to slowly gain altitude near obstacles. The default value ensures safe operations in most environments, but it can be adjusted based on specific terrain or operational needs.
1267
// @Units: m
1268
// @Range: 0 50
1269
// @Increment: 1
1270
// @User: Advanced
1271
AP_GROUPINFO("CLIMB_SLOPE_HGT", 39, ParametersG2, waypoint_climb_slope_height_min, 25),
1272
1273
// @Param: GUIDED_TIMEOUT
1274
// @DisplayName: Timeout for external guided command.
1275
// @Description: If external guided command was not received by this timeout, the vehicle will revert to regular GUIDED mode.
1276
// @Units: s
1277
// @Range: 0 10
1278
// @Increment: 0.5
1279
// @User: Advanced
1280
AP_GROUPINFO("GUIDED_TIMEOUT", 40, ParametersG2, guided_timeout, 3.0f),
1281
1282
AP_GROUPEND
1283
};
1284
1285
ParametersG2::ParametersG2(void) :
1286
unused_integer{1}
1287
#if HAL_BUTTON_ENABLED
1288
,button_ptr(&plane.button)
1289
#endif
1290
#if HAL_SOARING_ENABLED
1291
,soaring_controller(plane.TECS_controller, plane.aparm)
1292
#endif
1293
{
1294
AP_Param::setup_object_defaults(this, var_info);
1295
}
1296
1297
/*
1298
This is a conversion table from old parameter values to new
1299
parameter names. The startup code looks for saved values of the old
1300
parameters and will copy them across to the new parameters if the
1301
new parameter does not yet have a saved value. It then saves the new
1302
value.
1303
1304
Note that this works even if the old parameter has been removed. It
1305
relies on the old k_param index not being removed
1306
1307
The second column below is the index in the var_info[] table for the
1308
old object. This should be zero for top level parameters.
1309
*/
1310
static const AP_Param::ConversionInfo conversion_table[] = {
1311
{ Parameters::k_param_fence_minalt, 0, AP_PARAM_INT16, "FENCE_ALT_MIN"},
1312
{ Parameters::k_param_fence_maxalt, 0, AP_PARAM_INT16, "FENCE_ALT_MAX"},
1313
{ Parameters::k_param_fence_retalt, 0, AP_PARAM_INT16, "FENCE_RET_ALT"},
1314
{ Parameters::k_param_fence_ret_rally, 0, AP_PARAM_INT8, "FENCE_RET_RALLY"},
1315
{ Parameters::k_param_fence_autoenable, 0, AP_PARAM_INT8, "FENCE_AUTOENABLE"},
1316
};
1317
1318
struct RCConversionInfo {
1319
uint16_t old_key; // k_param_*
1320
uint32_t old_group_element; // index in old object
1321
RC_Channel::AUX_FUNC fun; // new function
1322
};
1323
1324
static const RCConversionInfo rc_option_conversion[] = {
1325
{ Parameters::k_param_flapin_channel_old, 0, RC_Channel::AUX_FUNC::FLAP},
1326
{ Parameters::k_param_g2, 968, RC_Channel::AUX_FUNC::SOARING},
1327
#if AP_FENCE_ENABLED
1328
{ Parameters::k_param_fence_channel, 0, RC_Channel::AUX_FUNC::FENCE},
1329
#endif
1330
#if AP_MISSION_ENABLED
1331
{ Parameters::k_param_reset_mission_chan, 0, RC_Channel::AUX_FUNC::MISSION_RESET},
1332
#endif
1333
#if HAL_PARACHUTE_ENABLED
1334
{ Parameters::k_param_parachute_channel, 0, RC_Channel::AUX_FUNC::PARACHUTE_RELEASE},
1335
#endif
1336
{ Parameters::k_param_fbwa_tdrag_chan, 0, RC_Channel::AUX_FUNC::FBWA_TAILDRAGGER},
1337
{ Parameters::k_param_reset_switch_chan, 0, RC_Channel::AUX_FUNC::MODE_SWITCH_RESET},
1338
};
1339
1340
void Plane::load_parameters(void)
1341
{
1342
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
1343
1344
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
1345
1346
// setup defaults in SRV_Channels
1347
g2.servo_channels.set_default_function(CH_1, SRV_Channel::k_aileron);
1348
g2.servo_channels.set_default_function(CH_2, SRV_Channel::k_elevator);
1349
g2.servo_channels.set_default_function(CH_3, SRV_Channel::k_throttle);
1350
g2.servo_channels.set_default_function(CH_4, SRV_Channel::k_rudder);
1351
1352
SRV_Channels::upgrade_parameters();
1353
1354
#if HAL_QUADPLANE_ENABLED
1355
if (quadplane.enable) {
1356
// quadplanes needs a higher loop rate
1357
AP_Param::set_default_by_name("SCHED_LOOP_RATE", 300);
1358
}
1359
#endif
1360
1361
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_PLANE);
1362
1363
// Convert chan params to RCx_OPTION
1364
for (uint8_t i=0; i<ARRAY_SIZE(rc_option_conversion); i++) {
1365
AP_Int8 chan_param;
1366
AP_Param::ConversionInfo info {rc_option_conversion[i].old_key, rc_option_conversion[i].old_group_element, AP_PARAM_INT8, nullptr};
1367
if (AP_Param::find_old_parameter(&info, &chan_param) && chan_param.get() > 0) {
1368
RC_Channel *chan = rc().channel(chan_param.get() - 1);
1369
if (chan != nullptr && !chan->option.configured()) {
1370
chan->option.set_and_save((int16_t)rc_option_conversion[i].fun); // save the new param
1371
}
1372
}
1373
}
1374
1375
1376
// PARAMETER_CONVERSION - Added: March 2021 for ArduPlane-4.1
1377
#if AP_FENCE_ENABLED
1378
enum ap_var_type ptype_fence_type;
1379
AP_Int8 *fence_type_new = (AP_Int8*)AP_Param::find("FENCE_TYPE", &ptype_fence_type);
1380
if (fence_type_new && !fence_type_new->configured()) {
1381
// If we find the new parameter and it hasn't been configured
1382
// attempt to upgrade the altitude fences.
1383
int8_t fence_type_new_val = AC_FENCE_TYPE_POLYGON;
1384
AP_Int16 fence_alt_min_old;
1385
AP_Param::ConversionInfo fence_alt_min_info_old = {
1386
Parameters::k_param_fence_minalt,
1387
0,
1388
AP_PARAM_INT16,
1389
nullptr
1390
};
1391
if (AP_Param::find_old_parameter(&fence_alt_min_info_old, &fence_alt_min_old)) {
1392
if (fence_alt_min_old.configured()) {
1393
//
1394
fence_type_new_val |= AC_FENCE_TYPE_ALT_MIN;
1395
}
1396
}
1397
1398
AP_Int16 fence_alt_max_old;
1399
AP_Param::ConversionInfo fence_alt_max_info_old = {
1400
Parameters::k_param_fence_maxalt,
1401
0,
1402
AP_PARAM_INT16,
1403
nullptr
1404
};
1405
if (AP_Param::find_old_parameter(&fence_alt_max_info_old, &fence_alt_max_old)) {
1406
if (fence_alt_max_old.configured()) {
1407
fence_type_new_val |= AC_FENCE_TYPE_ALT_MAX;
1408
}
1409
}
1410
1411
fence_type_new->set_and_save((int8_t)fence_type_new_val);
1412
}
1413
1414
AP_Int8 fence_action_old;
1415
AP_Param::ConversionInfo fence_action_info_old = {
1416
Parameters::k_param_fence_action,
1417
0,
1418
AP_PARAM_INT8,
1419
"FENCE_ACTION"
1420
};
1421
if (AP_Param::find_old_parameter(&fence_action_info_old, &fence_action_old)) {
1422
enum ap_var_type ptype;
1423
AP_Int8 *fence_action_new = (AP_Int8*)AP_Param::find(&fence_action_info_old.new_name[0], &ptype);
1424
AC_Fence::Action fence_action_new_val;
1425
if (fence_action_new && !fence_action_new->configured()) {
1426
switch(fence_action_old.get()) {
1427
case 0: // FENCE_ACTION_NONE
1428
case 2: // FENCE_ACTION_REPORT_ONLY
1429
default:
1430
fence_action_new_val = AC_Fence::Action::REPORT_ONLY;
1431
break;
1432
case 1: // FENCE_ACTION_GUIDED
1433
fence_action_new_val = AC_Fence::Action::GUIDED;
1434
break;
1435
case 3: // FENCE_ACTION_GUIDED_THR_PASS
1436
fence_action_new_val = AC_Fence::Action::GUIDED_THROTTLE_PASS;
1437
break;
1438
case 4: // FENCE_ACTION_RTL
1439
fence_action_new_val = AC_Fence::Action::RTL_AND_LAND;
1440
break;
1441
}
1442
fence_action_new->set_and_save((int8_t)fence_action_new_val);
1443
1444
// Now upgrade the new fence enable at the same time
1445
enum ap_var_type ptype_fence_enable;
1446
AP_Int8 *fence_enable = (AP_Int8*)AP_Param::find("FENCE_ENABLE", &ptype_fence_enable);
1447
// fences were used if there was a count, and the old fence action was not zero
1448
AC_Fence *ap_fence = AP::fence();
1449
bool fences_exist = false;
1450
if (ap_fence) {
1451
// If the fence library is present, attempt to read the fence count
1452
fences_exist = ap_fence->polyfence().total_fence_count() > 0;
1453
}
1454
1455
bool fences_used = fence_action_old.get() != 0;
1456
if (fence_enable && !fence_enable->configured()) {
1457
// The fence enable parameter exists, so now set it accordingly
1458
fence_enable->set_and_save(fences_exist && fences_used);
1459
}
1460
}
1461
}
1462
#endif // AP_FENCE_ENABLED
1463
1464
#if AP_TERRAIN_AVAILABLE
1465
g.terrain_follow.convert_parameter_width(AP_PARAM_INT8);
1466
#endif
1467
1468
g.use_reverse_thrust.convert_parameter_width(AP_PARAM_INT16);
1469
1470
#if AP_AIRSPEED_ENABLED
1471
// PARAMETER_CONVERSION - Added: Jan-2022
1472
{
1473
const uint16_t old_key = g.k_param_airspeed;
1474
const uint16_t old_index = 0; // Old parameter index in the tree
1475
AP_Param::convert_class(old_key, &airspeed, airspeed.var_info, old_index, true);
1476
}
1477
#endif
1478
1479
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
1480
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
1481
if (!ins.harmonic_notches[1].params.enabled()) {
1482
// notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch
1483
const AP_Param::ConversionInfo notchfilt_conversion_info[] {
1484
{ Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" },
1485
{ Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" },
1486
{ Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" },
1487
{ Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" },
1488
};
1489
AP_Param::convert_old_parameters(&notchfilt_conversion_info[0], ARRAY_SIZE(notchfilt_conversion_info));
1490
AP_Param::set_default_by_name("INS_HNTC2_MODE", 0);
1491
AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);
1492
}
1493
#endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS
1494
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
1495
1496
// PARAMETER_CONVERSION - Added: Mar-2022
1497
#if AP_FENCE_ENABLED
1498
AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, true);
1499
#endif
1500
1501
// PARAMETER_CONVERSION - Added: July-2025 for ArduPilot-4.7
1502
#if AP_RPM_ENABLED
1503
AP_Param::convert_class(g.k_param_rpm_sensor_old, &rpm_sensor, rpm_sensor.var_info, 0, true, true);
1504
#endif
1505
1506
// PARAMETER_CONVERSION - Added: Dec 2023
1507
// Convert _CM (centimeter) parameters to meters and _CD (centidegrees) parameters to meters
1508
g.pitch_trim.convert_centi_parameter(AP_PARAM_INT16);
1509
aparm.airspeed_cruise.convert_centi_parameter(AP_PARAM_INT32);
1510
aparm.min_groundspeed.convert_centi_parameter(AP_PARAM_INT32);
1511
g.RTL_altitude.convert_centi_parameter(AP_PARAM_INT32);
1512
g.cruise_alt_floor.convert_centi_parameter(AP_PARAM_INT16);
1513
aparm.pitch_limit_max.convert_centi_parameter(AP_PARAM_INT16);
1514
aparm.pitch_limit_min.convert_centi_parameter(AP_PARAM_INT16);
1515
aparm.roll_limit.convert_centi_parameter(AP_PARAM_INT16);
1516
1517
landing.convert_parameters();
1518
1519
static const AP_Param::G2ObjectConversion g2_conversions[] {
1520
// PARAMETER_CONVERSION - Added: Oct-2021
1521
#if HAL_EFI_ENABLED
1522
{ &efi, efi.var_info, 22 },
1523
#endif
1524
#if AP_STATS_ENABLED
1525
// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6
1526
{ &stats, stats.var_info, 5 },
1527
#endif
1528
#if AP_SCRIPTING_ENABLED
1529
// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6
1530
{ &scripting, scripting.var_info, 14 },
1531
#endif
1532
#if AP_GRIPPER_ENABLED
1533
// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6
1534
{ &gripper, gripper.var_info, 12 },
1535
#endif
1536
};
1537
1538
AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));
1539
1540
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
1541
#if HAL_LOGGING_ENABLED
1542
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
1543
#endif
1544
1545
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
1546
#if AP_SERIALMANAGER_ENABLED
1547
// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6
1548
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
1549
#endif
1550
};
1551
1552
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
1553
1554
#if HAL_GCS_ENABLED
1555
// Move parameters into new MAV_ parameter namespace
1556
// PARAMETER_CONVERSION - Added: Mar-2025 for ArduPilot-4.7
1557
{
1558
static const AP_Param::ConversionInfo gcs_conversion_info[] {
1559
{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },
1560
{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },
1561
{ Parameters::k_param_g2, 4, AP_PARAM_INT8, "MAV_OPTIONS" },
1562
{ Parameters::k_param_telem_delay_old, 0, AP_PARAM_INT8, "MAV_TELEM_DELAY" },
1563
};
1564
AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));
1565
}
1566
#endif // HAL_GCS_ENABLED
1567
}
1568
1569