Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduPlane/Parameters.h
Views: 1798
#pragma once12#define AP_PARAM_VEHICLE_NAME plane34#include <AP_Common/AP_Common.h>56// Global parameter class.7//8class Parameters {9public:1011/*12* The value of k_format_version determines whether the existing13* eeprom data is considered valid. You should only change this14* value under the following circumstances:15*16* 1) the meaning of an existing eeprom parameter changes17*18* 2) the value of an existing k_param_* enum value changes19*20* Adding a new parameter should _not_ require a change to21* k_format_version except under special circumstances. If you22* change it anyway then all ArduPlane users will need to reload all23* their parameters. We want that to be an extremely rare24* thing. Please do not just change it "just in case".25*26* To determine if a k_param_* value has changed, use the rules of27* C++ enums to work out the value of the neighboring enum28* values. If you don't know the C++ enum rules then please ask for29* help.30*/3132//////////////////////////////////////////////////////////////////33// STOP!!! DO NOT CHANGE THIS VALUE UNTIL YOU FULLY UNDERSTAND THE34// COMMENTS ABOVE. IF UNSURE, ASK ANOTHER DEVELOPER!!!35static const uint16_t k_format_version = 13;36//////////////////////////////////////////////////////////////////373839enum {40// Layout version number, always key zero.41//42k_param_format_version = 0,43k_param_software_type, // unused;44k_param_num_resets, // unused45k_param_NavEKF2,46k_param_g2,47k_param_avoidance_adsb,48k_param_landing,49k_param_NavEKF3,50k_param_can_mgr,51k_param_osd,5253// Misc54//55k_param_auto_trim = 10, // unused56k_param_log_bitmask_old, // unused57k_param_pitch_trim,58k_param_mix_mode,59k_param_reverse_elevons, // unused60k_param_reverse_ch1_elevon, // unused61k_param_reverse_ch2_elevon, // unused62k_param_flap_1_percent,63k_param_flap_1_speed,64k_param_flap_2_percent,65k_param_flap_2_speed,66k_param_reset_switch_chan, // unused - moved to RC option67k_param_manual_level, // unused68k_param_land_pitch_cd, // unused - moved to AP_Landing69k_param_ins_old, // *** Deprecated, remove with next eeprom number change70k_param_stick_mixing,71k_param_reset_mission_chan, // unused - moved to RC option72k_param_land_flare_alt, // unused - moved to AP_Landing73k_param_land_flare_sec, // unused - moved to AP_Landing74k_param_crosstrack_min_distance, // unused75k_param_rudder_steer, // unused76k_param_throttle_nudge,77k_param_alt_offset,78k_param_ins, // libraries/AP_InertialSensor variables79k_param_takeoff_throttle_min_speed,80k_param_takeoff_throttle_min_accel,81k_param_takeoff_heading_hold, // unused82k_param_level_roll_limit,83k_param_hil_servos_unused, // unused84k_param_vtail_output, // unused85k_param_nav_controller, // unused86k_param_elevon_output, // unused87k_param_att_controller, // unused88k_param_mixing_gain,89k_param_scheduler,90k_param_relay,91k_param_takeoff_throttle_delay,92k_param_mode_takeoff, // was skip_gyro_cal93k_param_auto_fbw_steer, // unused94k_param_waypoint_max_radius,95k_param_ground_steer_alt,96k_param_ground_steer_dps,97k_param_rally_limit_km_old, //unused anymore -- just holding this index98k_param_hil_err_limit_unused, // unused99k_param_sonar_old, // unused100k_param_log_bitmask,101k_param_BoardConfig,102k_param_rssi_range, // unused, replaced by rssi_ library parameters103k_param_flapin_channel_old, // unused, moved to RC_OPTION104k_param_flaperon_output, // unused105k_param_gps,106k_param_autotune_level,107k_param_rally,108k_param_serial0_baud, // deprecated109k_param_serial1_baud, // deprecated110k_param_serial2_baud, // deprecated111k_param_takeoff_tdrag_elevator,112k_param_takeoff_tdrag_speed1,113k_param_takeoff_rotate_speed,114k_param_takeoff_throttle_slewrate,115k_param_takeoff_throttle_max,116k_param_rangefinder,117k_param_terrain,118k_param_terrain_follow,119k_param_stab_pitch_down_cd_old, // deprecated120k_param_glide_slope_min,121k_param_stab_pitch_down,122k_param_terrain_lookahead,123k_param_fbwa_tdrag_chan, // unused - moved to RC option124k_param_rangefinder_landing,125k_param_land_flap_percent, // unused - moved to AP_Landing126k_param_takeoff_flap_percent,127k_param_flap_slewrate,128k_param_rtl_autoland,129k_param_override_channel,130k_param_stall_prevention,131k_param_optflow,132k_param_cli_enabled_old, // unused - CLI removed133k_param_trim_rc_at_start, // unused134k_param_hil_mode_unused, // unused135k_param_land_disarm_delay, // unused - moved to AP_Landing136k_param_glide_slope_threshold,137k_param_rudder_only,138k_param_gcs3, // 93139k_param_gcs_pid_mask,140k_param_crash_detection_enable,141k_param_land_abort_throttle_enable, // unused - moved to AP_Landing142k_param_rssi = 97,143k_param_rpm_sensor,144k_param_parachute,145k_param_arming = 100,146k_param_parachute_channel, // unused - moved to RC option147k_param_crash_accel_threshold,148k_param_override_safety, // unused149k_param_land_throttle_slewrate, // 104 unused - moved to AP_Landing150151// 105: Extra parameters152k_param_fence_retalt = 105,153k_param_fence_autoenable,154k_param_fence_ret_rally,155k_param_q_attitude_control,156k_param_takeoff_pitch_limit_reduction_sec,157158// 110: Telemetry control159//160k_param_gcs0 = 110, // stream rates for SERIAL0161k_param_gcs1, // stream rates for SERIAL1162k_param_sysid_this_mav,163k_param_sysid_my_gcs,164k_param_serial1_baud_old, // deprecated165k_param_telem_delay,166k_param_serial0_baud_old, // deprecated167k_param_gcs2, // stream rates for SERIAL2168k_param_serial2_baud_old, // deprecated169k_param_serial2_protocol, // deprecated170171// 120: Fly-by-wire control172//173k_param_airspeed_min = 120,174k_param_airspeed_max,175k_param_cruise_alt_floor,176k_param_flybywire_elev_reverse,177k_param_alt_control_algorithm, // unused178k_param_flybywire_climb_rate,179k_param_acro_roll_rate,180k_param_acro_pitch_rate,181k_param_acro_locking,182k_param_use_reverse_thrust = 129,183184//185// 130: Sensor parameters186//187k_param_imu = 130, // unused188k_param_altitude_mix, // deprecated189190k_param_compass_enabled_deprecated,191k_param_compass,192k_param_battery_monitoring, // unused193k_param_volt_div_ratio, // unused194k_param_curr_amp_per_volt, // unused195k_param_input_voltage, // deprecated, can be deleted196k_param_pack_capacity, // unused197k_param_sonar_enabled_old, // unused198k_param_ahrs, // AHRS group199k_param_barometer, // barometer ground calibration200k_param_airspeed, // only used for parameter conversion; AP_Airspeed parameters moved to AP_Vehicle201k_param_curr_amp_offset,202k_param_NavEKF, // deprecated - remove203k_param_mission, // mission library204k_param_serial_manager_old, // serial manager library205k_param_NavEKF2_old, // deprecated - remove206k_param_land_pre_flare_alt, // unused - moved to AP_Landing207k_param_land_pre_flare_airspeed = 149, // unused - moved to AP_Landing208209//210// 150: Navigation parameters211//212k_param_crosstrack_gain = 150, // unused213k_param_crosstrack_entry_angle, // unused214k_param_roll_limit,215k_param_pitch_limit_max,216k_param_pitch_limit_min,217k_param_airspeed_cruise,218k_param_RTL_altitude,219k_param_inverted_flight_ch_unused, // unused220k_param_min_groundspeed,221k_param_crosstrack_use_wind, // unused222223224//225// Camera and mount parameters226//227k_param_camera = 160,228k_param_camera_mount,229k_param_camera_mount2, // unused230k_param_adsb,231k_param_notify,232k_param_land_pre_flare_sec = 165, // unused - moved to AP_Landing233234//235// Battery monitoring parameters236//237k_param_battery = 166,238k_param_rssi_pin, // unused, replaced by rssi_ library parameters - 167239k_param_battery_volt_pin, // unused - 168240k_param_battery_curr_pin, // unused - 169241242//243// 170: Radio settings - all unused now244//245k_param_rc_1_old = 170,246k_param_rc_2_old,247k_param_rc_3_old,248k_param_rc_4_old,249k_param_rc_5_old,250k_param_rc_6_old,251k_param_rc_7_old,252k_param_rc_8_old,253k_param_rc_9_old,254k_param_rc_10_old,255k_param_rc_11_old,256257k_param_throttle_min,258k_param_throttle_max,259k_param_throttle_fs_enabled,260k_param_throttle_fs_value,261k_param_throttle_cruise,262263k_param_fs_action_short,264k_param_fs_action_long,265k_param_gcs_heartbeat_fs_enabled,266k_param_throttle_slewrate,267k_param_throttle_suppress_manual,268k_param_throttle_passthru_stabilize,269k_param_rc_12_old,270k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor271k_param_fs_batt_mah, // unused - moved to AP_BattMonitor272k_param_fs_timeout_short,273k_param_fs_timeout_long,274k_param_rc_13_old,275k_param_rc_14_old,276k_param_tuning,277278//279// 200: Feed-forward gains280//281k_param_kff_pitch_compensation = 200, // unused282k_param_kff_rudder_mix,283k_param_kff_pitch_to_throttle, // unused284k_param_kff_throttle_to_pitch,285k_param_scaling_speed,286k_param_quadplane,287k_param_rtl_radius,288k_param_land_then_servos_neutral, // unused - moved to AP_Landing289k_param_rc_15_old,290k_param_rc_16_old,291292//293// 210: flight modes294//295k_param_flight_mode_channel = 210,296k_param_flight_mode1,297k_param_flight_mode2,298k_param_flight_mode3,299k_param_flight_mode4,300k_param_flight_mode5,301k_param_flight_mode6,302k_param_initial_mode,303k_param_land_slope_recalc_shallow_threshold, // unused - moved to AP_Landing304k_param_land_slope_recalc_steep_threshold_to_abort, // unused - moved to AP_Landing305306//307// 220: Waypoint data308//309k_param_waypoint_mode = 220, // unused310k_param_command_total, // unused311k_param_command_index, // unused312k_param_waypoint_radius,313k_param_loiter_radius,314k_param_fence_action,315k_param_fence_total,316k_param_fence_channel, // unused - moved to RC option317k_param_fence_minalt,318k_param_fence_maxalt,319320// other objects321k_param_sitl = 230,322k_param_afs,323k_param_rollController,324k_param_pitchController,325k_param_yawController,326k_param_L1_controller,327k_param_rcmap,328k_param_TECS_controller,329k_param_rally_total_old, //unused330k_param_steerController,331332//333// 240: PID Controllers334k_param_pidNavRoll = 240, // unused335k_param_pidServoRoll, // unused336k_param_pidServoPitch, // unused337k_param_pidNavPitchAirspeed, // unused338k_param_pidServoRudder, // unused339k_param_pidTeThrottle, // unused340k_param_pidNavPitchAltitude, // unused341k_param_pidWheelSteer, // unused342343k_param_mixing_offset,344k_param_dspoiler_rud_rate,345k_param_airspeed_stall,346347k_param_logger = 253, // Logging Group348349// 254,255: reserved350351k_param_vehicle = 257, // vehicle common block of parameters352k_param_gcs4, // stream rates353k_param_gcs5, // stream rates354k_param_gcs6, // stream rates355k_param_fence, // vehicle fence - unused356k_param_acro_yaw_rate,357k_param_takeoff_throttle_max_t,358k_param_autotune_options,359k_param_takeoff_throttle_min,360k_param_takeoff_options,361k_param_takeoff_throttle_idle,362363k_param_pullup = 270,364k_param_quicktune,365k_param_mode_autoland,366367};368369AP_Int16 format_version;370371// Telemetry control372//373AP_Int16 sysid_this_mav;374AP_Int16 sysid_my_gcs;375AP_Int8 telem_delay;376377AP_Enum<RtlAutoland> rtl_autoland;378379AP_Int8 crash_accel_threshold;380381// Feed-forward gains382//383AP_Float kff_rudder_mix;384AP_Float kff_pitch_to_throttle;385AP_Float kff_throttle_to_pitch;386AP_Float ground_steer_alt;387AP_Int16 ground_steer_dps;388AP_Float stab_pitch_down;389390// speed used for speed scaling391AP_Float scaling_speed;392393// Waypoints394//395AP_Int16 waypoint_radius;396AP_Int16 waypoint_max_radius;397AP_Int16 rtl_radius;398399// Fly-by-wire400//401AP_Int8 flybywire_elev_reverse;402AP_Int8 flybywire_climb_rate;403404// Throttle405//406AP_Int8 throttle_suppress_manual;407AP_Int8 throttle_passthru_stabilize;408AP_Int8 throttle_fs_enabled;409AP_Int16 throttle_fs_value;410AP_Int8 throttle_nudge;411AP_Int32 use_reverse_thrust;412413// Failsafe414AP_Int8 fs_action_short;415AP_Int8 fs_action_long;416AP_Float fs_timeout_short;417AP_Float fs_timeout_long;418AP_Int8 gcs_heartbeat_fs_enabled;419420// Flight modes421//422AP_Int8 flight_mode_channel;423AP_Int8 flight_mode1;424AP_Int8 flight_mode2;425AP_Int8 flight_mode3;426AP_Int8 flight_mode4;427AP_Int8 flight_mode5;428AP_Int8 flight_mode6;429AP_Int8 initial_mode;430431// Navigational manoeuvring limits432//433AP_Int16 alt_offset;434AP_Int16 acro_roll_rate;435AP_Int16 acro_pitch_rate;436AP_Int16 acro_yaw_rate;437AP_Int8 acro_locking;438439// Misc440//441AP_Int8 rudder_only;442AP_Float mixing_gain;443AP_Int16 mixing_offset;444AP_Int16 dspoiler_rud_rate;445AP_Int32 log_bitmask;446AP_Float RTL_altitude;447AP_Float pitch_trim;448AP_Float cruise_alt_floor;449450AP_Int8 flap_1_percent;451AP_Int8 flap_1_speed;452AP_Int8 flap_2_percent;453AP_Int8 flap_2_speed;454AP_Int8 takeoff_flap_percent;455AP_Enum<StickMixing> stick_mixing;456AP_Float takeoff_throttle_min_speed;457AP_Float takeoff_throttle_min_accel;458AP_Int8 takeoff_throttle_delay;459AP_Int8 takeoff_tdrag_elevator;460AP_Float takeoff_tdrag_speed1;461AP_Float takeoff_rotate_speed;462AP_Int8 takeoff_throttle_slewrate;463AP_Float takeoff_pitch_limit_reduction_sec;464AP_Int8 level_roll_limit;465#if AP_TERRAIN_AVAILABLE466AP_Int32 terrain_follow;467AP_Int16 terrain_lookahead;468#endif469AP_Int16 glide_slope_min;470AP_Float glide_slope_threshold;471AP_Int8 rangefinder_landing;472AP_Int8 flap_slewrate;473#if HAL_WITH_IO_MCU474AP_Int8 override_channel;475#endif476AP_Int16 gcs_pid_mask;477};478479/*4802nd block of parameters, to avoid going past 256 top level keys481*/482class ParametersG2 {483public:484ParametersG2(void);485486// var_info for holding Parameter information487static const struct AP_Param::GroupInfo var_info[];488489// just to make compilation easier when all things are compiled out...490uint8_t unused_integer;491492// button reporting library493#if HAL_BUTTON_ENABLED494AP_Button *button_ptr;495#endif496497#if AP_ICENGINE_ENABLED498// internal combustion engine control499AP_ICEngine ice_control;500#endif501502// RC input channels503RC_Channels_Plane rc_channels;504505// control over servo output ranges506SRV_Channels servo_channels;507508// whether to enforce acceptance of packets only from sysid_my_gcs509AP_Int8 sysid_enforce;510511#if HAL_SOARING_ENABLED512// ArduSoar parameters513SoaringController soaring_controller;514#endif515516// dual motor tailsitter rudder to differential thrust scaling: 0-100%517AP_Int8 rudd_dt_gain;518519// mask of channels to do manual pass-thru for520AP_Int32 manual_rc_mask;521522// home reset altitude threshold523AP_Int8 home_reset_threshold;524525AP_Int32 flight_options;526527AP_Int8 takeoff_throttle_accel_count;528AP_Int8 takeoff_timeout;529530#if AP_LANDINGGEAR_ENABLED531AP_LandingGear landing_gear;532#endif533534#if AC_PRECLAND_ENABLED535AC_PrecLand precland;536#endif537538// crow flaps weighting539AP_Int8 crow_flap_weight_outer;540AP_Int8 crow_flap_weight_inner;541AP_Int8 crow_flap_options;542AP_Int8 crow_flap_aileron_matching;543544// Forward throttle battery voltage compensation545class FWD_BATT_CMP {546public:547// Calculate the throttle scale to compensate for battery voltage drop548void update();549550// Apply throttle scale to min and max limits551void apply_min_max(int8_t &min_throttle, int8_t &max_throttle) const;552553// Apply throttle scale to throttle demand554float apply_throttle(float throttle) const;555556AP_Float batt_voltage_max;557AP_Float batt_voltage_min;558AP_Int8 batt_idx;559560private:561bool enabled;562float ratio;563} fwd_batt_cmp;564565566#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED567// guided yaw heading PID568AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.0};569#endif570571#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED572AP_Follow follow;573#endif574575AP_Float fs_ekf_thresh;576577// min initial climb in RTL578AP_Int16 rtl_climb_min;579580AP_Int8 man_expo_roll;581AP_Int8 man_expo_pitch;582AP_Int8 man_expo_rudder;583584AP_Int32 oneshot_mask;585586AP_Int8 axis_bitmask; // axes to be autotuned587588#if AP_RANGEFINDER_ENABLED589// orientation of rangefinder to use for landing590AP_Int8 rangefinder_land_orient;591#endif592};593594extern const AP_Param::Info var_info[];595596597