ardupilot/ArduCopter/Parameters.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

699 lines
21 KiB
C
Raw Normal View History

#pragma once
#define AP_PARAM_VEHICLE_NAME copter
#include <AP_Common/AP_Common.h>
#include "RC_Channel.h"
#include <AP_Proximity/AP_Proximity.h>
#if MODE_FOLLOW_ENABLED
# include <AP_Follow/AP_Follow.h>
#endif
#if WEATHERVANE_ENABLED
2022-04-14 06:58:27 -03:00
#include <AC_AttitudeControl/AC_WeatherVane.h>
#endif
// Global parameter class.
//
class Parameters {
public:
2012-08-16 21:50:03 -03:00
// The version of the layout as described by the parameter enum.
//
// When changing the parameter enum in an incompatible fashion, this
// value should be incremented by one.
//
// The increment will prevent old parameters from being used incorrectly
// by newer code.
//
static const uint16_t k_format_version = 120;
2012-08-16 21:50:03 -03:00
// Parameter identities.
//
// The enumeration defined here is used to ensure that every parameter
2020-04-23 01:14:18 -03:00
// or parameter group has a unique ID number. This number is used by
// AP_Param to store and locate parameters in EEPROM.
2012-08-16 21:50:03 -03:00
//
// Note that entries without a number are assigned the next number after
2020-04-23 01:14:18 -03:00
// the entry preceding them. When adding new entries, ensure that they
2012-08-16 21:50:03 -03:00
// don't overlap.
//
// Try to group related variables together, and assign them a set
2020-04-23 01:14:18 -03:00
// range in the enumeration. Place these groups in numerical order
2012-08-16 21:50:03 -03:00
// at the end of the enumeration.
//
// WARNING: Care should be taken when editing this enumeration as the
2020-04-23 01:14:18 -03:00
// AP_Param load/save code depends on the values here to identify
// variables saved in EEPROM.
//
//
2012-08-16 21:50:03 -03:00
enum {
// Layout version number, always key zero.
//
k_param_format_version = 0,
2018-06-01 22:21:32 -03:00
k_param_software_type, // deprecated
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
k_param_ins, // libraries/AP_InertialSensor variables
2016-07-14 02:08:43 -03:00
k_param_NavEKF2_old, // deprecated - remove
k_param_NavEKF2,
k_param_g2, // 2nd block of parameters
2016-07-14 02:08:43 -03:00
k_param_NavEKF3,
k_param_can_mgr,
k_param_osd,
2012-08-16 21:50:03 -03:00
// simulation
k_param_sitl = 10,
2012-12-18 06:15:11 -04:00
// barometer object (needed for SITL)
k_param_barometer,
2013-01-11 21:01:10 -04:00
// scheduler object (for debugging)
k_param_scheduler,
2013-06-24 23:46:53 -03:00
// relay object
k_param_relay,
// (old) EPM object
k_param_epm_unused,
2013-12-17 00:58:11 -04:00
2014-01-19 21:58:12 -04:00
// BoardConfig object
k_param_BoardConfig,
2014-03-31 16:18:16 -03:00
// GPS object
k_param_gps,
2014-04-02 12:19:54 -03:00
// Parachute object
k_param_parachute,
// Landing gear object
k_param_landinggear, // 18
2014-04-02 12:19:54 -03:00
2015-10-12 11:27:26 -03:00
// Input Management object
k_param_input_manager, // 19
2012-08-16 21:50:03 -03:00
// Misc
//
2014-10-16 21:37:49 -03:00
k_param_log_bitmask_old = 20, // Deprecated
2012-08-16 21:50:03 -03:00
k_param_log_last_filenumber, // *** Deprecated - remove
// with next eeprom number
// change
2013-10-29 01:30:56 -03:00
k_param_toy_yaw_rate, // deprecated - remove
2020-04-23 01:14:18 -03:00
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
k_param_rssi_pin, // unused, replaced by rssi_ library parameters
k_param_throttle_accel_enabled, // deprecated - remove
k_param_wp_yaw_behavior,
k_param_acro_trainer,
2021-09-03 20:44:25 -03:00
k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max
k_param_circle_rate, // deprecated - remove
k_param_rangefinder_gain, // deprecated - remove
k_param_ch8_option_old, // deprecated
k_param_arming_check_old, // deprecated - remove
k_param_sprayer,
2013-08-15 01:04:43 -03:00
k_param_angle_max,
2013-10-01 10:34:44 -03:00
k_param_gps_hdop_good,
k_param_battery,
2018-02-28 19:32:16 -04:00
k_param_fs_batt_mah, // unused - moved to AP_BattMonitor
2014-02-03 03:39:43 -04:00
k_param_angle_rate_max, // remove
k_param_rssi_range, // unused, replaced by rssi_ library parameters
k_param_rc_feel_rp, // deprecated
2016-07-14 02:08:43 -03:00
k_param_NavEKF, // deprecated - remove
k_param_mission, // mission library
2017-01-06 21:06:40 -04:00
k_param_rc_13_old,
k_param_rc_14_old,
2014-04-11 05:15:09 -03:00
k_param_rally,
2014-07-11 02:08:09 -03:00
k_param_poshold_brake_rate,
k_param_poshold_brake_angle_max,
k_param_pilot_accel_z,
k_param_serial0_baud, // deprecated - remove
k_param_serial1_baud, // deprecated - remove
k_param_serial2_baud, // deprecated - remove
2014-07-21 07:07:15 -03:00
k_param_land_repositioning,
2016-04-27 08:37:04 -03:00
k_param_rangefinder, // rangefinder object
k_param_fs_ekf_thresh,
2014-07-22 05:22:36 -03:00
k_param_terrain,
k_param_acro_rp_expo, // deprecated - remove
2014-10-16 04:18:06 -03:00
k_param_throttle_deadzone,
k_param_optflow,
2015-03-27 03:23:17 -03:00
k_param_dcmcheck_thresh, // deprecated - remove
2014-10-16 21:37:49 -03:00
k_param_log_bitmask,
2017-08-11 01:08:41 -03:00
k_param_cli_enabled_old, // deprecated - remove
k_param_throttle_filt,
k_param_throttle_behavior,
k_param_pilot_takeoff_alt, // 64
2012-11-10 01:55:51 -04:00
2012-08-16 21:50:03 -03:00
// 65: AP_Limits Library
2013-04-26 10:57:05 -03:00
k_param_limits = 65, // deprecated - remove
k_param_gpslock_limit, // deprecated - remove
k_param_geofence_limit, // deprecated - remove
k_param_altitude_limit, // deprecated - remove
2022-03-04 12:36:07 -04:00
k_param_fence_old, // only used for conversion
k_param_gps_glitch, // deprecated
2015-03-12 08:09:23 -03:00
k_param_baro_glitch, // 71 - deprecated
2012-08-16 21:50:03 -03:00
2015-11-25 19:22:21 -04:00
// AP_ADSB Library
k_param_adsb, // 72
k_param_notify, // 73
2015-11-25 19:22:21 -04:00
2015-10-12 11:27:26 -03:00
// 74: precision landing object
k_param_precland = 74,
//
// 75: Singlecopter, CoaxCopter
//
k_param_single_servo_1 = 75, // remove
k_param_single_servo_2, // remove
k_param_single_servo_3, // remove
k_param_single_servo_4, // 78 - remove
2012-08-16 21:50:03 -03:00
//
// 80: Heli
//
k_param_heli_servo_1 = 80, // remove
k_param_heli_servo_2, // remove
k_param_heli_servo_3, // remove
k_param_heli_servo_4, // remove
2014-02-03 03:39:43 -04:00
k_param_heli_pitch_ff, // remove
k_param_heli_roll_ff, // remove
k_param_heli_yaw_ff, // remove
k_param_heli_stab_col_min, // remove
k_param_heli_stab_col_max, // remove
k_param_heli_servo_rsc, // 89 = full! - remove
2012-08-16 21:50:03 -03:00
//
// 90: misc2
2012-08-16 21:50:03 -03:00
//
k_param_motors = 90,
k_param_disarm_delay,
k_param_fs_crash_check,
k_param_throw_motor_start,
k_param_rtl_alt_type,
2016-06-20 05:27:14 -03:00
k_param_avoid,
k_param_avoidance_adsb,
2012-08-16 21:50:03 -03:00
// 97: RSSI
k_param_rssi = 97,
//
// 100: Inertial Nav
//
k_param_inertial_nav = 100, // deprecated
k_param_wp_nav,
k_param_attitude_control,
k_param_pos_control,
k_param_circle_nav,
k_param_loiter_nav, // 105
2022-07-16 22:49:47 -03:00
k_param_custom_control,
2012-08-16 21:50:03 -03:00
// 110: Telemetry control
//
k_param_gcs0 = 110,
k_param_gcs1,
2012-08-16 21:50:03 -03:00
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial1_baud_old, // deprecated
2012-08-29 20:03:01 -03:00
k_param_telem_delay,
k_param_gcs2,
k_param_serial2_baud_old, // deprecated
k_param_serial2_protocol, // deprecated
k_param_serial_manager_old,
k_param_ch9_option_old,
k_param_ch10_option_old,
k_param_ch11_option_old,
k_param_ch12_option_old,
k_param_takeoff_trigger_dz_old,
k_param_gcs3,
k_param_gcs_pid_mask, // 126
k_param_gcs4,
k_param_gcs5,
k_param_gcs6,
2012-08-16 21:50:03 -03:00
//
// 135 : reserved for Solo until features merged with master
//
k_param_rtl_speed_cms = 135,
2016-01-06 03:00:29 -04:00
k_param_fs_batt_curr_rtl,
k_param_rtl_cone_slope, // 137
2012-08-16 21:50:03 -03:00
//
// 140: Sensor parameters
//
k_param_imu = 140, // deprecated - can be deleted
2013-10-01 10:34:44 -03:00
k_param_battery_monitoring = 141, // deprecated - can be deleted
k_param_volt_div_ratio, // deprecated - can be deleted
k_param_curr_amp_per_volt, // deprecated - can be deleted
k_param_input_voltage, // deprecated - can be deleted
2013-10-01 10:34:44 -03:00
k_param_pack_capacity, // deprecated - can be deleted
k_param_compass_enabled_deprecated,
2012-08-16 21:50:03 -03:00
k_param_compass,
2016-04-27 08:37:04 -03:00
k_param_rangefinder_enabled_old, // deprecated
k_param_frame_type,
k_param_optflow_enabled, // deprecated
2018-02-28 19:32:16 -04:00
k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor
k_param_ch7_option_old,
k_param_auto_slew_rate, // deprecated - can be deleted
2016-04-27 08:37:04 -03:00
k_param_rangefinder_type_old, // deprecated
k_param_super_simple = 155,
k_param_axis_enabled = 157, // deprecated - remove with next eeprom number change
k_param_copter_leds_mode, // deprecated - remove with next eeprom number change
2013-10-01 10:34:44 -03:00
k_param_ahrs, // AHRS group // 159
2012-08-16 21:50:03 -03:00
//
// 160: Navigation parameters
//
k_param_rtl_altitude = 160,
2020-04-23 01:14:18 -03:00
k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
k_param_rtl_loiter_time,
k_param_rtl_alt_final,
2020-04-23 01:14:18 -03:00
k_param_tilt_comp, // 164 deprecated - remove with next eeprom number change
2012-08-16 21:50:03 -03:00
//
// Camera and mount parameters
//
k_param_camera = 165,
k_param_camera_mount,
2014-12-16 08:23:33 -04:00
k_param_camera_mount2, // deprecated
2012-08-16 21:50:03 -03:00
//
// Battery monitoring parameters
//
2013-10-01 10:34:44 -03:00
k_param_battery_volt_pin = 168, // deprecated - can be deleted
k_param_battery_curr_pin, // 169 deprecated - can be deleted
2012-08-16 21:50:03 -03:00
//
// 170: Radio settings
//
2017-01-06 21:06:40 -04:00
k_param_rc_1_old = 170,
k_param_rc_2_old,
k_param_rc_3_old,
k_param_rc_4_old,
k_param_rc_5_old,
k_param_rc_6_old,
k_param_rc_7_old,
k_param_rc_8_old,
k_param_rc_10_old,
k_param_rc_11_old,
k_param_throttle_min, // remove
2015-03-16 01:35:57 -03:00
k_param_throttle_max, // remove
k_param_failsafe_throttle,
k_param_throttle_fs_action, // remove
k_param_failsafe_throttle_value,
k_param_throttle_trim, // remove
2012-08-16 21:50:03 -03:00
k_param_esc_calibrate,
k_param_radio_tuning,
k_param_radio_tuning_high_old, // unused
k_param_radio_tuning_low_old, // unused
2012-08-16 21:50:03 -03:00
k_param_rc_speed = 192,
2018-02-28 19:32:16 -04:00
k_param_failsafe_battery_enabled, // unused - moved to AP_BattMonitor
2016-06-09 10:09:55 -03:00
k_param_throttle_mid, // remove
k_param_failsafe_gps_enabled, // remove
2017-01-06 21:06:40 -04:00
k_param_rc_9_old,
k_param_rc_12_old,
k_param_failsafe_gcs,
k_param_rcmap, // 199
2012-08-16 21:50:03 -03:00
//
// 200: flight modes
//
k_param_flight_mode1 = 200,
k_param_flight_mode2,
k_param_flight_mode3,
k_param_flight_mode4,
k_param_flight_mode5,
k_param_flight_mode6,
k_param_simple_modes,
k_param_flight_mode_chan,
2020-11-02 13:46:01 -04:00
k_param_initial_mode,
2012-08-16 21:50:03 -03:00
//
// 210: Waypoint data
//
k_param_waypoint_mode = 210, // remove
k_param_command_total, // remove
k_param_command_index, // remove
k_param_command_nav_index, // remove
k_param_waypoint_radius, // remove
2014-02-03 03:39:43 -04:00
k_param_circle_radius, // remove
k_param_waypoint_speed_max, // remove
k_param_land_speed,
k_param_auto_velocity_z_min, // remove
k_param_auto_velocity_z_max, // remove - 219
k_param_land_speed_high,
2012-08-16 21:50:03 -03:00
//
// 220: PI/D Controllers
//
k_param_acro_rp_p = 221, // remove
k_param_axis_lock_p, // remove
k_param_pid_rate_roll, // remove
k_param_pid_rate_pitch, // remove
k_param_pid_rate_yaw, // remove
k_param_p_stabilize_roll, // remove
k_param_p_stabilize_pitch, // remove
k_param_p_stabilize_yaw, // remove
k_param_p_pos_xy, // remove
k_param_p_loiter_lon, // remove
k_param_pid_loiter_rate_lat, // remove
k_param_pid_loiter_rate_lon, // remove
k_param_pid_nav_lat, // remove
k_param_pid_nav_lon, // remove
k_param_p_alt_hold, // remove
k_param_p_vel_z, // remove
k_param_pid_optflow_roll, // remove
k_param_pid_optflow_pitch, // remove
k_param_acro_balance_roll_old, // remove
k_param_acro_balance_pitch_old, // remove
k_param_pid_accel_z, // remove
k_param_acro_balance_roll,
k_param_acro_balance_pitch,
k_param_acro_yaw_p, // remove
k_param_autotune_axis_bitmask, // remove
k_param_autotune_aggressiveness, // remove
k_param_pi_vel_xy, // remove
k_param_fs_ekf_action,
k_param_rtl_climb_min,
k_param_rpm_sensor,
k_param_autotune_min_d, // remove
k_param_arming, // 252 - AP_Arming
k_param_logger = 253, // 253 - Logging Group
2012-08-16 21:50:03 -03:00
// 254,255: reserved
k_param_vehicle = 257, // vehicle common block of parameters
k_param_throw_altitude_min,
k_param_throw_altitude_max,
// the k_param_* space is 9-bits in size
// 511: reserved
2012-08-16 21:50:03 -03:00
};
AP_Int16 format_version;
// Telemetry control
//
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
2012-08-29 20:03:01 -03:00
AP_Int8 telem_delay;
2012-08-16 21:50:03 -03:00
AP_Float throttle_filt;
AP_Int16 throttle_behavior;
AP_Float pilot_takeoff_alt;
#if MODE_RTL_ENABLED
2021-09-15 01:00:54 -03:00
AP_Int32 rtl_altitude;
2015-10-19 21:19:37 -03:00
AP_Int16 rtl_speed_cms;
2016-01-06 03:00:29 -04:00
AP_Float rtl_cone_slope;
2021-01-07 08:18:31 -04:00
AP_Int16 rtl_alt_final;
AP_Int16 rtl_climb_min; // rtl minimum climb in cm
AP_Int32 rtl_loiter_time;
AP_Enum<ModeRTL::RTLAltType> rtl_alt_type;
2021-01-07 08:18:31 -04:00
#endif
2013-04-29 09:30:22 -03:00
AP_Int8 failsafe_gcs; // ground station failsafe behavior
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
2012-11-13 10:43:54 -04:00
2012-08-16 21:50:03 -03:00
AP_Int8 super_simple;
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
2014-04-11 05:15:09 -03:00
#if MODE_POSHOLD_ENABLED
2014-07-11 02:08:09 -03:00
AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec
AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees
#endif
2012-08-16 21:50:03 -03:00
// Waypoints
//
AP_Int16 land_speed;
AP_Int16 land_speed_high;
AP_Int16 pilot_speed_up; // maximum vertical ascending velocity the pilot may request
AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request
2012-08-16 21:50:03 -03:00
// Throttle
//
AP_Int8 failsafe_throttle;
AP_Int16 failsafe_throttle_value;
AP_Int16 throttle_deadzone;
2012-08-16 21:50:03 -03:00
// Flight modes
//
AP_Int8 flight_mode1;
AP_Int8 flight_mode2;
AP_Int8 flight_mode3;
AP_Int8 flight_mode4;
AP_Int8 flight_mode5;
AP_Int8 flight_mode6;
AP_Int8 simple_modes;
AP_Int8 flight_mode_chan;
2020-11-02 13:46:01 -04:00
AP_Int8 initial_mode;
2012-08-16 21:50:03 -03:00
// Misc
//
2014-10-16 21:37:49 -03:00
AP_Int32 log_bitmask;
2012-08-16 21:50:03 -03:00
AP_Int8 esc_calibrate;
AP_Int8 radio_tuning;
AP_Int8 frame_type;
AP_Int8 disarm_delay;
2012-08-16 21:50:03 -03:00
AP_Int8 land_repositioning;
AP_Int8 fs_ekf_action;
AP_Int8 fs_crash_check;
AP_Float fs_ekf_thresh;
AP_Int16 gcs_pid_mask;
#if MODE_THROW_ENABLED
AP_Enum<ModeThrow::PreThrowMotorState> throw_motor_start;
AP_Int16 throw_altitude_min; // minimum altitude in m above which a throw can be detected
AP_Int16 throw_altitude_max; // maximum altitude in m below which a throw can be detected
#endif
2012-08-16 21:50:03 -03:00
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
// Acro parameters
AP_Float acro_balance_roll;
AP_Float acro_balance_pitch;
#endif
#if MODE_ACRO_ENABLED
// Acro parameters
AP_Int8 acro_trainer;
#endif
2012-08-16 21:50:03 -03:00
// Note: keep initializers here in the same order as they are declared
// above.
Parameters()
2012-08-16 21:50:03 -03:00
{
}
};
/*
2nd block of parameters, to avoid going past 256 top level keys
*/
class ParametersG2 {
public:
ParametersG2(void);
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
2022-12-30 22:11:31 -04:00
static const struct AP_Param::GroupInfo var_info2[];
// altitude at which nav control can start in takeoff
AP_Float wp_navalt_min;
2016-07-21 22:24:13 -03:00
// unused_integer simply exists so that the constructor for
// ParametersG2 can be created with a relatively easy syntax in
// the face of many #ifs:
uint8_t unused_integer;
2016-07-21 22:24:13 -03:00
// button checking
#if HAL_BUTTON_ENABLED
AP_Button *button_ptr;
#endif
2016-10-28 19:08:22 -03:00
#if MODE_THROW_ENABLED
// Throw mode parameters
AP_Int8 throw_nextmode;
AP_Enum<ModeThrow::ThrowType> throw_type;
#endif
// ground effect compensation enable/disable
AP_Int8 gndeffect_comp_enabled;
#if AP_TEMPCALIBRATION_ENABLED
// temperature calibration handling
AP_TempCalibration temp_calibration;
#endif
#if AP_BEACON_ENABLED
// beacon (non-GPS positioning) library
AP_Beacon beacon;
#endif
#if HAL_PROXIMITY_ENABLED
2016-10-14 02:02:29 -03:00
// proximity (aka object avoidance) library
AP_Proximity proximity;
#endif
// whether to enforce acceptance of packets only from sysid_my_gcs
AP_Int8 sysid_enforce;
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// advanced failsafe library
AP_AdvancedFailsafe_Copter afs;
#endif
// developer options
AP_Int32 dev_options;
#if MODE_ACRO_ENABLED
AP_Float acro_thr_mid;
#endif
2016-12-12 06:22:56 -04:00
// frame class
AP_Int8 frame_class;
2017-01-06 21:06:40 -04:00
// RC input channels
RC_Channels_Copter rc_channels;
2017-01-06 21:06:40 -04:00
// control over servo output ranges
SRV_Channels servo_channels;
2017-07-26 14:14:40 -03:00
#if MODE_SMARTRTL_ENABLED
2017-07-26 14:14:40 -03:00
// Safe RTL library
2017-09-08 23:45:31 -03:00
AP_SmartRTL smart_rtl;
#endif
// wheel encoder and winch
#if AP_WINCH_ENABLED
AP_Winch winch;
2018-02-10 10:23:06 -04:00
#endif
// Additional pilot velocity items
AP_Int16 pilot_speed_dn;
2018-01-23 08:33:24 -04:00
// Land alt final stage
AP_Int16 land_alt_low;
#if TOY_MODE_ENABLED
ToyMode toy_mode;
#endif
#if MODE_FLOWHOLD_ENABLED
// we need a pointer to the mode for the G2 table
void *mode_flowhold_ptr;
#endif
#if MODE_FOLLOW_ENABLED
// follow
AP_Follow follow;
#endif
2018-06-23 04:11:05 -03:00
#if USER_PARAMS_ENABLED
2018-08-21 10:02:40 -03:00
// User custom parameters
UserParameters user_parameters;
#endif
#if AUTOTUNE_ENABLED
// we need a pointer to autotune for the G2 table
void *autotune_ptr;
#endif
2019-03-01 02:40:53 -04:00
AP_Float tuning_min;
AP_Float tuning_max;
2019-06-05 07:47:32 -03:00
#if AP_OAPATHPLANNER_ENABLED
2019-06-05 07:47:32 -03:00
// object avoidance path planning
AP_OAPathPlanner oa;
#endif
2019-07-29 04:55:40 -03:00
#if MODE_SYSTEMID_ENABLED
2019-07-29 04:55:40 -03:00
// we need a pointer to the mode for the G2 table
void *mode_systemid_ptr;
#endif
2019-03-21 06:51:35 -03:00
// vibration failsafe enable/disable
AP_Int8 fs_vibe_enabled;
// Failsafe options bitmask #36
AP_Int32 fs_options;
#if MODE_AUTOROTATE_ENABLED
// Autonmous autorotation
AC_Autorotation arot;
#endif
#if MODE_ZIGZAG_ENABLED
2020-05-11 23:17:21 -03:00
// we need a pointer to the mode for the G2 table
void *mode_zigzag_ptr;
2020-04-02 05:25:39 -03:00
#endif
2020-02-02 09:07:21 -04:00
// command model parameters
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
AC_CommandModel command_model_acro_rp;
#endif
#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED
AC_CommandModel command_model_acro_y;
#endif
AC_CommandModel command_model_pilot;
#if MODE_ACRO_ENABLED
AP_Int8 acro_options;
#endif
#if MODE_AUTO_ENABLED
AP_Int32 auto_options;
#endif
#if MODE_GUIDED_ENABLED
AP_Int32 guided_options;
#endif
AP_Float fs_gcs_timeout;
#if MODE_RTL_ENABLED
AP_Int32 rtl_options;
#endif
AP_Int32 flight_options;
#if AP_RANGEFINDER_ENABLED
AP_Float rangefinder_filt;
#endif
#if MODE_GUIDED_ENABLED
AP_Float guided_timeout;
#endif
AP_Int8 surftrak_mode;
2022-05-10 23:17:13 -03:00
AP_Int8 failsafe_dr_enable;
AP_Int16 failsafe_dr_timeout;
AP_Float surftrak_tc;
// ramp time of throttle during take-off
AP_Float takeoff_throttle_slew_time;
2023-03-20 21:31:39 -03:00
AP_Float takeoff_throttle_max;
#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME
AP_Int16 takeoff_rpm_min;
AP_Int16 takeoff_rpm_max;
#endif
2022-04-14 06:58:27 -03:00
// EKF variance filter cutoff
AP_Float fs_ekf_filt_hz;
#if WEATHERVANE_ENABLED
2022-04-14 06:58:27 -03:00
AC_WeatherVane weathervane;
#endif
2022-12-30 22:11:31 -04:00
// payload place parameters
AP_Float pldp_thrust_placed_fraction;
AP_Float pldp_range_finder_maximum_m;
2022-12-30 22:11:31 -04:00
AP_Float pldp_delay_s;
AP_Float pldp_descent_speed_ms;
Copter: run copter attitude control with separate rate thread run motors output at rate thread loop rate allow rate thread to be enabled/disabled at runtime for in-flight impact testing setup the right PID notch sample rate when using the rate thread the PID notches run at a very different sample rate call update_dynamic_notch_at_specified_rate() in rate thread log RTDT messages to track rate loop performance set dt each cycle of the rate loop thread run rate controller on samples as soon as they are ready detect overload conditions in both the rate loop and main loop decimate the rate thread if the CPU appears overloaded decimate the gyro window inside the IMU add in gyro drift to attitude rate thread add fixed-rate thread option configure rate loop based on AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED better rate loop thread decimation management ensure fix rate attitude is enabled on arming add rate loop timing debug update backend filters rather than all the backends provide more options around attitude rates only log attitude and IMU from main loop force trigger_groups() and reduce attitude thread priority migrate fast rate enablement to FSTRATE_ENABLE remove rate thread logging configuration and choose sensible logging rates conditionally compile rate thread pieces allow fast rate decimation to be user throttled if target rate changes immediately jump to target rate recover quickly from rate changes ensure fixed rate always prints the rate on arming and is always up to date add support for fixed rate attitude that does not change when disarmed only push to subsystems at main loop rate add logging and motor timing debug correctly round gyro decimation rates set dshot rate when changing attitude rate fallback to higher dshot rates at lower loop rates re-factor rate loop rate updates log rates in systemid mode reset target modifiers at loop rate don't compile in support on tradheli move rate thread into its own compilation unit add rate loop config abstraction that allows code to be elided on non-copter builds dynamically enable/disable rate thread correctly add design comment for the rate thread Co-authored-by: Andrew Tridgell <andrew@tridgell.net>
2024-02-11 01:19:56 -04:00
AP_Int8 att_enable;
AP_Int8 att_decimation;
};
2012-08-16 21:50:03 -03:00
extern const AP_Param::Info var_info[];