CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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