APM:Copter
Parameters.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 /*
19  * ArduCopter parameter definitions
20  *
21  */
22 
23 #define GSCALAR(v, name, def) { copter.g.v.vtype, name, Parameters::k_param_ ## v, &copter.g.v, {def_value : def} }
24 #define ASCALAR(v, name, def) { copter.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&copter.aparm.v, {def_value : def} }
25 #define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &copter.g.v, {group_info : class::var_info} }
26 #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info} }
27 #define GOBJECTPTR(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info}, AP_PARAM_FLAG_POINTER }
28 #define GOBJECTVARPTR(v, name, var_info_ptr) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info_ptr : var_info_ptr}, AP_PARAM_FLAG_POINTER | AP_PARAM_FLAG_INFO_POINTER }
29 #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&copter.v, {group_info : class::var_info} }
30 
32  // @Param: SYSID_SW_MREV
33  // @DisplayName: Eeprom format version number
34  // @Description: This value is incremented when changes are made to the eeprom format
35  // @User: Advanced
36  // @ReadOnly: True
37  GSCALAR(format_version, "SYSID_SW_MREV", 0),
38 
39  // @Param: SYSID_SW_TYPE
40  // @DisplayName: Software Type
41  // @Description: This is used by the ground station to recognise the software type (eg ArduPlane vs ArduCopter)
42  // @Values: 0:ArduPlane,4:AntennaTracker,10:Copter,20:Rover,40:ArduSub
43  // @User: Advanced
44  // @ReadOnly: True
45  GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
46 
47  // @Param: SYSID_THISMAV
48  // @DisplayName: MAVLink system ID of this vehicle
49  // @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
50  // @Range: 1 255
51  // @User: Advanced
52  GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
53 
54  // @Param: SYSID_MYGCS
55  // @DisplayName: My ground station number
56  // @Description: Allows restricting radio overrides to only come from my ground station
57  // @Values: 255:Mission Planner and DroidPlanner, 252: AP Planner 2
58  // @User: Advanced
59  GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
60 
61  // @Param: PILOT_THR_FILT
62  // @DisplayName: Throttle filter cutoff
63  // @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
64  // @User: Advanced
65  // @Units: Hz
66  // @Range: 0 10
67  // @Increment: .5
68  GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),
69 
70  // @Param: PILOT_TKOFF_ALT
71  // @DisplayName: Pilot takeoff altitude
72  // @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.
73  // @User: Standard
74  // @Units: cm
75  // @Range: 0.0 1000.0
76  // @Increment: 10
77  GSCALAR(pilot_takeoff_alt, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT),
78 
79  // @Param: PILOT_TKOFF_DZ
80  // @DisplayName: Takeoff trigger deadzone
81  // @Description: Offset from mid stick at which takeoff is triggered
82  // @User: Standard
83  // @Range: 0 500
84  // @Increment: 10
85  GSCALAR(takeoff_trigger_dz, "PILOT_TKOFF_DZ", THR_DZ_DEFAULT),
86 
87  // @Param: PILOT_THR_BHV
88  // @DisplayName: Throttle stick behavior
89  // @Description: Bitmask containing various throttle stick options. Add up the values for options that you want.
90  // @User: Standard
91  // @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection
92  // @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
93  GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),
94 
95  // @Group: SERIAL
96  // @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
97  GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
98 
99  // @Param: TELEM_DELAY
100  // @DisplayName: Telemetry startup delay
101  // @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
102  // @User: Advanced
103  // @Units: s
104  // @Range: 0 30
105  // @Increment: 1
106  GSCALAR(telem_delay, "TELEM_DELAY", 0),
107 
108  // @Param: GCS_PID_MASK
109  // @DisplayName: GCS PID tuning mask
110  // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
111  // @User: Advanced
112  // @Values: 0:None,1:Roll,2:Pitch,4:Yaw
113  // @Bitmask: 0:Roll,1:Pitch,2:Yaw
114  GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
115 
116 #if MODE_RTL_ENABLED == ENABLED
117  // @Param: RTL_ALT
118  // @DisplayName: RTL Altitude
119  // @Description: The minimum relative altitude the model will move to before Returning to Launch. Set to zero to return at current altitude.
120  // @Units: cm
121  // @Range: 0 8000
122  // @Increment: 1
123  // @User: Standard
124  GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT),
125 
126  // @Param: RTL_CONE_SLOPE
127  // @DisplayName: RTL cone slope
128  // @Description: Defines a cone above home which determines maximum climb
129  // @Range: 0.5 10.0
130  // @Increment: .1
131  // @Values: 0:Disabled,1:Shallow,3:Steep
132  // @User: Standard
133  GSCALAR(rtl_cone_slope, "RTL_CONE_SLOPE", RTL_CONE_SLOPE_DEFAULT),
134 
135  // @Param: RTL_SPEED
136  // @DisplayName: RTL speed
137  // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.
138  // @Units: cm/s
139  // @Range: 0 2000
140  // @Increment: 50
141  // @User: Standard
142  GSCALAR(rtl_speed_cms, "RTL_SPEED", 0),
143 
144  // @Param: RTL_ALT_FINAL
145  // @DisplayName: RTL Final Altitude
146  // @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission. Set to zero to land.
147  // @Units: cm
148  // @Range: -1 1000
149  // @Increment: 1
150  // @User: Standard
151  GSCALAR(rtl_alt_final, "RTL_ALT_FINAL", RTL_ALT_FINAL),
152 
153  // @Param: RTL_CLIMB_MIN
154  // @DisplayName: RTL minimum climb
155  // @Description: The vehicle will climb this many cm during the initial climb portion of the RTL
156  // @Units: cm
157  // @Range: 0 3000
158  // @Increment: 10
159  // @User: Standard
160  GSCALAR(rtl_climb_min, "RTL_CLIMB_MIN", RTL_CLIMB_MIN_DEFAULT),
161 
162  // @Param: RTL_LOIT_TIME
163  // @DisplayName: RTL loiter time
164  // @Description: Time (in milliseconds) to loiter above home before beginning final descent
165  // @Units: ms
166  // @Range: 0 60000
167  // @Increment: 1000
168  // @User: Standard
169  GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME),
170 #endif
171 
172 #if RANGEFINDER_ENABLED == ENABLED
173  // @Param: RNGFND_GAIN
174  // @DisplayName: Rangefinder gain
175  // @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter
176  // @Range: 0.01 2.0
177  // @Increment: 0.01
178  // @User: Standard
179  GSCALAR(rangefinder_gain, "RNGFND_GAIN", RANGEFINDER_GAIN_DEFAULT),
180 #endif
181 
182  // @Param: FS_GCS_ENABLE
183  // @DisplayName: Ground Station Failsafe Enable
184  // @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. NB. The GCS Failsafe is only active when RC_OVERRIDE is being used to control the vehicle.
185  // @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always SmartRTL or RTL,4:Enabled always SmartRTL or Land
186  // @User: Standard
187  GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_ENABLED_ALWAYS_RTL),
188 
189  // @Param: GPS_HDOP_GOOD
190  // @DisplayName: GPS Hdop Good
191  // @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks
192  // @Range: 100 900
193  // @User: Advanced
194  GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),
195 
196  // @Param: MAG_ENABLE
197  // @DisplayName: Compass enable/disable
198  // @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass
199  // @Values: 0:Disabled,1:Enabled
200  // @User: Standard
201  GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
202 
203  // @Param: SUPER_SIMPLE
204  // @DisplayName: Super Simple Mode
205  // @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
206  // @Values: 0:Disabled,1:Mode1,2:Mode2,3:Mode1+2,4:Mode3,5:Mode1+3,6:Mode2+3,7:Mode1+2+3,8:Mode4,9:Mode1+4,10:Mode2+4,11:Mode1+2+4,12:Mode3+4,13:Mode1+3+4,14:Mode2+3+4,15:Mode1+2+3+4,16:Mode5,17:Mode1+5,18:Mode2+5,19:Mode1+2+5,20:Mode3+5,21:Mode1+3+5,22:Mode2+3+5,23:Mode1+2+3+5,24:Mode4+5,25:Mode1+4+5,26:Mode2+4+5,27:Mode1+2+4+5,28:Mode3+4+5,29:Mode1+3+4+5,30:Mode2+3+4+5,31:Mode1+2+3+4+5,32:Mode6,33:Mode1+6,34:Mode2+6,35:Mode1+2+6,36:Mode3+6,37:Mode1+3+6,38:Mode2+3+6,39:Mode1+2+3+6,40:Mode4+6,41:Mode1+4+6,42:Mode2+4+6,43:Mode1+2+4+6,44:Mode3+4+6,45:Mode1+3+4+6,46:Mode2+3+4+6,47:Mode1+2+3+4+6,48:Mode5+6,49:Mode1+5+6,50:Mode2+5+6,51:Mode1+2+5+6,52:Mode3+5+6,53:Mode1+3+5+6,54:Mode2+3+5+6,55:Mode1+2+3+5+6,56:Mode4+5+6,57:Mode1+4+5+6,58:Mode2+4+5+6,59:Mode1+2+4+5+6,60:Mode3+4+5+6,61:Mode1+3+4+5+6,62:Mode2+3+4+5+6,63:Mode1+2+3+4+5+6
207  // @User: Standard
208  GSCALAR(super_simple, "SUPER_SIMPLE", 0),
209 
210  // @Param: WP_YAW_BEHAVIOR
211  // @DisplayName: Yaw behaviour during missions
212  // @Description: Determines how the autopilot controls the yaw during missions and RTL
213  // @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course
214  // @User: Standard
215  GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),
216 
217  // @Param: LAND_SPEED
218  // @DisplayName: Land speed
219  // @Description: The descent speed for the final stage of landing in cm/s
220  // @Units: cm/s
221  // @Range: 30 200
222  // @Increment: 10
223  // @User: Standard
224  GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),
225 
226  // @Param: LAND_SPEED_HIGH
227  // @DisplayName: Land speed high
228  // @Description: The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used
229  // @Units: cm/s
230  // @Range: 0 500
231  // @Increment: 10
232  // @User: Standard
233  GSCALAR(land_speed_high, "LAND_SPEED_HIGH", 0),
234 
235  // @Param: PILOT_SPEED_UP
236  // @DisplayName: Pilot maximum vertical speed ascending
237  // @Description: The maximum vertical ascending velocity the pilot may request in cm/s
238  // @Units: cm/s
239  // @Range: 50 500
240  // @Increment: 10
241  // @User: Standard
242  GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX),
243 
244  // @Param: PILOT_ACCEL_Z
245  // @DisplayName: Pilot vertical acceleration
246  // @Description: The vertical acceleration used when pilot is controlling the altitude
247  // @Units: cm/s/s
248  // @Range: 50 500
249  // @Increment: 10
250  // @User: Standard
251  GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),
252 
253  // @Param: FS_THR_ENABLE
254  // @DisplayName: Throttle Failsafe Enable
255  // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
256  // @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land
257  // @User: Standard
258  GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL),
259 
260  // @Param: FS_THR_VALUE
261  // @DisplayName: Throttle Failsafe Value
262  // @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers
263  // @Range: 925 1100
264  // @Units: PWM
265  // @Increment: 1
266  // @User: Standard
267  GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
268 
269  // @Param: THR_DZ
270  // @DisplayName: Throttle deadzone
271  // @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
272  // @User: Standard
273  // @Range: 0 300
274  // @Units: PWM
275  // @Increment: 1
276  GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),
277 
278  // @Param: FLTMODE1
279  // @DisplayName: Flight Mode 1
280  // @Description: Flight mode when Channel 5 pwm is <= 1230
281  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow
282  // @User: Standard
283  GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
284 
285  // @Param: FLTMODE2
286  // @DisplayName: Flight Mode 2
287  // @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
288  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow
289  // @User: Standard
290  GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
291 
292  // @Param: FLTMODE3
293  // @DisplayName: Flight Mode 3
294  // @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
295  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow
296  // @User: Standard
297  GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
298 
299  // @Param: FLTMODE4
300  // @DisplayName: Flight Mode 4
301  // @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
302  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow
303  // @User: Standard
304  GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
305 
306  // @Param: FLTMODE5
307  // @DisplayName: Flight Mode 5
308  // @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
309  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow
310  // @User: Standard
311  GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
312 
313  // @Param: FLTMODE6
314  // @DisplayName: Flight Mode 6
315  // @Description: Flight mode when Channel 5 pwm is >=1750
316  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow
317  // @User: Standard
318  GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
319 
320  // @Param: FLTMODE_CH
321  // @DisplayName: Flightmode channel
322  // @Description: RC Channel to use for flight mode control
323  // @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8
324  // @User: Advanced
325  GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT),
326 
327  // @Param: SIMPLE
328  // @DisplayName: Simple mode bitmask
329  // @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode)
330  // @User: Advanced
331  GSCALAR(simple_modes, "SIMPLE", 0),
332 
333  // @Param: LOG_BITMASK
334  // @DisplayName: Log bitmask
335  // @Description: 4 byte bitmap of log types to enable
336  // @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,397310:All+FastIMU+PID,655358:All+FullIMU,0:Disabled
337  // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW
338  // @User: Standard
339  GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
340 
341  // @Param: ESC_CALIBRATION
342  // @DisplayName: ESC Calibration
343  // @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
344  // @User: Advanced
345  // @Values: 0:Normal Start-up, 1:Start-up in ESC Calibration mode if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle, 3:Start-up and automatically calibrate ESCs, 9:Disabled
346  GSCALAR(esc_calibrate, "ESC_CALIBRATION", 0),
347 
348  // @Param: TUNE
349  // @DisplayName: Channel 6 Tuning
350  // @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
351  // @User: Standard
352  // @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,41:RangeFinder Gain,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,57:Winch
353  GSCALAR(radio_tuning, "TUNE", 0),
354 
355  // @Param: TUNE_LOW
356  // @DisplayName: Tuning minimum
357  // @Description: The minimum value that will be applied to the parameter currently being tuned with the transmitter's channel 6 knob
358  // @User: Standard
359  // @Range: 0 32767
360  GSCALAR(radio_tuning_low, "TUNE_LOW", 0),
361 
362  // @Param: TUNE_HIGH
363  // @DisplayName: Tuning maximum
364  // @Description: The maximum value that will be applied to the parameter currently being tuned with the transmitter's channel 6 knob
365  // @User: Standard
366  // @Range: 0 32767
367  GSCALAR(radio_tuning_high, "TUNE_HIGH", 1000),
368 
369  // @Param: FRAME_TYPE
370  // @DisplayName: Frame Type (+, X, V, etc)
371  // @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
372  // @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B
373  // @User: Standard
374  // @RebootRequired: True
375  GSCALAR(frame_type, "FRAME_TYPE", AP_Motors::MOTOR_FRAME_TYPE_X),
376 
377  // @Param: CH7_OPT
378  // @DisplayName: Channel 7 option
379  // @Description: Select which function is performed when CH7 is above 1800 pwm
380  // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
381  // @User: Standard
382  GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
383 
384  // @Param: CH8_OPT
385  // @DisplayName: Channel 8 option
386  // @Description: Select which function is performed when CH8 is above 1800 pwm
387  // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
388  // @User: Standard
389  GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
390 
391  // @Param: CH9_OPT
392  // @DisplayName: Channel 9 option
393  // @Description: Select which function is performed when CH9 is above 1800 pwm
394  // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
395  // @User: Standard
396  GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
397 
398  // @Param: CH10_OPT
399  // @DisplayName: Channel 10 option
400  // @Description: Select which function is performed when CH10 is above 1800 pwm
401  // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
402  // @User: Standard
403  GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
404 
405  // @Param: CH11_OPT
406  // @DisplayName: Channel 11 option
407  // @Description: Select which function is performed when CH11 is above 1800 pwm
408  // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
409  // @User: Standard
410  GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
411 
412  // @Param: CH12_OPT
413  // @DisplayName: Channel 12 option
414  // @Description: Select which function is performed when CH12 is above 1800 pwm
415  // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
416  // @User: Standard
417  GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
418 
419  // @Group: ARMING_
420  // @Path: ../libraries/AP_Arming/AP_Arming.cpp
421  GOBJECT(arming, "ARMING_", AP_Arming_Copter),
422 
423  // @Param: DISARM_DELAY
424  // @DisplayName: Disarm delay
425  // @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm.
426  // @Units: s
427  // @Range: 0 127
428  // @User: Advanced
429  GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),
430 
431  // @Param: ANGLE_MAX
432  // @DisplayName: Angle Max
433  // @Description: Maximum lean angle in all flight modes
434  // @Units: cdeg
435  // @Range: 1000 8000
436  // @User: Advanced
437  ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),
438 
439  // @Param: PHLD_BRAKE_RATE
440  // @DisplayName: PosHold braking rate
441  // @Description: PosHold flight mode's rotation rate during braking in deg/sec
442  // @Units: deg/s
443  // @Range: 4 12
444  // @User: Advanced
445  GSCALAR(poshold_brake_rate, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT),
446 
447  // @Param: PHLD_BRAKE_ANGLE
448  // @DisplayName: PosHold braking angle max
449  // @Description: PosHold flight mode's max lean angle during braking in centi-degrees
450  // @Units: cdeg
451  // @Range: 2000 4500
452  // @User: Advanced
453  GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),
454 
455  // @Param: LAND_REPOSITION
456  // @DisplayName: Land repositioning
457  // @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
458  // @Values: 0:No repositioning, 1:Repositioning
459  // @User: Advanced
460  GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),
461 
462  // @Param: FS_EKF_ACTION
463  // @DisplayName: EKF Failsafe Action
464  // @Description: Controls the action that will be taken when an EKF failsafe is invoked
465  // @Values: 1:Land, 2:AltHold, 3:Land even in Stabilize
466  // @User: Advanced
467  GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),
468 
469  // @Param: FS_EKF_THRESH
470  // @DisplayName: EKF failsafe variance threshold
471  // @Description: Allows setting the maximum acceptable compass and velocity variance
472  // @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
473  // @User: Advanced
474  GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),
475 
476  // @Param: FS_CRASH_CHECK
477  // @DisplayName: Crash check enable
478  // @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
479  // @Values: 0:Disabled, 1:Enabled
480  // @User: Advanced
481  GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 1),
482 
483  // @Param: RC_SPEED
484  // @DisplayName: ESC Update Speed
485  // @Description: This is the speed in Hertz that your ESCs will receive updates
486  // @Units: Hz
487  // @Range: 50 490
488  // @Increment: 1
489  // @User: Advanced
490  GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),
491 
492  // @Param: ACRO_RP_P
493  // @DisplayName: Acro Roll and Pitch P gain
494  // @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
495  // @Range: 1 10
496  // @User: Standard
497  GSCALAR(acro_rp_p, "ACRO_RP_P", ACRO_RP_P),
498 
499  // @Param: ACRO_YAW_P
500  // @DisplayName: Acro Yaw P gain
501  // @Description: Converts pilot yaw input into a desired rate of rotation in ACRO, Stabilize and SPORT modes. Higher values mean faster rate of rotation.
502  // @Range: 1 10
503  // @User: Standard
504  GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),
505 
506 #if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
507  // @Param: ACRO_BAL_ROLL
508  // @DisplayName: Acro Balance Roll
509  // @Description: rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster.
510  // @Range: 0 3
511  // @Increment: 0.1
512  // @User: Advanced
513  GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),
514 
515  // @Param: ACRO_BAL_PITCH
516  // @DisplayName: Acro Balance Pitch
517  // @Description: rate at which pitch angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster.
518  // @Range: 0 3
519  // @Increment: 0.1
520  // @User: Advanced
521  GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
522 #endif
523 
524 #if MODE_ACRO_ENABLED == ENABLED
525  // @Param: ACRO_TRAINER
526  // @DisplayName: Acro Trainer
527  // @Description: Type of trainer used in acro mode
528  // @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
529  // @User: Advanced
530  GSCALAR(acro_trainer, "ACRO_TRAINER", ACRO_TRAINER_LIMITED),
531 
532  // @Param: ACRO_RP_EXPO
533  // @DisplayName: Acro Roll/Pitch Expo
534  // @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges
535  // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
536  // @Range: -0.5 1.0
537  // @User: Advanced
538  GSCALAR(acro_rp_expo, "ACRO_RP_EXPO", ACRO_RP_EXPO_DEFAULT),
539 #endif
540 
541  // variables not in the g class which contain EEPROM saved variables
542 
543 #if CAMERA == ENABLED
544  // @Group: CAM_
545  // @Path: ../libraries/AP_Camera/AP_Camera.cpp
546  GOBJECT(camera, "CAM_", AP_Camera),
547 #endif
548 
549  // @Group: RELAY_
550  // @Path: ../libraries/AP_Relay/AP_Relay.cpp
551  GOBJECT(relay, "RELAY_", AP_Relay),
552 
553 #if PARACHUTE == ENABLED
554  // @Group: CHUTE_
555  // @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
556  GOBJECT(parachute, "CHUTE_", AP_Parachute),
557 #endif
558 
559  // @Group: LGR_
560  // @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
561  GOBJECT(landinggear, "LGR_", AP_LandingGear),
562 
563 #if FRAME_CONFIG == HELI_FRAME
564  // @Group: IM_
565  // @Path: ../libraries/AC_InputManager/AC_InputManager_Heli.cpp
566  GOBJECT(input_manager, "IM_", AC_InputManager_Heli),
567 #endif
568 
569  // @Group: COMPASS_
570  // @Path: ../libraries/AP_Compass/AP_Compass.cpp
571  GOBJECT(compass, "COMPASS_", Compass),
572 
573  // @Group: INS_
574  // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
575  GOBJECT(ins, "INS_", AP_InertialSensor),
576 
577  // @Group: WPNAV_
578  // @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
579  GOBJECTPTR(wp_nav, "WPNAV_", AC_WPNav),
580 
581  // @Group: LOIT_
582  // @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
583  GOBJECTPTR(loiter_nav, "LOIT_", AC_Loiter),
584 
585 #if MODE_CIRCLE_ENABLED == ENABLED
586  // @Group: CIRCLE_
587  // @Path: ../libraries/AC_WPNav/AC_Circle.cpp
588  GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),
589 #endif
590 
591  // @Group: ATC_
592  // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
593 #if FRAME_CONFIG == HELI_FRAME
594  GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Heli),
595 #else
596  GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
597 #endif
598 
599  // @Group: PSC
600  // @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
601  GOBJECTPTR(pos_control, "PSC", AC_PosControl),
602 
603  // @Group: SR0_
604  // @Path: GCS_Mavlink.cpp
605  GOBJECTN(_gcs._chan[0], gcs0, "SR0_", GCS_MAVLINK),
606 
607  // @Group: SR1_
608  // @Path: GCS_Mavlink.cpp
609  GOBJECTN(_gcs._chan[1], gcs1, "SR1_", GCS_MAVLINK),
610 
611  // @Group: SR2_
612  // @Path: GCS_Mavlink.cpp
613  GOBJECTN(_gcs._chan[2], gcs2, "SR2_", GCS_MAVLINK),
614 
615  // @Group: SR3_
616  // @Path: GCS_Mavlink.cpp
617  GOBJECTN(_gcs._chan[3], gcs3, "SR3_", GCS_MAVLINK),
618 
619  // @Group: AHRS_
620  // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
621  GOBJECT(ahrs, "AHRS_", AP_AHRS),
622 
623 #if MOUNT == ENABLED
624  // @Group: MNT
625  // @Path: ../libraries/AP_Mount/AP_Mount.cpp
626  GOBJECT(camera_mount, "MNT", AP_Mount),
627 #endif
628 
629  // @Group: LOG
630  // @Path: ../libraries/DataFlash/DataFlash.cpp
632 
633  // @Group: BATT
634  // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
635  GOBJECT(battery, "BATT", AP_BattMonitor),
636 
637  // @Group: BRD_
638  // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
639  GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
640 
641 #if HAL_WITH_UAVCAN
642  // @Group: CAN_
643  // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp
644  GOBJECT(BoardConfig_CAN, "CAN_", AP_BoardConfig_CAN),
645 #endif
646 
647 #if SPRAYER == ENABLED
648  // @Group: SPRAY_
649  // @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
650  GOBJECT(sprayer, "SPRAY_", AC_Sprayer),
651 #endif
652 
653 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
654  GOBJECT(sitl, "SIM_", SITL::SITL),
655 #endif
656 
657  // @Group: GND_
658  // @Path: ../libraries/AP_Baro/AP_Baro.cpp
659  GOBJECT(barometer, "GND_", AP_Baro),
660 
661  // GPS driver
662  // @Group: GPS_
663  // @Path: ../libraries/AP_GPS/AP_GPS.cpp
664  GOBJECT(gps, "GPS_", AP_GPS),
665 
666  // @Group: SCHED_
667  // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
668  GOBJECT(scheduler, "SCHED_", AP_Scheduler),
669 
670 #if AC_FENCE == ENABLED
671  // @Group: FENCE_
672  // @Path: ../libraries/AC_Fence/AC_Fence.cpp
673  GOBJECT(fence, "FENCE_", AC_Fence),
674 #endif
675 
676  // @Group: AVOID_
677  // @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
678 #if AC_AVOID_ENABLED == ENABLED
679  GOBJECT(avoid, "AVOID_", AC_Avoid),
680 #endif
681 
682 #if AC_RALLY == ENABLED
683  // @Group: RALLY_
684  // @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
685  GOBJECT(rally, "RALLY_", AP_Rally_Copter),
686 #endif
687 
688 #if FRAME_CONFIG == HELI_FRAME
689  // @Group: H_
690  // @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp,../libraries/AP_Motors/AP_MotorsHeli_Dual.cpp,../libraries/AP_Motors/AP_MotorsHeli.cpp
691  GOBJECTVARPTR(motors, "H_", &copter.motors_var_info),
692 #else
693  // @Group: MOT_
694  // @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
695  GOBJECTVARPTR(motors, "MOT_", &copter.motors_var_info),
696 #endif
697 
698  // @Group: RCMAP_
699  // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
700  GOBJECT(rcmap, "RCMAP_", RCMapper),
701 
702  // @Group: EK2_
703  // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
704  GOBJECTN(EKF2, NavEKF2, "EK2_", NavEKF2),
705 
706  // @Group: EK3_
707  // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
708  GOBJECTN(EKF3, NavEKF3, "EK3_", NavEKF3),
709 
710 #if MODE_AUTO_ENABLED == ENABLED
711  // @Group: MIS_
712  // @Path: ../libraries/AP_Mission/AP_Mission.cpp
713  GOBJECT(mission, "MIS_", AP_Mission),
714 #endif
715 
716  // @Group: RSSI_
717  // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
718  GOBJECT(rssi, "RSSI_", AP_RSSI),
719 
720 #if RANGEFINDER_ENABLED == ENABLED
721  // @Group: RNGFND
722  // @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp
723  GOBJECT(rangefinder, "RNGFND", RangeFinder),
724 #endif
725 
726 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
727  // @Group: TERRAIN_
728  // @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
729  GOBJECT(terrain, "TERRAIN_", AP_Terrain),
730 #endif
731 
732 #if OPTFLOW == ENABLED
733  // @Group: FLOW
734  // @Path: ../libraries/AP_OpticalFlow/OpticalFlow.cpp
735  GOBJECT(optflow, "FLOW", OpticalFlow),
736 #endif
737 
738 #if PRECISION_LANDING == ENABLED
739  // @Group: PLND_
740  // @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
741  GOBJECT(precland, "PLND_", AC_PrecLand),
742 #endif
743 
744 #if RPM_ENABLED == ENABLED
745  // @Group: RPM
746  // @Path: ../libraries/AP_RPM/AP_RPM.cpp
747  GOBJECT(rpm_sensor, "RPM", AP_RPM),
748 #endif
749 
750 #if ADSB_ENABLED == ENABLED
751  // @Group: ADSB_
752  // @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
753  GOBJECT(adsb, "ADSB_", AP_ADSB),
754 
755  // @Group: AVD_
756  // @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp
757  GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Copter),
758 #endif
759 
760 #if AUTOTUNE_ENABLED == ENABLED
761  // @Param: AUTOTUNE_AXES
762  // @DisplayName: Autotune axis bitmask
763  // @Description: 1-byte bitmap of axes to autotune
764  // @Values: 7:All,1:Roll Only,2:Pitch Only,4:Yaw Only,3:Roll and Pitch,5:Roll and Yaw,6:Pitch and Yaw
765  // @Bitmask: 0:Roll,1:Pitch,2:Yaw
766  // @User: Standard
767  GSCALAR(autotune_axis_bitmask, "AUTOTUNE_AXES", 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
768 
769  // @Param: AUTOTUNE_AGGR
770  // @DisplayName: Autotune aggressiveness
771  // @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
772  // @Range: 0.05 0.10
773  // @User: Standard
774  GSCALAR(autotune_aggressiveness, "AUTOTUNE_AGGR", 0.1f),
775 
776  // @Param: AUTOTUNE_MIN_D
777  // @DisplayName: AutoTune minimum D
778  // @Description: Defines the minimum D gain
779  // @Range: 0.001 0.006
780  // @User: Standard
781  GSCALAR(autotune_min_d, "AUTOTUNE_MIN_D", 0.001f),
782 #endif
783 
784  // @Group: NTF_
785  // @Path: ../libraries/AP_Notify/AP_Notify.cpp
786  GOBJECT(notify, "NTF_", AP_Notify),
787 
788 #if MODE_THROW_ENABLED == ENABLED
789  // @Param: THROW_MOT_START
790  // @DisplayName: Start motors before throwing is detected
791  // @Description: Used by THROW mode. Controls whether motors will run at the speed set by THR_MIN or will be stopped when armed and waiting for the throw.
792  // @Values: 0:Stopped,1:Running
793  // @User: Standard
794  GSCALAR(throw_motor_start, "THROW_MOT_START", 0),
795 #endif
796 
797 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
798  // @Param: TERRAIN_FOLLOW
799  // @DisplayName: Terrain Following use control
800  // @Description: This enables terrain following for RTL and LAND flight modes. To use this option TERRAIN_ENABLE must be 1 and the GCS must support sending terrain data to the aircraft. In RTL the RTL_ALT will be considered a height above the terrain. In LAND mode the vehicle will slow to LAND_SPEED 10m above terrain (instead of 10m above home). This parameter does not affect AUTO and Guided which use a per-command flag to determine if the height is above-home, absolute or above-terrain.
801  // @Values: 0:Do Not Use in RTL and Land,1:Use in RTL and Land
802  // @User: Standard
803  GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),
804 #endif
805 
806  // @Group:
807  // @Path: Parameters.cpp
808  GOBJECT(g2, "", ParametersG2),
809 
810  AP_VAREND
811 };
812 
813 /*
814  2nd group of parameters
815  */
817 
818  // @Param: WP_NAVALT_MIN
819  // @DisplayName: Minimum navigation altitude
820  // @Description: This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing.
821  // @Range: 0 5
822  // @User: Standard
823  AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min, 0),
824 
825  // @Group: BTN_
826  // @Path: ../libraries/AP_Button/AP_Button.cpp
827  AP_SUBGROUPINFO(button, "BTN_", 2, ParametersG2, AP_Button),
828 
829 #if MODE_THROW_ENABLED == ENABLED
830  // @Param: THROW_NEXTMODE
831  // @DisplayName: Throw mode's follow up mode
832  // @Description: Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)
833  // @Values: 3:Auto,4:Guided,5:LOITER,6:RTL,9:Land,17:Brake,18:Throw
834  // @User: Standard
835  AP_GROUPINFO("THROW_NEXTMODE", 3, ParametersG2, throw_nextmode, 18),
836 
837  // @Param: THROW_TYPE
838  // @DisplayName: Type of Type
839  // @Description: Used by THROW mode. Specifies whether Copter is thrown upward or dropped.
840  // @Values: 0:Upward Throw,1:Drop
841  // @User: Standard
842  AP_GROUPINFO("THROW_TYPE", 4, ParametersG2, throw_type, Copter::ModeThrow::ThrowType_Upward),
843 #endif
844 
845  // @Param: GND_EFFECT_COMP
846  // @DisplayName: Ground Effect Compensation Enable/Disable
847  // @Description: Ground Effect Compensation Enable/Disable
848  // @Values: 0:Disabled,1:Enabled
849  // @User: Advanced
850  AP_GROUPINFO("GND_EFFECT_COMP", 5, ParametersG2, gndeffect_comp_enabled, 0),
851 
852 #if ADVANCED_FAILSAFE == ENABLED
853  // @Group: AFS_
854  // @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
856 #endif
857 
858  // @Param: DEV_OPTIONS
859  // @DisplayName: Development options
860  // @Description: Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning
861  // @Bitmask: 0:ADSBMavlinkProcessing
862  // @User: Advanced
863  AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),
864 
865 #if BEACON_ENABLED == ENABLED
866  // @Group: BCN
867  // @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
869 #endif
870 
871 #if PROXIMITY_ENABLED == ENABLED
872  // @Group: PRX
873  // @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
874  AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity),
875 #endif
876 
877  // @Param: ACRO_Y_EXPO
878  // @DisplayName: Acro Yaw Expo
879  // @Description: Acro yaw expo to allow faster rotation when stick at edges
880  // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
881  // @Range: -0.5 1.0
882  // @User: Advanced
883  AP_GROUPINFO("ACRO_Y_EXPO", 9, ParametersG2, acro_y_expo, ACRO_Y_EXPO_DEFAULT),
884 
885 #if MODE_ACRO_ENABLED == ENABLED
886  // @Param: ACRO_THR_MID
887  // @DisplayName: Acro Thr Mid
888  // @Description: Acro Throttle Mid
889  // @Range: 0 1
890  // @User: Advanced
891  AP_GROUPINFO("ACRO_THR_MID", 10, ParametersG2, acro_thr_mid, ACRO_THR_MID_DEFAULT),
892 #endif
893 
894  // @Param: SYSID_ENFORCE
895  // @DisplayName: GCS sysid enforcement
896  // @Description: This controls whether packets from other than the expected GCS system ID will be accepted
897  // @Values: 0:NotEnforced,1:Enforced
898  // @User: Advanced
899  AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0),
900 
901 #if STATS_ENABLED == ENABLED
902  // @Group: STAT
903  // @Path: ../libraries/AP_Stats/AP_Stats.cpp
904  AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats),
905 #endif
906 
907 #if GRIPPER_ENABLED == ENABLED
908  // @Group: GRIP_
909  // @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
910  AP_SUBGROUPINFO(gripper, "GRIP_", 13, ParametersG2, AP_Gripper),
911 #endif
912 
913  // @Param: FRAME_CLASS
914  // @DisplayName: Frame Class
915  // @Description: Controls major frame class for multicopter component
916  // @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad
917  // @User: Standard
918  // @RebootRequired: True
919  AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, 0),
920 
921  // @Group: SERVO
922  // @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
923  AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),
924 
925  // @Group: RC
926  // @Path: ../libraries/RC_Channel/RC_Channels.cpp
927  AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),
928 
929 #if VISUAL_ODOMETRY_ENABLED == ENABLED
930  // @Group: VISO
931  // @Path: ../libraries/AP_VisualOdom/AP_VisualOdom.cpp
932  AP_SUBGROUPINFO(visual_odom, "VISO", 18, ParametersG2, AP_VisualOdom),
933 #endif
934 
935  // @Group: TCAL
936  // @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp
937  AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration),
938 
939 #if TOY_MODE_ENABLED == ENABLED
940  // @Group: TMODE
941  // @Path: toy_mode.cpp
942  AP_SUBGROUPINFO(toy_mode, "TMODE", 20, ParametersG2, ToyMode),
943 #endif
944 
945 #if MODE_SMARTRTL_ENABLED == ENABLED
946  // @Group: SRTL_
947  // @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
949 #endif
950 
951 #if WINCH_ENABLED == ENABLED
952  // @Group: WENC
953  // @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp
954  AP_SUBGROUPINFO(wheel_encoder, "WENC", 22, ParametersG2, AP_WheelEncoder),
955 
956  // @Group: WINCH_
957  // @Path: ../libraries/AP_Winch/AP_Winch.cpp
958  AP_SUBGROUPINFO(winch, "WINCH", 23, ParametersG2, AP_Winch),
959 #endif
960 
961  // @Param: PILOT_SPEED_DN
962  // @DisplayName: Pilot maximum vertical speed descending
963  // @Description: The maximum vertical descending velocity the pilot may request in cm/s
964  // @Units: cm/s
965  // @Range: 50 500
966  // @Increment: 10
967  // @User: Standard
968  AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn, 0),
969 
970  // @Param: LAND_ALT_LOW
971  // @DisplayName: Land alt low
972  // @Description: Altitude during Landing at which vehicle slows to LAND_SPEED
973  // @Units: cm
974  // @Range: 100 10000
975  // @Increment: 10
976  // @User: Advanced
977  AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000),
978 
979 #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
980  // @Group: FHLD
981  // @Path: mode_flowhold.cpp
982  AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, Copter::ModeFlowHold),
983 #endif
984 
985 #if MODE_FOLLOW_ENABLED == ENABLED
986  // @Group: FOLL
987  // @Path: ../libraries/AP_Follow/AP_Follow.cpp
988  AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow),
989 #endif
990 
992 };
993 
994 
995 /*
996  constructor for g2 object
997  */
999  : temp_calibration() // this doesn't actually need constructing, but removing it here is problematic syntax-wise
1000 #if BEACON_ENABLED == ENABLED
1001  , beacon(copter.serial_manager)
1002 #endif
1004  , proximity(copter.serial_manager)
1005 #endif
1007  ,afs(copter.mission, copter.gps)
1008 #endif
1010  ,smart_rtl()
1011 #endif
1013  ,mode_flowhold_ptr(&copter.mode_flowhold)
1014 #endif
1016  ,follow()
1017 #endif
1018 {
1020 }
1021 
1022 /*
1023  This is a conversion table from old parameter values to new
1024  parameter names. The startup code looks for saved values of the old
1025  parameters and will copy them across to the new parameters if the
1026  new parameter does not yet have a saved value. It then saves the new
1027  value.
1028 
1029  Note that this works even if the old parameter has been removed. It
1030  relies on the old k_param index not being removed
1031 
1032  The second column below is the index in the var_info[] table for the
1033  old object. This should be zero for top level parameters.
1034  */
1036  { Parameters::k_param_battery_monitoring, 0, AP_PARAM_INT8, "BATT_MONITOR" },
1037  { Parameters::k_param_battery_volt_pin, 0, AP_PARAM_INT8, "BATT_VOLT_PIN" },
1038  { Parameters::k_param_battery_curr_pin, 0, AP_PARAM_INT8, "BATT_CURR_PIN" },
1039  { Parameters::k_param_volt_div_ratio, 0, AP_PARAM_FLOAT, "BATT_VOLT_MULT" },
1040  { Parameters::k_param_curr_amp_per_volt, 0, AP_PARAM_FLOAT, "BATT_AMP_PERVOLT" },
1041  { Parameters::k_param_pack_capacity, 0, AP_PARAM_INT32, "BATT_CAPACITY" },
1042  { Parameters::k_param_log_bitmask_old, 0, AP_PARAM_INT16, "LOG_BITMASK" },
1043  { Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },
1044  { Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },
1045  { Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
1046  { Parameters::k_param_arming_check_old, 0, AP_PARAM_INT8, "ARMING_CHECK" },
1047  // battery
1048  { Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_INT8, "BATT_FS_LOW_VOLT" },
1049  { Parameters::k_param_fs_batt_mah, 0, AP_PARAM_INT8, "BATT_FS_LOW_MAH" },
1051 };
1052 
1054 {
1055  if (!AP_Param::check_var_info()) {
1056  hal.console->printf("Bad var table\n");
1057  AP_HAL::panic("Bad var table");
1058  }
1059 
1060  // disable centrifugal force correction, it will be enabled as part of the arming process
1062  hal.util->set_soft_armed(false);
1063 
1064  if (!g.format_version.load() ||
1065  g.format_version != Parameters::k_format_version) {
1066 
1067  // erase all parameters
1068  hal.console->printf("Firmware change: erasing EEPROM...\n");
1070 
1071  // save the current format version
1072  g.format_version.set_and_save(Parameters::k_format_version);
1073  hal.console->printf("done.\n");
1074  }
1075 
1076  uint32_t before = micros();
1077  // Load all auto-loaded EEPROM variables
1078  AP_Param::load_all(false);
1079  AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
1080  hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
1081 
1082  // setup AP_Param frame type flags
1084 
1085 }
1086 
1087 // handle conversion of PID gains from Copter-3.3 to Copter-3.4
1089 {
1090  // conversion info
1091  const AP_Param::ConversionInfo pid_conversion_info[] = {
1092  { Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_RAT_RLL_P" },
1093  { Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_RAT_RLL_I" },
1094  { Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_RAT_RLL_D" },
1095  { Parameters::k_param_pid_rate_pitch, 0, AP_PARAM_FLOAT, "ATC_RAT_PIT_P" },
1096  { Parameters::k_param_pid_rate_pitch, 1, AP_PARAM_FLOAT, "ATC_RAT_PIT_I" },
1097  { Parameters::k_param_pid_rate_pitch, 2, AP_PARAM_FLOAT, "ATC_RAT_PIT_D" },
1098  { Parameters::k_param_pid_rate_yaw, 0, AP_PARAM_FLOAT, "ATC_RAT_YAW_P" },
1099  { Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_RAT_YAW_I" },
1100  { Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_RAT_YAW_D" },
1101 #if FRAME_CONFIG == HELI_FRAME
1102  { Parameters::k_param_pid_rate_roll, 4, AP_PARAM_FLOAT, "ATC_RAT_RLL_VFF" },
1103  { Parameters::k_param_pid_rate_pitch, 4, AP_PARAM_FLOAT, "ATC_RAT_PIT_VFF" },
1104  { Parameters::k_param_pid_rate_yaw , 4, AP_PARAM_FLOAT, "ATC_RAT_YAW_VFF" },
1105 #endif
1106  };
1107  const AP_Param::ConversionInfo imax_conversion_info[] = {
1108  { Parameters::k_param_pid_rate_roll, 5, AP_PARAM_FLOAT, "ATC_RAT_RLL_IMAX" },
1109  { Parameters::k_param_pid_rate_pitch, 5, AP_PARAM_FLOAT, "ATC_RAT_PIT_IMAX" },
1110  { Parameters::k_param_pid_rate_yaw, 5, AP_PARAM_FLOAT, "ATC_RAT_YAW_IMAX" },
1111 #if FRAME_CONFIG == HELI_FRAME
1112  { Parameters::k_param_pid_rate_roll, 7, AP_PARAM_FLOAT, "ATC_RAT_RLL_ILMI" },
1113  { Parameters::k_param_pid_rate_pitch, 7, AP_PARAM_FLOAT, "ATC_RAT_PIT_ILMI" },
1114  { Parameters::k_param_pid_rate_yaw, 7, AP_PARAM_FLOAT, "ATC_RAT_YAW_ILMI" },
1115 #endif
1116  };
1117  const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {
1118  { Parameters::k_param_p_stabilize_roll, 0, AP_PARAM_FLOAT, "ATC_ANG_RLL_P" },
1119  { Parameters::k_param_p_stabilize_pitch, 0, AP_PARAM_FLOAT, "ATC_ANG_PIT_P" },
1120  { Parameters::k_param_p_stabilize_yaw, 0, AP_PARAM_FLOAT, "ATC_ANG_YAW_P" },
1121  { Parameters::k_param_pid_rate_roll, 6, AP_PARAM_FLOAT, "ATC_RAT_RLL_FILT" },
1122  { Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" },
1123  { Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" },
1124  { Parameters::k_param_pi_vel_xy, 0, AP_PARAM_FLOAT, "PSC_VELXY_P" },
1125  { Parameters::k_param_pi_vel_xy, 1, AP_PARAM_FLOAT, "PSC_VELXY_I" },
1126  { Parameters::k_param_pi_vel_xy, 2, AP_PARAM_FLOAT, "PSC_VELXY_IMAX" },
1127  { Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_VELXY_FILT" },
1128  { Parameters::k_param_p_vel_z, 0, AP_PARAM_FLOAT, "PSC_VELZ_P" },
1129  { Parameters::k_param_pid_accel_z, 0, AP_PARAM_FLOAT, "PSC_ACCZ_P" },
1130  { Parameters::k_param_pid_accel_z, 1, AP_PARAM_FLOAT, "PSC_ACCZ_I" },
1131  { Parameters::k_param_pid_accel_z, 2, AP_PARAM_FLOAT, "PSC_ACCZ_D" },
1132  { Parameters::k_param_pid_accel_z, 5, AP_PARAM_FLOAT, "PSC_ACCZ_IMAX" },
1133  { Parameters::k_param_pid_accel_z, 6, AP_PARAM_FLOAT, "PSC_ACCZ_FILT" },
1134  { Parameters::k_param_p_alt_hold, 0, AP_PARAM_FLOAT, "PSC_POSZ_P" },
1135  { Parameters::k_param_p_pos_xy, 0, AP_PARAM_FLOAT, "PSC_POSXY_P" },
1136  };
1137  const AP_Param::ConversionInfo throttle_conversion_info[] = {
1138  { Parameters::k_param_throttle_min, 0, AP_PARAM_FLOAT, "MOT_SPIN_MIN" },
1139  { Parameters::k_param_throttle_mid, 0, AP_PARAM_FLOAT, "MOT_THST_HOVER" }
1140  };
1141  const AP_Param::ConversionInfo loiter_conversion_info[] = {
1142  { Parameters::k_param_wp_nav, 4, AP_PARAM_FLOAT, "LOIT_SPEED" },
1143  { Parameters::k_param_wp_nav, 7, AP_PARAM_FLOAT, "LOIT_BRK_JERK" },
1144  { Parameters::k_param_wp_nav, 8, AP_PARAM_FLOAT, "LOIT_ACC_MAX" },
1145  { Parameters::k_param_wp_nav, 9, AP_PARAM_FLOAT, "LOIT_BRK_ACCEL" }
1146  };
1147 
1148  // gains increase by 27% due to attitude controller's switch to use radians instead of centi-degrees
1149  // and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500
1150  float pid_scaler = 1.27f;
1151 
1152 #if FRAME_CONFIG != HELI_FRAME
1153  // Multicopter x-frame gains are 40% lower because -1 or +1 input to motors now results in maximum rotation
1154  if (g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_X || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_V || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_H) {
1155  pid_scaler = 0.9f;
1156  }
1157 #endif
1158 
1159  // scale PID gains
1160  uint8_t table_size = ARRAY_SIZE(pid_conversion_info);
1161  for (uint8_t i=0; i<table_size; i++) {
1162  AP_Param::convert_old_parameter(&pid_conversion_info[i], pid_scaler);
1163  }
1164  // reduce IMAX into -1 ~ +1 range
1165  table_size = ARRAY_SIZE(imax_conversion_info);
1166  for (uint8_t i=0; i<table_size; i++) {
1167  AP_Param::convert_old_parameter(&imax_conversion_info[i], 1.0f/4500.0f);
1168  }
1169  // convert angle controller gain and filter without scaling
1170  table_size = ARRAY_SIZE(angle_and_filt_conversion_info);
1171  for (uint8_t i=0; i<table_size; i++) {
1172  AP_Param::convert_old_parameter(&angle_and_filt_conversion_info[i], 1.0f);
1173  }
1174  // convert throttle parameters (multicopter only)
1175  table_size = ARRAY_SIZE(throttle_conversion_info);
1176  for (uint8_t i=0; i<table_size; i++) {
1177  AP_Param::convert_old_parameter(&throttle_conversion_info[i], 0.001f);
1178  }
1179  // convert RC_FEEL_RP to ATC_INPUT_TC
1180  const AP_Param::ConversionInfo rc_feel_rp_conversion_info = { Parameters::k_param_rc_feel_rp, 0, AP_PARAM_INT8, "ATC_INPUT_TC" };
1181  AP_Int8 rc_feel_rp_old;
1182  if (AP_Param::find_old_parameter(&rc_feel_rp_conversion_info, &rc_feel_rp_old)) {
1183  AP_Param::set_default_by_name(rc_feel_rp_conversion_info.new_name, (1.0f / (2.0f + rc_feel_rp_old.get() * 0.1f)));
1184  }
1185  // convert loiter parameters
1186  table_size = ARRAY_SIZE(loiter_conversion_info);
1187  for (uint8_t i=0; i<table_size; i++) {
1188  AP_Param::convert_old_parameter(&loiter_conversion_info[i], 1.0f);
1189  }
1190 
1191  const uint8_t old_rc_keys[14] = { Parameters::k_param_rc_1_old, Parameters::k_param_rc_2_old,
1198  const uint16_t old_aux_chan_mask = 0x3FF0;
1199  // note that we don't pass in rcmap as we don't want output channel functions changed based on rcmap
1200  if (SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, nullptr)) {
1201  // the rest needs to be done after motors allocation
1202  upgrading_frame_params = true;
1203  }
1204 }
#define LAND_SPEED
Definition: config.h:407
#define WP_YAW_BEHAVIOR_DEFAULT
Definition: config.h:525
Compass & compass()
#define FLIGHT_MODE_5
Definition: config.h:381
#define PILOT_TKOFF_ALT_DEFAULT
Definition: config.h:399
#define GOBJECTPTR(v, name, class)
Definition: Parameters.cpp:27
#define DEFAULT_LOG_BITMASK
Definition: config.h:622
static const struct AP_Param::GroupInfo var_info[]
Definition: Parameters.h:498
#define ACRO_THR_MID_DEFAULT
Definition: config.h:487
#define ACRO_BALANCE_ROLL
Definition: config.h:471
#define RTL_CONE_SLOPE_DEFAULT
Definition: config.h:512
AP_Beacon beacon
#define ASCALAR(v, name, def)
Definition: Parameters.cpp:24
#define FLIGHT_MODE_6
Definition: config.h:384
AP_AHRS_NavEKF & ahrs
ParametersG2(void)
Definition: Parameters.cpp:998
#define MAGNETOMETER
Definition: config.h:49
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap)
AP_HAL::UARTDriver * console
void convert_pid_parameters(void)
static bool load_all(bool check_defaults_file=true)
#define POSHOLD_BRAKE_ANGLE_DEFAULT
Definition: config.h:571
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define POSHOLD_BRAKE_RATE_DEFAULT
Definition: config.h:568
AP_HAL::Util * util
#define FLIGHT_MODE_3
Definition: config.h:375
#define BEACON_ENABLED
Definition: config.h:355
#define PROXIMITY_ENABLED
Definition: config.h:123
#define FS_EKF_ACTION_DEFAULT
Definition: config.h:182
#define CH_MODE_DEFAULT
Definition: config.h:709
AP_RSSI * rssi()
#define ACRO_YAW_P
Definition: config.h:463
static const AP_Param::Info var_info[]
Definition: Copter.h:626
const AP_Param::ConversionInfo conversion_table[]
#define GOBJECTN(v, pname, name, class)
Definition: Parameters.cpp:29
static const uint16_t k_format_version
Definition: Parameters.h:17
#define RANGEFINDER_GAIN_DEFAULT
Definition: config.h:92
AP_MotorsMatrix motors(400)
SITL::SITL * sitl()
#define FS_EKF_THRESHOLD_DEFAULT
Definition: config.h:185
AP_SmartRTL smart_rtl
#define MODE_FOLLOW_ENABLED
Definition: config.h:301
#define FS_THR_VALUE_DEFAULT
Definition: config.h:392
virtual void printf(const char *,...) FMT_PRINTF(2
#define AP_SUBGROUPPTR(element, name, idx, thisclazz, elclazz)
#define MAV_SYSTEM_ID
Definition: config.h:127
#define THR_DZ_DEFAULT
Definition: config.h:579
void load_parameters(void)
static void erase_all(void)
#define f(i)
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
AP_PARAM_INT8
void set_correct_centrifugal(bool setting)
#define FS_GCS_ENABLED_ALWAYS_RTL
Definition: defines.h:464
#define FLIGHT_MODE_2
Definition: config.h:372
#define PILOT_ACCEL_Z_DEFAULT
Definition: config.h:587
#define AUTO_DISARMING_DELAY
Definition: config.h:600
static void set_frame_type_flags(uint16_t flags_to_set)
#define RC_FAST_SPEED
Definition: config.h:76
#define ARRAY_SIZE(_arr)
#define HAL_MINIMIZE_FEATURES
#define PILOT_VELZ_MAX
Definition: config.h:584
GCS_Dummy _gcs
AP_PARAM_FLOAT
AP_BattMonitor & battery()
#define ACRO_RP_EXPO_DEFAULT
Definition: config.h:479
AP_Int32 log_bitmask
#define FS_THR_ENABLED_ALWAYS_RTL
Definition: defines.h:456
AP_PARAM_INT32
void set_soft_armed(const bool b)
DataFlash_Class DataFlash
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
#define GOBJECT(v, name, class)
Definition: Parameters.cpp:26
#define AP_PARAM_FRAME_COPTER
#define ACRO_BALANCE_PITCH
Definition: config.h:475
#define ADVANCED_FAILSAFE
Definition: config.h:705
#define LAND_REPOSITION_DEFAULT
Definition: config.h:410
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0)
static const uint16_t k_software_type
Definition: Parameters.h:25
#define ACRO_TRAINER_LIMITED
Definition: defines.h:185
#define RTL_CLIMB_MIN_DEFAULT
Definition: config.h:504
#define DEFAULT_ANGLE_MAX
Definition: config.h:548
AP_InertialSensor & ins()
AP_GPS & gps()
#define MODE_SMARTRTL_ENABLED
Definition: config.h:337
void panic(const char *errormsg,...) FMT_PRINTF(1
#define FLIGHT_MODE_4
Definition: config.h:378
#define ENABLED
Definition: defines.h:6
AP_PARAM_INT16
#define OPTFLOW
Definition: config.h:208
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
#define ACRO_RP_P
Definition: config.h:459
#define GOBJECTVARPTR(v, name, var_info_ptr)
Definition: Parameters.cpp:28
uint32_t micros()
#define RTL_ALT
Definition: config.h:496
#define RTL_LOITER_TIME
Definition: config.h:520
#define ACRO_Y_EXPO_DEFAULT
Definition: config.h:483
#define GPS_HDOP_GOOD_DEFAULT
Definition: config.h:144
#define FLIGHT_MODE_1
Definition: config.h:369
#define AP_GROUPEND
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0)
#define RTL_ALT_FINAL
Definition: config.h:492
#define GSCALAR(v, name, def)
Definition: Parameters.cpp:23
static bool check_var_info(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
static bool set_default_by_name(const char *name, float value)
#define AP_VAREND