ArduCopter
Parameters.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 
5 // Global parameter class.
6 //
7 class Parameters {
8 public:
9  // The version of the layout as described by the parameter enum.
10  //
11  // When changing the parameter enum in an incompatible fashion, this
12  // value should be incremented by one.
13  //
14  // The increment will prevent old parameters from being used incorrectly
15  // by newer code.
16  //
17  static const uint16_t k_format_version = 120;
18 
19  // The parameter software_type is set up solely for ground station use
20  // and identifies the software type (eg ArduPilotMega versus
21  // ArduCopterMega)
22  // GCS will interpret values 0-9 as ArduPilotMega. Developers may use
23  // values within that range to identify different branches.
24  //
25  static const uint16_t k_software_type = 10; // 0 for APM
26  // trunk
27 
28  // Parameter identities.
29  //
30  // The enumeration defined here is used to ensure that every parameter
31  // or parameter group has a unique ID number. This number is used by
32  // AP_Param to store and locate parameters in EEPROM.
33  //
34  // Note that entries without a number are assigned the next number after
35  // the entry preceding them. When adding new entries, ensure that they
36  // don't overlap.
37  //
38  // Try to group related variables together, and assign them a set
39  // range in the enumeration. Place these groups in numerical order
40  // at the end of the enumeration.
41  //
42  // WARNING: Care should be taken when editing this enumeration as the
43  // AP_Param load/save code depends on the values here to identify
44  // variables saved in EEPROM.
45  //
46  //
47  enum {
48  // Layout version number, always key zero.
49  //
52  k_param_ins_old, // *** Deprecated, remove with next eeprom number change
53  k_param_ins, // libraries/AP_InertialSensor variables
54  k_param_NavEKF2_old, // deprecated - remove
56  k_param_g2, // 2nd block of parameters
59 
60  // simulation
62 
63  // barometer object (needed for SITL)
65 
66  // scheduler object (for debugging)
68 
69  // relay object
71 
72  // (old) EPM object
74 
75  // BoardConfig object
77 
78  // GPS object
80 
81  // Parachute object
83 
84  // Landing gear object
86 
87  // Input Management object
89 
90  // Misc
91  //
92  k_param_log_bitmask_old = 20, // Deprecated
93  k_param_log_last_filenumber, // *** Deprecated - remove
94  // with next eeprom number
95  // change
96  k_param_toy_yaw_rate, // deprecated - remove
97  k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
98  k_param_rssi_pin, // unused, replaced by rssi_ library parameters
99  k_param_throttle_accel_enabled, // deprecated - remove
102  k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max
103  k_param_circle_rate, // deprecated - remove
106  k_param_arming_check_old, // deprecated - remove
111  k_param_fs_batt_mah, // unused - moved to AP_BattMonitor
113  k_param_rssi_range, // unused, replaced by rssi_ library parameters
114  k_param_rc_feel_rp, // deprecated
115  k_param_NavEKF, // deprecated - remove
116  k_param_mission, // mission library
123  k_param_serial0_baud, // deprecated - remove
124  k_param_serial1_baud, // deprecated - remove
125  k_param_serial2_baud, // deprecated - remove
127  k_param_rangefinder, // rangefinder object
133  k_param_dcmcheck_thresh, // deprecated - remove
135  k_param_cli_enabled_old, // deprecated - remove
139 
140  // 65: AP_Limits Library
141  k_param_limits = 65, // deprecated - remove
142  k_param_gpslock_limit, // deprecated - remove
143  k_param_geofence_limit, // deprecated - remove
144  k_param_altitude_limit, // deprecated - remove
146  k_param_gps_glitch, // deprecated
147  k_param_baro_glitch, // 71 - deprecated
148 
149  // AP_ADSB Library
152 
153  // 74: precision landing object
155 
156  //
157  // 75: Singlecopter, CoaxCopter
158  //
159  k_param_single_servo_1 = 75, // remove
162  k_param_single_servo_4, // 78 - remove
163 
164  //
165  // 80: Heli
166  //
167  k_param_heli_servo_1 = 80, // remove
176  k_param_heli_servo_rsc, // 89 = full! - remove
177 
178  //
179  // 90: misc2
180  //
188 
189  // 97: RSSI
191 
192  //
193  // 100: Inertial Nav
194  //
195  k_param_inertial_nav = 100, // deprecated
201 
202  // 110: Telemetry control
203  //
221 
222  //
223  // 135 : reserved for Solo until features merged with master
224  //
228 
229  //
230  // 140: Sensor parameters
231  //
232  k_param_imu = 140, // deprecated - can be deleted
233  k_param_battery_monitoring = 141, // deprecated - can be deleted
234  k_param_volt_div_ratio, // deprecated - can be deleted
235  k_param_curr_amp_per_volt, // deprecated - can be deleted
236  k_param_input_voltage, // deprecated - can be deleted
237  k_param_pack_capacity, // deprecated - can be deleted
242  k_param_optflow_enabled, // deprecated
243  k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor
245  k_param_auto_slew_rate, // deprecated - can be deleted
248  k_param_axis_enabled = 157, // deprecated - remove with next eeprom number change
249  k_param_copter_leds_mode, // deprecated - remove with next eeprom number change
250  k_param_ahrs, // AHRS group // 159
251 
252  //
253  // 160: Navigation parameters
254  //
256  k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
259  k_param_tilt_comp, //164 deprecated - remove with next eeprom number change
260 
261 
262  //
263  // Camera and mount parameters
264  //
267  k_param_camera_mount2, // deprecated
268 
269  //
270  // Batery monitoring parameters
271  //
272  k_param_battery_volt_pin = 168, // deprecated - can be deleted
273  k_param_battery_curr_pin, // 169 deprecated - can be deleted
274 
275  //
276  // 170: Radio settings
277  //
299  k_param_failsafe_battery_enabled, // unused - moved to AP_BattMonitor
306 
307  //
308  // 200: flight modes
309  //
318 
319  //
320  // 210: Waypoint data
321  //
322  k_param_waypoint_mode = 210, // remove
333 
334  //
335  // 220: PI/D Controllers
336  //
345  k_param_p_pos_xy, // remove
352  k_param_p_vel_z, // remove
363  k_param_pi_vel_xy, // remove
368  k_param_arming, // 252 - AP_Arming
369  k_param_DataFlash = 253, // 253 - Logging Group
370 
371  // 254,255: reserved
372 
373  // the k_param_* space is 9-bits in size
374  // 511: reserved
375  };
376 
377  AP_Int16 format_version;
378  AP_Int8 software_type;
379 
380  // Telemetry control
381  //
382  AP_Int16 sysid_this_mav;
383  AP_Int16 sysid_my_gcs;
384  AP_Int8 telem_delay;
385 
386  AP_Float throttle_filt;
390 
391  AP_Int16 rtl_altitude;
392  AP_Int16 rtl_speed_cms;
393  AP_Float rtl_cone_slope;
394 #if RANGEFINDER_ENABLED == ENABLED
396 #endif
397 
398  AP_Int8 failsafe_gcs; // ground station failsafe behavior
399  AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
400 
402  AP_Int8 super_simple;
403  AP_Int16 rtl_alt_final;
404  AP_Int16 rtl_climb_min; // rtl minimum climb in cm
405 
406  AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
407 
408  AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec
409  AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees
410 
411  // Waypoints
412  //
413  AP_Int32 rtl_loiter_time;
414  AP_Int16 land_speed;
415  AP_Int16 land_speed_high;
416  AP_Int16 pilot_speed_up; // maximum vertical ascending velocity the pilot may request
417  AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request
418 
419  // Throttle
420  //
424 
425  // Flight modes
426  //
427  AP_Int8 flight_mode1;
428  AP_Int8 flight_mode2;
429  AP_Int8 flight_mode3;
430  AP_Int8 flight_mode4;
431  AP_Int8 flight_mode5;
432  AP_Int8 flight_mode6;
433  AP_Int8 simple_modes;
435 
436  // Misc
437  //
438  AP_Int32 log_bitmask;
439  AP_Int8 esc_calibrate;
440  AP_Int8 radio_tuning;
443  AP_Int8 frame_type;
444  AP_Int8 ch7_option;
445  AP_Int8 ch8_option;
446  AP_Int8 ch9_option;
447  AP_Int8 ch10_option;
448  AP_Int8 ch11_option;
449  AP_Int8 ch12_option;
450  AP_Int8 disarm_delay;
451 
453  AP_Int8 fs_ekf_action;
454  AP_Int8 fs_crash_check;
455  AP_Float fs_ekf_thresh;
456  AP_Int16 gcs_pid_mask;
457 
458 #if MODE_THROW_ENABLED == ENABLED
460 #endif
461 
462 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
463  AP_Int8 terrain_follow;
464 #endif
465 
466  AP_Int16 rc_speed; // speed of fast RC Channels in Hz
467 
468  // Acro parameters
469  AP_Float acro_rp_p;
470  AP_Float acro_yaw_p;
473  AP_Int8 acro_trainer;
474  AP_Float acro_rp_expo;
475 
476  // Autotune
477 #if AUTOTUNE_ENABLED == ENABLED
480  AP_Float autotune_min_d;
481 #endif
482 
483  // Note: keep initializers here in the same order as they are declared
484  // above.
486  {
487  }
488 };
489 
490 /*
491  2nd block of parameters, to avoid going past 256 top level keys
492  */
494 public:
495  ParametersG2(void);
496 
497  // var_info for holding Parameter information
498  static const struct AP_Param::GroupInfo var_info[];
499 
500  // altitude at which nav control can start in takeoff
501  AP_Float wp_navalt_min;
502 
503  // button checking
504  AP_Button button;
505 
506 #if STATS_ENABLED == ENABLED
507  // vehicle statistics
508  AP_Stats stats;
509 #endif
510 
511 #if GRIPPER_ENABLED
512  AP_Gripper gripper;
513 #endif
514 
515 #if MODE_THROW_ENABLED == ENABLED
516  // Throw mode parameters
517  AP_Int8 throw_nextmode;
518  AP_Int8 throw_type;
519 #endif
520 
521  // ground effect compensation enable/disable
523 
524  // temperature calibration handling
525  AP_TempCalibration temp_calibration;
526 
527 #if BEACON_ENABLED == ENABLED
528  // beacon (non-GPS positioning) library
529  AP_Beacon beacon;
530 #endif
531 
532 #if VISUAL_ODOMETRY_ENABLED == ENABLED
533  // Visual Odometry camera
534  AP_VisualOdom visual_odom;
535 #endif
536 
537 #if PROXIMITY_ENABLED == ENABLED
538  // proximity (aka object avoidance) library
539  AP_Proximity proximity;
540 #endif
541 
542  // whether to enforce acceptance of packets only from sysid_my_gcs
543  AP_Int8 sysid_enforce;
544 
545 #if ADVANCED_FAILSAFE == ENABLED
546  // advanced failsafe library
548 #endif
549 
550  // developer options
551  AP_Int32 dev_options;
552 
553  // acro exponent parameters
554  AP_Float acro_y_expo;
555 #if MODE_ACRO_ENABLED == ENABLED
556  AP_Float acro_thr_mid;
557 #endif
558 
559  // frame class
560  AP_Int8 frame_class;
561 
562  // RC input channels
563  RC_Channels rc_channels;
564 
565  // control over servo output ranges
566  SRV_Channels servo_channels;
567 
568 #if MODE_SMARTRTL_ENABLED == ENABLED
569  // Safe RTL library
570  AP_SmartRTL smart_rtl;
571 #endif
572 
573  // wheel encoder and winch
574 #if WINCH_ENABLED == ENABLED
575  AP_WheelEncoder wheel_encoder;
576  AP_Winch winch;
577 #endif
578 
579  // Additional pilot velocity items
580  AP_Int16 pilot_speed_dn;
581 
582  // Land alt final stage
583  AP_Int16 land_alt_low;
584 
585 #if TOY_MODE_ENABLED == ENABLED
587 #endif
588 
589 #if OPTFLOW == ENABLED
590  // we need a pointer to the mode for the G2 table
592 #endif
593 
594 #if MODE_FOLLOW_ENABLED == ENABLED
595  // follow
596  AP_Follow follow;
597 #endif
598 };
599 
600 extern const AP_Param::Info var_info[];
AP_Int8 flight_mode1
Definition: Parameters.h:427
Definition: Parameters.h:310
Definition: Parameters.h:174
AP_Int8 fs_ekf_action
Definition: Parameters.h:453
Definition: Parameters.h:239
Definition: Parameters.h:361
Definition: Parameters.h:245
Definition: Parameters.h:143
ParametersG2(void)
Definition: Parameters.cpp:998
AP_Int32 log_bitmask
Definition: Parameters.h:438
Definition: Parameters.h:212
Definition: Parameters.h:98
AP_Int8 throw_type
Definition: Parameters.h:518
Definition: Parameters.h:186
Definition: Parameters.h:298
Definition: Parameters.h:76
Definition: Parameters.h:118
AP_Int8 frame_type
Definition: Parameters.h:443
Definition: Parameters.h:350
Definition: Parameters.h:352
Definition: Parameters.h:108
Definition: Parameters.h:304
Definition: Parameters.h:117
AP_Follow follow
Definition: Parameters.h:596
AP_Int16 throttle_behavior
Definition: Parameters.h:387
AP_Int16 rtl_speed_cms
Definition: Parameters.h:392
AP_Int8 autotune_axis_bitmask
Definition: Parameters.h:478
Definition: Parameters.h:238
AP_Int16 rtl_alt_final
Definition: Parameters.h:403
Definition: Parameters.h:285
const AP_Param::Info var_info[]
AP_TempCalibration temp_calibration
Definition: Parameters.h:525
Definition: Parameters.h:120
Definition: Parameters.h:116
Definition: Parameters.h:183
Definition: Parameters.h:54
AP_Float acro_balance_roll
Definition: Parameters.h:471
AP_Int8 simple_modes
Definition: Parameters.h:433
Definition: Parameters.h:190
Definition: Parameters.h:172
AP_Float autotune_min_d
Definition: Parameters.h:480
Definition: Parameters.h:135
Definition: Parameters.h:218
Definition: Parameters.h:103
Definition: Parameters.h:198
Definition: Parameters.h:184
Definition: Parameters.h:343
Definition: toy_mode.h:8
Definition: Parameters.h:109
Definition: Parameters.h:213
Definition: Parameters.h:105
Definition: Parameters.h:56
AP_Int8 flight_mode4
Definition: Parameters.h:430
AP_Stats stats
Definition: Parameters.h:508
Definition: Parameters.h:367
ToyMode toy_mode
Definition: Parameters.h:586
Definition: Parameters.h:247
Definition: Parameters.h:347
AP_Int16 land_speed_high
Definition: Parameters.h:415
Definition: Parameters.h:332
AP_Int8 compass_enabled
Definition: Parameters.h:401
Definition: Parameters.h:138
AP_Int8 ch9_option
Definition: Parameters.h:446
Definition: Parameters.h:326
AP_Int8 gndeffect_comp_enabled
Definition: Parameters.h:522
Definition: Parameters.h:50
Definition: Parameters.h:185
Definition: Parameters.h:114
Parameters()
Definition: Parameters.h:485
Definition: Parameters.h:293
Definition: Parameters.h:173
Definition: Parameters.h:132
AP_Int16 radio_tuning_high
Definition: Parameters.h:441
AP_WheelEncoder wheel_encoder
Definition: Parameters.h:575
Definition: Parameters.h:282
AP_Int16 throttle_deadzone
Definition: Parameters.h:423
Definition: Parameters.h:348
Definition: Parameters.h:236
Definition: Parameters.h:137
Definition: Parameters.h:7
Definition: Parameters.h:181
AP_Float acro_y_expo
Definition: Parameters.h:554
Definition: Parameters.h:360
AP_Int8 esc_calibrate
Definition: Parameters.h:439
AP_Int8 failsafe_gcs
Definition: Parameters.h:398
Definition: Parameters.h:161
Definition: Parameters.h:265
AP_Int16 sysid_this_mav
Definition: Parameters.h:382
Definition: Parameters.h:207
Definition: Parameters.h:359
Definition: Parameters.h:123
Definition: Parameters.h:317
AP_Int16 pilot_speed_up
Definition: Parameters.h:416
Definition: Parameters.h:283
Definition: Parameters.h:214
AP_Int8 land_repositioning
Definition: Parameters.h:452
Definition: Parameters.h:111
static const uint16_t k_software_type
Definition: Parameters.h:25
AP_Float pilot_takeoff_alt
Definition: Parameters.h:389
Definition: Parameters.h:142
Definition: Parameters.h:315
Definition: Parameters.h:134
Definition: Parameters.h:235
AP_Int8 ch12_option
Definition: Parameters.h:449
Definition: Parameters.h:337
AP_Beacon beacon
Definition: Parameters.h:529
Definition: Parameters.h:159
Definition: Parameters.h:107
Definition: Parameters.h:369
AP_Int8 software_type
Definition: Parameters.h:378
AP_Int8 ch11_option
Definition: Parameters.h:448
Definition: Parameters.h:182
Definition: Parameters.h:340
Definition: Parameters.h:493
Definition: Parameters.h:51
AP_Int8 ch7_option
Definition: Parameters.h:444
AP_Float fs_ekf_thresh
Definition: Parameters.h:455
Definition: Parameters.h:325
AP_Int8 radio_tuning
Definition: Parameters.h:440
AP_Int16 rtl_altitude
Definition: Parameters.h:391
AP_Int8 fs_crash_check
Definition: Parameters.h:454
AP_Int16 format_version
Definition: Parameters.h:377
AP_Int16 rtl_climb_min
Definition: Parameters.h:404
Definition: Parameters.h:248
Definition: Parameters.h:176
Definition: Parameters.h:162
AP_Int16 poshold_brake_angle_max
Definition: Parameters.h:409
Definition: Parameters.h:226
Definition: Parameters.h:296
Definition: Parameters.h:227
Definition: Parameters.h:136
AP_Int8 acro_trainer
Definition: Parameters.h:473
AP_AdvancedFailsafe_Copter afs
Definition: Parameters.h:547
Definition: Parameters.h:284
Definition: Parameters.h:124
Definition: Parameters.h:243
SRV_Channels servo_channels
Definition: Parameters.h:566
Definition: Parameters.h:88
Definition: Parameters.h:102
Definition: Parameters.h:300
Definition: Parameters.h:145
Definition: Parameters.h:122
Definition: Parameters.h:225
Definition: Parameters.h:354
AP_Int16 poshold_brake_rate
Definition: Parameters.h:408
AP_Float acro_rp_p
Definition: Parameters.h:469
Definition: Parameters.h:160
Definition: Parameters.h:280
Definition: Parameters.h:195
Definition: Parameters.h:167
Definition: Parameters.h:301
Definition: Parameters.h:73
Definition: Parameters.h:244
Definition: Parameters.h:58
Definition: Parameters.h:199
Definition: Parameters.h:281
Definition: Parameters.h:303
Definition: Parameters.h:257
AP_Int8 flight_mode3
Definition: Parameters.h:429
AP_Int8 ch10_option
Definition: Parameters.h:447
Definition: Parameters.h:287
AP_Winch winch
Definition: Parameters.h:576
Definition: Parameters.h:53
AP_Int8 ch8_option
Definition: Parameters.h:445
Definition: Parameters.h:57
Definition: Parameters.h:255
Definition: Parameters.h:322
Definition: Parameters.h:358
Definition: Parameters.h:341
Definition: Parameters.h:119
Definition: Parameters.h:323
Definition: Parameters.h:302
Definition: Parameters.h:110
AP_Int16 rc_speed
Definition: Parameters.h:466
Definition: Parameters.h:279
Definition: Parameters.h:197
Definition: Parameters.h:101
Definition: Parameters.h:127
Definition: Parameters.h:205
Definition: Parameters.h:346
Definition: Parameters.h:363
Definition: Parameters.h:208
Definition: Parameters.h:294
Definition: Parameters.h:241
Definition: Parameters.h:266
static const struct AP_Param::GroupInfo var_info[]
Definition: Parameters.h:498
AP_Float acro_thr_mid
Definition: Parameters.h:556
Definition: Parameters.h:329
AP_Int8 flight_mode6
Definition: Parameters.h:432
Definition: Parameters.h:349
Definition: Parameters.h:366
Definition: Parameters.h:291
Definition: Parameters.h:219
Definition: Parameters.h:93
AP_Int16 pilot_accel_z
Definition: Parameters.h:417
AP_Int8 wp_yaw_behavior
Definition: Parameters.h:406
Definition: Parameters.h:129
Definition: Parameters.h:115
Definition: Parameters.h:175
Definition: Parameters.h:314
Definition: Parameters.h:210
Definition: Parameters.h:170
AP_Int16 failsafe_throttle_value
Definition: Parameters.h:422
AP_Int8 telem_delay
Definition: Parameters.h:384
Definition: Parameters.h:104
Definition: Parameters.h:278
Definition: Parameters.h:259
Definition: Parameters.h:345
AP_Int8 frame_class
Definition: Parameters.h:560
Definition: Parameters.h:357
Definition: Parameters.h:200
Definition: Parameters.h:237
Definition: afs_copter.h:27
Definition: Parameters.h:316
Definition: Parameters.h:353
AP_Int8 throw_nextmode
Definition: Parameters.h:517
Definition: Parameters.h:82
Definition: Parameters.h:216
Definition: Parameters.h:169
Definition: Parameters.h:204
Definition: Parameters.h:112
Definition: Parameters.h:171
Definition: Parameters.h:342
AP_Button button
Definition: Parameters.h:504
Definition: Parameters.h:311
Definition: Parameters.h:356
Definition: Parameters.h:324
Definition: Parameters.h:272
Definition: Parameters.h:288
AP_VisualOdom visual_odom
Definition: Parameters.h:534
AP_Int16 radio_tuning_low
Definition: Parameters.h:442
Definition: Parameters.h:290
Definition: Parameters.h:61
Definition: Parameters.h:150
AP_Float autotune_aggressiveness
Definition: Parameters.h:479
Definition: Parameters.h:187
Definition: Parameters.h:55
Definition: Parameters.h:339
AP_Int8 throw_motor_start
Definition: Parameters.h:459
void * mode_flowhold_ptr
Definition: Parameters.h:591
Definition: Parameters.h:206
Definition: Parameters.h:130
Definition: Parameters.h:368
AP_Int16 land_alt_low
Definition: Parameters.h:583
Definition: Parameters.h:133
Definition: Parameters.h:355
Definition: Parameters.h:217
Definition: Parameters.h:249
Definition: Parameters.h:246
AP_Float acro_yaw_p
Definition: Parameters.h:470
Definition: Parameters.h:215
Definition: Parameters.h:100
Definition: Parameters.h:144
Definition: Parameters.h:344
Definition: Parameters.h:273
Definition: Parameters.h:147
AP_Float throttle_filt
Definition: Parameters.h:386
Definition: Parameters.h:125
AP_Int32 dev_options
Definition: Parameters.h:551
AP_Float rtl_cone_slope
Definition: Parameters.h:393
AP_Int16 pilot_speed_dn
Definition: Parameters.h:580
AP_Float rangefinder_gain
Definition: Parameters.h:395
Definition: Parameters.h:327
Definition: Parameters.h:146
Definition: Parameters.h:79
Definition: Parameters.h:96
AP_Int8 disarm_delay
Definition: Parameters.h:450
AP_Int16 gcs_pid_mask
Definition: Parameters.h:456
AP_Int16 takeoff_trigger_dz
Definition: Parameters.h:388
Definition: Parameters.h:64
Definition: Parameters.h:338
AP_Float wp_navalt_min
Definition: Parameters.h:501
Definition: Parameters.h:52
Definition: Parameters.h:151
Definition: Parameters.h:330
Definition: Parameters.h:256
Definition: Parameters.h:131
Definition: Parameters.h:92
Definition: Parameters.h:267
Definition: Parameters.h:209
Definition: Parameters.h:351
Definition: Parameters.h:67
Definition: Parameters.h:232
Definition: Parameters.h:331
AP_Int16 sysid_my_gcs
Definition: Parameters.h:383
Definition: Parameters.h:196
Definition: Parameters.h:305
AP_Int8 failsafe_throttle
Definition: Parameters.h:421
Definition: Parameters.h:250
Definition: Parameters.h:113
Definition: Parameters.h:295
Definition: Parameters.h:70
Definition: Parameters.h:168
Definition: Parameters.h:328
Definition: Parameters.h:258
Definition: Parameters.h:242
Definition: Parameters.h:141
Definition: Parameters.h:106
AP_Float acro_rp_expo
Definition: Parameters.h:474
Definition: Parameters.h:154
Definition: Parameters.h:364
AP_Int16 land_speed
Definition: Parameters.h:414
Definition: Parameters.h:312
AP_Int8 flight_mode2
Definition: Parameters.h:428
Definition: Parameters.h:365
Definition: Parameters.h:286
Definition: Parameters.h:211
AP_Int32 rtl_loiter_time
Definition: Parameters.h:413
Definition: Parameters.h:289
Definition: Parameters.h:313
Definition: Parameters.h:126
AP_Proximity proximity
Definition: Parameters.h:539
Definition: Parameters.h:220
static const uint16_t k_format_version
Definition: Parameters.h:17
AP_Int16 gps_hdop_good
Definition: Parameters.h:399
Definition: Parameters.h:233
Definition: Parameters.h:297
Definition: Parameters.h:234
Definition: Parameters.h:128
AP_Int8 flight_mode_chan
Definition: Parameters.h:434
AP_Int8 sysid_enforce
Definition: Parameters.h:543
AP_SmartRTL smart_rtl
Definition: Parameters.h:570
AP_Int8 super_simple
Definition: Parameters.h:402
Definition: Parameters.h:85
AP_Float acro_balance_pitch
Definition: Parameters.h:472
RC_Channels rc_channels
Definition: Parameters.h:563
AP_Int8 flight_mode5
Definition: Parameters.h:431