ArduSub: get MAV_STATE_BOOT on reboot
[ardupilot.git] / ArduPlane / Parameters.h
blobba89c4577281129b2b3e4b8b45ded0af2d0b0236
1 #pragma once
3 #define AP_PARAM_VEHICLE_NAME plane
5 #include <AP_Common/AP_Common.h>
7 // Global parameter class.
8 //
9 class Parameters {
10 public:
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:
17 * 1) the meaning of an existing eeprom parameter changes
19 * 2) the value of an existing k_param_* enum value changes
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".
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.
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 //////////////////////////////////////////////////////////////////
40 enum {
41 // Layout version number, always key zero.
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,
54 // Misc
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
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,
159 // 110: Telemetry control
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
172 // 120: Fly-by-wire control
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,
186 // 130: Sensor parameters
188 k_param_imu = 130, // unused
189 k_param_altitude_mix, // deprecated
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
211 // 150: Navigation parameters
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
226 // Camera and mount parameters
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
236 // Battery monitoring parameters
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
244 // 170: Radio settings - all unused now
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,
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,
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,
280 // 200: Feed-forward gains
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,
294 // 210: flight modes
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
308 // 220: Waypoint data
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,
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,
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
344 k_param_mixing_offset,
345 k_param_dspoiler_rud_rate,
347 k_param_logger = 253, // Logging Group
349 // 254,255: reserved
351 k_param_vehicle = 257, // vehicle common block of parameters
352 k_param_gcs4, // stream rates
353 k_param_gcs5, // stream rates
354 k_param_gcs6, // stream rates
355 k_param_fence, // vehicle fence - unused
356 k_param_acro_yaw_rate,
357 k_param_takeoff_throttle_max_t,
358 k_param_autotune_options,
361 AP_Int16 format_version;
363 // Telemetry control
365 AP_Int16 sysid_this_mav;
366 AP_Int16 sysid_my_gcs;
367 AP_Int8 telem_delay;
369 AP_Enum<RtlAutoland> rtl_autoland;
371 AP_Int8 crash_accel_threshold;
373 // Feed-forward gains
375 AP_Float kff_rudder_mix;
376 AP_Float kff_pitch_to_throttle;
377 AP_Float kff_throttle_to_pitch;
378 AP_Float ground_steer_alt;
379 AP_Int16 ground_steer_dps;
380 AP_Float stab_pitch_down;
382 // speed used for speed scaling
383 AP_Float scaling_speed;
385 // Waypoints
387 AP_Int16 waypoint_radius;
388 AP_Int16 waypoint_max_radius;
389 AP_Int16 rtl_radius;
391 // Fly-by-wire
393 AP_Int8 flybywire_elev_reverse;
394 AP_Int8 flybywire_climb_rate;
396 // Throttle
398 AP_Int8 throttle_suppress_manual;
399 AP_Int8 throttle_passthru_stabilize;
400 AP_Int8 throttle_fs_enabled;
401 AP_Int16 throttle_fs_value;
402 AP_Int8 throttle_nudge;
403 AP_Int32 use_reverse_thrust;
405 // Failsafe
406 AP_Int8 fs_action_short;
407 AP_Int8 fs_action_long;
408 AP_Float fs_timeout_short;
409 AP_Float fs_timeout_long;
410 AP_Int8 gcs_heartbeat_fs_enabled;
412 // Flight modes
414 AP_Int8 flight_mode_channel;
415 AP_Int8 flight_mode1;
416 AP_Int8 flight_mode2;
417 AP_Int8 flight_mode3;
418 AP_Int8 flight_mode4;
419 AP_Int8 flight_mode5;
420 AP_Int8 flight_mode6;
421 AP_Int8 initial_mode;
423 // Navigational manoeuvring limits
425 AP_Int16 alt_offset;
426 AP_Int16 acro_roll_rate;
427 AP_Int16 acro_pitch_rate;
428 AP_Int16 acro_yaw_rate;
429 AP_Int8 acro_locking;
431 // Misc
433 AP_Int8 rudder_only;
434 AP_Float mixing_gain;
435 AP_Int16 mixing_offset;
436 AP_Int16 dspoiler_rud_rate;
437 AP_Int32 log_bitmask;
438 AP_Float RTL_altitude;
439 AP_Float pitch_trim;
440 AP_Float cruise_alt_floor;
442 AP_Int8 flap_1_percent;
443 AP_Int8 flap_1_speed;
444 AP_Int8 flap_2_percent;
445 AP_Int8 flap_2_speed;
446 AP_Int8 takeoff_flap_percent;
447 AP_Enum<StickMixing> stick_mixing;
448 AP_Float takeoff_throttle_min_speed;
449 AP_Float takeoff_throttle_min_accel;
450 AP_Int8 takeoff_throttle_delay;
451 AP_Int8 takeoff_tdrag_elevator;
452 AP_Float takeoff_tdrag_speed1;
453 AP_Float takeoff_rotate_speed;
454 AP_Int8 takeoff_throttle_slewrate;
455 AP_Float takeoff_pitch_limit_reduction_sec;
456 AP_Int8 level_roll_limit;
457 #if AP_TERRAIN_AVAILABLE
458 AP_Int32 terrain_follow;
459 AP_Int16 terrain_lookahead;
460 #endif
461 AP_Int16 glide_slope_min;
462 AP_Float glide_slope_threshold;
463 AP_Int8 rangefinder_landing;
464 AP_Int8 flap_slewrate;
465 #if HAL_WITH_IO_MCU
466 AP_Int8 override_channel;
467 #endif
468 AP_Int16 gcs_pid_mask;
472 2nd block of parameters, to avoid going past 256 top level keys
474 class ParametersG2 {
475 public:
476 ParametersG2(void);
478 // var_info for holding Parameter information
479 static const struct AP_Param::GroupInfo var_info[];
481 // button reporting library
482 #if HAL_BUTTON_ENABLED
483 AP_Button *button_ptr;
484 #endif
486 #if AP_ICENGINE_ENABLED
487 // internal combustion engine control
488 AP_ICEngine ice_control;
489 #endif
491 // RC input channels
492 RC_Channels_Plane rc_channels;
494 // control over servo output ranges
495 SRV_Channels servo_channels;
497 // whether to enforce acceptance of packets only from sysid_my_gcs
498 AP_Int8 sysid_enforce;
500 #if HAL_SOARING_ENABLED
501 // ArduSoar parameters
502 SoaringController soaring_controller;
503 #endif
505 // dual motor tailsitter rudder to differential thrust scaling: 0-100%
506 AP_Int8 rudd_dt_gain;
508 // mask of channels to do manual pass-thru for
509 AP_Int32 manual_rc_mask;
511 // home reset altitude threshold
512 AP_Int8 home_reset_threshold;
514 AP_Int32 flight_options;
516 AP_Int8 takeoff_throttle_accel_count;
517 AP_Int8 takeoff_timeout;
519 #if AP_LANDINGGEAR_ENABLED
520 AP_LandingGear landing_gear;
521 #endif
523 #if AC_PRECLAND_ENABLED
524 AC_PrecLand precland;
525 #endif
527 // crow flaps weighting
528 AP_Int8 crow_flap_weight_outer;
529 AP_Int8 crow_flap_weight_inner;
530 AP_Int8 crow_flap_options;
531 AP_Int8 crow_flap_aileron_matching;
533 // Forward throttle battery voltage compensation
534 class FWD_BATT_CMP {
535 public:
536 // Calculate the throttle scale to compensate for battery voltage drop
537 void update();
539 // Apply throttle scale to min and max limits
540 void apply_min_max(int8_t &min_throttle, int8_t &max_throttle) const;
542 // Apply throttle scale to throttle demand
543 float apply_throttle(float throttle) const;
545 AP_Float batt_voltage_max;
546 AP_Float batt_voltage_min;
547 AP_Int8 batt_idx;
549 private:
550 bool enabled;
551 float ratio;
552 } fwd_batt_cmp;
555 #if OFFBOARD_GUIDED == ENABLED
556 // guided yaw heading PID
557 AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.0};
558 #endif
560 #if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
561 AP_Follow follow;
562 #endif
564 AP_Float fs_ekf_thresh;
566 // min initial climb in RTL
567 AP_Int16 rtl_climb_min;
569 AP_Int8 man_expo_roll;
570 AP_Int8 man_expo_pitch;
571 AP_Int8 man_expo_rudder;
573 AP_Int32 oneshot_mask;
575 AP_Int8 axis_bitmask; // axes to be autotuned
577 // just to make compilation easier when all things are compiled out...
578 uint8_t unused_integer;
581 extern const AP_Param::Info var_info[];