Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/Parameters.cpp
9377 views
1
#include "Copter.h"
2
3
#include <AP_Gripper/AP_Gripper.h>
4
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
5
6
/*
7
This program is free software: you can redistribute it and/or modify
8
it under the terms of the GNU General Public License as published by
9
the Free Software Foundation, either version 3 of the License, or
10
(at your option) any later version.
11
12
This program is distributed in the hope that it will be useful,
13
but WITHOUT ANY WARRANTY; without even the implied warranty of
14
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15
GNU General Public License for more details.
16
17
You should have received a copy of the GNU General Public License
18
along with this program. If not, see <http://www.gnu.org/licenses/>.
19
*/
20
21
/*
22
* ArduCopter parameter definitions
23
*
24
*/
25
26
#if FRAME_CONFIG == HELI_FRAME
27
// 6 here is AP_Motors::MOTOR_FRAME_HELI
28
#define DEFAULT_FRAME_CLASS 6
29
#else
30
#define DEFAULT_FRAME_CLASS 0
31
#endif
32
33
const AP_Param::Info Copter::var_info[] = {
34
// @Param: FORMAT_VERSION
35
// @DisplayName: Eeprom format version number
36
// @Description: This value is incremented when changes are made to the eeprom format
37
// @User: Advanced
38
GSCALAR(format_version, "FORMAT_VERSION", 0),
39
40
// SYSID_THISMAV was here
41
42
// SYSID_MYGCS was here
43
44
// @Param: PILOT_THR_FILT
45
// @DisplayName: Throttle filter cutoff
46
// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
47
// @User: Advanced
48
// @Units: Hz
49
// @Range: 0 10
50
// @Increment: 0.5
51
GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),
52
53
// @Param: PILOT_TKOFF_ALT
54
// @DisplayName: Pilot takeoff altitude
55
// @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.
56
// @User: Standard
57
// @Units: cm
58
// @Range: 0.0 1000.0
59
// @Increment: 10
60
GSCALAR(pilot_takeoff_alt_cm, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT),
61
62
// @Param: PILOT_THR_BHV
63
// @DisplayName: Throttle stick behavior
64
// @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.
65
// @User: Standard
66
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
67
GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),
68
69
// AP_SerialManager was here
70
71
// @Param: GCS_PID_MASK
72
// @DisplayName: GCS PID tuning mask
73
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
74
// @User: Advanced
75
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:AccelZ
76
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
77
78
#if MODE_RTL_ENABLED
79
// @Param: RTL_CONE_SLOPE
80
// @DisplayName: RTL cone slope
81
// @Description: Defines a cone above home which determines maximum climb
82
// @Range: 0 10.0
83
// @Increment: 0.1
84
// @Values: 0:Disabled,1:Shallow,3:Steep
85
// @User: Standard
86
GSCALAR(rtl_cone_slope, "RTL_CONE_SLOPE", RTL_CONE_SLOPE_DEFAULT),
87
88
// @Param: RTL_LOIT_TIME
89
// @DisplayName: RTL loiter time
90
// @Description: Time (in milliseconds) to loiter above home before beginning final descent
91
// @Units: ms
92
// @Range: 0 60000
93
// @Increment: 1000
94
// @User: Standard
95
GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME),
96
97
// @Param: RTL_ALT_TYPE
98
// @DisplayName: RTL mode altitude type
99
// @Description: RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database
100
// @Values: 0:Relative to Home, 1:Terrain
101
// @User: Standard
102
GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),
103
#endif
104
105
// @Param: FS_GCS_ENABLE
106
// @DisplayName: Ground Station Failsafe Enable
107
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
108
// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Brake or Land
109
// @User: Standard
110
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),
111
112
// @Param: GPS_HDOP_GOOD
113
// @DisplayName: GPS Hdop Good
114
// @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks
115
// @Range: 100 900
116
// @User: Advanced
117
GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),
118
119
// @Param: SUPER_SIMPLE
120
// @DisplayName: Super Simple Mode
121
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode. The bitmask is for flight mode switch positions
122
// @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6
123
// @User: Standard
124
GSCALAR(super_simple, "SUPER_SIMPLE", 0),
125
126
// @Param: WP_YAW_BEHAVIOR
127
// @DisplayName: Yaw behaviour during missions
128
// @Description: Determines how the autopilot controls the yaw during missions and RTL
129
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course
130
// @User: Standard
131
GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),
132
133
// @Param: PILOT_SPEED_UP
134
// @DisplayName: Pilot maximum vertical speed ascending
135
// @Description: The maximum vertical ascending velocity the pilot may request in cm/s
136
// @Units: cm/s
137
// @Range: 50 500
138
// @Increment: 10
139
// @User: Standard
140
GSCALAR(pilot_speed_up_cms, "PILOT_SPEED_UP", PILOT_SPEED_UP_DEFAULT),
141
142
// @Param: PILOT_ACCEL_Z
143
// @DisplayName: Pilot vertical acceleration
144
// @Description: The vertical acceleration used when pilot is controlling the altitude
145
// @Units: cm/s/s
146
// @Range: 50 500
147
// @Increment: 10
148
// @User: Standard
149
GSCALAR(pilot_accel_d_cmss, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),
150
151
// @Param: FS_THR_ENABLE
152
// @DisplayName: Throttle Failsafe Enable
153
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
154
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Removed in 4.0+),3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land,6:Enabled Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Enabled always Brake or Land
155
// @User: Standard
156
GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL),
157
158
// @Param: FS_THR_VALUE
159
// @DisplayName: Throttle Failsafe Value
160
// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers
161
// @Range: 910 1100
162
// @Units: PWM
163
// @Increment: 1
164
// @User: Standard
165
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
166
167
// @Param: THR_DZ
168
// @DisplayName: Throttle deadzone
169
// @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
170
// @User: Standard
171
// @Range: 0 300
172
// @Units: PWM
173
// @Increment: 1
174
GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),
175
176
// @Param: FLTMODE1
177
// @DisplayName: Flight Mode 1
178
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230
179
// @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,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL,28:Turtle
180
// @User: Standard
181
GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),
182
183
// @Param: FLTMODE2
184
// @CopyFieldsFrom: FLTMODE1
185
// @DisplayName: Flight Mode 2
186
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360
187
GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),
188
189
// @Param: FLTMODE3
190
// @CopyFieldsFrom: FLTMODE1
191
// @DisplayName: Flight Mode 3
192
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490
193
GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),
194
195
// @Param: FLTMODE4
196
// @CopyFieldsFrom: FLTMODE1
197
// @DisplayName: Flight Mode 4
198
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620
199
GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),
200
201
// @Param: FLTMODE5
202
// @CopyFieldsFrom: FLTMODE1
203
// @DisplayName: Flight Mode 5
204
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749
205
GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),
206
207
// @Param: FLTMODE6
208
// @CopyFieldsFrom: FLTMODE1
209
// @DisplayName: Flight Mode 6
210
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750
211
GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),
212
213
// @Param: FLTMODE_CH
214
// @DisplayName: Flightmode channel
215
// @Description: RC Channel to use for flight mode control
216
// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8,9:Channel9,10:Channel 10,11:Channel 11,12:Channel 12,13:Channel 13,14:Channel 14,15:Channel 15
217
// @User: Advanced
218
GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT),
219
220
// @Param: INITIAL_MODE
221
// @DisplayName: Initial flight mode
222
// @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.
223
// @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,24:ZigZag,25:SystemID,26:Heli_Autorotate
224
// @User: Advanced
225
GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)Mode::Number::STABILIZE),
226
227
// @Param: SIMPLE
228
// @DisplayName: Simple mode bitmask
229
// @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode). The bitmask is for flightmode switch positions.
230
// @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6
231
// @User: Advanced
232
GSCALAR(simple_modes, "SIMPLE", 0),
233
234
// @Param: LOG_BITMASK
235
// @DisplayName: Log bitmask
236
// @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 basiclog types by setting this to 65535. Note that if you want to reduce log sizes you should consider using LOG_FILE_RATEMAX instead of disabling logging items with this parameter.
237
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging
238
// @User: Standard
239
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
240
241
// @Param: ESC_CALIBRATION
242
// @DisplayName: ESC Calibration
243
// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
244
// @User: Advanced
245
// @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
246
GSCALAR(esc_calibrate, "ESC_CALIBRATION", 0),
247
248
#if AP_RC_TRANSMITTER_TUNING_ENABLED
249
// @Param: TUNE
250
// @DisplayName: Tuning Parameter
251
// @Description: Selects parameter (normally a PID gain) that is being tuned with an RC transmitter's knob. The RC input channel used is assigned by setting RCx_OPTION to 219.
252
// @User: Standard
253
// @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 Roll/Pitch deg/s,40:Acro Yaw deg/s,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,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,58:SysID Magnitude,59:PSC Angle Max,60:Loiter Speed
254
GSCALAR(rc_tuning_param, "TUNE", 0),
255
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
256
257
// @Param: FRAME_TYPE
258
// @DisplayName: Frame Type (+, X, V, etc)
259
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
260
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B, 11:Y6F, 12:BetaFlightX, 13:DJIX, 14:ClockwiseX, 15: I, 18: BetaFlightXReversed, 19:Y4
261
// @User: Standard
262
// @RebootRequired: True
263
GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT),
264
265
// @Group: ARMING_
266
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
267
GOBJECT(arming, "ARMING_", AP_Arming_Copter),
268
269
// @Param: DISARM_DELAY
270
// @DisplayName: Disarm delay
271
// @Description: Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value.
272
// @Units: s
273
// @Range: 0 127
274
// @User: Advanced
275
GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),
276
277
#if MODE_POSHOLD_ENABLED
278
// @Param: PHLD_BRAKE_RATE
279
// @DisplayName: PosHold braking rate
280
// @Description: PosHold flight mode's rotation rate during braking in deg/sec
281
// @Units: deg/s
282
// @Range: 4 12
283
// @User: Advanced
284
GSCALAR(poshold_brake_rate_degs, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT),
285
286
// @Param: PHLD_BRAKE_ANGLE
287
// @DisplayName: PosHold braking angle max
288
// @Description: PosHold flight mode's max lean angle during braking in centi-degrees
289
// @Units: cdeg
290
// @Increment: 10
291
// @Range: 2000 4500
292
// @User: Advanced
293
GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),
294
#endif
295
296
// @Param: LAND_REPOSITION
297
// @DisplayName: Land repositioning
298
// @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
299
// @Values: 0:No repositioning, 1:Repositioning
300
// @User: Advanced
301
GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),
302
303
// @Param: FS_EKF_ACTION
304
// @DisplayName: EKF Failsafe Action
305
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
306
// @Values: 0:Report only, 1:Switch to Land mode if current mode requires position, 2:Switch to AltHold mode if current mode requires position, 3:Switch to Land mode from all modes
307
// @User: Advanced
308
GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),
309
310
// @Param: FS_EKF_THRESH
311
// @DisplayName: EKF failsafe variance threshold
312
// @Description: Allows setting the maximum acceptable compass, velocity, position and height variances. Used in arming check and EKF failsafe.
313
// @Values: 0:Disabled, 0.6:Strict, 0.8:Default, 1.0:Relaxed
314
// @Range: 0.0 1.0
315
// @User: Advanced
316
GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),
317
318
// @Param: FS_CRASH_CHECK
319
// @DisplayName: Crash check enable
320
// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
321
// @Values: 0:Disabled, 1:Enabled
322
// @User: Advanced
323
GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 1),
324
325
// @Param: RC_SPEED
326
// @DisplayName: ESC Update Speed
327
// @Description: This is the speed in Hertz that your ESCs will receive updates
328
// @Units: Hz
329
// @Range: 50 490
330
// @Increment: 1
331
// @User: Advanced
332
GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),
333
334
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
335
// @Param: ACRO_BAL_ROLL
336
// @DisplayName: Acro Balance Roll
337
// @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. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude.
338
// @Range: 0 3
339
// @Increment: 0.1
340
// @User: Advanced
341
GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),
342
343
// @Param: ACRO_BAL_PITCH
344
// @DisplayName: Acro Balance Pitch
345
// @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. For helicopter sets the decay rate of the virtual flybar in the pitch axis. A higher value causes faster decay of desired to actual attitude.
346
// @Range: 0 3
347
// @Increment: 0.1
348
// @User: Advanced
349
GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
350
#endif
351
352
// ACRO_RP_EXPO moved to Command Model class
353
354
#if MODE_ACRO_ENABLED
355
// @Param: ACRO_TRAINER
356
// @DisplayName: Acro Trainer
357
// @Description: Type of trainer used in acro mode
358
// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
359
// @User: Advanced
360
GSCALAR(acro_trainer, "ACRO_TRAINER", (uint8_t)ModeAcro::Trainer::LIMITED),
361
#endif
362
363
// variables not in the g class which contain EEPROM saved variables
364
365
#if AP_CAMERA_ENABLED
366
// @Group: CAM
367
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
368
GOBJECT(camera, "CAM", AP_Camera),
369
#endif
370
371
#if AP_RELAY_ENABLED
372
// @Group: RELAY
373
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
374
GOBJECT(relay, "RELAY", AP_Relay),
375
#endif
376
377
#if HAL_PARACHUTE_ENABLED
378
// @Group: CHUTE_
379
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
380
GOBJECT(parachute, "CHUTE_", AP_Parachute),
381
#endif
382
383
#if AP_LANDINGGEAR_ENABLED
384
// @Group: LGR_
385
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
386
GOBJECT(landinggear, "LGR_", AP_LandingGear),
387
#endif
388
389
#if FRAME_CONFIG == HELI_FRAME
390
// @Group: IM_
391
// @Path: ../libraries/AC_InputManager/AC_InputManager_Heli.cpp
392
GOBJECT(input_manager, "IM_", AC_InputManager_Heli),
393
#endif
394
395
// @Group: COMPASS_
396
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
397
GOBJECT(compass, "COMPASS_", Compass),
398
399
// @Group: INS
400
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
401
GOBJECT(ins, "INS", AP_InertialSensor),
402
403
// @Group: WPNAV_
404
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
405
GOBJECTPTR(wp_nav, "WPNAV_", AC_WPNav),
406
407
// @Group: LOIT_
408
// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
409
GOBJECTPTR(loiter_nav, "LOIT_", AC_Loiter),
410
411
#if MODE_CIRCLE_ENABLED
412
// @Group: CIRCLE_
413
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
414
GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),
415
#endif
416
417
// @Group: ATC_
418
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
419
GOBJECTVARPTR(attitude_control, "ATC_", &copter.attitude_control_var_info),
420
421
// @Group: PSC
422
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
423
GOBJECTPTR(pos_control, "PSC", AC_PosControl),
424
425
// SR0 through SR6 was here
426
427
// @Group: AHRS_
428
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
429
GOBJECT(ahrs, "AHRS_", AP_AHRS),
430
431
#if HAL_MOUNT_ENABLED
432
// @Group: MNT
433
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
434
GOBJECT(camera_mount, "MNT", AP_Mount),
435
#endif
436
437
// @Group: BATT
438
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
439
GOBJECT(battery, "BATT", AP_BattMonitor),
440
441
// @Group: BRD_
442
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
443
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
444
445
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
446
// @Group: CAN_
447
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
448
GOBJECT(can_mgr, "CAN_", AP_CANManager),
449
#endif
450
451
#if HAL_SPRAYER_ENABLED
452
// @Group: SPRAY_
453
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
454
GOBJECT(sprayer, "SPRAY_", AC_Sprayer),
455
#endif
456
457
#if AP_SIM_ENABLED
458
// @Group: SIM_
459
// @Path: ../libraries/SITL/SITL.cpp
460
GOBJECT(sitl, "SIM_", SITL::SIM),
461
#endif
462
463
// @Group: BARO
464
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
465
GOBJECT(barometer, "BARO", AP_Baro),
466
467
// GPS driver
468
// @Group: GPS
469
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
470
GOBJECT(gps, "GPS", AP_GPS),
471
472
// @Group: SCHED_
473
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
474
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
475
476
// @Group: AVOID_
477
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
478
#if AP_AVOIDANCE_ENABLED
479
GOBJECT(avoid, "AVOID_", AC_Avoid),
480
#endif
481
482
#if HAL_RALLY_ENABLED
483
// @Group: RALLY_
484
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
485
GOBJECT(rally, "RALLY_", AP_Rally_Copter),
486
#endif
487
488
#if FRAME_CONFIG == HELI_FRAME
489
// @Group: H_
490
// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp,../libraries/AP_Motors/AP_MotorsHeli_Dual.cpp,../libraries/AP_Motors/AP_MotorsHeli.cpp
491
GOBJECTVARPTR(motors, "H_", &copter.motors_var_info),
492
#else
493
// @Group: MOT_
494
// @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
495
GOBJECTVARPTR(motors, "MOT_", &copter.motors_var_info),
496
#endif
497
498
// @Group: RCMAP_
499
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
500
GOBJECT(rcmap, "RCMAP_", RCMapper),
501
502
#if HAL_NAVEKF2_AVAILABLE
503
// @Group: EK2_
504
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
505
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
506
#endif
507
508
#if HAL_NAVEKF3_AVAILABLE
509
// @Group: EK3_
510
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
511
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
512
#endif
513
514
#if MODE_AUTO_ENABLED
515
// @Group: MIS_
516
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
517
GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
518
#endif
519
520
#if AP_RSSI_ENABLED
521
// @Group: RSSI_
522
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
523
GOBJECT(rssi, "RSSI_", AP_RSSI),
524
#endif
525
526
#if AP_RANGEFINDER_ENABLED
527
// @Group: RNGFND
528
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
529
GOBJECT(rangefinder, "RNGFND", RangeFinder),
530
#endif
531
532
#if AP_TERRAIN_AVAILABLE
533
// @Group: TERRAIN_
534
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
535
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
536
#endif
537
538
#if AP_OPTICALFLOW_ENABLED
539
// @Group: FLOW
540
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
541
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
542
#endif
543
544
#if AC_PRECLAND_ENABLED
545
// @Group: PLND_
546
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
547
GOBJECT(precland, "PLND_", AC_PrecLand),
548
#endif
549
550
#if HAL_ADSB_ENABLED
551
// @Group: ADSB_
552
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
553
GOBJECT(adsb, "ADSB_", AP_ADSB),
554
#endif // HAL_ADSB_ENABLED
555
556
#if AP_ADSB_AVOIDANCE_ENABLED
557
// @Group: AVD_
558
// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp
559
GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Copter),
560
#endif // AP_ADSB_AVOIDANCE_ENABLED
561
562
// @Group: NTF_
563
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
564
GOBJECT(notify, "NTF_", AP_Notify),
565
566
#if MODE_THROW_ENABLED
567
// @Param: THROW_MOT_START
568
// @DisplayName: Start motors before throwing is detected
569
// @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.
570
// @Values: 0:Stopped,1:Running
571
// @User: Standard
572
GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),
573
574
// @Param: THROW_ALT_MIN
575
// @DisplayName: Throw mode minimum altitude
576
// @Description: Minimum altitude above which Throw mode will detect a throw or a drop - 0 to disable the check
577
// @Units: m
578
// @User: Advanced
579
GSCALAR(throw_altitude_min, "THROW_ALT_MIN", 0),
580
581
// @Param: THROW_ALT_MAX
582
// @DisplayName: Throw mode maximum altitude
583
// @Description: Maximum altitude under which Throw mode will detect a throw or a drop - 0 to disable the check
584
// @Units: m
585
// @User: Advanced
586
GSCALAR(throw_altitude_max, "THROW_ALT_MAX", 0),
587
588
// @Param: THROW_ALT_DCSND
589
// @DisplayName: Throw mode target altitude to descend
590
// @Description: Target altitude to descend during a drop, (must be positive). This allows for rapidly clearing surrounding obstacles.
591
// @Units: m
592
// @User: Advanced
593
GSCALAR(throw_altitude_descend, "THROW_ALT_DCSND", 1.0),
594
595
// @Param: THROW_ALT_ACSND
596
// @DisplayName: Throw mode target altitude to ascsend
597
// @Description: Target altitude to ascend during a throw upwards (must be positive). This allows for rapidly clearing surrounding obstacles.
598
// @Units: m
599
// @User: Advanced
600
GSCALAR(throw_altitude_ascend, "THROW_ALT_ACSND", 3.0),
601
#endif
602
603
#if OSD_ENABLED || OSD_PARAM_ENABLED
604
// @Group: OSD
605
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
606
GOBJECT(osd, "OSD", AP_OSD),
607
#endif
608
609
#if AC_CUSTOMCONTROL_MULTI_ENABLED
610
// @Group: CC
611
// @Path: ../libraries/AC_CustomControl/AC_CustomControl.cpp
612
GOBJECT(custom_control, "CC", AC_CustomControl),
613
#endif
614
615
// @Group:
616
// @Path: Parameters.cpp
617
GOBJECT(g2, "", ParametersG2),
618
619
// @Group:
620
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
621
PARAM_VEHICLE_INFO,
622
623
#if HAL_GCS_ENABLED
624
// @Group: MAV
625
// @Path: ../libraries/GCS_MAVLink/GCS.cpp
626
GOBJECT(_gcs, "MAV", GCS),
627
#endif
628
629
AP_VAREND
630
};
631
632
/*
633
2nd group of parameters
634
*/
635
const AP_Param::GroupInfo ParametersG2::var_info[] = {
636
637
// @Param: WP_NAVALT_MIN
638
// @DisplayName: Waypoint navigation altitude minimum
639
// @Description: Altitude in meters above which navigation will begin during auto takeoff
640
// @Units: m
641
// @Range: 0 5
642
// @User: Standard
643
AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min_m, 0),
644
645
#if HAL_BUTTON_ENABLED
646
// @Group: BTN_
647
// @Path: ../libraries/AP_Button/AP_Button.cpp
648
AP_SUBGROUPPTR(button_ptr, "BTN_", 2, ParametersG2, AP_Button),
649
#endif
650
651
#if MODE_THROW_ENABLED
652
// @Param: THROW_NEXTMODE
653
// @DisplayName: Throw mode's follow up mode
654
// @Description: Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)
655
// @Values: 3:Auto,4:Guided,5:LOITER,6:RTL,9:Land,17:Brake,18:Throw
656
// @User: Standard
657
AP_GROUPINFO("THROW_NEXTMODE", 3, ParametersG2, throw_nextmode, 18),
658
659
// @Param: THROW_TYPE
660
// @DisplayName: Type of Type
661
// @Description: Used by Throw mode. Specifies whether Copter is thrown upward or dropped.
662
// @Values: 0:Upward Throw,1:Drop
663
// @User: Standard
664
AP_GROUPINFO("THROW_TYPE", 4, ParametersG2, throw_type, (float)ModeThrow::ThrowType::Upward),
665
#endif
666
667
// @Param: GND_EFFECT_COMP
668
// @DisplayName: Ground Effect Compensation Enable/Disable
669
// @Description: Ground Effect Compensation Enable/Disable
670
// @Values: 0:Disabled,1:Enabled
671
// @User: Advanced
672
AP_GROUPINFO("GND_EFFECT_COMP", 5, ParametersG2, gndeffect_comp_enabled, 1),
673
674
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
675
// @Group: AFS_
676
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
677
AP_SUBGROUPINFO(afs, "AFS_", 6, ParametersG2, AP_AdvancedFailsafe),
678
#endif
679
680
// @Param: DEV_OPTIONS
681
// @DisplayName: Development options
682
// @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
683
// @Bitmask: 0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt
684
// @User: Advanced
685
AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),
686
687
#if AP_BEACON_ENABLED
688
// @Group: BCN
689
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
690
AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon),
691
#endif
692
693
#if HAL_PROXIMITY_ENABLED
694
// @Group: PRX
695
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
696
AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity),
697
#endif
698
699
// ACRO_Y_EXPO (9) moved to Command Model Class
700
701
#if MODE_ACRO_ENABLED
702
// @Param: ACRO_THR_MID
703
// @DisplayName: Acro Thr Mid
704
// @Description: Acro Throttle Mid
705
// @Range: 0 1
706
// @User: Advanced
707
AP_GROUPINFO("ACRO_THR_MID", 10, ParametersG2, acro_thr_mid, ACRO_THR_MID_DEFAULT),
708
#endif
709
710
// 11 was SYSID_ENFORCE
711
712
// 12 was AP_Stats
713
714
// 13 was AP_Gripper
715
716
// @Param: FRAME_CLASS
717
// @DisplayName: Frame Class
718
// @Description: Controls major frame class for multicopter component
719
// @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 10:BiCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad, 14:Deca, 15:Scripting Matrix, 16:6DoF Scripting, 17:Dynamic Scripting Matrix
720
// @User: Standard
721
// @RebootRequired: True
722
AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, DEFAULT_FRAME_CLASS),
723
724
// @Group: SERVO
725
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
726
AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),
727
728
// @Group: RC
729
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
730
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter),
731
732
// 18 was used by AP_VisualOdom
733
734
#if AP_TEMPCALIBRATION_ENABLED
735
// @Group: TCAL
736
// @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp
737
AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration),
738
#endif
739
740
#if TOY_MODE_ENABLED
741
// @Group: TMODE
742
// @Path: toy_mode.cpp
743
AP_SUBGROUPINFO(toy_mode, "TMODE", 20, ParametersG2, ToyMode),
744
#endif
745
746
#if MODE_SMARTRTL_ENABLED
747
// @Group: SRTL_
748
// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
749
AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL),
750
#endif
751
752
#if AP_WINCH_ENABLED
753
// 22 was AP_WheelEncoder
754
755
// @Group: WINCH
756
// @Path: ../libraries/AP_Winch/AP_Winch.cpp
757
AP_SUBGROUPINFO(winch, "WINCH", 23, ParametersG2, AP_Winch),
758
#endif
759
760
// @Param: PILOT_SPEED_DN
761
// @DisplayName: Pilot maximum vertical speed descending
762
// @Description: The maximum vertical descending velocity the pilot may request in cm/s. If 0 PILOT_SPEED_UP value is used.
763
// @Units: cm/s
764
// @Range: 0 500
765
// @Increment: 10
766
// @User: Standard
767
AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn_cms, 0),
768
769
// 25 was LAND_ALT_LOW
770
771
#if MODE_FLOWHOLD_ENABLED
772
// @Group: FHLD
773
// @Path: mode_flowhold.cpp
774
AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold),
775
#endif
776
777
#if MODE_FOLLOW_ENABLED
778
// @Group: FOLL
779
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
780
AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow),
781
#endif
782
783
#if USER_PARAMS_ENABLED
784
AP_SUBGROUPINFO(user_parameters, "USR", 28, ParametersG2, UserParameters),
785
#endif
786
787
#if AUTOTUNE_ENABLED
788
// @Group: AUTOTUNE_
789
// @Path: ../libraries/AC_AutoTune/AC_AutoTune_Multi.cpp,../libraries/AC_AutoTune/AC_AutoTune_Heli.cpp
790
AP_SUBGROUPPTR(autotune_ptr, "AUTOTUNE_", 29, ParametersG2, AutoTune),
791
#endif
792
793
// 30 was AP_Scripting
794
795
#if AP_RC_TRANSMITTER_TUNING_ENABLED
796
// @Param: TUNE_MIN
797
// @DisplayName: Tuning minimum
798
// @Description: Transmitter Tuning minum value. The parameter being tuned will have its value set to this minimum value when the tuning knob is at its lowest position
799
// @User: Standard
800
AP_GROUPINFO("TUNE_MIN", 31, ParametersG2, rc_tuning_min, 0),
801
802
// @Param: TUNE_MAX
803
// @DisplayName: Tuning maximum
804
// @Description: Transmitter Tuning maximum value. The parameter being tuned will have its value set to this maximum value when the tuning knob is at its highest position
805
// @User: Standard
806
AP_GROUPINFO("TUNE_MAX", 32, ParametersG2, rc_tuning_max, 0),
807
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
808
809
#if AP_OAPATHPLANNER_ENABLED
810
// @Group: OA_
811
// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp
812
AP_SUBGROUPINFO(oa, "OA_", 33, ParametersG2, AP_OAPathPlanner),
813
#endif
814
815
#if MODE_SYSTEMID_ENABLED
816
// @Group: SID
817
// @Path: mode_systemid.cpp
818
AP_SUBGROUPPTR(mode_systemid_ptr, "SID", 34, ParametersG2, ModeSystemId),
819
#endif
820
821
// @Param: FS_VIBE_ENABLE
822
// @DisplayName: Vibration Failsafe enable
823
// @Description: This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations
824
// @Values: 0:Disabled, 1:Enabled
825
// @User: Standard
826
AP_GROUPINFO("FS_VIBE_ENABLE", 35, ParametersG2, fs_vibe_enabled, 1),
827
828
// @Param: FS_OPTIONS
829
// @DisplayName: Failsafe options bitmask
830
// @Description: Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.
831
// @Bitmask: 0:Continue if in Auto on RC failsafe, 1:Continue if in Auto on GCS failsafe, 2:Continue if in Guided on RC failsafe, 3:Continue if landing on any failsafe, 4:Continue if in pilot controlled modes on GCS failsafe, 5:Release Gripper
832
// @User: Advanced
833
AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Copter::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL),
834
835
#if MODE_AUTOROTATE_ENABLED
836
// @Group: AROT_
837
// @Path: ../libraries/AC_Autorotation/AC_Autorotation.cpp
838
AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation),
839
#endif
840
841
#if MODE_ZIGZAG_ENABLED
842
// @Group: ZIGZ_
843
// @Path: mode_zigzag.cpp
844
AP_SUBGROUPPTR(mode_zigzag_ptr, "ZIGZ_", 38, ParametersG2, ModeZigZag),
845
#endif
846
847
#if MODE_ACRO_ENABLED
848
// @Param: ACRO_OPTIONS
849
// @DisplayName: Acro mode options
850
// @Description: A range of options that can be applied to change acro mode behaviour. Air-mode enables ATC_THR_MIX_MAN at all times (air-mode has no effect on helicopters). Rate Loop Only disables the use of angle stabilization and uses angular rate stabilization only.
851
// @Bitmask: 0:Air-mode,1:Rate Loop Only
852
// @User: Advanced
853
AP_GROUPINFO("ACRO_OPTIONS", 39, ParametersG2, acro_options, 0),
854
#endif
855
856
#if MODE_AUTO_ENABLED
857
// @Param: AUTO_OPTIONS
858
// @DisplayName: Auto mode options
859
// @Description: A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle. Ignore pilot yaw overrides the pilot's yaw stick being used while in auto.
860
// @Bitmask: 0:Allow Arming,1:Allow Takeoff Without Raising Throttle,2:Ignore pilot yaw,7:Allow weathervaning
861
// @User: Advanced
862
AP_GROUPINFO("AUTO_OPTIONS", 40, ParametersG2, auto_options, 0),
863
#endif
864
865
#if MODE_GUIDED_ENABLED
866
// @Param: GUID_OPTIONS
867
// @DisplayName: Guided mode options
868
// @Description: Options that can be applied to change guided mode behaviour
869
// @Bitmask: 0:Allow Arming from Transmitter,2:Ignore pilot yaw,3:SetAttitudeTarget interprets Thrust As Thrust,4:Do not stabilize PositionXY,5:Do not stabilize VelocityXY,6:Waypoint navigation used for position targets,7:Allow weathervaning
870
// @User: Advanced
871
AP_GROUPINFO("GUID_OPTIONS", 41, ParametersG2, guided_options, 0),
872
#endif
873
874
// @Param: FS_GCS_TIMEOUT
875
// @DisplayName: GCS failsafe timeout
876
// @Description: Timeout before triggering the GCS failsafe
877
// @Units: s
878
// @Range: 2 120
879
// @Increment: 1
880
// @User: Standard
881
AP_GROUPINFO("FS_GCS_TIMEOUT", 42, ParametersG2, fs_gcs_timeout, 5),
882
883
#if MODE_RTL_ENABLED
884
// @Param: RTL_OPTIONS
885
// @DisplayName: RTL mode options
886
// @Description: Options that can be applied to change RTL mode behaviour
887
// @Bitmask: 2:Ignore pilot yaw
888
// @User: Advanced
889
AP_GROUPINFO("RTL_OPTIONS", 43, ParametersG2, rtl_options, 0),
890
#endif
891
892
// @Param: FLIGHT_OPTIONS
893
// @DisplayName: Flight mode options
894
// @Description: Flight mode specific options
895
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss
896
// @User: Advanced
897
AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),
898
899
#if AP_RANGEFINDER_ENABLED
900
// @Param: RNGFND_FILT
901
// @DisplayName: Rangefinder filter
902
// @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering
903
// @Units: Hz
904
// @Range: 0 5
905
// @Increment: 0.05
906
// @User: Standard
907
// @RebootRequired: True
908
AP_GROUPINFO("RNGFND_FILT", 45, ParametersG2, rangefinder_filt, RANGEFINDER_FILT_DEFAULT),
909
#endif
910
911
#if MODE_GUIDED_ENABLED
912
// @Param: GUID_TIMEOUT
913
// @DisplayName: Guided mode timeout
914
// @Description: Guided mode timeout after which vehicle will stop or return to level if no updates are received from caller. Only applicable during any combination of velocity, acceleration, angle control, and/or angular rate control
915
// @Units: s
916
// @Range: 0.1 5
917
// @User: Advanced
918
AP_GROUPINFO("GUID_TIMEOUT", 46, ParametersG2, guided_timeout, 3.0),
919
#endif
920
921
// ACRO_PR_RATE (47), ACRO_Y_RATE (48), PILOT_Y_RATE (49) and PILOT_Y_EXPO (50) moved to command model class
922
923
#if AP_RANGEFINDER_ENABLED
924
// @Param: SURFTRAK_MODE
925
// @DisplayName: Surface Tracking Mode
926
// @Description: set which surface to track in surface tracking
927
// @Values: 0:Do not track, 1:Ground, 2:Ceiling
928
// @User: Advanced
929
// @RebootRequired: True
930
AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND),
931
#endif
932
933
// @Param: FS_DR_ENABLE
934
// @DisplayName: DeadReckon Failsafe Action
935
// @Description: Failsafe action taken immediately as deadreckoning starts. Deadreckoning starts when EKF loses position and velocity source and relies only on wind estimates
936
// @Values: 0:Disabled/NoAction,1:Land, 2:RTL, 3:SmartRTL or RTL, 4:SmartRTL or Land, 6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL
937
// @User: Standard
938
AP_GROUPINFO("FS_DR_ENABLE", 52, ParametersG2, failsafe_dr_enable, (uint8_t)Copter::FailsafeAction::RTL),
939
940
// @Param: FS_DR_TIMEOUT
941
// @DisplayName: DeadReckon Failsafe Timeout
942
// @Description: DeadReckoning is available for this many seconds after losing position and/or velocity source. After this timeout elapses the EKF failsafe will trigger in modes requiring a position estimate
943
// @Range: 0 120
944
// @User: Standard
945
AP_GROUPINFO("FS_DR_TIMEOUT", 53, ParametersG2, failsafe_dr_timeout, 30),
946
947
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
948
// @Param: ACRO_RP_RATE
949
// @DisplayName: Acro Roll and Pitch Rate
950
// @Description: Acro mode maximum roll and pitch rate. Higher values mean faster rate of rotation
951
// @Units: deg/s
952
// @Range: 1 1080
953
// @User: Standard
954
955
// @Param: ACRO_RP_EXPO
956
// @DisplayName: Acro Roll/Pitch Expo
957
// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges
958
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
959
// @Range: -0.5 0.95
960
// @User: Advanced
961
962
// @Param: ACRO_RP_RATE_TC
963
// @DisplayName: Acro roll/pitch rate control input time constant
964
// @Description: Acro roll and pitch rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response
965
// @Units: s
966
// @Range: 0 1
967
// @Increment: 0.01
968
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
969
// @User: Standard
970
AP_SUBGROUPINFO(command_model_acro_rp, "ACRO_RP_", 54, ParametersG2, AC_CommandModel),
971
#endif
972
973
#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED
974
// @Param: ACRO_Y_RATE
975
// @DisplayName: Acro Yaw Rate
976
// @Description: Acro mode maximum yaw rate. Higher value means faster rate of rotation
977
// @Units: deg/s
978
// @Range: 1 360
979
// @User: Standard
980
981
// @Param: ACRO_Y_EXPO
982
// @DisplayName: Acro Yaw Expo
983
// @Description: Acro yaw expo to allow faster rotation when stick at edges
984
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
985
// @Range: -1.0 0.95
986
// @User: Advanced
987
988
// @Param: ACRO_Y_RATE_TC
989
// @DisplayName: Acro yaw rate control input time constant
990
// @Description: Acro yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response
991
// @Units: s
992
// @Range: 0 1
993
// @Increment: 0.01
994
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
995
// @User: Standard
996
AP_SUBGROUPINFO(command_model_acro_y, "ACRO_Y_", 55, ParametersG2, AC_CommandModel),
997
#endif
998
999
// @Param: PILOT_Y_RATE
1000
// @DisplayName: Pilot controlled yaw rate
1001
// @Description: Pilot controlled yaw rate max. Used in all pilot controlled modes except Acro
1002
// @Units: deg/s
1003
// @Range: 1 360
1004
// @User: Standard
1005
1006
// @Param: PILOT_Y_EXPO
1007
// @DisplayName: Pilot controlled yaw expo
1008
// @Description: Pilot controlled yaw expo to allow faster rotation when stick at edges
1009
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
1010
// @Range: -0.5 1.0
1011
// @User: Advanced
1012
1013
// @Param: PILOT_Y_RATE_TC
1014
// @DisplayName: Pilot yaw rate control input time constant
1015
// @Description: Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response
1016
// @Units: s
1017
// @Range: 0 1
1018
// @Increment: 0.01
1019
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
1020
// @User: Standard
1021
AP_SUBGROUPINFO(command_model_pilot_y, "PILOT_Y_", 56, ParametersG2, AC_CommandModel),
1022
1023
// @Param: TKOFF_SLEW_TIME
1024
// @DisplayName: Slew time of throttle during take-off
1025
// @Description: Time to slew the throttle from minimum to maximum while checking for a successful takeoff.
1026
// @Units: s
1027
// @Range: 0.25 5.0
1028
// @User: Standard
1029
AP_GROUPINFO("TKOFF_SLEW_TIME", 57, ParametersG2, takeoff_throttle_slew_time, 2.0),
1030
1031
#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME
1032
// @Param: TKOFF_RPM_MIN
1033
// @DisplayName: Takeoff Check RPM minimum
1034
// @Description: Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check
1035
// @Range: 0 10000
1036
// @User: Standard
1037
AP_GROUPINFO("TKOFF_RPM_MIN", 58, ParametersG2, takeoff_rpm_min, 0),
1038
#endif
1039
1040
#if WEATHERVANE_ENABLED
1041
// @Group: WVANE_
1042
// @Path: ../libraries/AC_AttitudeControl/AC_WeatherVane.cpp
1043
AP_SUBGROUPINFO(weathervane, "WVANE_", 59, ParametersG2, AC_WeatherVane),
1044
#endif
1045
1046
// ID 60 is reserved for the SHIP_OPS
1047
1048
// extend to a new group
1049
AP_SUBGROUPEXTENSION("", 61, ParametersG2, var_info2),
1050
1051
// ID 62 is reserved for the SHOW_... parameters from the Skybrush fork at
1052
// https://github.com/skybrush-io/ardupilot
1053
1054
AP_GROUPEND
1055
};
1056
1057
/*
1058
extension to g2 parameters
1059
*/
1060
const AP_Param::GroupInfo ParametersG2::var_info2[] = {
1061
1062
#if AC_PAYLOAD_PLACE_ENABLED
1063
// @Param: PLDP_THRESH
1064
// @DisplayName: Payload Place thrust ratio threshold
1065
// @Description: Ratio of vertical thrust during decent below which payload touchdown will trigger.
1066
// @Range: 0.5 0.9
1067
// @User: Standard
1068
AP_GROUPINFO("PLDP_THRESH", 1, ParametersG2, pldp_thrust_placed_fraction, 0.9),
1069
1070
// @Param: PLDP_RNG_MAX
1071
// @DisplayName: Payload Place maximum range finder altitude
1072
// @Description: Maximum range finder altitude in m to trigger payload touchdown, set to zero to disable.
1073
// @Units: m
1074
// @Range: 0 100
1075
// @User: Standard
1076
AP_GROUPINFO("PLDP_RNG_MAX", 2, ParametersG2, pldp_range_finder_maximum_m, 0.0),
1077
1078
// @Param: PLDP_DELAY
1079
// @DisplayName: Payload Place climb delay
1080
// @Description: Delay after release, in seconds, before aircraft starts to climb back to starting altitude.
1081
// @Units: s
1082
// @Range: 0 120
1083
// @User: Standard
1084
AP_GROUPINFO("PLDP_DELAY", 3, ParametersG2, pldp_delay_s, 0.0),
1085
1086
// @Param: PLDP_SPEED_DN
1087
// @DisplayName: Payload Place decent speed
1088
// @Description: The maximum vertical decent velocity in m/s. If 0 LAND_SPD_MS value is used.
1089
// @Units: m/s
1090
// @Range: 0 5
1091
// @User: Standard
1092
AP_GROUPINFO("PLDP_SPEED_DN", 4, ParametersG2, pldp_descent_speed_ms, 0.0),
1093
#endif // AC_PAYLOAD_PLACE_ENABLED
1094
1095
// @Param: SURFTRAK_TC
1096
// @DisplayName: Surface Tracking Filter Time Constant
1097
// @Description: Time to achieve 63.2% of the surface altitude measurement change. If 0 filtering is disabled
1098
// @Units: s
1099
// @Range: 0 5
1100
// @User: Advanced
1101
AP_GROUPINFO("SURFTRAK_TC", 5, ParametersG2, surftrak_tc, 1.0),
1102
1103
// @Param: TKOFF_THR_MAX
1104
// @DisplayName: Takeoff maximum throttle during take-off ramp up
1105
// @Description: Takeoff maximum throttle allowed before controllers assume the aircraft is airborne during the takeoff process.
1106
// @Range: 0.0 0.9
1107
// @User: Advanced
1108
AP_GROUPINFO("TKOFF_THR_MAX", 6, ParametersG2, takeoff_throttle_max, 0.9),
1109
1110
#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME
1111
// @Param: TKOFF_RPM_MAX
1112
// @DisplayName: Takeoff Check RPM maximum
1113
// @Description: Takeoff is not permitted until motors report no more than this RPM. Set to zero to disable check
1114
// @Range: 0 10000
1115
// @User: Standard
1116
AP_GROUPINFO("TKOFF_RPM_MAX", 7, ParametersG2, takeoff_rpm_max, 0),
1117
#endif
1118
1119
// @Param: FS_EKF_FILT
1120
// @DisplayName: EKF Failsafe filter cutoff
1121
// @Description: EKF Failsafe filter cutoff frequency. EKF variances are filtered using this value to avoid spurious failsafes from transient high variances. A higher value means the failsafe is more likely to trigger.
1122
// @Range: 0 10
1123
// @Units: Hz
1124
// @User: Advanced
1125
AP_GROUPINFO("FS_EKF_FILT", 8, ParametersG2, fs_ekf_filt_hz, FS_EKF_FILT_DEFAULT),
1126
1127
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
1128
// @Param: FSTRATE_ENABLE
1129
// @DisplayName: Enable the fast Rate thread
1130
// @Description: Enable the fast Rate thread. In the default case the fast rate divisor, which controls the update frequency of the thread, is dynamically scaled from FSTRATE_DIV to avoid overrun in the gyro sample buffer and main loop slow-downs. Other values can be selected to fix the divisor to FSTRATE_DIV on arming or always.
1131
// @User: Advanced
1132
// @Values: 0:Disabled,1:Enabled-Dynamic,2:Enabled-FixedWhenArmed,3:Enabled-Fixed
1133
AP_GROUPINFO("FSTRATE_ENABLE", 9, ParametersG2, att_enable, 0),
1134
1135
// @Param: FSTRATE_DIV
1136
// @DisplayName: Fast rate thread divisor
1137
// @Description: Fast rate thread divisor used to control the maximum fast rate update rate. The actual rate is the gyro rate in Hz divided by this value. This value is scaled depending on the configuration of FSTRATE_ENABLE.
1138
// @User: Advanced
1139
// @Range: 1 10
1140
AP_GROUPINFO("FSTRATE_DIV", 10, ParametersG2, att_decimation, 1),
1141
#endif
1142
1143
#if AP_RC_TRANSMITTER_TUNING_ENABLED
1144
// @Param: TUNE2_MIN
1145
// @DisplayName: Tuning minimum
1146
// @Description: Minimum value that the parameter currently being tuned with the transmitter's TRANSMITTER_TUNING2 knob will be set to
1147
// @User: Standard
1148
AP_GROUPINFO("TUNE2_MIN", 11, ParametersG2, rc_tuning2_min, 0),
1149
1150
// @Param: TUNE2_MAX
1151
// @DisplayName: Tuning maximum
1152
// @Description: Maximum value that the parameter currently being tuned with the transmitter's TRANSMITTER2_TUNING knob will be set to
1153
// @User: Standard
1154
AP_GROUPINFO("TUNE2_MAX", 12, ParametersG2, rc_tuning2_max, 0),
1155
1156
// @Param: TUNE2
1157
// @CopyFieldsFrom: TUNE
1158
// @DisplayName: Tuning Parameter for TRANSMITTER_TUNE2
1159
// @Description: Selects parameter (normally a PID gain) that is being tuned with an RC transmitter's knob. The RC input channel used is assigned by setting RCx_OPTION to 220.
1160
AP_GROUPINFO("TUNE2", 13, ParametersG2, rc_tuning2_param, 0),
1161
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
1162
1163
#if MODE_RTL_ENABLED
1164
// @Group: RTL_
1165
// @Path: mode_rtl.cpp
1166
AP_SUBGROUPPTR(mode_rtl_ptr, "RTL_", 14, ParametersG2, ModeRTL),
1167
#endif
1168
1169
// @Group: LAND_
1170
// @Path: mode_land.cpp
1171
AP_SUBGROUPPTR(mode_land_ptr, "LAND_", 15, ParametersG2, ModeLand),
1172
1173
// ID 62 is reserved for the AP_SUBGROUPEXTENSION
1174
1175
AP_GROUPEND
1176
};
1177
1178
/*
1179
constructor for g2 object
1180
*/
1181
ParametersG2::ParametersG2(void) :
1182
unused_integer{17}
1183
#if HAL_BUTTON_ENABLED
1184
,button_ptr(&copter.button)
1185
#endif
1186
#if AP_TEMPCALIBRATION_ENABLED
1187
, temp_calibration()
1188
#endif
1189
#if AP_BEACON_ENABLED
1190
, beacon()
1191
#endif
1192
#if HAL_PROXIMITY_ENABLED
1193
, proximity()
1194
#endif
1195
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
1196
,afs()
1197
#endif
1198
#if MODE_SMARTRTL_ENABLED
1199
,smart_rtl()
1200
#endif
1201
#if USER_PARAMS_ENABLED
1202
,user_parameters()
1203
#endif
1204
#if MODE_FLOWHOLD_ENABLED
1205
,mode_flowhold_ptr(&copter.mode_flowhold)
1206
#endif
1207
#if MODE_FOLLOW_ENABLED
1208
,follow()
1209
#endif
1210
#if AUTOTUNE_ENABLED
1211
,autotune_ptr(&copter.mode_autotune.autotune)
1212
#endif
1213
#if MODE_SYSTEMID_ENABLED
1214
,mode_systemid_ptr(&copter.mode_systemid)
1215
#endif
1216
#if MODE_AUTOROTATE_ENABLED
1217
,arot(copter.motors, copter.attitude_control)
1218
#endif
1219
#if MODE_ZIGZAG_ENABLED
1220
,mode_zigzag_ptr(&copter.mode_zigzag)
1221
#endif
1222
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
1223
,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f)
1224
#endif
1225
1226
#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED
1227
,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f)
1228
#endif
1229
1230
,command_model_pilot_y(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)
1231
1232
#if WEATHERVANE_ENABLED
1233
,weathervane()
1234
#endif
1235
#if MODE_RTL_ENABLED
1236
,mode_rtl_ptr(&copter.mode_rtl)
1237
#endif
1238
,mode_land_ptr(&copter.mode_land)
1239
{
1240
AP_Param::setup_object_defaults(this, var_info);
1241
AP_Param::setup_object_defaults(this, var_info2);
1242
}
1243
1244
void Copter::load_parameters(void)
1245
{
1246
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
1247
1248
// PARAMETER_CONVERSION - Added: Mar-2022
1249
#if AP_FENCE_ENABLED
1250
AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true);
1251
#endif
1252
1253
// PARAMETER_CONVERSION - Added: July-2025 for ArduPilot-4.7
1254
#if AP_RPM_ENABLED
1255
AP_Param::convert_class(g.k_param_rpm_sensor_old, &rpm_sensor, rpm_sensor.var_info, 0, true, true);
1256
#endif
1257
1258
static const AP_Param::G2ObjectConversion g2_conversions[] {
1259
#if AP_STATS_ENABLED
1260
// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6
1261
{ &stats, stats.var_info, 12 },
1262
#endif
1263
#if AP_SCRIPTING_ENABLED
1264
// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6
1265
{ &scripting, scripting.var_info, 30 },
1266
#endif
1267
#if AP_GRIPPER_ENABLED
1268
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
1269
{ &gripper, gripper.var_info, 13 },
1270
#endif
1271
};
1272
1273
AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));
1274
1275
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
1276
#if HAL_LOGGING_ENABLED
1277
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
1278
#endif
1279
1280
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
1281
#if AP_SERIALMANAGER_ENABLED
1282
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
1283
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
1284
#endif
1285
};
1286
1287
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
1288
1289
#if HAL_GCS_ENABLED
1290
// Move parameters into new MAV_ parameter namespace
1291
// PARAMETER_CONVERSION - Added: Mar-2025 for ArduPilot-4.7
1292
{
1293
const AP_Param::ConversionInfo gcs_conversion_info[] {
1294
{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },
1295
{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },
1296
{ Parameters::k_param_g2, 11, AP_PARAM_INT8, "MAV_OPTIONS" },
1297
{ Parameters::k_param_telem_delay_old, 0, AP_PARAM_INT8, "MAV_TELEM_DELAY" },
1298
};
1299
AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));
1300
}
1301
#endif // HAL_GCS_ENABLED
1302
1303
#if MODE_RTL_ENABLED
1304
// convert RTL parameters
1305
copter.mode_rtl.convert_params();
1306
#endif
1307
1308
// convert LAND parameters
1309
copter.mode_land.convert_params();
1310
1311
// setup AP_Param frame type flags
1312
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);
1313
}
1314
1315
// handle conversion of PID gains
1316
void Copter::convert_pid_parameters(void)
1317
{
1318
const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {
1319
// PARAMETER_CONVERSION - Added: Aug-2021
1320
{ Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_NE_VEL_FLTE" },
1321
};
1322
1323
// convert angle controller gain and filter without scaling
1324
for (const auto &info : angle_and_filt_conversion_info) {
1325
AP_Param::convert_old_parameter(&info, 1.0f);
1326
}
1327
1328
// TradHeli default parameters
1329
#if FRAME_CONFIG == HELI_FRAME
1330
static const struct AP_Param::defaults_table_struct heli_defaults_table[] = {
1331
{ "LOIT_ACC_MAX_M", 5.0f },
1332
{ "LOIT_BRK_ACC_M", 1.25f },
1333
{ "LOIT_BRK_DELAY", 1.0f },
1334
{ "LOIT_BRK_JRK_M", 2.5f },
1335
{ "LOIT_SPEED_MS", 30.0f },
1336
{ "PHLD_BRAKE_ANGLE", 800.0f },
1337
{ "PHLD_BRAKE_RATE", 4.0f },
1338
{ "PSC_D_ACC_P", 0.028f },
1339
{ "PSC_NE_VEL_D", 0.0f },
1340
{ "PSC_NE_VEL_I", 0.5f },
1341
{ "PSC_NE_VEL_P", 1.0f },
1342
{ "RC8_OPTION", 32 },
1343
{ "RC_OPTIONS", 0 },
1344
{ "ATC_RAT_RLL_ILMI", 0.05},
1345
{ "ATC_RAT_PIT_ILMI", 0.05},
1346
};
1347
AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table));
1348
#endif // FRAME_CONFIG == HELI_FRAME
1349
1350
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
1351
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
1352
if (!ins.harmonic_notches[1].params.enabled()) {
1353
// notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch
1354
const AP_Param::ConversionInfo notchfilt_conversion_info[] {
1355
// PARAMETER_CONVERSION - Added: Apr 2022
1356
{ Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" },
1357
{ Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" },
1358
{ Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" },
1359
{ Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" },
1360
};
1361
AP_Param::convert_old_parameters(&notchfilt_conversion_info[0], ARRAY_SIZE(notchfilt_conversion_info));
1362
AP_Param::set_default_by_name("INS_HNTC2_MODE", 0);
1363
AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);
1364
}
1365
#endif
1366
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
1367
1368
// ACRO_RP_P and ACRO_Y_P replaced with ACRO_RP_RATE and ACRO_Y_RATE for Copter-4.2
1369
// PARAMETER_CONVERSION - Added: Sep-2021
1370
const AP_Param::ConversionInfo acro_rpy_conversion_info[] = {
1371
{ Parameters::k_param_acro_rp_p, 0, AP_PARAM_FLOAT, "ACRO_RP_RATE" },
1372
{ Parameters::k_param_acro_yaw_p, 0, AP_PARAM_FLOAT, "ACRO_Y_RATE" }
1373
};
1374
for (const auto &info : acro_rpy_conversion_info) {
1375
AP_Param::convert_old_parameter(&info, 45.0);
1376
}
1377
1378
// convert rate and expo command model parameters for Copter-4.3
1379
// PARAMETER_CONVERSION - Added: June-2022
1380
const AP_Param::ConversionInfo cmd_mdl_conversion_info[] = {
1381
{ Parameters::k_param_g2, 47, AP_PARAM_FLOAT, "ACRO_RP_RATE" },
1382
{ Parameters::k_param_acro_rp_expo, 0, AP_PARAM_FLOAT, "ACRO_RP_EXPO" },
1383
{ Parameters::k_param_g2, 48, AP_PARAM_FLOAT, "ACRO_Y_RATE" },
1384
{ Parameters::k_param_g2, 9, AP_PARAM_FLOAT, "ACRO_Y_EXPO" },
1385
{ Parameters::k_param_g2, 49, AP_PARAM_FLOAT, "PILOT_Y_RATE" },
1386
{ Parameters::k_param_g2, 50, AP_PARAM_FLOAT, "PILOT_Y_EXPO" },
1387
};
1388
for (const auto &info : cmd_mdl_conversion_info) {
1389
AP_Param::convert_old_parameter(&info, 1.0);
1390
}
1391
1392
// make any SRV_Channel upgrades needed
1393
SRV_Channels::upgrade_parameters();
1394
}
1395
1396
#if HAL_PROXIMITY_ENABLED
1397
void Copter::convert_prx_parameters()
1398
{
1399
// convert PRX to PRX1_ parameters for Copter-4.3
1400
// PARAMETER_CONVERSION - Added: Aug-2022
1401
static const AP_Param::ConversionInfo prx_conversion_info[] = {
1402
{ Parameters::k_param_g2, 72, AP_PARAM_INT8, "PRX1_TYPE" },
1403
{ Parameters::k_param_g2, 136, AP_PARAM_INT8, "PRX1_ORIENT" },
1404
{ Parameters::k_param_g2, 200, AP_PARAM_INT16, "PRX1_YAW_CORR" },
1405
{ Parameters::k_param_g2, 264, AP_PARAM_INT16, "PRX1_IGN_ANG1" },
1406
{ Parameters::k_param_g2, 328, AP_PARAM_INT8, "PRX1_IGN_WID1" },
1407
{ Parameters::k_param_g2, 392, AP_PARAM_INT16, "PRX1_IGN_ANG2" },
1408
{ Parameters::k_param_g2, 456, AP_PARAM_INT8, "PRX1_IGN_WID2" },
1409
{ Parameters::k_param_g2, 520, AP_PARAM_INT16, "PRX1_IGN_ANG3" },
1410
{ Parameters::k_param_g2, 584, AP_PARAM_INT8, "PRX1_IGN_WID3" },
1411
{ Parameters::k_param_g2, 648, AP_PARAM_INT16, "PRX1_IGN_ANG4" },
1412
{ Parameters::k_param_g2, 712, AP_PARAM_INT8, "PRX1_IGN_WID4" },
1413
{ Parameters::k_param_g2, 1224, AP_PARAM_FLOAT, "PRX1_MIN" },
1414
{ Parameters::k_param_g2, 1288, AP_PARAM_FLOAT, "PRX1_MAX" },
1415
};
1416
for (const auto &info : prx_conversion_info) {
1417
AP_Param::convert_old_parameter(&info, 1.0);
1418
}
1419
}
1420
#endif
1421
1422