#include "Plane.h"12#include <AP_Gripper/AP_Gripper.h>34/*5* ArduPlane parameter definitions6*7*/89const AP_Param::Info Plane::var_info[] = {10// @Param: FORMAT_VERSION11// @DisplayName: Eeprom format version number12// @Description: This value is incremented when changes are made to the eeprom format13// @User: Advanced14GSCALAR(format_version, "FORMAT_VERSION", 0),1516// SYSID_THISMAV was here1718// SYSID_MYGCS was here1920// AP_SerialManager was here2122// @Param: AUTOTUNE_LEVEL23// @DisplayName: Autotune level24// @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 values25// @Range: 0 1026// @Increment: 127// @User: Standard28ASCALAR(autotune_level, "AUTOTUNE_LEVEL", 6),2930// @Param: AUTOTUNE_OPTIONS31// @DisplayName: Autotune options bitmask32// @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.33// @Bitmask: 0: Disable FLTD update by Autotune34// @Bitmask: 1: Disable FLTT update by Autotune35// @User: Advanced36ASCALAR(autotune_options, "AUTOTUNE_OPTIONS", 0),3738// TELEM_DELAY was here3940// @Param: GCS_PID_MASK41// @DisplayName: GCS PID tuning mask42// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for43// @User: Advanced44// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ45GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),4647// @Param: KFF_RDDRMIX48// @DisplayName: Rudder Mix49// @Description: Amount of rudder to add during aileron movement. Increase if nose initially yaws away from roll. Reduces adverse yaw.50// @Range: 0 151// @Increment: 0.0152// @User: Standard53GSCALAR(kff_rudder_mix, "KFF_RDDRMIX", RUDDER_MIX),5455// @Param: KFF_THR2PTCH56// @DisplayName: Throttle to Pitch Mix57// @Description: Pitch up to add in proportion to throttle. 100% throttle will add this number of degrees to the pitch target.58// @Range: -5 559// @Increment: 0.0160// @User: Advanced61GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", 0),6263// @Param: STAB_PITCH_DOWN64// @DisplayName: Low throttle pitch down trim65// @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.66// @Range: 0 1567// @Increment: 0.168// @Units: deg69// @User: Advanced70GSCALAR(stab_pitch_down, "STAB_PITCH_DOWN", 2.0f),7172// @Param: ALT_SLOPE_MIN73// @DisplayName: Altitude slope minimum74// @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.75// @Range: 0 100076// @Increment: 177// @Units: m78// @User: Advanced79GSCALAR(alt_slope_min, "ALT_SLOPE_MIN", 15),8081// @Param: ALT_SLOPE_MAXHGT82// @DisplayName: Altitude slope maximum height83// @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.84// @Range: 0 10085// @Increment: 186// @Units: m87// @User: Advanced88GSCALAR(alt_slope_max_height, "ALT_SLOPE_MAXHGT", 5.0),8990// @Param: STICK_MIXING91// @DisplayName: Stick Mixing92// @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.93// @Values: 0:Disabled,1:FBW style,3:VTOL Yaw only,4:FBW style (no pitch)94// @User: Advanced95GSCALAR(stick_mixing, "STICK_MIXING", uint8_t(StickMixing::FBW)),9697// @Param: TKOFF_THR_MINSPD98// @DisplayName: Takeoff throttle min speed99// @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.100// @Units: m/s101// @Range: 0 30102// @Increment: 0.1103// @User: Standard104GSCALAR(takeoff_throttle_min_speed, "TKOFF_THR_MINSPD", 0),105106// @Param: TKOFF_THR_MINACC107// @DisplayName: Takeoff throttle min acceleration108// @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".109// @Units: m/s/s110// @Range: 0 30111// @Increment: 0.1112// @User: Standard113GSCALAR(takeoff_throttle_min_accel, "TKOFF_THR_MINACC", 0),114115// @Param: TKOFF_THR_DELAY116// @DisplayName: Takeoff throttle delay117// @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.118// @Units: ds119// @Range: 0 127120// @Increment: 1121// @User: Standard122GSCALAR(takeoff_throttle_delay, "TKOFF_THR_DELAY", 2),123124// @Param: TKOFF_THR_MAX_T125// @DisplayName: Takeoff throttle maximum time126// @Description: This sets the time that maximum throttle will be forced during a fixed wing takeoff.127// @Units: s128// @Range: 0 10129// @Increment: 0.5130// @User: Standard131ASCALAR(takeoff_throttle_max_t, "TKOFF_THR_MAX_T", 4),132133// @Param: TKOFF_THR_MIN134// @DisplayName: Takeoff minimum throttle135// @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.136// @Units: %137// @Range: 0 100138// @Increment: 1139// @User: Standard140ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),141142// @Param: TKOFF_THR_IDLE143// @DisplayName: Takeoff idle throttle144// @Description: The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes.145// @Units: %146// @Range: 0 100147// @Increment: 1148// @User: Standard149ASCALAR(takeoff_throttle_idle, "TKOFF_THR_IDLE", 0),150151// @Param: TKOFF_OPTIONS152// @DisplayName: Takeoff options153// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.154// @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.155// @User: Advanced156ASCALAR(takeoff_options, "TKOFF_OPTIONS", 0),157158// @Param: TKOFF_TDRAG_ELEV159// @DisplayName: Takeoff tail dragger elevator160// @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.161// @Units: %162// @Range: -100 100163// @Increment: 1164// @User: Standard165GSCALAR(takeoff_tdrag_elevator, "TKOFF_TDRAG_ELEV", 0),166167// @Param: TKOFF_TDRAG_SPD1168// @DisplayName: Takeoff tail dragger speed1169// @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.170// @Units: m/s171// @Range: 0 30172// @Increment: 0.1173// @User: Standard174GSCALAR(takeoff_tdrag_speed1, "TKOFF_TDRAG_SPD1", 0),175176// @Param: TKOFF_ROTATE_SPD177// @DisplayName: Takeoff rotate speed178// @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.179// @Units: m/s180// @Range: 0 30181// @Increment: 0.1182// @User: Standard183GSCALAR(takeoff_rotate_speed, "TKOFF_ROTATE_SPD", 0),184185// @Param: TKOFF_THR_SLEW186// @DisplayName: Takeoff throttle slew rate187// @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.188// @Units: %/s189// @Range: -1 127190// @Increment: 1191// @User: Standard192GSCALAR(takeoff_throttle_slewrate, "TKOFF_THR_SLEW", 0),193194// @Param: TKOFF_PLIM_SEC195// @DisplayName: Takeoff pitch limit reduction196// @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.197// @Units: s198// @Range: 0 10199// @Increment: 0.5200// @User: Advanced201GSCALAR(takeoff_pitch_limit_reduction_sec, "TKOFF_PLIM_SEC", 2),202203// @Param: TKOFF_FLAP_PCNT204// @DisplayName: Takeoff flap percentage205// @Description: The amount of flaps (as a percentage) to apply in automatic takeoff206// @Range: 0 100207// @Units: %208// @Increment: 1209// @User: Advanced210GSCALAR(takeoff_flap_percent, "TKOFF_FLAP_PCNT", 0),211212// @Param: LEVEL_ROLL_LIMIT213// @DisplayName: Level flight roll limit214// @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.215// @Units: deg216// @Range: 0 45217// @Increment: 1218// @User: Standard219GSCALAR(level_roll_limit, "LEVEL_ROLL_LIMIT", 5),220221// @Param: USE_REV_THRUST222// @DisplayName: Bitmask for when to allow negative reverse thrust223// @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.224// @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:THERMAL225// @User: Advanced226GSCALAR(use_reverse_thrust, "USE_REV_THRUST", float(UseReverseThrust::AUTO_LAND_APPROACH)),227228// @Param: ALT_OFFSET229// @DisplayName: Altitude offset230// @Description: This is added to the target altitude in automatic flight. It can be used to add a global altitude offset to a mission231// @Units: m232// @Range: -32767 32767233// @Increment: 1234// @User: Advanced235GSCALAR(alt_offset, "ALT_OFFSET", 0),236237// @Param: WP_RADIUS238// @DisplayName: Waypoint Radius239// @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.240// @Units: m241// @Range: 1 32767242// @Increment: 1243// @User: Standard244GSCALAR(waypoint_radius, "WP_RADIUS", WP_RADIUS_DEFAULT),245246// @Param: WP_MAX_RADIUS247// @DisplayName: Waypoint Maximum Radius248// @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.249// @Units: m250// @Range: 0 32767251// @Increment: 1252// @User: Standard253GSCALAR(waypoint_max_radius, "WP_MAX_RADIUS", 0),254255// @Param: WP_LOITER_RAD256// @DisplayName: Waypoint Loiter Radius257// @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.258// @Units: m259// @Range: -32767 32767260// @Increment: 1261// @User: Standard262ASCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),263264// @Param: RTL_RADIUS265// @DisplayName: RTL loiter radius266// @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.267// @Units: m268// @Range: -32767 32767269// @Increment: 1270// @User: Standard271GSCALAR(rtl_radius, "RTL_RADIUS", 0),272273// @Param: STALL_PREVENTION274// @DisplayName: Enable stall prevention275// @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.276// @Values: 0:Disabled,1:Enabled277// @User: Standard278ASCALAR(stall_prevention, "STALL_PREVENTION", 1),279280// @Param: AIRSPEED_CRUISE281// @DisplayName: Target cruise airspeed282// @Description: Target cruise airspeed in m/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.283// @Units: m/s284// @User: Standard285ASCALAR(airspeed_cruise, "AIRSPEED_CRUISE", AIRSPEED_CRUISE),286287// @Param: AIRSPEED_MIN288// @DisplayName: Minimum Airspeed289// @Description: Minimum airspeed demanded in automatic throttle modes. Should be set to 20% higher than level flight stall speed.290// @Units: m/s291// @Range: 5 100292// @Increment: 1293// @User: Standard294ASCALAR(airspeed_min, "AIRSPEED_MIN", AIRSPEED_FBW_MIN),295296// @Param: AIRSPEED_MAX297// @DisplayName: Maximum Airspeed298// @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.299// @Units: m/s300// @Range: 5 100301// @Increment: 1302// @User: Standard303ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX),304305// @Param: AIRSPEED_STALL306// @DisplayName: Stall airspeed307// @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.308// @Units: m/s309// @Range: 5 75310// @User: Standard311ASCALAR(airspeed_stall, "AIRSPEED_STALL", 0),312313// @Param: FBWB_ELEV_REV314// @DisplayName: Fly By Wire elevator reverse315// @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.316// @Values: 0:Disabled,1:Enabled317// @User: Standard318GSCALAR(flybywire_elev_reverse, "FBWB_ELEV_REV", 0),319320#if AP_TERRAIN_AVAILABLE321// @Param: TERRAIN_FOLLOW322// @DisplayName: Use terrain following323// @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.324// @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:AUTOLAND325// @User: Standard326GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),327328// @Param: TERRAIN_LOOKAHD329// @DisplayName: Terrain lookahead330// @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.331// @Range: 0 10000332// @Units: m333// @User: Standard334GSCALAR(terrain_lookahead, "TERRAIN_LOOKAHD", 2000),335#endif336337// @Param: FBWB_CLIMB_RATE338// @DisplayName: Fly By Wire B altitude change rate339// @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.340// @Range: 1 10341// @Units: m/s342// @Increment: 0.1343// @User: Standard344GSCALAR(flybywire_climb_rate, "FBWB_CLIMB_RATE", 2.0f),345346// @Param: THR_MIN347// @DisplayName: Minimum Throttle348// @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.349// @Units: %350// @Range: -100 100351// @Increment: 1352// @User: Standard353ASCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),354355// @Param: THR_MAX356// @DisplayName: Maximum Throttle357// @Description: Maximum throttle percentage used in all modes except manual, provided THR_PASS_STAB is not set.358// @Units: %359// @Range: 0 100360// @Increment: 1361// @User: Standard362ASCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),363364// @Param: TKOFF_THR_MAX365// @DisplayName: Maximum Throttle for takeoff366// @Description: The maximum throttle setting during automatic takeoff. If this is zero then THR_MAX is used for takeoff as well.367// @Units: %368// @Range: 0 100369// @Increment: 1370// @User: Advanced371ASCALAR(takeoff_throttle_max, "TKOFF_THR_MAX", 0),372373// @Param: THR_SLEWRATE374// @DisplayName: Throttle slew rate375// @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.376// @Units: %/s377// @Range: 0 127378// @Increment: 1379// @User: Standard380ASCALAR(throttle_slewrate, "THR_SLEWRATE", 100),381382// @Param: FLAP_SLEWRATE383// @DisplayName: Flap slew rate384// @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.385// @Units: %/s386// @Range: 0 100387// @Increment: 1388// @User: Advanced389GSCALAR(flap_slewrate, "FLAP_SLEWRATE", 75),390391// @Param: THR_SUPP_MAN392// @DisplayName: Throttle suppress manual passthru393// @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 takeoff394// @Values: 0:Disabled,1:Enabled395// @User: Advanced396GSCALAR(throttle_suppress_manual,"THR_SUPP_MAN", 0),397398// @Param: THR_PASS_STAB399// @DisplayName: Throttle passthru in stabilize400// @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.401// @Values: 0:Disabled,1:Enabled402// @User: Advanced403GSCALAR(throttle_passthru_stabilize,"THR_PASS_STAB", 0),404405// @Param: THR_FAILSAFE406// @DisplayName: Throttle and RC Failsafe Enable407// @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.408// @Values: 0:Disabled,1:Enabled,2:EnabledNoFailsafe409// @User: Standard410GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", int(ThrFailsafe::Enabled)),411412413// @Param: THR_FS_VALUE414// @DisplayName: Throttle Failsafe Value415// @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.416// @Range: 925 2200417// @Increment: 1418// @User: Standard419GSCALAR(throttle_fs_value, "THR_FS_VALUE", 950),420421// @Param: TRIM_THROTTLE422// @DisplayName: Throttle cruise percentage423// @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.424// @Units: %425// @Range: 0 100426// @Increment: 1427// @User: Standard428ASCALAR(throttle_cruise, "TRIM_THROTTLE", AP_PLANE_TRIM_THROTTLE_DEFAULT),429430// @Param: THROTTLE_NUDGE431// @DisplayName: Throttle nudge enable432// @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%.433// @Values: 0:Disabled,1:Enabled434// @User: Standard435GSCALAR(throttle_nudge, "THROTTLE_NUDGE", 1),436437// @Param: FS_SHORT_ACTN438// @DisplayName: Short failsafe action439// @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.440// @Values: 0:CIRCLE/no change(if already in AUTO|GUIDED|LOITER),1:CIRCLE,2:FBWA at zero throttle,3:Disable,4:FBWB441// @User: Standard442GSCALAR(fs_action_short, "FS_SHORT_ACTN", FS_ACTION_SHORT_BESTGUESS),443444// @Param: FS_LONG_ACTN445// @DisplayName: Long failsafe action446// @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.447// @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute,4:Auto,5:AUTOLAND448// @User: Standard449GSCALAR(fs_action_long, "FS_LONG_ACTN", FS_ACTION_LONG_CONTINUE),450451// @Param: FS_LONG_TIMEOUT452// @DisplayName: Long failsafe timeout453// @Description: The time in seconds that a failsafe condition has to persist before a long failsafe event will occur. This defaults to 5 seconds.454// @Units: s455// @Range: 1 300456// @Increment: 0.5457// @User: Standard458GSCALAR(fs_timeout_long, "FS_LONG_TIMEOUT", 5),459460// @Param: FS_GCS_ENABL461// @DisplayName: GCS failsafe enable462// @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.463// @Values: 0:Disabled,1:Heartbeat,2:HeartbeatAndREMRSSI,3:HeartbeatAndAUTO464// @User: Standard465GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL", GCS_FAILSAFE_OFF),466467// @Param: FLTMODE_CH468// @DisplayName: Flightmode channel469// @Description: RC Channel to use for flight mode control470// @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 16471// @User: Advanced472GSCALAR(flight_mode_channel, "FLTMODE_CH", FLIGHT_MODE_CHANNEL),473474// @Param: FLTMODE1475// @DisplayName: FlightMode1476// @Description: Flight mode for switch position 1 (910 to 1230 and above 2049)477// @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:AUTOLAND478// @User: Standard479GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),480481// @Param: FLTMODE2482// @CopyFieldsFrom: FLTMODE1483// @DisplayName: FlightMode2484// @Description: Flight mode for switch position 2 (1231 to 1360)485GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),486487// @Param: FLTMODE3488// @CopyFieldsFrom: FLTMODE1489// @DisplayName: FlightMode3490// @Description: Flight mode for switch position 3 (1361 to 1490)491GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),492493// @Param: FLTMODE4494// @CopyFieldsFrom: FLTMODE1495// @DisplayName: FlightMode4496// @Description: Flight mode for switch position 4 (1491 to 1620)497GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),498499// @Param: FLTMODE5500// @CopyFieldsFrom: FLTMODE1501// @DisplayName: FlightMode5502// @Description: Flight mode for switch position 5 (1621 to 1749)503GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),504505// @Param: FLTMODE6506// @CopyFieldsFrom: FLTMODE1507// @DisplayName: FlightMode6508// @Description: Flight mode for switch position 6 (1750 to 2049)509GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),510511// @Param: INITIAL_MODE512// @DisplayName: Initial flight mode513// @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.514// @CopyValuesFrom: FLTMODE1515// @User: Advanced516GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL),517518// @Param: ROLL_LIMIT_DEG519// @DisplayName: Maximum Bank Angle520// @Description: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls.521// @Units: deg522// @Range: 0 90523// @Increment: 1524// @User: Standard525ASCALAR(roll_limit, "ROLL_LIMIT_DEG", ROLL_LIMIT_DEG),526527// @Param: PTCH_LIM_MAX_DEG528// @DisplayName: Maximum Pitch Angle529// @Description: Maximum pitch up angle commanded in modes with stabilized limits.530// @Units: deg531// @Range: 0 90532// @Increment: 1533// @User: Standard534ASCALAR(pitch_limit_max, "PTCH_LIM_MAX_DEG", PITCH_MAX),535536// @Param: PTCH_LIM_MIN_DEG537// @DisplayName: Minimum Pitch Angle538// @Description: Maximum pitch down angle commanded in modes with stabilized limits539// @Units: deg540// @Range: -90 0541// @Increment: 1542// @User: Standard543ASCALAR(pitch_limit_min, "PTCH_LIM_MIN_DEG", PITCH_MIN),544545// @Param: ACRO_ROLL_RATE546// @DisplayName: ACRO mode roll rate547// @Description: The maximum roll rate at full stick deflection in ACRO mode548// @Units: deg/s549// @Range: 10 500550// @Increment: 1551// @User: Standard552GSCALAR(acro_roll_rate, "ACRO_ROLL_RATE", 180),553554// @Param: ACRO_PITCH_RATE555// @DisplayName: ACRO mode pitch rate556// @Description: The maximum pitch rate at full stick deflection in ACRO mode557// @Units: deg/s558// @Range: 10 500559// @Increment: 1560// @User: Standard561GSCALAR(acro_pitch_rate, "ACRO_PITCH_RATE", 180),562563// @Param: ACRO_YAW_RATE564// @DisplayName: ACRO mode yaw rate565// @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.566// @Units: deg/s567// @Range: 0 500568// @Increment: 1569// @User: Standard570GSCALAR(acro_yaw_rate, "ACRO_YAW_RATE", 0),571572// @Param: ACRO_LOCKING573// @DisplayName: ACRO mode attitude locking574// @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 attitude575// @Values: 0:Disabled,1:Enabled,2:Quaternion576// @User: Standard577GSCALAR(acro_locking, "ACRO_LOCKING", 0),578579// @Param: GROUND_STEER_ALT580// @DisplayName: Ground steer altitude581// @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.582// @Units: m583// @Range: -100 100584// @Increment: 0.1585// @User: Standard586GSCALAR(ground_steer_alt, "GROUND_STEER_ALT", 0),587588// @Param: GROUND_STEER_DPS589// @DisplayName: Ground steer rate590// @Description: Ground steering rate in degrees per second for full rudder stick deflection591// @Units: deg/s592// @Range: 10 360593// @Increment: 1594// @User: Advanced595GSCALAR(ground_steer_dps, "GROUND_STEER_DPS", 90),596597// @Param: MIXING_GAIN598// @DisplayName: Mixing Gain599// @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.600// @Range: 0.5 1.2601// @User: Standard602GSCALAR(mixing_gain, "MIXING_GAIN", 0.5f),603604// @Param: RUDDER_ONLY605// @DisplayName: Rudder only aircraft606// @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.607// @Values: 0:Disabled,1:Enabled608// @User: Standard609GSCALAR(rudder_only, "RUDDER_ONLY", 0),610611// @Param: MIXING_OFFSET612// @DisplayName: Mixing Offset613// @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.614// @Units: d%615// @Range: -1000 1000616// @User: Standard617GSCALAR(mixing_offset, "MIXING_OFFSET", 0),618619// @Param: DSPOILR_RUD_RATE620// @DisplayName: Differential spoilers rudder rate621// @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).622// @Units: %623// @Range: -100 100624// @User: Standard625GSCALAR(dspoiler_rud_rate, "DSPOILR_RUD_RATE", DSPOILR_RUD_RATE_DEFAULT),626627// @Param: LOG_BITMASK628// @DisplayName: Log bitmask629// @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.630// @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 Notch631// @User: Advanced632GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),633634// @Param: SCALING_SPEED635// @DisplayName: speed used for speed scaling calculations636// @Description: Airspeed in m/s to use when calculating surface speed scaling. Note that changing this value will affect all PID values637// @Units: m/s638// @Range: 0 50639// @Increment: 0.1640// @User: Advanced641GSCALAR(scaling_speed, "SCALING_SPEED", SCALING_SPEED),642643// @Param: MIN_GROUNDSPEED644// @DisplayName: Minimum ground speed645// @Description: Minimum ground speed when under airspeed control646// @Units: m/s647// @User: Advanced648ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED),649650// @Param: PTCH_TRIM_DEG651// @DisplayName: Pitch angle offset652// @Description: Offset in degrees used for in-flight pitch trimming for level flight. Correct ground leveling is an alternative to changing this parameter.653// @Units: deg654// @Range: -45 45655// @User: Standard656GSCALAR(pitch_trim, "PTCH_TRIM_DEG", 0.0f),657658// @Param: RTL_ALTITUDE659// @DisplayName: RTL altitude660// @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.661// @Units: m662// @User: Standard663GSCALAR(RTL_altitude, "RTL_ALTITUDE", ALT_HOLD_HOME),664665// @Param: CRUISE_ALT_FLOOR666// @DisplayName: Minimum altitude for FBWB and CRUISE mode667// @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.668// @Units: m669// @User: Standard670GSCALAR(cruise_alt_floor, "CRUISE_ALT_FLOOR", CRUISE_ALT_FLOOR),671672// @Param: FLAP_1_PERCNT673// @DisplayName: Flap 1 percentage674// @Description: The percentage change in flap position when FLAP_1_SPEED is reached. Use zero to disable flaps675// @Range: 0 100676// @Increment: 1677// @Units: %678// @User: Advanced679GSCALAR(flap_1_percent, "FLAP_1_PERCNT", FLAP_1_PERCENT),680681// @Param: FLAP_1_SPEED682// @DisplayName: Flap 1 speed683// @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_SPEED684// @Range: 0 100685// @Increment: 1686// @Units: m/s687// @User: Advanced688GSCALAR(flap_1_speed, "FLAP_1_SPEED", FLAP_1_SPEED),689690// @Param: FLAP_2_PERCNT691// @DisplayName: Flap 2 percentage692// @Description: The percentage change in flap position when FLAP_2_SPEED is reached. Use zero to disable flaps693// @Range: 0 100694// @Units: %695// @Increment: 1696// @User: Advanced697GSCALAR(flap_2_percent, "FLAP_2_PERCNT", FLAP_2_PERCENT),698699// @Param: FLAP_2_SPEED700// @DisplayName: Flap 2 speed701// @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_SPEED702// @Range: 0 100703// @Units: m/s704// @Increment: 1705// @User: Advanced706GSCALAR(flap_2_speed, "FLAP_2_SPEED", FLAP_2_SPEED),707708#if HAL_WITH_IO_MCU709// @Param: OVERRIDE_CHAN710// @DisplayName: IO override channel711// @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.712// @Range: 0 16713// @Increment: 1714// @User: Advanced715GSCALAR(override_channel, "OVERRIDE_CHAN", 0),716#endif717718// @Param: RTL_AUTOLAND719// @DisplayName: RTL auto land720// @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.721// @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 item722// @User: Standard723GSCALAR(rtl_autoland, "RTL_AUTOLAND", float(RtlAutoland::RTL_DISABLE)),724725// @Param: CRASH_ACC_THRESH726// @DisplayName: Crash Deceleration Threshold727// @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.728// @Units: m/s/s729// @Range: 10 127730// @Increment: 1731// @User: Advanced732GSCALAR(crash_accel_threshold, "CRASH_ACC_THRESH", 0),733734// @Param: CRASH_DETECT735// @DisplayName: Crash Detection736// @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.737// @Bitmask: 0:Disarm738// @User: Advanced739ASCALAR(crash_detection_enable, "CRASH_DETECT", 0),740741// @Group: BARO742// @Path: ../libraries/AP_Baro/AP_Baro.cpp743GOBJECT(barometer, "BARO", AP_Baro),744745// GPS driver746// @Group: GPS747// @Path: ../libraries/AP_GPS/AP_GPS.cpp748GOBJECT(gps, "GPS", AP_GPS),749750#if AP_CAMERA_ENABLED751// @Group: CAM752// @Path: ../libraries/AP_Camera/AP_Camera.cpp753GOBJECT(camera, "CAM", AP_Camera),754#endif755756// @Group: ARMING_757// @Path: AP_Arming_Plane.cpp,../libraries/AP_Arming/AP_Arming.cpp758GOBJECT(arming, "ARMING_", AP_Arming_Plane),759760#if AP_RELAY_ENABLED761// @Group: RELAY762// @Path: ../libraries/AP_Relay/AP_Relay.cpp763GOBJECT(relay, "RELAY", AP_Relay),764#endif765766#if HAL_PARACHUTE_ENABLED767// @Group: CHUTE_768// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp769GOBJECT(parachute, "CHUTE_", AP_Parachute),770#endif771772#if AP_RANGEFINDER_ENABLED773// @Group: RNGFND774// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp775GOBJECT(rangefinder, "RNGFND", RangeFinder),776777// @Param: RNGFND_LANDING778// @DisplayName: Enable use of rangefinder779// @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.780// @Bitmask: 0:All, 1:TakeoffAndLanding, 2:Assist, 3:InitialClimb781// @User: Standard782GSCALAR(rangefinder_landing, "RNGFND_LANDING", 0),783#endif784785#if AP_TERRAIN_AVAILABLE786// @Group: TERRAIN_787// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp788GOBJECT(terrain, "TERRAIN_", AP_Terrain),789#endif790791#if HAL_ADSB_ENABLED792// @Group: ADSB_793// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp794GOBJECT(adsb, "ADSB_", AP_ADSB),795#endif // HAL_ADSB_ENABLED796797#if AP_ADSB_AVOIDANCE_ENABLED798// @Group: AVD_799// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp800GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Plane),801#endif // AP_ADSB_AVOIDANCE_ENABLED802803#if HAL_QUADPLANE_ENABLED804// @Group: Q_805// @Path: quadplane.cpp806GOBJECT(quadplane, "Q_", QuadPlane),807#endif808809#if AP_TUNING_ENABLED810// @Group: TUNE_811// @Path: tuning.cpp,../libraries/AP_Tuning/AP_Tuning.cpp812GOBJECT(tuning, "TUNE_", AP_Tuning_Plane),813#endif814815#if HAL_QUADPLANE_ENABLED816// @Group: Q_A_817// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp818{ "Q_A_", (const void *)&plane.quadplane.attitude_control,819{group_info : AC_AttitudeControl_Multi::var_info}, AP_PARAM_FLAG_POINTER,820Parameters::k_param_q_attitude_control, AP_PARAM_GROUP },821#endif822823// @Group: RLL824// @Path: ../libraries/APM_Control/AP_RollController.cpp825GOBJECT(rollController, "RLL", AP_RollController),826827// @Group: PTCH828// @Path: ../libraries/APM_Control/AP_PitchController.cpp829GOBJECT(pitchController, "PTCH", AP_PitchController),830831// @Group: YAW832// @Path: ../libraries/APM_Control/AP_YawController.cpp833GOBJECT(yawController, "YAW", AP_YawController),834835// @Group: STEER2SRV_836// @Path: ../libraries/APM_Control/AP_SteerController.cpp837GOBJECT(steerController, "STEER2SRV_", AP_SteerController),838839// variables not in the g class which contain EEPROM saved variables840841// @Group: COMPASS_842// @Path: ../libraries/AP_Compass/AP_Compass.cpp843GOBJECT(compass, "COMPASS_", Compass),844845// @Group: SCHED_846// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp847GOBJECT(scheduler, "SCHED_", AP_Scheduler),848849// @Group: RCMAP_850// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp851GOBJECT(rcmap, "RCMAP_", RCMapper),852853// SR0 through SR6 were here854855// @Group: INS856// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp857GOBJECT(ins, "INS", AP_InertialSensor),858859// @Group: AHRS_860// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp861GOBJECT(ahrs, "AHRS_", AP_AHRS),862863// Airspeed was here864865// @Group: NAVL1_866// @Path: ../libraries/AP_L1_Control/AP_L1_Control.cpp867GOBJECT(L1_controller, "NAVL1_", AP_L1_Control),868869// @Group: TECS_870// @Path: ../libraries/AP_TECS/AP_TECS.cpp871GOBJECT(TECS_controller, "TECS_", AP_TECS),872873#if HAL_MOUNT_ENABLED874// @Group: MNT875// @Path: ../libraries/AP_Mount/AP_Mount.cpp876GOBJECT(camera_mount, "MNT", AP_Mount),877#endif878879// @Group: BATT880// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp881GOBJECT(battery, "BATT", AP_BattMonitor),882883// @Group: BRD_884// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp885GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),886887#if HAL_MAX_CAN_PROTOCOL_DRIVERS888// @Group: CAN_889// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp890GOBJECT(can_mgr, "CAN_", AP_CANManager),891#endif892893#if AP_SIM_ENABLED894// @Group: SIM_895// @Path: ../libraries/SITL/SITL.cpp896GOBJECT(sitl, "SIM_", SITL::SIM),897#endif898899#if AP_ADVANCEDFAILSAFE_ENABLED900// @Group: AFS_901// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp902GOBJECT(afs, "AFS_", AP_AdvancedFailsafe),903#endif904905#if AP_OPTICALFLOW_ENABLED906// @Group: FLOW907// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp908GOBJECT(optflow, "FLOW", AP_OpticalFlow),909#endif910911// @Group: MIS_912// @Path: ../libraries/AP_Mission/AP_Mission.cpp913GOBJECT(mission, "MIS_", AP_Mission),914915#if HAL_RALLY_ENABLED916// @Group: RALLY_917// @Path: ../libraries/AP_Rally/AP_Rally.cpp918GOBJECT(rally, "RALLY_", AP_Rally),919#endif920921#if HAL_NAVEKF2_AVAILABLE922// @Group: EK2_923// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp924GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),925#endif926927#if HAL_NAVEKF3_AVAILABLE928// @Group: EK3_929// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp930GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),931#endif932933#if AP_RSSI_ENABLED934// @Group: RSSI_935// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp936GOBJECT(rssi, "RSSI_", AP_RSSI),937#endif938939// @Group: NTF_940// @Path: ../libraries/AP_Notify/AP_Notify.cpp941GOBJECT(notify, "NTF_", AP_Notify),942943// @Group:944// @Path: Parameters.cpp945GOBJECT(g2, "", ParametersG2),946947// @Group: LAND_948// @Path: ../libraries/AP_Landing/AP_Landing.cpp949GOBJECT(landing, "LAND_", AP_Landing),950951#if OSD_ENABLED || OSD_PARAM_ENABLED952// @Group: OSD953// @Path: ../libraries/AP_OSD/AP_OSD.cpp954GOBJECT(osd, "OSD", AP_OSD),955#endif956957// @Group: TKOFF_958// @Path: mode_takeoff.cpp959GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff),960961#if MODE_AUTOLAND_ENABLED962// @Group: AUTOLAND_963// @Path: mode_autoland.cpp964GOBJECT(mode_autoland, "AUTOLAND_", ModeAutoLand),965#endif966967#if AP_PLANE_GLIDER_PULLUP_ENABLED968// @Group: PUP_969// @Path: pullup.cpp970GOBJECTN(mode_auto.pullup, pullup, "PUP_", GliderPullup),971#endif972973// @Group:974// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp975PARAM_VEHICLE_INFO,976977#if AP_QUICKTUNE_ENABLED978// @Group: QWIK_979// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp980GOBJECT(quicktune, "QWIK_", AP_Quicktune),981#endif982983#if HAL_GCS_ENABLED984// @Group: MAV985// @Path: ../libraries/GCS_MAVLink/GCS.cpp986GOBJECT(_gcs, "MAV", GCS),987#endif988989AP_VAREND990};991992/*9932nd group of parameters994*/995const AP_Param::GroupInfo ParametersG2::var_info[] = {996997#if HAL_BUTTON_ENABLED998// @Group: BTN_999// @Path: ../libraries/AP_Button/AP_Button.cpp1000AP_SUBGROUPPTR(button_ptr, "BTN_", 1, ParametersG2, AP_Button),1001#endif10021003#if AP_ICENGINE_ENABLED1004// @Group: ICE_1005// @Path: ../libraries/AP_ICEngine/AP_ICEngine.cpp1006AP_SUBGROUPINFO(ice_control, "ICE_", 2, ParametersG2, AP_ICEngine),1007#endif10081009// 3 was used by prototype for servo_channels10101011// 4 was used by SYSID_ENFORCE10121013// AP_Stats was 510141015// @Group: SERVO1016// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp1017AP_SUBGROUPINFO(servo_channels, "SERVO", 6, ParametersG2, SRV_Channels),10181019// @Group: RC1020// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h1021AP_SUBGROUPINFO(rc_channels, "RC", 7, ParametersG2, RC_Channels_Plane),10221023#if HAL_SOARING_ENABLED1024// @Group: SOAR_1025// @Path: ../libraries/AP_Soaring/AP_Soaring.cpp1026AP_SUBGROUPINFO(soaring_controller, "SOAR_", 8, ParametersG2, SoaringController),1027#endif10281029// @Param: RUDD_DT_GAIN1030// @DisplayName: rudder differential thrust gain1031// @Description: gain control from rudder to differential thrust1032// @Range: 0 1001033// @Units: %1034// @Increment: 11035// @User: Standard1036AP_GROUPINFO("RUDD_DT_GAIN", 9, ParametersG2, rudd_dt_gain, 10),10371038// @Param: MANUAL_RCMASK1039// @DisplayName: Manual R/C pass-through mask1040// @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.1041// @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:Chan161042// @User: Advanced1043AP_GROUPINFO("MANUAL_RCMASK", 10, ParametersG2, manual_rc_mask, 0),10441045// @Param: HOME_RESET_ALT1046// @DisplayName: Home reset altitude threshold1047// @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.1048// @Values: -1:Never reset,0:Always reset1049// @Range: -1 1271050// @Units: m1051// @User: Advanced1052AP_GROUPINFO("HOME_RESET_ALT", 11, ParametersG2, home_reset_threshold, 0),10531054// 12 was AP_Gripper10551056// @Param: FLIGHT_OPTIONS1057// @DisplayName: Flight mode options1058// @Description: Flight mode specific options1059// @Bitmask: 0: Rudder mixing in direct flight modes only (Manual/Stabilize/Acro)1060// @Bitmask: 1: Use centered throttle in Cruise or FBWB to indicate trim airspeed1061// @Bitmask: 2: Disable attitude check for takeoff arming1062// @Bitmask: 3: Force target airspeed to trim airspeed in Cruise or FBWB1063// @Bitmask: 4: Climb to RTL_ALTITUDE before turning for RTL1064// @Bitmask: 5: Enable yaw damper in acro mode1065// @Bitmask: 6: Suppress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airspeed sensor.1066// @Bitmask: 7: EnableDefaultAirspeed for takeoff1067// @Bitmask: 8: Remove the PTCH_TRIM_DEG on the GCS horizon1068// @Bitmask: 9: Remove the PTCH_TRIM_DEG on the OSD horizon1069// @Bitmask: 10: Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL1070// @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode1071// @Bitmask: 12: Enable FBWB style loiter altitude control1072// @Bitmask: 13: Indicate takeoff waiting for neutral rudder with flight control surfaces1073// @Bitmask: 14: In AUTO - climb to next waypoint altitude immediately instead of linear climb1074// @Bitmask: 15: Enable autoflap in manual modes and use minimum of target and actual speed for flap setting1075// @Bitmask: 16: Enable full aerodynamic load factor-based roll limits when an airspeed sensor is enabled and AIRSPEED_STALL is set1076// @User: Advanced1077AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),10781079// 14 was AP_Scripting10801081// @Param: TKOFF_ACCEL_CNT1082// @DisplayName: Takeoff throttle acceleration count1083// @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.1084// @Range: 1 101085// @User: Standard1086AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1),10871088#if AP_LANDINGGEAR_ENABLED1089// @Group: LGR_1090// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp1091AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),1092#endif10931094// @Param: DSPOILER_CROW_W11095// @DisplayName: Differential spoiler crow flaps outer weight1096// @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.1097// @Range: 0 1001098// @Units: %1099// @Increment: 11100// @User: Advanced1101AP_GROUPINFO("DSPOILER_CROW_W1", 17, ParametersG2, crow_flap_weight_outer, 0),11021103// @Param: DSPOILER_CROW_W21104// @DisplayName: Differential spoiler crow flaps inner weight1105// @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.1106// @Range: 0 1001107// @Units: %1108// @Increment: 11109// @User: Advanced1110AP_GROUPINFO("DSPOILER_CROW_W2", 18, ParametersG2, crow_flap_weight_inner, 0),11111112// @Param: TKOFF_TIMEOUT1113// @DisplayName: Takeoff timeout1114// @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.1115// @Range: 0 1201116// @Increment: 11117// @Units: s1118// @User: Standard1119AP_GROUPINFO("TKOFF_TIMEOUT", 19, ParametersG2, takeoff_timeout, 0),11201121// @Param: DSPOILER_OPTS1122// @DisplayName: Differential spoiler and crow flaps options1123// @Description: Differential spoiler and crow flaps options. Progressive crow flaps only first (0-50% flap in) then crow flaps (50 - 100% flap in).1124// @Bitmask: 0:Pitch input, 1:use both control surfaces on each wing for roll, 2:Progressive crow flaps1125// @User: Advanced1126AP_GROUPINFO("DSPOILER_OPTS", 20, ParametersG2, crow_flap_options, 3),11271128// @Param: DSPOILER_AILMTCH1129// @DisplayName: Differential spoiler aileron matching1130// @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 unaffected1131// @Range: 0 1001132// @Units: %1133// @Increment: 11134// @User: Advanced1135AP_GROUPINFO("DSPOILER_AILMTCH", 21, ParametersG2, crow_flap_aileron_matching, 100),113611371138// 22 was EFI11391140// @Param: FWD_BAT_VOLT_MAX1141// @DisplayName: Forward throttle battery voltage compensation maximum voltage1142// @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.1143// @Range: 6 351144// @Units: V1145// @Increment: 0.11146// @User: Advanced1147AP_GROUPINFO("FWD_BAT_VOLT_MAX", 23, ParametersG2, fwd_batt_cmp.batt_voltage_max, 0.0f),11481149// @Param: FWD_BAT_VOLT_MIN1150// @DisplayName: Forward throttle battery voltage compensation minimum voltage1151// @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.1152// @Range: 6 351153// @Units: V1154// @Increment: 0.11155// @User: Advanced1156AP_GROUPINFO("FWD_BAT_VOLT_MIN", 24, ParametersG2, fwd_batt_cmp.batt_voltage_min, 0.0f),11571158// @Param: FWD_BAT_IDX1159// @DisplayName: Forward throttle battery compensation index1160// @Description: Which battery monitor should be used for doing compensation for the forward throttle1161// @Values: 0:First battery, 1:Second battery1162// @Range: 0 151163// @User: Advanced1164AP_GROUPINFO("FWD_BAT_IDX", 25, ParametersG2, fwd_batt_cmp.batt_idx, 0),11651166// @Param: FS_EKF_THRESH1167// @DisplayName: EKF failsafe variance threshold1168// @Description: Allows setting the maximum acceptable compass and velocity variance used to check navigation health in VTOL modes1169// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed1170// @Range: 0.6 1.01171// @User: Advanced1172AP_GROUPINFO("FS_EKF_THRESH", 26, ParametersG2, fs_ekf_thresh, FS_EKF_THRESHOLD_DEFAULT),11731174// @Param: RTL_CLIMB_MIN1175// @DisplayName: RTL minimum climb1176// @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.1177// @Units: m1178// @Range: 0 301179// @Increment: 11180// @User: Standard1181AP_GROUPINFO("RTL_CLIMB_MIN", 27, ParametersG2, rtl_climb_min, 0),11821183#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED1184// @Group: GUIDED_1185// @Path: ../libraries/AC_PID/AC_PID.cpp1186AP_SUBGROUPINFO(guidedHeading, "GUIDED_", 28, ParametersG2, AC_PID),1187#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED11881189// @Param: MAN_EXPO_ROLL1190// @DisplayName: Manual control expo for roll1191// @Description: Percentage exponential for roll input in MANUAL, ACRO and TRAINING modes1192// @Range: 0 1001193// @Increment: 11194// @User: Standard1195AP_GROUPINFO("MAN_EXPO_ROLL", 29, ParametersG2, man_expo_roll, 0),11961197// @Param: MAN_EXPO_PITCH1198// @DisplayName: Manual input expo for pitch1199// @Description: Percentage exponential for pitch input in MANUAL, ACRO and TRAINING modes1200// @Range: 0 1001201// @Increment: 11202// @User: Standard1203AP_GROUPINFO("MAN_EXPO_PITCH", 30, ParametersG2, man_expo_pitch, 0),12041205// @Param: MAN_EXPO_RUDDER1206// @DisplayName: Manual input expo for rudder1207// @Description: Percentage exponential for rudder input in MANUAL, ACRO and TRAINING modes1208// @Range: 0 1001209// @Increment: 11210// @User: Standard1211AP_GROUPINFO("MAN_EXPO_RUDDER", 31, ParametersG2, man_expo_rudder, 0),12121213// @Param: ONESHOT_MASK1214// @DisplayName: Oneshot output mask1215// @Description: Mask of output channels to use oneshot on1216// @User: Advanced1217// @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 321218AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0),12191220#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED1221// @Group: FOLL1222// @Path: ../libraries/AP_Follow/AP_Follow.cpp1223AP_SUBGROUPINFO(follow, "FOLL", 33, ParametersG2, AP_Follow),1224#endif12251226// @Param: AUTOTUNE_AXES1227// @DisplayName: Autotune axis bitmask1228// @Description: 1-byte bitmap of axes to autotune1229// @Bitmask: 0:Roll,1:Pitch,2:Yaw1230// @User: Standard1231AP_GROUPINFO("AUTOTUNE_AXES", 34, ParametersG2, axis_bitmask, 7),12321233#if AC_PRECLAND_ENABLED1234// @Group: PLND_1235// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp1236AP_SUBGROUPINFO(precland, "PLND_", 35, ParametersG2, AC_PrecLand),1237#endif12381239#if AP_RANGEFINDER_ENABLED1240// @Param: RNGFND_LND_ORNT1241// @DisplayName: rangefinder landing orientation1242// @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.1243// @Values: 4:Back, 25:Down, 101:Custom1, 102:Custom21244// @User: Standard1245AP_GROUPINFO("RNGFND_LND_ORNT", 36, ParametersG2, rangefinder_land_orient, ROTATION_PITCH_270),1246#endif12471248// @Param: FWD_BAT_THR_CUT1249// @DisplayName: Forward throttle cutoff battery voltage1250// @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.1251// @Range: 0 351252// @Units: V1253// @Increment: 0.11254// @User: Standard1255AP_GROUPINFO("FWD_BAT_THR_CUT", 37, ParametersG2, fwd_batt_cmp.batt_voltage_throttle_cutoff, 0.0f),12561257#if AP_PLANE_SYSTEMID_ENABLED1258// @Group: SID1259// @Path: systemid.cpp1260AP_SUBGROUPINFO(systemid, "SID", 38, ParametersG2, AP_SystemID),1261#endif12621263// @Param: CLIMB_SLOPE_HGT1264// @DisplayName: Climb slope minimum height1265// @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.1266// @Units: m1267// @Range: 0 501268// @Increment: 11269// @User: Advanced1270AP_GROUPINFO("CLIMB_SLOPE_HGT", 39, ParametersG2, waypoint_climb_slope_height_min, 25),12711272// @Param: GUIDED_TIMEOUT1273// @DisplayName: Timeout for external guided command.1274// @Description: If external guided command was not received by this timeout, the vehicle will revert to regular GUIDED mode.1275// @Units: s1276// @Range: 0 101277// @Increment: 0.51278// @User: Advanced1279AP_GROUPINFO("GUIDED_TIMEOUT", 40, ParametersG2, guided_timeout, 3.0f),12801281AP_GROUPEND1282};12831284ParametersG2::ParametersG2(void) :1285unused_integer{1}1286#if HAL_BUTTON_ENABLED1287,button_ptr(&plane.button)1288#endif1289#if HAL_SOARING_ENABLED1290,soaring_controller(plane.TECS_controller, plane.aparm)1291#endif1292{1293AP_Param::setup_object_defaults(this, var_info);1294}12951296/*1297This is a conversion table from old parameter values to new1298parameter names. The startup code looks for saved values of the old1299parameters and will copy them across to the new parameters if the1300new parameter does not yet have a saved value. It then saves the new1301value.13021303Note that this works even if the old parameter has been removed. It1304relies on the old k_param index not being removed13051306The second column below is the index in the var_info[] table for the1307old object. This should be zero for top level parameters.1308*/1309static const AP_Param::ConversionInfo conversion_table[] = {1310{ Parameters::k_param_fence_minalt, 0, AP_PARAM_INT16, "FENCE_ALT_MIN"},1311{ Parameters::k_param_fence_maxalt, 0, AP_PARAM_INT16, "FENCE_ALT_MAX"},1312{ Parameters::k_param_fence_retalt, 0, AP_PARAM_INT16, "FENCE_RET_ALT"},1313{ Parameters::k_param_fence_ret_rally, 0, AP_PARAM_INT8, "FENCE_RET_RALLY"},1314{ Parameters::k_param_fence_autoenable, 0, AP_PARAM_INT8, "FENCE_AUTOENABLE"},1315};13161317struct RCConversionInfo {1318uint16_t old_key; // k_param_*1319uint32_t old_group_element; // index in old object1320RC_Channel::AUX_FUNC fun; // new function1321};13221323static const RCConversionInfo rc_option_conversion[] = {1324{ Parameters::k_param_flapin_channel_old, 0, RC_Channel::AUX_FUNC::FLAP},1325{ Parameters::k_param_g2, 968, RC_Channel::AUX_FUNC::SOARING},1326#if AP_FENCE_ENABLED1327{ Parameters::k_param_fence_channel, 0, RC_Channel::AUX_FUNC::FENCE},1328#endif1329#if AP_MISSION_ENABLED1330{ Parameters::k_param_reset_mission_chan, 0, RC_Channel::AUX_FUNC::MISSION_RESET},1331#endif1332#if HAL_PARACHUTE_ENABLED1333{ Parameters::k_param_parachute_channel, 0, RC_Channel::AUX_FUNC::PARACHUTE_RELEASE},1334#endif1335{ Parameters::k_param_fbwa_tdrag_chan, 0, RC_Channel::AUX_FUNC::FBWA_TAILDRAGGER},1336{ Parameters::k_param_reset_switch_chan, 0, RC_Channel::AUX_FUNC::MODE_SWITCH_RESET},1337};13381339void Plane::load_parameters(void)1340{1341AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);13421343AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));13441345// setup defaults in SRV_Channels1346g2.servo_channels.set_default_function(CH_1, SRV_Channel::k_aileron);1347g2.servo_channels.set_default_function(CH_2, SRV_Channel::k_elevator);1348g2.servo_channels.set_default_function(CH_3, SRV_Channel::k_throttle);1349g2.servo_channels.set_default_function(CH_4, SRV_Channel::k_rudder);13501351SRV_Channels::upgrade_parameters();13521353#if HAL_QUADPLANE_ENABLED1354if (quadplane.enable) {1355// quadplanes needs a higher loop rate1356AP_Param::set_default_by_name("SCHED_LOOP_RATE", 300);1357}1358#endif13591360AP_Param::set_frame_type_flags(AP_PARAM_FRAME_PLANE);13611362// Convert chan params to RCx_OPTION1363for (uint8_t i=0; i<ARRAY_SIZE(rc_option_conversion); i++) {1364AP_Int8 chan_param;1365AP_Param::ConversionInfo info {rc_option_conversion[i].old_key, rc_option_conversion[i].old_group_element, AP_PARAM_INT8, nullptr};1366if (AP_Param::find_old_parameter(&info, &chan_param) && chan_param.get() > 0) {1367RC_Channel *chan = rc().channel(chan_param.get() - 1);1368if (chan != nullptr && !chan->option.configured()) {1369chan->option.set_and_save((int16_t)rc_option_conversion[i].fun); // save the new param1370}1371}1372}137313741375// PARAMETER_CONVERSION - Added: March 2021 for ArduPlane-4.11376#if AP_FENCE_ENABLED1377enum ap_var_type ptype_fence_type;1378AP_Int8 *fence_type_new = (AP_Int8*)AP_Param::find("FENCE_TYPE", &ptype_fence_type);1379if (fence_type_new && !fence_type_new->configured()) {1380// If we find the new parameter and it hasn't been configured1381// attempt to upgrade the altitude fences.1382int8_t fence_type_new_val = AC_FENCE_TYPE_POLYGON;1383AP_Int16 fence_alt_min_old;1384AP_Param::ConversionInfo fence_alt_min_info_old = {1385Parameters::k_param_fence_minalt,13860,1387AP_PARAM_INT16,1388nullptr1389};1390if (AP_Param::find_old_parameter(&fence_alt_min_info_old, &fence_alt_min_old)) {1391if (fence_alt_min_old.configured()) {1392//1393fence_type_new_val |= AC_FENCE_TYPE_ALT_MIN;1394}1395}13961397AP_Int16 fence_alt_max_old;1398AP_Param::ConversionInfo fence_alt_max_info_old = {1399Parameters::k_param_fence_maxalt,14000,1401AP_PARAM_INT16,1402nullptr1403};1404if (AP_Param::find_old_parameter(&fence_alt_max_info_old, &fence_alt_max_old)) {1405if (fence_alt_max_old.configured()) {1406fence_type_new_val |= AC_FENCE_TYPE_ALT_MAX;1407}1408}14091410fence_type_new->set_and_save((int8_t)fence_type_new_val);1411}14121413AP_Int8 fence_action_old;1414AP_Param::ConversionInfo fence_action_info_old = {1415Parameters::k_param_fence_action,14160,1417AP_PARAM_INT8,1418"FENCE_ACTION"1419};1420if (AP_Param::find_old_parameter(&fence_action_info_old, &fence_action_old)) {1421enum ap_var_type ptype;1422AP_Int8 *fence_action_new = (AP_Int8*)AP_Param::find(&fence_action_info_old.new_name[0], &ptype);1423AC_Fence::Action fence_action_new_val;1424if (fence_action_new && !fence_action_new->configured()) {1425switch(fence_action_old.get()) {1426case 0: // FENCE_ACTION_NONE1427case 2: // FENCE_ACTION_REPORT_ONLY1428default:1429fence_action_new_val = AC_Fence::Action::REPORT_ONLY;1430break;1431case 1: // FENCE_ACTION_GUIDED1432fence_action_new_val = AC_Fence::Action::GUIDED;1433break;1434case 3: // FENCE_ACTION_GUIDED_THR_PASS1435fence_action_new_val = AC_Fence::Action::GUIDED_THROTTLE_PASS;1436break;1437case 4: // FENCE_ACTION_RTL1438fence_action_new_val = AC_Fence::Action::RTL_AND_LAND;1439break;1440}1441fence_action_new->set_and_save((int8_t)fence_action_new_val);14421443// Now upgrade the new fence enable at the same time1444enum ap_var_type ptype_fence_enable;1445AP_Int8 *fence_enable = (AP_Int8*)AP_Param::find("FENCE_ENABLE", &ptype_fence_enable);1446// fences were used if there was a count, and the old fence action was not zero1447AC_Fence *ap_fence = AP::fence();1448bool fences_exist = false;1449if (ap_fence) {1450// If the fence library is present, attempt to read the fence count1451fences_exist = ap_fence->polyfence().total_fence_count() > 0;1452}14531454bool fences_used = fence_action_old.get() != 0;1455if (fence_enable && !fence_enable->configured()) {1456// The fence enable parameter exists, so now set it accordingly1457fence_enable->set_and_save(fences_exist && fences_used);1458}1459}1460}1461#endif // AP_FENCE_ENABLED14621463#if AP_TERRAIN_AVAILABLE1464g.terrain_follow.convert_parameter_width(AP_PARAM_INT8);1465#endif14661467g.use_reverse_thrust.convert_parameter_width(AP_PARAM_INT16);14681469#if AP_AIRSPEED_ENABLED1470// PARAMETER_CONVERSION - Added: Jan-20221471{1472const uint16_t old_key = g.k_param_airspeed;1473const uint16_t old_index = 0; // Old parameter index in the tree1474AP_Param::convert_class(old_key, &airspeed, airspeed.var_info, old_index, true);1475}1476#endif14771478#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED1479#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 11480if (!ins.harmonic_notches[1].params.enabled()) {1481// notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch1482const AP_Param::ConversionInfo notchfilt_conversion_info[] {1483{ Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" },1484{ Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" },1485{ Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" },1486{ Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" },1487};1488AP_Param::convert_old_parameters(¬chfilt_conversion_info[0], ARRAY_SIZE(notchfilt_conversion_info));1489AP_Param::set_default_by_name("INS_HNTC2_MODE", 0);1490AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);1491}1492#endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS1493#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED14941495// PARAMETER_CONVERSION - Added: Mar-20221496#if AP_FENCE_ENABLED1497AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, true);1498#endif14991500// PARAMETER_CONVERSION - Added: July-2025 for ArduPilot-4.71501#if AP_RPM_ENABLED1502AP_Param::convert_class(g.k_param_rpm_sensor_old, &rpm_sensor, rpm_sensor.var_info, 0, true, true);1503#endif15041505// PARAMETER_CONVERSION - Added: Dec 20231506// Convert _CM (centimeter) parameters to meters and _CD (centidegrees) parameters to meters1507g.pitch_trim.convert_centi_parameter(AP_PARAM_INT16);1508aparm.airspeed_cruise.convert_centi_parameter(AP_PARAM_INT32);1509aparm.min_groundspeed.convert_centi_parameter(AP_PARAM_INT32);1510g.RTL_altitude.convert_centi_parameter(AP_PARAM_INT32);1511g.cruise_alt_floor.convert_centi_parameter(AP_PARAM_INT16);1512aparm.pitch_limit_max.convert_centi_parameter(AP_PARAM_INT16);1513aparm.pitch_limit_min.convert_centi_parameter(AP_PARAM_INT16);1514aparm.roll_limit.convert_centi_parameter(AP_PARAM_INT16);15151516landing.convert_parameters();15171518static const AP_Param::G2ObjectConversion g2_conversions[] {1519// PARAMETER_CONVERSION - Added: Oct-20211520#if HAL_EFI_ENABLED1521{ &efi, efi.var_info, 22 },1522#endif1523#if AP_STATS_ENABLED1524// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.61525{ &stats, stats.var_info, 5 },1526#endif1527#if AP_SCRIPTING_ENABLED1528// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.61529{ &scripting, scripting.var_info, 14 },1530#endif1531#if AP_GRIPPER_ENABLED1532// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.61533{ &gripper, gripper.var_info, 12 },1534#endif1535};15361537AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));15381539// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.61540#if HAL_LOGGING_ENABLED1541AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);1542#endif15431544static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {1545#if AP_SERIALMANAGER_ENABLED1546// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.61547{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },1548#endif1549};15501551AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));15521553#if HAL_GCS_ENABLED1554// Move parameters into new MAV_ parameter namespace1555// PARAMETER_CONVERSION - Added: Mar-2025 for ArduPilot-4.71556{1557static const AP_Param::ConversionInfo gcs_conversion_info[] {1558{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },1559{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },1560{ Parameters::k_param_g2, 4, AP_PARAM_INT8, "MAV_OPTIONS" },1561{ Parameters::k_param_telem_delay_old, 0, AP_PARAM_INT8, "MAV_TELEM_DELAY" },1562};1563AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));1564}1565#endif // HAL_GCS_ENABLED1566}156715681569