CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

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

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/Parameters.h
Views: 1798
1
#pragma once
2
3
#define AP_PARAM_VEHICLE_NAME plane
4
5
#include <AP_Common/AP_Common.h>
6
7
// Global parameter class.
8
//
9
class Parameters {
10
public:
11
12
/*
13
* The value of k_format_version determines whether the existing
14
* eeprom data is considered valid. You should only change this
15
* value under the following circumstances:
16
*
17
* 1) the meaning of an existing eeprom parameter changes
18
*
19
* 2) the value of an existing k_param_* enum value changes
20
*
21
* Adding a new parameter should _not_ require a change to
22
* k_format_version except under special circumstances. If you
23
* change it anyway then all ArduPlane users will need to reload all
24
* their parameters. We want that to be an extremely rare
25
* thing. Please do not just change it "just in case".
26
*
27
* To determine if a k_param_* value has changed, use the rules of
28
* C++ enums to work out the value of the neighboring enum
29
* values. If you don't know the C++ enum rules then please ask for
30
* help.
31
*/
32
33
//////////////////////////////////////////////////////////////////
34
// STOP!!! DO NOT CHANGE THIS VALUE UNTIL YOU FULLY UNDERSTAND THE
35
// COMMENTS ABOVE. IF UNSURE, ASK ANOTHER DEVELOPER!!!
36
static const uint16_t k_format_version = 13;
37
//////////////////////////////////////////////////////////////////
38
39
40
enum {
41
// Layout version number, always key zero.
42
//
43
k_param_format_version = 0,
44
k_param_software_type, // unused;
45
k_param_num_resets, // unused
46
k_param_NavEKF2,
47
k_param_g2,
48
k_param_avoidance_adsb,
49
k_param_landing,
50
k_param_NavEKF3,
51
k_param_can_mgr,
52
k_param_osd,
53
54
// Misc
55
//
56
k_param_auto_trim = 10, // unused
57
k_param_log_bitmask_old, // unused
58
k_param_pitch_trim,
59
k_param_mix_mode,
60
k_param_reverse_elevons, // unused
61
k_param_reverse_ch1_elevon, // unused
62
k_param_reverse_ch2_elevon, // unused
63
k_param_flap_1_percent,
64
k_param_flap_1_speed,
65
k_param_flap_2_percent,
66
k_param_flap_2_speed,
67
k_param_reset_switch_chan, // unused - moved to RC option
68
k_param_manual_level, // unused
69
k_param_land_pitch_cd, // unused - moved to AP_Landing
70
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
71
k_param_stick_mixing,
72
k_param_reset_mission_chan, // unused - moved to RC option
73
k_param_land_flare_alt, // unused - moved to AP_Landing
74
k_param_land_flare_sec, // unused - moved to AP_Landing
75
k_param_crosstrack_min_distance, // unused
76
k_param_rudder_steer, // unused
77
k_param_throttle_nudge,
78
k_param_alt_offset,
79
k_param_ins, // libraries/AP_InertialSensor variables
80
k_param_takeoff_throttle_min_speed,
81
k_param_takeoff_throttle_min_accel,
82
k_param_takeoff_heading_hold, // unused
83
k_param_level_roll_limit,
84
k_param_hil_servos_unused, // unused
85
k_param_vtail_output, // unused
86
k_param_nav_controller, // unused
87
k_param_elevon_output, // unused
88
k_param_att_controller, // unused
89
k_param_mixing_gain,
90
k_param_scheduler,
91
k_param_relay,
92
k_param_takeoff_throttle_delay,
93
k_param_mode_takeoff, // was skip_gyro_cal
94
k_param_auto_fbw_steer, // unused
95
k_param_waypoint_max_radius,
96
k_param_ground_steer_alt,
97
k_param_ground_steer_dps,
98
k_param_rally_limit_km_old, //unused anymore -- just holding this index
99
k_param_hil_err_limit_unused, // unused
100
k_param_sonar_old, // unused
101
k_param_log_bitmask,
102
k_param_BoardConfig,
103
k_param_rssi_range, // unused, replaced by rssi_ library parameters
104
k_param_flapin_channel_old, // unused, moved to RC_OPTION
105
k_param_flaperon_output, // unused
106
k_param_gps,
107
k_param_autotune_level,
108
k_param_rally,
109
k_param_serial0_baud, // deprecated
110
k_param_serial1_baud, // deprecated
111
k_param_serial2_baud, // deprecated
112
k_param_takeoff_tdrag_elevator,
113
k_param_takeoff_tdrag_speed1,
114
k_param_takeoff_rotate_speed,
115
k_param_takeoff_throttle_slewrate,
116
k_param_takeoff_throttle_max,
117
k_param_rangefinder,
118
k_param_terrain,
119
k_param_terrain_follow,
120
k_param_stab_pitch_down_cd_old, // deprecated
121
k_param_glide_slope_min,
122
k_param_stab_pitch_down,
123
k_param_terrain_lookahead,
124
k_param_fbwa_tdrag_chan, // unused - moved to RC option
125
k_param_rangefinder_landing,
126
k_param_land_flap_percent, // unused - moved to AP_Landing
127
k_param_takeoff_flap_percent,
128
k_param_flap_slewrate,
129
k_param_rtl_autoland,
130
k_param_override_channel,
131
k_param_stall_prevention,
132
k_param_optflow,
133
k_param_cli_enabled_old, // unused - CLI removed
134
k_param_trim_rc_at_start, // unused
135
k_param_hil_mode_unused, // unused
136
k_param_land_disarm_delay, // unused - moved to AP_Landing
137
k_param_glide_slope_threshold,
138
k_param_rudder_only,
139
k_param_gcs3, // 93
140
k_param_gcs_pid_mask,
141
k_param_crash_detection_enable,
142
k_param_land_abort_throttle_enable, // unused - moved to AP_Landing
143
k_param_rssi = 97,
144
k_param_rpm_sensor,
145
k_param_parachute,
146
k_param_arming = 100,
147
k_param_parachute_channel, // unused - moved to RC option
148
k_param_crash_accel_threshold,
149
k_param_override_safety, // unused
150
k_param_land_throttle_slewrate, // 104 unused - moved to AP_Landing
151
152
// 105: Extra parameters
153
k_param_fence_retalt = 105,
154
k_param_fence_autoenable,
155
k_param_fence_ret_rally,
156
k_param_q_attitude_control,
157
k_param_takeoff_pitch_limit_reduction_sec,
158
159
// 110: Telemetry control
160
//
161
k_param_gcs0 = 110, // stream rates for SERIAL0
162
k_param_gcs1, // stream rates for SERIAL1
163
k_param_sysid_this_mav,
164
k_param_sysid_my_gcs,
165
k_param_serial1_baud_old, // deprecated
166
k_param_telem_delay,
167
k_param_serial0_baud_old, // deprecated
168
k_param_gcs2, // stream rates for SERIAL2
169
k_param_serial2_baud_old, // deprecated
170
k_param_serial2_protocol, // deprecated
171
172
// 120: Fly-by-wire control
173
//
174
k_param_airspeed_min = 120,
175
k_param_airspeed_max,
176
k_param_cruise_alt_floor,
177
k_param_flybywire_elev_reverse,
178
k_param_alt_control_algorithm, // unused
179
k_param_flybywire_climb_rate,
180
k_param_acro_roll_rate,
181
k_param_acro_pitch_rate,
182
k_param_acro_locking,
183
k_param_use_reverse_thrust = 129,
184
185
//
186
// 130: Sensor parameters
187
//
188
k_param_imu = 130, // unused
189
k_param_altitude_mix, // deprecated
190
191
k_param_compass_enabled_deprecated,
192
k_param_compass,
193
k_param_battery_monitoring, // unused
194
k_param_volt_div_ratio, // unused
195
k_param_curr_amp_per_volt, // unused
196
k_param_input_voltage, // deprecated, can be deleted
197
k_param_pack_capacity, // unused
198
k_param_sonar_enabled_old, // unused
199
k_param_ahrs, // AHRS group
200
k_param_barometer, // barometer ground calibration
201
k_param_airspeed, // only used for parameter conversion; AP_Airspeed parameters moved to AP_Vehicle
202
k_param_curr_amp_offset,
203
k_param_NavEKF, // deprecated - remove
204
k_param_mission, // mission library
205
k_param_serial_manager_old, // serial manager library
206
k_param_NavEKF2_old, // deprecated - remove
207
k_param_land_pre_flare_alt, // unused - moved to AP_Landing
208
k_param_land_pre_flare_airspeed = 149, // unused - moved to AP_Landing
209
210
//
211
// 150: Navigation parameters
212
//
213
k_param_crosstrack_gain = 150, // unused
214
k_param_crosstrack_entry_angle, // unused
215
k_param_roll_limit,
216
k_param_pitch_limit_max,
217
k_param_pitch_limit_min,
218
k_param_airspeed_cruise,
219
k_param_RTL_altitude,
220
k_param_inverted_flight_ch_unused, // unused
221
k_param_min_groundspeed,
222
k_param_crosstrack_use_wind, // unused
223
224
225
//
226
// Camera and mount parameters
227
//
228
k_param_camera = 160,
229
k_param_camera_mount,
230
k_param_camera_mount2, // unused
231
k_param_adsb,
232
k_param_notify,
233
k_param_land_pre_flare_sec = 165, // unused - moved to AP_Landing
234
235
//
236
// Battery monitoring parameters
237
//
238
k_param_battery = 166,
239
k_param_rssi_pin, // unused, replaced by rssi_ library parameters - 167
240
k_param_battery_volt_pin, // unused - 168
241
k_param_battery_curr_pin, // unused - 169
242
243
//
244
// 170: Radio settings - all unused now
245
//
246
k_param_rc_1_old = 170,
247
k_param_rc_2_old,
248
k_param_rc_3_old,
249
k_param_rc_4_old,
250
k_param_rc_5_old,
251
k_param_rc_6_old,
252
k_param_rc_7_old,
253
k_param_rc_8_old,
254
k_param_rc_9_old,
255
k_param_rc_10_old,
256
k_param_rc_11_old,
257
258
k_param_throttle_min,
259
k_param_throttle_max,
260
k_param_throttle_fs_enabled,
261
k_param_throttle_fs_value,
262
k_param_throttle_cruise,
263
264
k_param_fs_action_short,
265
k_param_fs_action_long,
266
k_param_gcs_heartbeat_fs_enabled,
267
k_param_throttle_slewrate,
268
k_param_throttle_suppress_manual,
269
k_param_throttle_passthru_stabilize,
270
k_param_rc_12_old,
271
k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor
272
k_param_fs_batt_mah, // unused - moved to AP_BattMonitor
273
k_param_fs_timeout_short,
274
k_param_fs_timeout_long,
275
k_param_rc_13_old,
276
k_param_rc_14_old,
277
k_param_tuning,
278
279
//
280
// 200: Feed-forward gains
281
//
282
k_param_kff_pitch_compensation = 200, // unused
283
k_param_kff_rudder_mix,
284
k_param_kff_pitch_to_throttle, // unused
285
k_param_kff_throttle_to_pitch,
286
k_param_scaling_speed,
287
k_param_quadplane,
288
k_param_rtl_radius,
289
k_param_land_then_servos_neutral, // unused - moved to AP_Landing
290
k_param_rc_15_old,
291
k_param_rc_16_old,
292
293
//
294
// 210: flight modes
295
//
296
k_param_flight_mode_channel = 210,
297
k_param_flight_mode1,
298
k_param_flight_mode2,
299
k_param_flight_mode3,
300
k_param_flight_mode4,
301
k_param_flight_mode5,
302
k_param_flight_mode6,
303
k_param_initial_mode,
304
k_param_land_slope_recalc_shallow_threshold, // unused - moved to AP_Landing
305
k_param_land_slope_recalc_steep_threshold_to_abort, // unused - moved to AP_Landing
306
307
//
308
// 220: Waypoint data
309
//
310
k_param_waypoint_mode = 220, // unused
311
k_param_command_total, // unused
312
k_param_command_index, // unused
313
k_param_waypoint_radius,
314
k_param_loiter_radius,
315
k_param_fence_action,
316
k_param_fence_total,
317
k_param_fence_channel, // unused - moved to RC option
318
k_param_fence_minalt,
319
k_param_fence_maxalt,
320
321
// other objects
322
k_param_sitl = 230,
323
k_param_afs,
324
k_param_rollController,
325
k_param_pitchController,
326
k_param_yawController,
327
k_param_L1_controller,
328
k_param_rcmap,
329
k_param_TECS_controller,
330
k_param_rally_total_old, //unused
331
k_param_steerController,
332
333
//
334
// 240: PID Controllers
335
k_param_pidNavRoll = 240, // unused
336
k_param_pidServoRoll, // unused
337
k_param_pidServoPitch, // unused
338
k_param_pidNavPitchAirspeed, // unused
339
k_param_pidServoRudder, // unused
340
k_param_pidTeThrottle, // unused
341
k_param_pidNavPitchAltitude, // unused
342
k_param_pidWheelSteer, // unused
343
344
k_param_mixing_offset,
345
k_param_dspoiler_rud_rate,
346
k_param_airspeed_stall,
347
348
k_param_logger = 253, // Logging Group
349
350
// 254,255: reserved
351
352
k_param_vehicle = 257, // vehicle common block of parameters
353
k_param_gcs4, // stream rates
354
k_param_gcs5, // stream rates
355
k_param_gcs6, // stream rates
356
k_param_fence, // vehicle fence - unused
357
k_param_acro_yaw_rate,
358
k_param_takeoff_throttle_max_t,
359
k_param_autotune_options,
360
k_param_takeoff_throttle_min,
361
k_param_takeoff_options,
362
k_param_takeoff_throttle_idle,
363
364
k_param_pullup = 270,
365
k_param_quicktune,
366
k_param_mode_autoland,
367
368
};
369
370
AP_Int16 format_version;
371
372
// Telemetry control
373
//
374
AP_Int16 sysid_this_mav;
375
AP_Int16 sysid_my_gcs;
376
AP_Int8 telem_delay;
377
378
AP_Enum<RtlAutoland> rtl_autoland;
379
380
AP_Int8 crash_accel_threshold;
381
382
// Feed-forward gains
383
//
384
AP_Float kff_rudder_mix;
385
AP_Float kff_pitch_to_throttle;
386
AP_Float kff_throttle_to_pitch;
387
AP_Float ground_steer_alt;
388
AP_Int16 ground_steer_dps;
389
AP_Float stab_pitch_down;
390
391
// speed used for speed scaling
392
AP_Float scaling_speed;
393
394
// Waypoints
395
//
396
AP_Int16 waypoint_radius;
397
AP_Int16 waypoint_max_radius;
398
AP_Int16 rtl_radius;
399
400
// Fly-by-wire
401
//
402
AP_Int8 flybywire_elev_reverse;
403
AP_Int8 flybywire_climb_rate;
404
405
// Throttle
406
//
407
AP_Int8 throttle_suppress_manual;
408
AP_Int8 throttle_passthru_stabilize;
409
AP_Int8 throttle_fs_enabled;
410
AP_Int16 throttle_fs_value;
411
AP_Int8 throttle_nudge;
412
AP_Int32 use_reverse_thrust;
413
414
// Failsafe
415
AP_Int8 fs_action_short;
416
AP_Int8 fs_action_long;
417
AP_Float fs_timeout_short;
418
AP_Float fs_timeout_long;
419
AP_Int8 gcs_heartbeat_fs_enabled;
420
421
// Flight modes
422
//
423
AP_Int8 flight_mode_channel;
424
AP_Int8 flight_mode1;
425
AP_Int8 flight_mode2;
426
AP_Int8 flight_mode3;
427
AP_Int8 flight_mode4;
428
AP_Int8 flight_mode5;
429
AP_Int8 flight_mode6;
430
AP_Int8 initial_mode;
431
432
// Navigational manoeuvring limits
433
//
434
AP_Int16 alt_offset;
435
AP_Int16 acro_roll_rate;
436
AP_Int16 acro_pitch_rate;
437
AP_Int16 acro_yaw_rate;
438
AP_Int8 acro_locking;
439
440
// Misc
441
//
442
AP_Int8 rudder_only;
443
AP_Float mixing_gain;
444
AP_Int16 mixing_offset;
445
AP_Int16 dspoiler_rud_rate;
446
AP_Int32 log_bitmask;
447
AP_Float RTL_altitude;
448
AP_Float pitch_trim;
449
AP_Float cruise_alt_floor;
450
451
AP_Int8 flap_1_percent;
452
AP_Int8 flap_1_speed;
453
AP_Int8 flap_2_percent;
454
AP_Int8 flap_2_speed;
455
AP_Int8 takeoff_flap_percent;
456
AP_Enum<StickMixing> stick_mixing;
457
AP_Float takeoff_throttle_min_speed;
458
AP_Float takeoff_throttle_min_accel;
459
AP_Int8 takeoff_throttle_delay;
460
AP_Int8 takeoff_tdrag_elevator;
461
AP_Float takeoff_tdrag_speed1;
462
AP_Float takeoff_rotate_speed;
463
AP_Int8 takeoff_throttle_slewrate;
464
AP_Float takeoff_pitch_limit_reduction_sec;
465
AP_Int8 level_roll_limit;
466
#if AP_TERRAIN_AVAILABLE
467
AP_Int32 terrain_follow;
468
AP_Int16 terrain_lookahead;
469
#endif
470
AP_Int16 glide_slope_min;
471
AP_Float glide_slope_threshold;
472
AP_Int8 rangefinder_landing;
473
AP_Int8 flap_slewrate;
474
#if HAL_WITH_IO_MCU
475
AP_Int8 override_channel;
476
#endif
477
AP_Int16 gcs_pid_mask;
478
};
479
480
/*
481
2nd block of parameters, to avoid going past 256 top level keys
482
*/
483
class ParametersG2 {
484
public:
485
ParametersG2(void);
486
487
// var_info for holding Parameter information
488
static const struct AP_Param::GroupInfo var_info[];
489
490
// just to make compilation easier when all things are compiled out...
491
uint8_t unused_integer;
492
493
// button reporting library
494
#if HAL_BUTTON_ENABLED
495
AP_Button *button_ptr;
496
#endif
497
498
#if AP_ICENGINE_ENABLED
499
// internal combustion engine control
500
AP_ICEngine ice_control;
501
#endif
502
503
// RC input channels
504
RC_Channels_Plane rc_channels;
505
506
// control over servo output ranges
507
SRV_Channels servo_channels;
508
509
// whether to enforce acceptance of packets only from sysid_my_gcs
510
AP_Int8 sysid_enforce;
511
512
#if HAL_SOARING_ENABLED
513
// ArduSoar parameters
514
SoaringController soaring_controller;
515
#endif
516
517
// dual motor tailsitter rudder to differential thrust scaling: 0-100%
518
AP_Int8 rudd_dt_gain;
519
520
// mask of channels to do manual pass-thru for
521
AP_Int32 manual_rc_mask;
522
523
// home reset altitude threshold
524
AP_Int8 home_reset_threshold;
525
526
AP_Int32 flight_options;
527
528
AP_Int8 takeoff_throttle_accel_count;
529
AP_Int8 takeoff_timeout;
530
531
#if AP_LANDINGGEAR_ENABLED
532
AP_LandingGear landing_gear;
533
#endif
534
535
#if AC_PRECLAND_ENABLED
536
AC_PrecLand precland;
537
#endif
538
539
// crow flaps weighting
540
AP_Int8 crow_flap_weight_outer;
541
AP_Int8 crow_flap_weight_inner;
542
AP_Int8 crow_flap_options;
543
AP_Int8 crow_flap_aileron_matching;
544
545
// Forward throttle battery voltage compensation
546
class FWD_BATT_CMP {
547
public:
548
// Calculate the throttle scale to compensate for battery voltage drop
549
void update();
550
551
// Apply throttle scale to min and max limits
552
void apply_min_max(int8_t &min_throttle, int8_t &max_throttle) const;
553
554
// Apply throttle scale to throttle demand
555
float apply_throttle(float throttle) const;
556
557
AP_Float batt_voltage_max;
558
AP_Float batt_voltage_min;
559
AP_Int8 batt_idx;
560
561
private:
562
bool enabled;
563
float ratio;
564
} fwd_batt_cmp;
565
566
567
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
568
// guided yaw heading PID
569
AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.0};
570
#endif
571
572
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
573
AP_Follow follow;
574
#endif
575
576
AP_Float fs_ekf_thresh;
577
578
// min initial climb in RTL
579
AP_Int16 rtl_climb_min;
580
581
AP_Int8 man_expo_roll;
582
AP_Int8 man_expo_pitch;
583
AP_Int8 man_expo_rudder;
584
585
AP_Int32 oneshot_mask;
586
587
AP_Int8 axis_bitmask; // axes to be autotuned
588
589
#if AP_RANGEFINDER_ENABLED
590
// orientation of rangefinder to use for landing
591
AP_Int8 rangefinder_land_orient;
592
#endif
593
};
594
595
extern const AP_Param::Info var_info[];
596
597