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/ArduCopter/Parameters.h
Views: 1798
#pragma once12#define AP_PARAM_VEHICLE_NAME copter34#include <AP_Common/AP_Common.h>5#include "RC_Channel_Copter.h"6#include <AP_Proximity/AP_Proximity.h>78#if MODE_FOLLOW_ENABLED9# include <AP_Follow/AP_Follow.h>10#endif11#if WEATHERVANE_ENABLED12#include <AC_AttitudeControl/AC_WeatherVane.h>13#endif1415// Global parameter class.16//17class Parameters {18public:19// The version of the layout as described by the parameter enum.20//21// When changing the parameter enum in an incompatible fashion, this22// value should be incremented by one.23//24// The increment will prevent old parameters from being used incorrectly25// by newer code.26//27static const uint16_t k_format_version = 120;2829// Parameter identities.30//31// The enumeration defined here is used to ensure that every parameter32// or parameter group has a unique ID number. This number is used by33// AP_Param to store and locate parameters in EEPROM.34//35// Note that entries without a number are assigned the next number after36// the entry preceding them. When adding new entries, ensure that they37// don't overlap.38//39// Try to group related variables together, and assign them a set40// range in the enumeration. Place these groups in numerical order41// at the end of the enumeration.42//43// WARNING: Care should be taken when editing this enumeration as the44// AP_Param load/save code depends on the values here to identify45// variables saved in EEPROM.46//47//48enum {49// Layout version number, always key zero.50//51k_param_format_version = 0,52k_param_software_type, // deprecated53k_param_ins_old, // *** Deprecated, remove with next eeprom number change54k_param_ins, // libraries/AP_InertialSensor variables55k_param_NavEKF2_old, // deprecated - remove56k_param_NavEKF2,57k_param_g2, // 2nd block of parameters58k_param_NavEKF3,59k_param_can_mgr,60k_param_osd,6162// simulation63k_param_sitl = 10,6465// barometer object (needed for SITL)66k_param_barometer,6768// scheduler object (for debugging)69k_param_scheduler,7071// relay object72k_param_relay,7374// (old) EPM object75k_param_epm_unused,7677// BoardConfig object78k_param_BoardConfig,7980// GPS object81k_param_gps,8283// Parachute object84k_param_parachute,8586// Landing gear object87k_param_landinggear, // 188889// Input Management object90k_param_input_manager, // 199192// Misc93//94k_param_log_bitmask_old = 20, // Deprecated95k_param_log_last_filenumber, // *** Deprecated - remove96// with next eeprom number97// change98k_param_toy_yaw_rate, // deprecated - remove99k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change100k_param_rssi_pin, // unused, replaced by rssi_ library parameters101k_param_throttle_accel_enabled, // deprecated - remove102k_param_wp_yaw_behavior,103k_param_acro_trainer,104k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max105k_param_circle_rate, // deprecated - remove106k_param_rangefinder_gain, // deprecated - remove107k_param_ch8_option_old, // deprecated108k_param_arming_check_old, // deprecated - remove109k_param_sprayer,110k_param_angle_max,111k_param_gps_hdop_good,112k_param_battery,113k_param_fs_batt_mah, // unused - moved to AP_BattMonitor114k_param_angle_rate_max, // remove115k_param_rssi_range, // unused, replaced by rssi_ library parameters116k_param_rc_feel_rp, // deprecated117k_param_NavEKF, // deprecated - remove118k_param_mission, // mission library119k_param_rc_13_old,120k_param_rc_14_old,121k_param_rally,122k_param_poshold_brake_rate,123k_param_poshold_brake_angle_max,124k_param_pilot_accel_z,125k_param_serial0_baud, // deprecated - remove126k_param_serial1_baud, // deprecated - remove127k_param_serial2_baud, // deprecated - remove128k_param_land_repositioning,129k_param_rangefinder, // rangefinder object130k_param_fs_ekf_thresh,131k_param_terrain,132k_param_acro_rp_expo, // deprecated - remove133k_param_throttle_deadzone,134k_param_optflow,135k_param_dcmcheck_thresh, // deprecated - remove136k_param_log_bitmask,137k_param_cli_enabled_old, // deprecated - remove138k_param_throttle_filt,139k_param_throttle_behavior,140k_param_pilot_takeoff_alt, // 64141142// 65: AP_Limits Library143k_param_limits = 65, // deprecated - remove144k_param_gpslock_limit, // deprecated - remove145k_param_geofence_limit, // deprecated - remove146k_param_altitude_limit, // deprecated - remove147k_param_fence_old, // only used for conversion148k_param_gps_glitch, // deprecated149k_param_baro_glitch, // 71 - deprecated150151// AP_ADSB Library152k_param_adsb, // 72153k_param_notify, // 73154155// 74: precision landing object156k_param_precland = 74,157158//159// 75: Singlecopter, CoaxCopter160//161k_param_single_servo_1 = 75, // remove162k_param_single_servo_2, // remove163k_param_single_servo_3, // remove164k_param_single_servo_4, // 78 - remove165166//167// 80: Heli168//169k_param_heli_servo_1 = 80, // remove170k_param_heli_servo_2, // remove171k_param_heli_servo_3, // remove172k_param_heli_servo_4, // remove173k_param_heli_pitch_ff, // remove174k_param_heli_roll_ff, // remove175k_param_heli_yaw_ff, // remove176k_param_heli_stab_col_min, // remove177k_param_heli_stab_col_max, // remove178k_param_heli_servo_rsc, // 89 = full! - remove179180//181// 90: misc2182//183k_param_motors = 90,184k_param_disarm_delay,185k_param_fs_crash_check,186k_param_throw_motor_start,187k_param_rtl_alt_type,188k_param_avoid,189k_param_avoidance_adsb,190191// 97: RSSI192k_param_rssi = 97,193194//195// 100: Inertial Nav196//197k_param_inertial_nav = 100, // deprecated198k_param_wp_nav,199k_param_attitude_control,200k_param_pos_control,201k_param_circle_nav,202k_param_loiter_nav, // 105203k_param_custom_control,204205// 110: Telemetry control206//207k_param_gcs0 = 110,208k_param_gcs1,209k_param_sysid_this_mav,210k_param_sysid_my_gcs,211k_param_serial1_baud_old, // deprecated212k_param_telem_delay,213k_param_gcs2,214k_param_serial2_baud_old, // deprecated215k_param_serial2_protocol, // deprecated216k_param_serial_manager_old,217k_param_ch9_option_old,218k_param_ch10_option_old,219k_param_ch11_option_old,220k_param_ch12_option_old,221k_param_takeoff_trigger_dz_old,222k_param_gcs3,223k_param_gcs_pid_mask, // 126224k_param_gcs4,225k_param_gcs5,226k_param_gcs6,227228//229// 135 : reserved for Solo until features merged with master230//231k_param_rtl_speed_cms = 135,232k_param_fs_batt_curr_rtl,233k_param_rtl_cone_slope, // 137234235//236// 140: Sensor parameters237//238k_param_imu = 140, // deprecated - can be deleted239k_param_battery_monitoring = 141, // deprecated - can be deleted240k_param_volt_div_ratio, // deprecated - can be deleted241k_param_curr_amp_per_volt, // deprecated - can be deleted242k_param_input_voltage, // deprecated - can be deleted243k_param_pack_capacity, // deprecated - can be deleted244k_param_compass_enabled_deprecated,245k_param_compass,246k_param_rangefinder_enabled_old, // deprecated247k_param_frame_type,248k_param_optflow_enabled, // deprecated249k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor250k_param_ch7_option_old,251k_param_auto_slew_rate, // deprecated - can be deleted252k_param_rangefinder_type_old, // deprecated253k_param_super_simple = 155,254k_param_axis_enabled = 157, // deprecated - remove with next eeprom number change255k_param_copter_leds_mode, // deprecated - remove with next eeprom number change256k_param_ahrs, // AHRS group // 159257258//259// 160: Navigation parameters260//261k_param_rtl_altitude = 160,262k_param_crosstrack_gain, // deprecated - remove with next eeprom number change263k_param_rtl_loiter_time,264k_param_rtl_alt_final,265k_param_tilt_comp, // 164 deprecated - remove with next eeprom number change266267268//269// Camera and mount parameters270//271k_param_camera = 165,272k_param_camera_mount,273k_param_camera_mount2, // deprecated274275//276// Battery monitoring parameters277//278k_param_battery_volt_pin = 168, // deprecated - can be deleted279k_param_battery_curr_pin, // 169 deprecated - can be deleted280281//282// 170: Radio settings283//284k_param_rc_1_old = 170,285k_param_rc_2_old,286k_param_rc_3_old,287k_param_rc_4_old,288k_param_rc_5_old,289k_param_rc_6_old,290k_param_rc_7_old,291k_param_rc_8_old,292k_param_rc_10_old,293k_param_rc_11_old,294k_param_throttle_min, // remove295k_param_throttle_max, // remove296k_param_failsafe_throttle,297k_param_throttle_fs_action, // remove298k_param_failsafe_throttle_value,299k_param_throttle_trim, // remove300k_param_esc_calibrate,301k_param_radio_tuning,302k_param_radio_tuning_high_old, // unused303k_param_radio_tuning_low_old, // unused304k_param_rc_speed = 192,305k_param_failsafe_battery_enabled, // unused - moved to AP_BattMonitor306k_param_throttle_mid, // remove307k_param_failsafe_gps_enabled, // remove308k_param_rc_9_old,309k_param_rc_12_old,310k_param_failsafe_gcs,311k_param_rcmap, // 199312313//314// 200: flight modes315//316k_param_flight_mode1 = 200,317k_param_flight_mode2,318k_param_flight_mode3,319k_param_flight_mode4,320k_param_flight_mode5,321k_param_flight_mode6,322k_param_simple_modes,323k_param_flight_mode_chan,324k_param_initial_mode,325326//327// 210: Waypoint data328//329k_param_waypoint_mode = 210, // remove330k_param_command_total, // remove331k_param_command_index, // remove332k_param_command_nav_index, // remove333k_param_waypoint_radius, // remove334k_param_circle_radius, // remove335k_param_waypoint_speed_max, // remove336k_param_land_speed,337k_param_auto_velocity_z_min, // remove338k_param_auto_velocity_z_max, // remove - 219339k_param_land_speed_high,340341//342// 220: PI/D Controllers343//344k_param_acro_rp_p = 221, // remove345k_param_axis_lock_p, // remove346k_param_pid_rate_roll, // remove347k_param_pid_rate_pitch, // remove348k_param_pid_rate_yaw, // remove349k_param_p_stabilize_roll, // remove350k_param_p_stabilize_pitch, // remove351k_param_p_stabilize_yaw, // remove352k_param_p_pos_xy, // remove353k_param_p_loiter_lon, // remove354k_param_pid_loiter_rate_lat, // remove355k_param_pid_loiter_rate_lon, // remove356k_param_pid_nav_lat, // remove357k_param_pid_nav_lon, // remove358k_param_p_alt_hold, // remove359k_param_p_vel_z, // remove360k_param_pid_optflow_roll, // remove361k_param_pid_optflow_pitch, // remove362k_param_acro_balance_roll_old, // remove363k_param_acro_balance_pitch_old, // remove364k_param_pid_accel_z, // remove365k_param_acro_balance_roll,366k_param_acro_balance_pitch,367k_param_acro_yaw_p, // remove368k_param_autotune_axis_bitmask, // remove369k_param_autotune_aggressiveness, // remove370k_param_pi_vel_xy, // remove371k_param_fs_ekf_action,372k_param_rtl_climb_min,373k_param_rpm_sensor,374k_param_autotune_min_d, // remove375k_param_arming, // 252 - AP_Arming376k_param_logger = 253, // 253 - Logging Group377378// 254,255: reserved379380k_param_vehicle = 257, // vehicle common block of parameters381k_param_throw_altitude_min,382k_param_throw_altitude_max,383384// the k_param_* space is 9-bits in size385// 511: reserved386};387388AP_Int16 format_version;389390// Telemetry control391//392AP_Int16 sysid_this_mav;393AP_Int16 sysid_my_gcs;394AP_Int8 telem_delay;395396AP_Float throttle_filt;397AP_Int16 throttle_behavior;398AP_Float pilot_takeoff_alt;399400#if MODE_RTL_ENABLED401AP_Int32 rtl_altitude;402AP_Int16 rtl_speed_cms;403AP_Float rtl_cone_slope;404AP_Int16 rtl_alt_final;405AP_Int16 rtl_climb_min; // rtl minimum climb in cm406AP_Int32 rtl_loiter_time;407AP_Enum<ModeRTL::RTLAltType> rtl_alt_type;408#endif409410AP_Int8 failsafe_gcs; // ground station failsafe behavior411AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position412413AP_Int8 super_simple;414415AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions416417#if MODE_POSHOLD_ENABLED418AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec419AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees420#endif421422// Waypoints423//424AP_Int16 land_speed;425AP_Int16 land_speed_high;426AP_Int16 pilot_speed_up; // maximum vertical ascending velocity the pilot may request427AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request428429// Throttle430//431AP_Int8 failsafe_throttle;432AP_Int16 failsafe_throttle_value;433AP_Int16 throttle_deadzone;434435// Flight modes436//437AP_Int8 flight_mode1;438AP_Int8 flight_mode2;439AP_Int8 flight_mode3;440AP_Int8 flight_mode4;441AP_Int8 flight_mode5;442AP_Int8 flight_mode6;443AP_Int8 simple_modes;444AP_Int8 flight_mode_chan;445AP_Int8 initial_mode;446447// Misc448//449AP_Int32 log_bitmask;450AP_Int8 esc_calibrate;451AP_Int8 radio_tuning;452AP_Int8 frame_type;453AP_Int8 disarm_delay;454455AP_Int8 land_repositioning;456AP_Int8 fs_ekf_action;457AP_Int8 fs_crash_check;458AP_Float fs_ekf_thresh;459AP_Int16 gcs_pid_mask;460461#if MODE_THROW_ENABLED462AP_Enum<ModeThrow::PreThrowMotorState> throw_motor_start;463AP_Int16 throw_altitude_min; // minimum altitude in m above which a throw can be detected464AP_Int16 throw_altitude_max; // maximum altitude in m below which a throw can be detected465#endif466467AP_Int16 rc_speed; // speed of fast RC Channels in Hz468469#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED470// Acro parameters471AP_Float acro_balance_roll;472AP_Float acro_balance_pitch;473#endif474475#if MODE_ACRO_ENABLED476// Acro parameters477AP_Int8 acro_trainer;478#endif479480// Note: keep initializers here in the same order as they are declared481// above.482Parameters()483{484}485};486487/*4882nd block of parameters, to avoid going past 256 top level keys489*/490class ParametersG2 {491public:492ParametersG2(void);493494// var_info for holding Parameter information495static const struct AP_Param::GroupInfo var_info[];496static const struct AP_Param::GroupInfo var_info2[];497498// altitude at which nav control can start in takeoff499AP_Float wp_navalt_min;500501// unused_integer simply exists so that the constructor for502// ParametersG2 can be created with a relatively easy syntax in503// the face of many #ifs:504uint8_t unused_integer;505506// button checking507#if HAL_BUTTON_ENABLED508AP_Button *button_ptr;509#endif510511#if MODE_THROW_ENABLED512// Throw mode parameters513AP_Int8 throw_nextmode;514AP_Enum<ModeThrow::ThrowType> throw_type;515#endif516517// ground effect compensation enable/disable518AP_Int8 gndeffect_comp_enabled;519520#if AP_TEMPCALIBRATION_ENABLED521// temperature calibration handling522AP_TempCalibration temp_calibration;523#endif524525#if AP_BEACON_ENABLED526// beacon (non-GPS positioning) library527AP_Beacon beacon;528#endif529530#if HAL_PROXIMITY_ENABLED531// proximity (aka object avoidance) library532AP_Proximity proximity;533#endif534535// whether to enforce acceptance of packets only from sysid_my_gcs536AP_Int8 sysid_enforce;537538#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED539// advanced failsafe library540AP_AdvancedFailsafe_Copter afs;541#endif542543// developer options544AP_Int32 dev_options;545546#if MODE_ACRO_ENABLED547AP_Float acro_thr_mid;548#endif549550// frame class551AP_Int8 frame_class;552553// RC input channels554RC_Channels_Copter rc_channels;555556// control over servo output ranges557SRV_Channels servo_channels;558559#if MODE_SMARTRTL_ENABLED560// Safe RTL library561AP_SmartRTL smart_rtl;562#endif563564// wheel encoder and winch565#if AP_WINCH_ENABLED566AP_Winch winch;567#endif568569// Additional pilot velocity items570AP_Int16 pilot_speed_dn;571572// Land alt final stage573AP_Int16 land_alt_low;574575#if TOY_MODE_ENABLED576ToyMode toy_mode;577#endif578579#if MODE_FLOWHOLD_ENABLED580// we need a pointer to the mode for the G2 table581void *mode_flowhold_ptr;582#endif583584#if MODE_FOLLOW_ENABLED585// follow586AP_Follow follow;587#endif588589#if USER_PARAMS_ENABLED590// User custom parameters591UserParameters user_parameters;592#endif593594#if AUTOTUNE_ENABLED595// we need a pointer to autotune for the G2 table596void *autotune_ptr;597#endif598599AP_Float tuning_min;600AP_Float tuning_max;601602#if AP_OAPATHPLANNER_ENABLED603// object avoidance path planning604AP_OAPathPlanner oa;605#endif606607#if MODE_SYSTEMID_ENABLED608// we need a pointer to the mode for the G2 table609void *mode_systemid_ptr;610#endif611612// vibration failsafe enable/disable613AP_Int8 fs_vibe_enabled;614615// Failsafe options bitmask #36616AP_Int32 fs_options;617618#if MODE_AUTOROTATE_ENABLED619// Autonmous autorotation620AC_Autorotation arot;621#endif622623#if MODE_ZIGZAG_ENABLED624// we need a pointer to the mode for the G2 table625void *mode_zigzag_ptr;626#endif627628// command model parameters629#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED630AC_CommandModel command_model_acro_rp;631#endif632633#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED634AC_CommandModel command_model_acro_y;635#endif636637AC_CommandModel command_model_pilot;638639#if MODE_ACRO_ENABLED640AP_Int8 acro_options;641#endif642643#if MODE_AUTO_ENABLED644AP_Int32 auto_options;645#endif646647#if MODE_GUIDED_ENABLED648AP_Int32 guided_options;649#endif650651AP_Float fs_gcs_timeout;652653#if MODE_RTL_ENABLED654AP_Int32 rtl_options;655#endif656657AP_Int32 flight_options;658659#if AP_RANGEFINDER_ENABLED660AP_Float rangefinder_filt;661#endif662663#if MODE_GUIDED_ENABLED664AP_Float guided_timeout;665#endif666667AP_Int8 surftrak_mode;668AP_Int8 failsafe_dr_enable;669AP_Int16 failsafe_dr_timeout;670AP_Float surftrak_tc;671672// ramp time of throttle during take-off673AP_Float takeoff_throttle_slew_time;674AP_Float takeoff_throttle_max;675#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME676AP_Int16 takeoff_rpm_min;677AP_Int16 takeoff_rpm_max;678#endif679680// EKF variance filter cutoff681AP_Float fs_ekf_filt_hz;682683#if WEATHERVANE_ENABLED684AC_WeatherVane weathervane;685#endif686687// payload place parameters688AP_Float pldp_thrust_placed_fraction;689AP_Float pldp_range_finder_maximum_m;690AP_Float pldp_delay_s;691AP_Float pldp_descent_speed_ms;692693AP_Int8 att_enable;694AP_Int8 att_decimation;695};696697extern const AP_Param::Info var_info[];698699700