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/ArduPlane/Parameters.cpp
Views: 1798
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
// @Param: SYSID_THISMAV
18
// @DisplayName: MAVLink system ID of this vehicle
19
// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
20
// @Range: 1 255
21
// @User: Advanced
22
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
23
24
// @Param: SYSID_MYGCS
25
// @DisplayName: Ground station MAVLink system ID
26
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
27
// @Range: 1 255
28
// @Increment: 1
29
// @User: Advanced
30
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
31
32
// AP_SerialManager was here
33
34
// @Param: AUTOTUNE_LEVEL
35
// @DisplayName: Autotune level
36
// @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
37
// @Range: 0 10
38
// @Increment: 1
39
// @User: Standard
40
ASCALAR(autotune_level, "AUTOTUNE_LEVEL", 6),
41
42
// @Param: AUTOTUNE_OPTIONS
43
// @DisplayName: Autotune options bitmask
44
// @Description: Fixed Wing Autotune specific options. Useful on QuadPlanes with higher INS_GYRO_FILTER settings to prevent these filter values from being set too agressively during Fixed Wing Autotune.
45
// @Bitmask: 0: Disable FLTD update by Autotune
46
// @Bitmask: 1: Disable FLTT update by Autotune
47
// @User: Advanced
48
ASCALAR(autotune_options, "AUTOTUNE_OPTIONS", 0),
49
50
// @Param: TELEM_DELAY
51
// @DisplayName: Telemetry startup delay
52
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
53
// @User: Standard
54
// @Units: s
55
// @Range: 0 30
56
// @Increment: 1
57
GSCALAR(telem_delay, "TELEM_DELAY", 0),
58
59
// @Param: GCS_PID_MASK
60
// @DisplayName: GCS PID tuning mask
61
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
62
// @User: Advanced
63
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ
64
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
65
66
// @Param: KFF_RDDRMIX
67
// @DisplayName: Rudder Mix
68
// @Description: Amount of rudder to add during aileron movement. Increase if nose initially yaws away from roll. Reduces adverse yaw.
69
// @Range: 0 1
70
// @Increment: 0.01
71
// @User: Standard
72
GSCALAR(kff_rudder_mix, "KFF_RDDRMIX", RUDDER_MIX),
73
74
// @Param: KFF_THR2PTCH
75
// @DisplayName: Throttle to Pitch Mix
76
// @Description: Pitch up to add in proportion to throttle. 100% throttle will add this number of degrees to the pitch target.
77
// @Range: -5 5
78
// @Increment: 0.01
79
// @User: Advanced
80
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", 0),
81
82
// @Param: STAB_PITCH_DOWN
83
// @DisplayName: Low throttle pitch down trim
84
// @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.
85
// @Range: 0 15
86
// @Increment: 0.1
87
// @Units: deg
88
// @User: Advanced
89
GSCALAR(stab_pitch_down, "STAB_PITCH_DOWN", 2.0f),
90
91
// @Param: GLIDE_SLOPE_MIN
92
// @DisplayName: Glide slope minimum
93
// @Description: This controls the minimum altitude change for a waypoint before a glide 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 glide slopes to be used in missions then you can set this to zero, which will disable glide slope calculations. Otherwise you can set it to a minimum number of meters of altitude error to the destination waypoint before a glide slope will be used to change altitude.
94
// @Range: 0 1000
95
// @Increment: 1
96
// @Units: m
97
// @User: Advanced
98
GSCALAR(glide_slope_min, "GLIDE_SLOPE_MIN", 15),
99
100
// @Param: GLIDE_SLOPE_THR
101
// @DisplayName: Glide slope threshold
102
// @Description: This controls the height above the glide slope the plane may be before rebuilding a glide slope. This is useful for smoothing out an autotakeoff
103
// @Range: 0 100
104
// @Increment: 1
105
// @Units: m
106
// @User: Advanced
107
GSCALAR(glide_slope_threshold, "GLIDE_SLOPE_THR", 5.0),
108
109
// @Param: STICK_MIXING
110
// @DisplayName: Stick Mixing
111
// @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 two types of stick mixing available. If you set STICK_MIXING to 1 then it will use "fly by wire" mixing, which controls the roll and pitch in the same way that the FBWA mode does. This is the safest option if you usually fly ArduPlane in FBWA or FBWB mode. 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.
112
// @Values: 0:Disabled,1:FBWMixing,3:VTOL Yaw only
113
// @User: Advanced
114
GSCALAR(stick_mixing, "STICK_MIXING", uint8_t(StickMixing::FBW)),
115
116
// @Param: TKOFF_THR_MINSPD
117
// @DisplayName: Takeoff throttle min speed
118
// @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.
119
// @Units: m/s
120
// @Range: 0 30
121
// @Increment: 0.1
122
// @User: Standard
123
GSCALAR(takeoff_throttle_min_speed, "TKOFF_THR_MINSPD", 0),
124
125
// @Param: TKOFF_THR_MINACC
126
// @DisplayName: Takeoff throttle min acceleration
127
// @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 paramter for control of full "shake to arm".
128
// @Units: m/s/s
129
// @Range: 0 30
130
// @Increment: 0.1
131
// @User: Standard
132
GSCALAR(takeoff_throttle_min_accel, "TKOFF_THR_MINACC", 0),
133
134
// @Param: TKOFF_THR_DELAY
135
// @DisplayName: Takeoff throttle delay
136
// @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.
137
// @Units: ds
138
// @Range: 0 127
139
// @Increment: 1
140
// @User: Standard
141
GSCALAR(takeoff_throttle_delay, "TKOFF_THR_DELAY", 2),
142
143
// @Param: TKOFF_THR_MAX_T
144
// @DisplayName: Takeoff throttle maximum time
145
// @Description: This sets the time that maximum throttle will be forced during a fixed wing takeoff.
146
// @Units: s
147
// @Range: 0 10
148
// @Increment: 0.5
149
// @User: Standard
150
ASCALAR(takeoff_throttle_max_t, "TKOFF_THR_MAX_T", 4),
151
152
// @Param: TKOFF_THR_MIN
153
// @DisplayName: Takeoff minimum throttle
154
// @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.
155
// @Units: %
156
// @Range: 0 100
157
// @Increment: 1
158
// @User: Standard
159
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),
160
161
// @Param: TKOFF_THR_IDLE
162
// @DisplayName: Takeoff idle throttle
163
// @Description: The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes.
164
// @Units: %
165
// @Range: 0 100
166
// @Increment: 1
167
// @User: Standard
168
ASCALAR(takeoff_throttle_idle, "TKOFF_THR_IDLE", 0),
169
170
// @Param: TKOFF_OPTIONS
171
// @DisplayName: Takeoff options
172
// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.
173
// @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.
174
// @User: Advanced
175
ASCALAR(takeoff_options, "TKOFF_OPTIONS", 0),
176
177
// @Param: TKOFF_TDRAG_ELEV
178
// @DisplayName: Takeoff tail dragger elevator
179
// @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.
180
// @Units: %
181
// @Range: -100 100
182
// @Increment: 1
183
// @User: Standard
184
GSCALAR(takeoff_tdrag_elevator, "TKOFF_TDRAG_ELEV", 0),
185
186
// @Param: TKOFF_TDRAG_SPD1
187
// @DisplayName: Takeoff tail dragger speed1
188
// @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.
189
// @Units: m/s
190
// @Range: 0 30
191
// @Increment: 0.1
192
// @User: Standard
193
GSCALAR(takeoff_tdrag_speed1, "TKOFF_TDRAG_SPD1", 0),
194
195
// @Param: TKOFF_ROTATE_SPD
196
// @DisplayName: Takeoff rotate speed
197
// @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.
198
// @Units: m/s
199
// @Range: 0 30
200
// @Increment: 0.1
201
// @User: Standard
202
GSCALAR(takeoff_rotate_speed, "TKOFF_ROTATE_SPD", 0),
203
204
// @Param: TKOFF_THR_SLEW
205
// @DisplayName: Takeoff throttle slew rate
206
// @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.
207
// @Units: %/s
208
// @Range: -1 127
209
// @Increment: 1
210
// @User: Standard
211
GSCALAR(takeoff_throttle_slewrate, "TKOFF_THR_SLEW", 0),
212
213
// @Param: TKOFF_PLIM_SEC
214
// @DisplayName: Takeoff pitch limit reduction
215
// @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.
216
// @Units: s
217
// @Range: 0 10
218
// @Increment: 0.5
219
// @User: Advanced
220
GSCALAR(takeoff_pitch_limit_reduction_sec, "TKOFF_PLIM_SEC", 2),
221
222
// @Param: TKOFF_FLAP_PCNT
223
// @DisplayName: Takeoff flap percentage
224
// @Description: The amount of flaps (as a percentage) to apply in automatic takeoff
225
// @Range: 0 100
226
// @Units: %
227
// @Increment: 1
228
// @User: Advanced
229
GSCALAR(takeoff_flap_percent, "TKOFF_FLAP_PCNT", 0),
230
231
// @Param: LEVEL_ROLL_LIMIT
232
// @DisplayName: Level flight roll limit
233
// @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.
234
// @Units: deg
235
// @Range: 0 45
236
// @Increment: 1
237
// @User: Standard
238
GSCALAR(level_roll_limit, "LEVEL_ROLL_LIMIT", 5),
239
240
// @Param: USE_REV_THRUST
241
// @DisplayName: Bitmask for when to allow negative reverse thrust
242
// @Description: This controls when to use reverse thrust. If set to zero then reverse thrust is never used. 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.
243
// @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
244
// @User: Advanced
245
GSCALAR(use_reverse_thrust, "USE_REV_THRUST", USE_REVERSE_THRUST_AUTO_LAND_APPROACH),
246
247
// @Param: ALT_OFFSET
248
// @DisplayName: Altitude offset
249
// @Description: This is added to the target altitude in automatic flight. It can be used to add a global altitude offset to a mission
250
// @Units: m
251
// @Range: -32767 32767
252
// @Increment: 1
253
// @User: Advanced
254
GSCALAR(alt_offset, "ALT_OFFSET", 0),
255
256
// @Param: WP_RADIUS
257
// @DisplayName: Waypoint Radius
258
// @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.
259
// @Units: m
260
// @Range: 1 32767
261
// @Increment: 1
262
// @User: Standard
263
GSCALAR(waypoint_radius, "WP_RADIUS", WP_RADIUS_DEFAULT),
264
265
// @Param: WP_MAX_RADIUS
266
// @DisplayName: Waypoint Maximum Radius
267
// @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.
268
// @Units: m
269
// @Range: 0 32767
270
// @Increment: 1
271
// @User: Standard
272
GSCALAR(waypoint_max_radius, "WP_MAX_RADIUS", 0),
273
274
// @Param: WP_LOITER_RAD
275
// @DisplayName: Waypoint Loiter Radius
276
// @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.
277
// @Units: m
278
// @Range: -32767 32767
279
// @Increment: 1
280
// @User: Standard
281
ASCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),
282
283
// @Param: RTL_RADIUS
284
// @DisplayName: RTL loiter radius
285
// @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.
286
// @Units: m
287
// @Range: -32767 32767
288
// @Increment: 1
289
// @User: Standard
290
GSCALAR(rtl_radius, "RTL_RADIUS", 0),
291
292
// @Param: STALL_PREVENTION
293
// @DisplayName: Enable stall prevention
294
// @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.
295
// @Values: 0:Disabled,1:Enabled
296
// @User: Standard
297
ASCALAR(stall_prevention, "STALL_PREVENTION", 1),
298
299
// @Param: AIRSPEED_CRUISE
300
// @DisplayName: Target cruise airspeed
301
// @Description: Target cruise airspeed in m/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
302
// @Units: m/s
303
// @User: Standard
304
ASCALAR(airspeed_cruise, "AIRSPEED_CRUISE", AIRSPEED_CRUISE),
305
306
// @Param: AIRSPEED_MIN
307
// @DisplayName: Minimum Airspeed
308
// @Description: Minimum airspeed demanded in automatic throttle modes. Should be set to 20% higher than level flight stall speed.
309
// @Units: m/s
310
// @Range: 5 100
311
// @Increment: 1
312
// @User: Standard
313
ASCALAR(airspeed_min, "AIRSPEED_MIN", AIRSPEED_FBW_MIN),
314
315
// @Param: AIRSPEED_MAX
316
// @DisplayName: Maximum Airspeed
317
// @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.
318
// @Units: m/s
319
// @Range: 5 100
320
// @Increment: 1
321
// @User: Standard
322
ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX),
323
324
// @Param: AIRSPEED_STALL
325
// @DisplayName: Stall airspeed
326
// @Description: If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. 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. Value is as an indicated (calibrated/apparent) airspeed.
327
// @Units: m/s
328
// @Range: 5 75
329
// @User: Standard
330
ASCALAR(airspeed_stall, "AIRSPEED_STALL", 0),
331
332
// @Param: FBWB_ELEV_REV
333
// @DisplayName: Fly By Wire elevator reverse
334
// @Description: Reverse sense of elevator in FBWB and CRUISE modes. When set to 0 up elevator (pulling back on the stick) means to lower altitude. When set to 1, up elevator means to raise altitude.
335
// @Values: 0:Disabled,1:Enabled
336
// @User: Standard
337
GSCALAR(flybywire_elev_reverse, "FBWB_ELEV_REV", 0),
338
339
#if AP_TERRAIN_AVAILABLE
340
// @Param: TERRAIN_FOLLOW
341
// @DisplayName: Use terrain following
342
// @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.
343
// @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
344
// @User: Standard
345
GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),
346
347
// @Param: TERRAIN_LOOKAHD
348
// @DisplayName: Terrain lookahead
349
// @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.
350
// @Range: 0 10000
351
// @Units: m
352
// @User: Standard
353
GSCALAR(terrain_lookahead, "TERRAIN_LOOKAHD", 2000),
354
#endif
355
356
// @Param: FBWB_CLIMB_RATE
357
// @DisplayName: Fly By Wire B altitude change rate
358
// @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.
359
// @Range: 1 10
360
// @Units: m/s
361
// @Increment: 0.1
362
// @User: Standard
363
GSCALAR(flybywire_climb_rate, "FBWB_CLIMB_RATE", 2.0f),
364
365
// @Param: THR_MIN
366
// @DisplayName: Minimum Throttle
367
// @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.
368
// @Units: %
369
// @Range: -100 100
370
// @Increment: 1
371
// @User: Standard
372
ASCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
373
374
// @Param: THR_MAX
375
// @DisplayName: Maximum Throttle
376
// @Description: Maximum throttle percentage used in all modes except manual, provided THR_PASS_STAB is not set.
377
// @Units: %
378
// @Range: 0 100
379
// @Increment: 1
380
// @User: Standard
381
ASCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
382
383
// @Param: TKOFF_THR_MAX
384
// @DisplayName: Maximum Throttle for takeoff
385
// @Description: The maximum throttle setting during automatic takeoff. If this is zero then THR_MAX is used for takeoff as well.
386
// @Units: %
387
// @Range: 0 100
388
// @Increment: 1
389
// @User: Advanced
390
ASCALAR(takeoff_throttle_max, "TKOFF_THR_MAX", 0),
391
392
// @Param: THR_SLEWRATE
393
// @DisplayName: Throttle slew rate
394
// @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.
395
// @Units: %/s
396
// @Range: 0 127
397
// @Increment: 1
398
// @User: Standard
399
ASCALAR(throttle_slewrate, "THR_SLEWRATE", 100),
400
401
// @Param: FLAP_SLEWRATE
402
// @DisplayName: Flap slew rate
403
// @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.
404
// @Units: %/s
405
// @Range: 0 100
406
// @Increment: 1
407
// @User: Advanced
408
GSCALAR(flap_slewrate, "FLAP_SLEWRATE", 75),
409
410
// @Param: THR_SUPP_MAN
411
// @DisplayName: Throttle suppress manual passthru
412
// @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
413
// @Values: 0:Disabled,1:Enabled
414
// @User: Advanced
415
GSCALAR(throttle_suppress_manual,"THR_SUPP_MAN", 0),
416
417
// @Param: THR_PASS_STAB
418
// @DisplayName: Throttle passthru in stabilize
419
// @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.
420
// @Values: 0:Disabled,1:Enabled
421
// @User: Advanced
422
GSCALAR(throttle_passthru_stabilize,"THR_PASS_STAB", 0),
423
424
// @Param: THR_FAILSAFE
425
// @DisplayName: Throttle and RC Failsafe Enable
426
// @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.
427
// @Values: 0:Disabled,1:Enabled,2:EnabledNoFailsafe
428
// @User: Standard
429
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", int(ThrFailsafe::Enabled)),
430
431
432
// @Param: THR_FS_VALUE
433
// @DisplayName: Throttle Failsafe Value
434
// @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.
435
// @Range: 925 2200
436
// @Increment: 1
437
// @User: Standard
438
GSCALAR(throttle_fs_value, "THR_FS_VALUE", 950),
439
440
// @Param: TRIM_THROTTLE
441
// @DisplayName: Throttle cruise percentage
442
// @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.
443
// @Units: %
444
// @Range: 0 100
445
// @Increment: 1
446
// @User: Standard
447
ASCALAR(throttle_cruise, "TRIM_THROTTLE", THROTTLE_CRUISE),
448
449
// @Param: THROTTLE_NUDGE
450
// @DisplayName: Throttle nudge enable
451
// @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%.
452
// @Values: 0:Disabled,1:Enabled
453
// @User: Standard
454
GSCALAR(throttle_nudge, "THROTTLE_NUDGE", 1),
455
456
// @Param: FS_SHORT_ACTN
457
// @DisplayName: Short failsafe action
458
// @Description: The action to take on a short (FS_SHORT_TIMEOUT) failsafe event. A short failsafe event can be triggered either by loss of RC control (see THR_FS_VALUE) or by loss of GCS control (see FS_GCS_ENABL). 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.
459
// @Values: 0:CIRCLE/no change(if already in AUTO|GUIDED|LOITER),1:CIRCLE,2:FBWA at zero throttle,3:Disable,4:FBWB
460
// @User: Standard
461
GSCALAR(fs_action_short, "FS_SHORT_ACTN", FS_ACTION_SHORT_BESTGUESS),
462
463
// @Param: FS_SHORT_TIMEOUT
464
// @DisplayName: Short failsafe timeout
465
// @Description: The time in seconds that a failsafe condition has to persist before a short failsafe event will occur. This defaults to 1.5 seconds
466
// @Units: s
467
// @Range: 1 100
468
// @Increment: 0.5
469
// @User: Standard
470
GSCALAR(fs_timeout_short, "FS_SHORT_TIMEOUT", 1.5f),
471
472
// @Param: FS_LONG_ACTN
473
// @DisplayName: Long failsafe action
474
// @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. 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.
475
// @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute,4:Auto
476
// @User: Standard
477
GSCALAR(fs_action_long, "FS_LONG_ACTN", FS_ACTION_LONG_CONTINUE),
478
479
// @Param: FS_LONG_TIMEOUT
480
// @DisplayName: Long failsafe timeout
481
// @Description: The time in seconds that a failsafe condition has to persist before a long failsafe event will occur. This defaults to 5 seconds.
482
// @Units: s
483
// @Range: 1 300
484
// @Increment: 0.5
485
// @User: Standard
486
GSCALAR(fs_timeout_long, "FS_LONG_TIMEOUT", 5),
487
488
// @Param: FS_GCS_ENABL
489
// @DisplayName: GCS failsafe enable
490
// @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. 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 3DR radio indicating that the 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.
491
// @Values: 0:Disabled,1:Heartbeat,2:HeartbeatAndREMRSSI,3:HeartbeatAndAUTO
492
// @User: Standard
493
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL", GCS_FAILSAFE_OFF),
494
495
// @Param: FLTMODE_CH
496
// @DisplayName: Flightmode channel
497
// @Description: RC Channel to use for flight mode control
498
// @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
499
// @User: Advanced
500
GSCALAR(flight_mode_channel, "FLTMODE_CH", FLIGHT_MODE_CHANNEL),
501
502
// @Param: FLTMODE1
503
// @DisplayName: FlightMode1
504
// @Description: Flight mode for switch position 1 (910 to 1230 and above 2049)
505
// @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
506
// @User: Standard
507
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
508
509
// @Param: FLTMODE2
510
// @CopyFieldsFrom: FLTMODE1
511
// @DisplayName: FlightMode2
512
// @Description: Flight mode for switch position 2 (1231 to 1360)
513
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
514
515
// @Param: FLTMODE3
516
// @CopyFieldsFrom: FLTMODE1
517
// @DisplayName: FlightMode3
518
// @Description: Flight mode for switch position 3 (1361 to 1490)
519
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
520
521
// @Param: FLTMODE4
522
// @CopyFieldsFrom: FLTMODE1
523
// @DisplayName: FlightMode4
524
// @Description: Flight mode for switch position 4 (1491 to 1620)
525
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
526
527
// @Param: FLTMODE5
528
// @CopyFieldsFrom: FLTMODE1
529
// @DisplayName: FlightMode5
530
// @Description: Flight mode for switch position 5 (1621 to 1749)
531
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
532
533
// @Param: FLTMODE6
534
// @CopyFieldsFrom: FLTMODE1
535
// @DisplayName: FlightMode6
536
// @Description: Flight mode for switch position 6 (1750 to 2049)
537
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
538
539
// @Param: INITIAL_MODE
540
// @DisplayName: Initial flight mode
541
// @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.
542
// @CopyValuesFrom: FLTMODE1
543
// @User: Advanced
544
GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL),
545
546
// @Param: ROLL_LIMIT_DEG
547
// @DisplayName: Maximum Bank Angle
548
// @Description: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls.
549
// @Units: deg
550
// @Range: 0 90
551
// @Increment: 1
552
// @User: Standard
553
ASCALAR(roll_limit, "ROLL_LIMIT_DEG", ROLL_LIMIT_DEG),
554
555
// @Param: PTCH_LIM_MAX_DEG
556
// @DisplayName: Maximum Pitch Angle
557
// @Description: Maximum pitch up angle commanded in modes with stabilized limits.
558
// @Units: deg
559
// @Range: 0 90
560
// @Increment: 1
561
// @User: Standard
562
ASCALAR(pitch_limit_max, "PTCH_LIM_MAX_DEG", PITCH_MAX),
563
564
// @Param: PTCH_LIM_MIN_DEG
565
// @DisplayName: Minimum Pitch Angle
566
// @Description: Maximum pitch down angle commanded in modes with stabilized limits
567
// @Units: deg
568
// @Range: -90 0
569
// @Increment: 1
570
// @User: Standard
571
ASCALAR(pitch_limit_min, "PTCH_LIM_MIN_DEG", PITCH_MIN),
572
573
// @Param: ACRO_ROLL_RATE
574
// @DisplayName: ACRO mode roll rate
575
// @Description: The maximum roll rate at full stick deflection in ACRO mode
576
// @Units: deg/s
577
// @Range: 10 500
578
// @Increment: 1
579
// @User: Standard
580
GSCALAR(acro_roll_rate, "ACRO_ROLL_RATE", 180),
581
582
// @Param: ACRO_PITCH_RATE
583
// @DisplayName: ACRO mode pitch rate
584
// @Description: The maximum pitch rate at full stick deflection in ACRO mode
585
// @Units: deg/s
586
// @Range: 10 500
587
// @Increment: 1
588
// @User: Standard
589
GSCALAR(acro_pitch_rate, "ACRO_PITCH_RATE", 180),
590
591
// @Param: ACRO_YAW_RATE
592
// @DisplayName: ACRO mode yaw rate
593
// @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.
594
// @Units: deg/s
595
// @Range: 0 500
596
// @Increment: 1
597
// @User: Standard
598
GSCALAR(acro_yaw_rate, "ACRO_YAW_RATE", 0),
599
600
// @Param: ACRO_LOCKING
601
// @DisplayName: ACRO mode attitude locking
602
// @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
603
// @Values: 0:Disabled,1:Enabled,2:Quaternion
604
// @User: Standard
605
GSCALAR(acro_locking, "ACRO_LOCKING", 0),
606
607
// @Param: GROUND_STEER_ALT
608
// @DisplayName: Ground steer altitude
609
// @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.
610
// @Units: m
611
// @Range: -100 100
612
// @Increment: 0.1
613
// @User: Standard
614
GSCALAR(ground_steer_alt, "GROUND_STEER_ALT", 0),
615
616
// @Param: GROUND_STEER_DPS
617
// @DisplayName: Ground steer rate
618
// @Description: Ground steering rate in degrees per second for full rudder stick deflection
619
// @Units: deg/s
620
// @Range: 10 360
621
// @Increment: 1
622
// @User: Advanced
623
GSCALAR(ground_steer_dps, "GROUND_STEER_DPS", 90),
624
625
// @Param: MIXING_GAIN
626
// @DisplayName: Mixing Gain
627
// @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.
628
// @Range: 0.5 1.2
629
// @User: Standard
630
GSCALAR(mixing_gain, "MIXING_GAIN", 0.5f),
631
632
// @Param: RUDDER_ONLY
633
// @DisplayName: Rudder only aircraft
634
// @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.
635
// @Values: 0:Disabled,1:Enabled
636
// @User: Standard
637
GSCALAR(rudder_only, "RUDDER_ONLY", 0),
638
639
// @Param: MIXING_OFFSET
640
// @DisplayName: Mixing Offset
641
// @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.
642
// @Units: d%
643
// @Range: -1000 1000
644
// @User: Standard
645
GSCALAR(mixing_offset, "MIXING_OFFSET", 0),
646
647
// @Param: DSPOILR_RUD_RATE
648
// @DisplayName: Differential spoilers rudder rate
649
// @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).
650
// @Units: %
651
// @Range: -100 100
652
// @User: Standard
653
GSCALAR(dspoiler_rud_rate, "DSPOILR_RUD_RATE", DSPOILR_RUD_RATE_DEFAULT),
654
655
// @Param: LOG_BITMASK
656
// @DisplayName: Log bitmask
657
// @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.
658
// @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
659
// @User: Advanced
660
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
661
662
// @Param: SCALING_SPEED
663
// @DisplayName: speed used for speed scaling calculations
664
// @Description: Airspeed in m/s to use when calculating surface speed scaling. Note that changing this value will affect all PID values
665
// @Units: m/s
666
// @Range: 0 50
667
// @Increment: 0.1
668
// @User: Advanced
669
GSCALAR(scaling_speed, "SCALING_SPEED", SCALING_SPEED),
670
671
// @Param: MIN_GROUNDSPEED
672
// @DisplayName: Minimum ground speed
673
// @Description: Minimum ground speed when under airspeed control
674
// @Units: m/s
675
// @User: Advanced
676
ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED),
677
678
// @Param: PTCH_TRIM_DEG
679
// @DisplayName: Pitch angle offset
680
// @Description: Offset in degrees used for in-flight pitch trimming for level flight. Correct ground leveling is an alternative to changing this parameter.
681
// @Units: deg
682
// @Range: -45 45
683
// @User: Standard
684
GSCALAR(pitch_trim, "PTCH_TRIM_DEG", 0.0f),
685
686
// @Param: RTL_ALTITUDE
687
// @DisplayName: RTL altitude
688
// @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.
689
// @Units: m
690
// @User: Standard
691
GSCALAR(RTL_altitude, "RTL_ALTITUDE", ALT_HOLD_HOME),
692
693
// @Param: CRUISE_ALT_FLOOR
694
// @DisplayName: Minimum altitude for FBWB and CRUISE mode
695
// @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.
696
// @Units: m
697
// @User: Standard
698
GSCALAR(cruise_alt_floor, "CRUISE_ALT_FLOOR", CRUISE_ALT_FLOOR),
699
700
// @Param: FLAP_1_PERCNT
701
// @DisplayName: Flap 1 percentage
702
// @Description: The percentage change in flap position when FLAP_1_SPEED is reached. Use zero to disable flaps
703
// @Range: 0 100
704
// @Increment: 1
705
// @Units: %
706
// @User: Advanced
707
GSCALAR(flap_1_percent, "FLAP_1_PERCNT", FLAP_1_PERCENT),
708
709
// @Param: FLAP_1_SPEED
710
// @DisplayName: Flap 1 speed
711
// @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
712
// @Range: 0 100
713
// @Increment: 1
714
// @Units: m/s
715
// @User: Advanced
716
GSCALAR(flap_1_speed, "FLAP_1_SPEED", FLAP_1_SPEED),
717
718
// @Param: FLAP_2_PERCNT
719
// @DisplayName: Flap 2 percentage
720
// @Description: The percentage change in flap position when FLAP_2_SPEED is reached. Use zero to disable flaps
721
// @Range: 0 100
722
// @Units: %
723
// @Increment: 1
724
// @User: Advanced
725
GSCALAR(flap_2_percent, "FLAP_2_PERCNT", FLAP_2_PERCENT),
726
727
// @Param: FLAP_2_SPEED
728
// @DisplayName: Flap 2 speed
729
// @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
730
// @Range: 0 100
731
// @Units: m/s
732
// @Increment: 1
733
// @User: Advanced
734
GSCALAR(flap_2_speed, "FLAP_2_SPEED", FLAP_2_SPEED),
735
736
#if HAL_WITH_IO_MCU
737
// @Param: OVERRIDE_CHAN
738
// @DisplayName: IO override channel
739
// @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.
740
// @Range: 0 16
741
// @Increment: 1
742
// @User: Advanced
743
GSCALAR(override_channel, "OVERRIDE_CHAN", 0),
744
#endif
745
746
// @Param: RTL_AUTOLAND
747
// @DisplayName: RTL auto land
748
// @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.
749
// @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
750
// @User: Standard
751
GSCALAR(rtl_autoland, "RTL_AUTOLAND", float(RtlAutoland::RTL_DISABLE)),
752
753
// @Param: CRASH_ACC_THRESH
754
// @DisplayName: Crash Deceleration Threshold
755
// @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 sensative (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.
756
// @Units: m/s/s
757
// @Range: 10 127
758
// @Increment: 1
759
// @User: Advanced
760
GSCALAR(crash_accel_threshold, "CRASH_ACC_THRESH", 0),
761
762
// @Param: CRASH_DETECT
763
// @DisplayName: Crash Detection
764
// @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.
765
// @Bitmask: 0:Disarm
766
// @User: Advanced
767
ASCALAR(crash_detection_enable, "CRASH_DETECT", 0),
768
769
// @Group: BARO
770
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
771
GOBJECT(barometer, "BARO", AP_Baro),
772
773
// GPS driver
774
// @Group: GPS
775
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
776
GOBJECT(gps, "GPS", AP_GPS),
777
778
#if AP_CAMERA_ENABLED
779
// @Group: CAM
780
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
781
GOBJECT(camera, "CAM", AP_Camera),
782
#endif
783
784
// @Group: ARMING_
785
// @Path: AP_Arming.cpp,../libraries/AP_Arming/AP_Arming.cpp
786
GOBJECT(arming, "ARMING_", AP_Arming_Plane),
787
788
#if AP_RELAY_ENABLED
789
// @Group: RELAY
790
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
791
GOBJECT(relay, "RELAY", AP_Relay),
792
#endif
793
794
#if HAL_PARACHUTE_ENABLED
795
// @Group: CHUTE_
796
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
797
GOBJECT(parachute, "CHUTE_", AP_Parachute),
798
#endif
799
800
#if AP_RANGEFINDER_ENABLED
801
// @Group: RNGFND
802
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
803
GOBJECT(rangefinder, "RNGFND", RangeFinder),
804
805
// @Param: RNGFND_LANDING
806
// @DisplayName: Enable rangefinder for landing
807
// @Description: This enables the use of a rangefinder for automatic landing. The rangefinder will be used both on the landing approach and for final flare
808
// @Values: 0:Disabled,1:Enabled
809
// @User: Standard
810
GSCALAR(rangefinder_landing, "RNGFND_LANDING", 0),
811
#endif
812
813
#if AP_TERRAIN_AVAILABLE
814
// @Group: TERRAIN_
815
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
816
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
817
#endif
818
819
#if HAL_ADSB_ENABLED
820
// @Group: ADSB_
821
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
822
GOBJECT(adsb, "ADSB_", AP_ADSB),
823
824
// @Group: AVD_
825
// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp
826
GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Plane),
827
#endif
828
829
#if HAL_QUADPLANE_ENABLED
830
// @Group: Q_
831
// @Path: quadplane.cpp
832
GOBJECT(quadplane, "Q_", QuadPlane),
833
#endif
834
835
#if AP_TUNING_ENABLED
836
// @Group: TUNE_
837
// @Path: tuning.cpp,../libraries/AP_Tuning/AP_Tuning.cpp
838
GOBJECT(tuning, "TUNE_", AP_Tuning_Plane),
839
#endif
840
841
#if HAL_QUADPLANE_ENABLED
842
// @Group: Q_A_
843
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
844
{ "Q_A_", (const void *)&plane.quadplane.attitude_control,
845
{group_info : AC_AttitudeControl_Multi::var_info}, AP_PARAM_FLAG_POINTER,
846
Parameters::k_param_q_attitude_control, AP_PARAM_GROUP },
847
#endif
848
849
// @Group: RLL
850
// @Path: ../libraries/APM_Control/AP_RollController.cpp
851
GOBJECT(rollController, "RLL", AP_RollController),
852
853
// @Group: PTCH
854
// @Path: ../libraries/APM_Control/AP_PitchController.cpp
855
GOBJECT(pitchController, "PTCH", AP_PitchController),
856
857
// @Group: YAW
858
// @Path: ../libraries/APM_Control/AP_YawController.cpp
859
GOBJECT(yawController, "YAW", AP_YawController),
860
861
// @Group: STEER2SRV_
862
// @Path: ../libraries/APM_Control/AP_SteerController.cpp
863
GOBJECT(steerController, "STEER2SRV_", AP_SteerController),
864
865
// variables not in the g class which contain EEPROM saved variables
866
867
// @Group: COMPASS_
868
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
869
GOBJECT(compass, "COMPASS_", Compass),
870
871
// @Group: SCHED_
872
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
873
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
874
875
// @Group: RCMAP_
876
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
877
GOBJECT(rcmap, "RCMAP_", RCMapper),
878
879
// @Group: SR0_
880
// @Path: GCS_MAVLink_Plane.cpp
881
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
882
883
#if MAVLINK_COMM_NUM_BUFFERS >= 2
884
// @Group: SR1_
885
// @Path: GCS_MAVLink_Plane.cpp
886
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
887
#endif
888
889
#if MAVLINK_COMM_NUM_BUFFERS >= 3
890
// @Group: SR2_
891
// @Path: GCS_MAVLink_Plane.cpp
892
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
893
#endif
894
895
#if MAVLINK_COMM_NUM_BUFFERS >= 4
896
// @Group: SR3_
897
// @Path: GCS_MAVLink_Plane.cpp
898
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
899
#endif
900
901
#if MAVLINK_COMM_NUM_BUFFERS >= 5
902
// @Group: SR4_
903
// @Path: GCS_MAVLink_Plane.cpp
904
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
905
#endif
906
907
#if MAVLINK_COMM_NUM_BUFFERS >= 6
908
// @Group: SR5_
909
// @Path: GCS_MAVLink_Plane.cpp
910
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
911
#endif
912
913
#if MAVLINK_COMM_NUM_BUFFERS >= 7
914
// @Group: SR6_
915
// @Path: GCS_MAVLink_Plane.cpp
916
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
917
#endif
918
919
// @Group: INS
920
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
921
GOBJECT(ins, "INS", AP_InertialSensor),
922
923
// @Group: AHRS_
924
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
925
GOBJECT(ahrs, "AHRS_", AP_AHRS),
926
927
// Airspeed was here
928
929
// @Group: NAVL1_
930
// @Path: ../libraries/AP_L1_Control/AP_L1_Control.cpp
931
GOBJECT(L1_controller, "NAVL1_", AP_L1_Control),
932
933
// @Group: TECS_
934
// @Path: ../libraries/AP_TECS/AP_TECS.cpp
935
GOBJECT(TECS_controller, "TECS_", AP_TECS),
936
937
#if HAL_MOUNT_ENABLED
938
// @Group: MNT
939
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
940
GOBJECT(camera_mount, "MNT", AP_Mount),
941
#endif
942
943
// @Group: BATT
944
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
945
GOBJECT(battery, "BATT", AP_BattMonitor),
946
947
// @Group: BRD_
948
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
949
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
950
951
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
952
// @Group: CAN_
953
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
954
GOBJECT(can_mgr, "CAN_", AP_CANManager),
955
#endif
956
957
#if AP_SIM_ENABLED
958
// @Group: SIM_
959
// @Path: ../libraries/SITL/SITL.cpp
960
GOBJECT(sitl, "SIM_", SITL::SIM),
961
#endif
962
963
#if AP_ADVANCEDFAILSAFE_ENABLED
964
// @Group: AFS_
965
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
966
GOBJECT(afs, "AFS_", AP_AdvancedFailsafe),
967
#endif
968
969
#if AP_OPTICALFLOW_ENABLED
970
// @Group: FLOW
971
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
972
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
973
#endif
974
975
// @Group: MIS_
976
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
977
GOBJECT(mission, "MIS_", AP_Mission),
978
979
#if HAL_RALLY_ENABLED
980
// @Group: RALLY_
981
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
982
GOBJECT(rally, "RALLY_", AP_Rally),
983
#endif
984
985
#if HAL_NAVEKF2_AVAILABLE
986
// @Group: EK2_
987
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
988
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
989
#endif
990
991
#if HAL_NAVEKF3_AVAILABLE
992
// @Group: EK3_
993
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
994
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
995
#endif
996
997
#if AP_RPM_ENABLED
998
// @Group: RPM
999
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
1000
GOBJECT(rpm_sensor, "RPM", AP_RPM),
1001
#endif
1002
1003
#if AP_RSSI_ENABLED
1004
// @Group: RSSI_
1005
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
1006
GOBJECT(rssi, "RSSI_", AP_RSSI),
1007
#endif
1008
1009
// @Group: NTF_
1010
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
1011
GOBJECT(notify, "NTF_", AP_Notify),
1012
1013
// @Group:
1014
// @Path: Parameters.cpp
1015
GOBJECT(g2, "", ParametersG2),
1016
1017
// @Group: LAND_
1018
// @Path: ../libraries/AP_Landing/AP_Landing.cpp
1019
GOBJECT(landing, "LAND_", AP_Landing),
1020
1021
#if OSD_ENABLED || OSD_PARAM_ENABLED
1022
// @Group: OSD
1023
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
1024
GOBJECT(osd, "OSD", AP_OSD),
1025
#endif
1026
1027
// @Group: TKOFF_
1028
// @Path: mode_takeoff.cpp
1029
GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff),
1030
1031
#if MODE_AUTOLAND_ENABLED
1032
// @Group: AUTOLAND_
1033
// @Path: mode_autoland.cpp
1034
GOBJECT(mode_autoland, "AUTOLAND_", ModeAutoLand),
1035
#endif
1036
1037
#if AP_PLANE_GLIDER_PULLUP_ENABLED
1038
// @Group: PUP_
1039
// @Path: pullup.cpp
1040
GOBJECTN(mode_auto.pullup, pullup, "PUP_", GliderPullup),
1041
#endif
1042
1043
// @Group:
1044
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
1045
PARAM_VEHICLE_INFO,
1046
1047
#if AP_QUICKTUNE_ENABLED
1048
// @Group: QWIK_
1049
// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp
1050
GOBJECT(quicktune, "QWIK_", AP_Quicktune),
1051
#endif
1052
1053
AP_VAREND
1054
};
1055
1056
/*
1057
2nd group of parameters
1058
*/
1059
const AP_Param::GroupInfo ParametersG2::var_info[] = {
1060
1061
#if HAL_BUTTON_ENABLED
1062
// @Group: BTN_
1063
// @Path: ../libraries/AP_Button/AP_Button.cpp
1064
AP_SUBGROUPPTR(button_ptr, "BTN_", 1, ParametersG2, AP_Button),
1065
#endif
1066
1067
#if AP_ICENGINE_ENABLED
1068
// @Group: ICE_
1069
// @Path: ../libraries/AP_ICEngine/AP_ICEngine.cpp
1070
AP_SUBGROUPINFO(ice_control, "ICE_", 2, ParametersG2, AP_ICEngine),
1071
#endif
1072
1073
// 3 was used by prototype for servo_channels
1074
1075
// @Param: SYSID_ENFORCE
1076
// @DisplayName: GCS sysid enforcement
1077
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
1078
// @Values: 0:NotEnforced,1:Enforced
1079
// @User: Advanced
1080
AP_GROUPINFO("SYSID_ENFORCE", 4, ParametersG2, sysid_enforce, 0),
1081
1082
// AP_Stats was 5
1083
1084
// @Group: SERVO
1085
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
1086
AP_SUBGROUPINFO(servo_channels, "SERVO", 6, ParametersG2, SRV_Channels),
1087
1088
// @Group: RC
1089
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
1090
AP_SUBGROUPINFO(rc_channels, "RC", 7, ParametersG2, RC_Channels_Plane),
1091
1092
#if HAL_SOARING_ENABLED
1093
// @Group: SOAR_
1094
// @Path: ../libraries/AP_Soaring/AP_Soaring.cpp
1095
AP_SUBGROUPINFO(soaring_controller, "SOAR_", 8, ParametersG2, SoaringController),
1096
#endif
1097
1098
// @Param: RUDD_DT_GAIN
1099
// @DisplayName: rudder differential thrust gain
1100
// @Description: gain control from rudder to differential thrust
1101
// @Range: 0 100
1102
// @Units: %
1103
// @Increment: 1
1104
// @User: Standard
1105
AP_GROUPINFO("RUDD_DT_GAIN", 9, ParametersG2, rudd_dt_gain, 10),
1106
1107
// @Param: MANUAL_RCMASK
1108
// @DisplayName: Manual R/C pass-through mask
1109
// @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.
1110
// @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
1111
// @User: Advanced
1112
AP_GROUPINFO("MANUAL_RCMASK", 10, ParametersG2, manual_rc_mask, 0),
1113
1114
// @Param: HOME_RESET_ALT
1115
// @DisplayName: Home reset altitude threshold
1116
// @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 continously reset it.
1117
// @Values: -1:Never reset,0:Always reset
1118
// @Range: -1 127
1119
// @Units: m
1120
// @User: Advanced
1121
AP_GROUPINFO("HOME_RESET_ALT", 11, ParametersG2, home_reset_threshold, 0),
1122
1123
// 12 was AP_Gripper
1124
1125
// @Param: FLIGHT_OPTIONS
1126
// @DisplayName: Flight mode options
1127
// @Description: Flight mode specific options
1128
// @Bitmask: 0: Rudder mixing in direct flight modes only (Manual/Stabilize/Acro)
1129
// @Bitmask: 1: Use centered throttle in Cruise or FBWB to indicate trim airspeed
1130
// @Bitmask: 2: Disable attitude check for takeoff arming
1131
// @Bitmask: 3: Force target airspeed to trim airspeed in Cruise or FBWB
1132
// @Bitmask: 4: Climb to RTL_ALTITUDE before turning for RTL
1133
// @Bitmask: 5: Enable yaw damper in acro mode
1134
// @Bitmask: 6: Supress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airspeed sensor.
1135
// @Bitmask: 7: EnableDefaultAirspeed for takeoff
1136
// @Bitmask: 8: Remove the PTCH_TRIM_DEG on the GCS horizon
1137
// @Bitmask: 9: Remove the PTCH_TRIM_DEG on the OSD horizon
1138
// @Bitmask: 10: Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL
1139
// @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode
1140
// @Bitmask: 12: Enable FBWB style loiter altitude control
1141
// @Bitmask: 13: Indicate takeoff waiting for neutral rudder with flight control surfaces
1142
// @Bitmask: 14: In AUTO - climb to next waypoint altitude immediately instead of linear climb
1143
// @User: Advanced
1144
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
1145
1146
// 14 was AP_Scripting
1147
1148
// @Param: TKOFF_ACCEL_CNT
1149
// @DisplayName: Takeoff throttle acceleration count
1150
// @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.
1151
// @Range: 1 10
1152
// @User: Standard
1153
AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1),
1154
1155
#if AP_LANDINGGEAR_ENABLED
1156
// @Group: LGR_
1157
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
1158
AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),
1159
#endif
1160
1161
// @Param: DSPOILER_CROW_W1
1162
// @DisplayName: Differential spoiler crow flaps outer weight
1163
// @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.
1164
// @Range: 0 100
1165
// @Units: %
1166
// @Increment: 1
1167
// @User: Advanced
1168
AP_GROUPINFO("DSPOILER_CROW_W1", 17, ParametersG2, crow_flap_weight_outer, 0),
1169
1170
// @Param: DSPOILER_CROW_W2
1171
// @DisplayName: Differential spoiler crow flaps inner weight
1172
// @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.
1173
// @Range: 0 100
1174
// @Units: %
1175
// @Increment: 1
1176
// @User: Advanced
1177
AP_GROUPINFO("DSPOILER_CROW_W2", 18, ParametersG2, crow_flap_weight_inner, 0),
1178
1179
// @Param: TKOFF_TIMEOUT
1180
// @DisplayName: Takeoff timeout
1181
// @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.
1182
// @Range: 0 120
1183
// @Increment: 1
1184
// @Units: s
1185
// @User: Standard
1186
AP_GROUPINFO("TKOFF_TIMEOUT", 19, ParametersG2, takeoff_timeout, 0),
1187
1188
// @Param: DSPOILER_OPTS
1189
// @DisplayName: Differential spoiler and crow flaps options
1190
// @Description: Differential spoiler and crow flaps options. Progressive crow flaps only first (0-50% flap in) then crow flaps (50 - 100% flap in).
1191
// @Bitmask: 0:Pitch input, 1:use both control surfaces on each wing for roll, 2:Progressive crow flaps
1192
// @User: Advanced
1193
AP_GROUPINFO("DSPOILER_OPTS", 20, ParametersG2, crow_flap_options, 3),
1194
1195
// @Param: DSPOILER_AILMTCH
1196
// @DisplayName: Differential spoiler aileron matching
1197
// @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
1198
// @Range: 0 100
1199
// @Units: %
1200
// @Increment: 1
1201
// @User: Advanced
1202
AP_GROUPINFO("DSPOILER_AILMTCH", 21, ParametersG2, crow_flap_aileron_matching, 100),
1203
1204
1205
// 22 was EFI
1206
1207
// @Param: FWD_BAT_VOLT_MAX
1208
// @DisplayName: Forward throttle battery voltage compensation maximum voltage
1209
// @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.
1210
// @Range: 6 35
1211
// @Units: V
1212
// @Increment: 0.1
1213
// @User: Advanced
1214
AP_GROUPINFO("FWD_BAT_VOLT_MAX", 23, ParametersG2, fwd_batt_cmp.batt_voltage_max, 0.0f),
1215
1216
// @Param: FWD_BAT_VOLT_MIN
1217
// @DisplayName: Forward throttle battery voltage compensation minimum voltage
1218
// @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.
1219
// @Range: 6 35
1220
// @Units: V
1221
// @Increment: 0.1
1222
// @User: Advanced
1223
AP_GROUPINFO("FWD_BAT_VOLT_MIN", 24, ParametersG2, fwd_batt_cmp.batt_voltage_min, 0.0f),
1224
1225
// @Param: FWD_BAT_IDX
1226
// @DisplayName: Forward throttle battery compensation index
1227
// @Description: Which battery monitor should be used for doing compensation for the forward throttle
1228
// @Values: 0:First battery, 1:Second battery
1229
// @User: Advanced
1230
AP_GROUPINFO("FWD_BAT_IDX", 25, ParametersG2, fwd_batt_cmp.batt_idx, 0),
1231
1232
// @Param: FS_EKF_THRESH
1233
// @DisplayName: EKF failsafe variance threshold
1234
// @Description: Allows setting the maximum acceptable compass and velocity variance used to check navigation health in VTOL modes
1235
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
1236
// @User: Advanced
1237
AP_GROUPINFO("FS_EKF_THRESH", 26, ParametersG2, fs_ekf_thresh, FS_EKF_THRESHOLD_DEFAULT),
1238
1239
// @Param: RTL_CLIMB_MIN
1240
// @DisplayName: RTL minimum climb
1241
// @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.
1242
// @Units: m
1243
// @Range: 0 30
1244
// @Increment: 1
1245
// @User: Standard
1246
AP_GROUPINFO("RTL_CLIMB_MIN", 27, ParametersG2, rtl_climb_min, 0),
1247
1248
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
1249
// @Group: GUIDED_
1250
// @Path: ../libraries/AC_PID/AC_PID.cpp
1251
AP_SUBGROUPINFO(guidedHeading, "GUIDED_", 28, ParametersG2, AC_PID),
1252
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
1253
1254
// @Param: MAN_EXPO_ROLL
1255
// @DisplayName: Manual control expo for roll
1256
// @Description: Percentage exponential for roll input in MANUAL, ACRO and TRAINING modes
1257
// @Range: 0 100
1258
// @Increment: 1
1259
// @User: Standard
1260
AP_GROUPINFO("MAN_EXPO_ROLL", 29, ParametersG2, man_expo_roll, 0),
1261
1262
// @Param: MAN_EXPO_PITCH
1263
// @DisplayName: Manual input expo for pitch
1264
// @Description: Percentage exponential for pitch input in MANUAL, ACRO and TRAINING modes
1265
// @Range: 0 100
1266
// @Increment: 1
1267
// @User: Standard
1268
AP_GROUPINFO("MAN_EXPO_PITCH", 30, ParametersG2, man_expo_pitch, 0),
1269
1270
// @Param: MAN_EXPO_RUDDER
1271
// @DisplayName: Manual input expo for rudder
1272
// @Description: Percentage exponential for rudder input in MANUAL, ACRO and TRAINING modes
1273
// @Range: 0 100
1274
// @Increment: 1
1275
// @User: Standard
1276
AP_GROUPINFO("MAN_EXPO_RUDDER", 31, ParametersG2, man_expo_rudder, 0),
1277
1278
// @Param: ONESHOT_MASK
1279
// @DisplayName: Oneshot output mask
1280
// @Description: Mask of output channels to use oneshot on
1281
// @User: Advanced
1282
// @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
1283
AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0),
1284
1285
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
1286
// @Group: FOLL
1287
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
1288
AP_SUBGROUPINFO(follow, "FOLL", 33, ParametersG2, AP_Follow),
1289
#endif
1290
1291
// @Param: AUTOTUNE_AXES
1292
// @DisplayName: Autotune axis bitmask
1293
// @Description: 1-byte bitmap of axes to autotune
1294
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
1295
// @User: Standard
1296
AP_GROUPINFO("AUTOTUNE_AXES", 34, ParametersG2, axis_bitmask, 7),
1297
1298
#if AC_PRECLAND_ENABLED
1299
// @Group: PLND_
1300
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
1301
AP_SUBGROUPINFO(precland, "PLND_", 35, ParametersG2, AC_PrecLand),
1302
#endif
1303
1304
#if AP_RANGEFINDER_ENABLED
1305
// @Param: RNGFND_LND_ORNT
1306
// @DisplayName: rangefinder landing orientation
1307
// @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.
1308
// @Values: 4:Back, 25:Down, 101:Custom1, 102:Custom2
1309
// @User: Standard
1310
AP_GROUPINFO("RNGFND_LND_ORNT", 36, ParametersG2, rangefinder_land_orient, ROTATION_PITCH_270),
1311
#endif
1312
1313
AP_GROUPEND
1314
};
1315
1316
ParametersG2::ParametersG2(void) :
1317
unused_integer{1}
1318
#if HAL_BUTTON_ENABLED
1319
,button_ptr(&plane.button)
1320
#endif
1321
#if HAL_SOARING_ENABLED
1322
,soaring_controller(plane.TECS_controller, plane.aparm)
1323
#endif
1324
{
1325
AP_Param::setup_object_defaults(this, var_info);
1326
}
1327
1328
/*
1329
This is a conversion table from old parameter values to new
1330
parameter names. The startup code looks for saved values of the old
1331
parameters and will copy them across to the new parameters if the
1332
new parameter does not yet have a saved value. It then saves the new
1333
value.
1334
1335
Note that this works even if the old parameter has been removed. It
1336
relies on the old k_param index not being removed
1337
1338
The second column below is the index in the var_info[] table for the
1339
old object. This should be zero for top level parameters.
1340
*/
1341
static const AP_Param::ConversionInfo conversion_table[] = {
1342
{ Parameters::k_param_fence_minalt, 0, AP_PARAM_INT16, "FENCE_ALT_MIN"},
1343
{ Parameters::k_param_fence_maxalt, 0, AP_PARAM_INT16, "FENCE_ALT_MAX"},
1344
{ Parameters::k_param_fence_retalt, 0, AP_PARAM_INT16, "FENCE_RET_ALT"},
1345
{ Parameters::k_param_fence_ret_rally, 0, AP_PARAM_INT8, "FENCE_RET_RALLY"},
1346
{ Parameters::k_param_fence_autoenable, 0, AP_PARAM_INT8, "FENCE_AUTOENABLE"},
1347
};
1348
1349
struct RCConversionInfo {
1350
uint16_t old_key; // k_param_*
1351
uint32_t old_group_element; // index in old object
1352
RC_Channel::AUX_FUNC fun; // new function
1353
};
1354
1355
static const RCConversionInfo rc_option_conversion[] = {
1356
{ Parameters::k_param_flapin_channel_old, 0, RC_Channel::AUX_FUNC::FLAP},
1357
{ Parameters::k_param_g2, 968, RC_Channel::AUX_FUNC::SOARING},
1358
#if AP_FENCE_ENABLED
1359
{ Parameters::k_param_fence_channel, 0, RC_Channel::AUX_FUNC::FENCE},
1360
#endif
1361
#if AP_MISSION_ENABLED
1362
{ Parameters::k_param_reset_mission_chan, 0, RC_Channel::AUX_FUNC::MISSION_RESET},
1363
#endif
1364
#if HAL_PARACHUTE_ENABLED
1365
{ Parameters::k_param_parachute_channel, 0, RC_Channel::AUX_FUNC::PARACHUTE_RELEASE},
1366
#endif
1367
{ Parameters::k_param_fbwa_tdrag_chan, 0, RC_Channel::AUX_FUNC::FBWA_TAILDRAGGER},
1368
{ Parameters::k_param_reset_switch_chan, 0, RC_Channel::AUX_FUNC::MODE_SWITCH_RESET},
1369
};
1370
1371
void Plane::load_parameters(void)
1372
{
1373
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
1374
1375
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
1376
1377
// setup defaults in SRV_Channels
1378
g2.servo_channels.set_default_function(CH_1, SRV_Channel::k_aileron);
1379
g2.servo_channels.set_default_function(CH_2, SRV_Channel::k_elevator);
1380
g2.servo_channels.set_default_function(CH_3, SRV_Channel::k_throttle);
1381
g2.servo_channels.set_default_function(CH_4, SRV_Channel::k_rudder);
1382
1383
SRV_Channels::upgrade_parameters();
1384
1385
#if HAL_QUADPLANE_ENABLED
1386
if (quadplane.enable) {
1387
// quadplanes needs a higher loop rate
1388
AP_Param::set_default_by_name("SCHED_LOOP_RATE", 300);
1389
}
1390
#endif
1391
1392
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_PLANE);
1393
1394
// Convert chan params to RCx_OPTION
1395
for (uint8_t i=0; i<ARRAY_SIZE(rc_option_conversion); i++) {
1396
AP_Int8 chan_param;
1397
AP_Param::ConversionInfo info {rc_option_conversion[i].old_key, rc_option_conversion[i].old_group_element, AP_PARAM_INT8, nullptr};
1398
if (AP_Param::find_old_parameter(&info, &chan_param) && chan_param.get() > 0) {
1399
RC_Channel *chan = rc().channel(chan_param.get() - 1);
1400
if (chan != nullptr && !chan->option.configured()) {
1401
chan->option.set_and_save((int16_t)rc_option_conversion[i].fun); // save the new param
1402
}
1403
}
1404
}
1405
1406
#if AP_FENCE_ENABLED
1407
enum ap_var_type ptype_fence_type;
1408
AP_Int8 *fence_type_new = (AP_Int8*)AP_Param::find("FENCE_TYPE", &ptype_fence_type);
1409
if (fence_type_new && !fence_type_new->configured()) {
1410
// If we find the new parameter and it hasn't been configured
1411
// attempt to upgrade the altitude fences.
1412
int8_t fence_type_new_val = AC_FENCE_TYPE_POLYGON;
1413
AP_Int16 fence_alt_min_old;
1414
AP_Param::ConversionInfo fence_alt_min_info_old = {
1415
Parameters::k_param_fence_minalt,
1416
0,
1417
AP_PARAM_INT16,
1418
nullptr
1419
};
1420
if (AP_Param::find_old_parameter(&fence_alt_min_info_old, &fence_alt_min_old)) {
1421
if (fence_alt_min_old.configured()) {
1422
//
1423
fence_type_new_val |= AC_FENCE_TYPE_ALT_MIN;
1424
}
1425
}
1426
1427
AP_Int16 fence_alt_max_old;
1428
AP_Param::ConversionInfo fence_alt_max_info_old = {
1429
Parameters::k_param_fence_maxalt,
1430
0,
1431
AP_PARAM_INT16,
1432
nullptr
1433
};
1434
if (AP_Param::find_old_parameter(&fence_alt_max_info_old, &fence_alt_max_old)) {
1435
if (fence_alt_max_old.configured()) {
1436
fence_type_new_val |= AC_FENCE_TYPE_ALT_MAX;
1437
}
1438
}
1439
1440
fence_type_new->set_and_save((int8_t)fence_type_new_val);
1441
}
1442
1443
AP_Int8 fence_action_old;
1444
AP_Param::ConversionInfo fence_action_info_old = {
1445
Parameters::k_param_fence_action,
1446
0,
1447
AP_PARAM_INT8,
1448
"FENCE_ACTION"
1449
};
1450
if (AP_Param::find_old_parameter(&fence_action_info_old, &fence_action_old)) {
1451
enum ap_var_type ptype;
1452
AP_Int8 *fence_action_new = (AP_Int8*)AP_Param::find(&fence_action_info_old.new_name[0], &ptype);
1453
uint8_t fence_action_new_val;
1454
if (fence_action_new && !fence_action_new->configured()) {
1455
switch(fence_action_old.get()) {
1456
case 0: // FENCE_ACTION_NONE
1457
case 2: // FENCE_ACTION_REPORT_ONLY
1458
default:
1459
fence_action_new_val = AC_FENCE_ACTION_REPORT_ONLY;
1460
break;
1461
case 1: // FENCE_ACTION_GUIDED
1462
fence_action_new_val = AC_FENCE_ACTION_GUIDED;
1463
break;
1464
case 3: // FENCE_ACTION_GUIDED_THR_PASS
1465
fence_action_new_val = AC_FENCE_ACTION_GUIDED_THROTTLE_PASS;
1466
break;
1467
case 4: // FENCE_ACTION_RTL
1468
fence_action_new_val = AC_FENCE_ACTION_RTL_AND_LAND;
1469
break;
1470
}
1471
fence_action_new->set_and_save((int8_t)fence_action_new_val);
1472
1473
// Now upgrade the new fence enable at the same time
1474
enum ap_var_type ptype_fence_enable;
1475
AP_Int8 *fence_enable = (AP_Int8*)AP_Param::find("FENCE_ENABLE", &ptype_fence_enable);
1476
// fences were used if there was a count, and the old fence action was not zero
1477
AC_Fence *ap_fence = AP::fence();
1478
bool fences_exist = false;
1479
if (ap_fence) {
1480
// If the fence library is present, attempt to read the fence count
1481
fences_exist = ap_fence->polyfence().total_fence_count() > 0;
1482
}
1483
1484
bool fences_used = fence_action_old.get() != 0;
1485
if (fence_enable && !fence_enable->configured()) {
1486
// The fence enable parameter exists, so now set it accordingly
1487
fence_enable->set_and_save(fences_exist && fences_used);
1488
}
1489
}
1490
}
1491
#endif // AP_FENCE_ENABLED
1492
1493
#if AP_TERRAIN_AVAILABLE
1494
g.terrain_follow.convert_parameter_width(AP_PARAM_INT8);
1495
#endif
1496
1497
g.use_reverse_thrust.convert_parameter_width(AP_PARAM_INT16);
1498
1499
#if AP_AIRSPEED_ENABLED
1500
// PARAMETER_CONVERSION - Added: Jan-2022
1501
{
1502
const uint16_t old_key = g.k_param_airspeed;
1503
const uint16_t old_index = 0; // Old parameter index in the tree
1504
AP_Param::convert_class(old_key, &airspeed, airspeed.var_info, old_index, true);
1505
}
1506
#endif
1507
1508
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
1509
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
1510
if (!ins.harmonic_notches[1].params.enabled()) {
1511
// notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch
1512
const AP_Param::ConversionInfo notchfilt_conversion_info[] {
1513
{ Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" },
1514
{ Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" },
1515
{ Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" },
1516
{ Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" },
1517
};
1518
AP_Param::convert_old_parameters(&notchfilt_conversion_info[0], ARRAY_SIZE(notchfilt_conversion_info));
1519
AP_Param::set_default_by_name("INS_HNTC2_MODE", 0);
1520
AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);
1521
}
1522
#endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS
1523
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
1524
1525
// PARAMETER_CONVERSION - Added: Mar-2022
1526
#if AP_FENCE_ENABLED
1527
AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, true);
1528
#endif
1529
1530
// PARAMETER_CONVERSION - Added: Dec 2023
1531
// Convert _CM (centimeter) parameters to meters and _CD (centidegrees) parameters to meters
1532
g.pitch_trim.convert_centi_parameter(AP_PARAM_INT16);
1533
aparm.airspeed_cruise.convert_centi_parameter(AP_PARAM_INT32);
1534
aparm.min_groundspeed.convert_centi_parameter(AP_PARAM_INT32);
1535
g.RTL_altitude.convert_centi_parameter(AP_PARAM_INT32);
1536
g.cruise_alt_floor.convert_centi_parameter(AP_PARAM_INT16);
1537
aparm.pitch_limit_max.convert_centi_parameter(AP_PARAM_INT16);
1538
aparm.pitch_limit_min.convert_centi_parameter(AP_PARAM_INT16);
1539
aparm.roll_limit.convert_centi_parameter(AP_PARAM_INT16);
1540
1541
landing.convert_parameters();
1542
1543
static const AP_Param::G2ObjectConversion g2_conversions[] {
1544
// PARAMETER_CONVERSION - Added: Oct-2021
1545
#if HAL_EFI_ENABLED
1546
{ &efi, efi.var_info, 22 },
1547
#endif
1548
#if AP_STATS_ENABLED
1549
// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6
1550
{ &stats, stats.var_info, 5 },
1551
#endif
1552
#if AP_SCRIPTING_ENABLED
1553
// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6
1554
{ &scripting, scripting.var_info, 14 },
1555
#endif
1556
#if AP_GRIPPER_ENABLED
1557
// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6
1558
{ &gripper, gripper.var_info, 12 },
1559
#endif
1560
};
1561
1562
AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));
1563
1564
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
1565
#if HAL_LOGGING_ENABLED
1566
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
1567
#endif
1568
1569
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
1570
#if AP_SERIALMANAGER_ENABLED
1571
// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6
1572
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
1573
#endif
1574
};
1575
1576
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
1577
}
1578
1579