#include "Copter.h"12#include <AP_Gripper/AP_Gripper.h>3#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>45/*6This program is free software: you can redistribute it and/or modify7it under the terms of the GNU General Public License as published by8the Free Software Foundation, either version 3 of the License, or9(at your option) any later version.1011This program is distributed in the hope that it will be useful,12but WITHOUT ANY WARRANTY; without even the implied warranty of13MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the14GNU General Public License for more details.1516You should have received a copy of the GNU General Public License17along with this program. If not, see <http://www.gnu.org/licenses/>.18*/1920/*21* ArduCopter parameter definitions22*23*/2425#if FRAME_CONFIG == HELI_FRAME26// 6 here is AP_Motors::MOTOR_FRAME_HELI27#define DEFAULT_FRAME_CLASS 628#else29#define DEFAULT_FRAME_CLASS 030#endif3132const AP_Param::Info Copter::var_info[] = {33// @Param: FORMAT_VERSION34// @DisplayName: Eeprom format version number35// @Description: This value is incremented when changes are made to the eeprom format36// @User: Advanced37GSCALAR(format_version, "FORMAT_VERSION", 0),3839// SYSID_THISMAV was here4041// SYSID_MYGCS was here4243// @Param: PILOT_THR_FILT44// @DisplayName: Throttle filter cutoff45// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable46// @User: Advanced47// @Units: Hz48// @Range: 0 1049// @Increment: 0.550GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),5152// @Param: PILOT_TKOFF_ALT53// @DisplayName: Pilot takeoff altitude54// @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.55// @User: Standard56// @Units: cm57// @Range: 0.0 1000.058// @Increment: 1059GSCALAR(pilot_takeoff_alt_cm, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT),6061// @Param: PILOT_THR_BHV62// @DisplayName: Throttle stick behavior63// @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.64// @User: Standard65// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection66GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),6768// AP_SerialManager was here6970// @Param: GCS_PID_MASK71// @DisplayName: GCS PID tuning mask72// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for73// @User: Advanced74// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:AccelZ75GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),7677#if MODE_RTL_ENABLED78// @Param: RTL_CONE_SLOPE79// @DisplayName: RTL cone slope80// @Description: Defines a cone above home which determines maximum climb81// @Range: 0 10.082// @Increment: 0.183// @Values: 0:Disabled,1:Shallow,3:Steep84// @User: Standard85GSCALAR(rtl_cone_slope, "RTL_CONE_SLOPE", RTL_CONE_SLOPE_DEFAULT),8687// @Param: RTL_LOIT_TIME88// @DisplayName: RTL loiter time89// @Description: Time (in milliseconds) to loiter above home before beginning final descent90// @Units: ms91// @Range: 0 6000092// @Increment: 100093// @User: Standard94GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME),9596// @Param: RTL_ALT_TYPE97// @DisplayName: RTL mode altitude type98// @Description: RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database99// @Values: 0:Relative to Home, 1:Terrain100// @User: Standard101GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),102#endif103104// @Param: FS_GCS_ENABLE105// @DisplayName: Ground Station Failsafe Enable106// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.107// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Brake or Land108// @User: Standard109GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),110111// @Param: GPS_HDOP_GOOD112// @DisplayName: GPS Hdop Good113// @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks114// @Range: 100 900115// @User: Advanced116GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),117118// @Param: SUPER_SIMPLE119// @DisplayName: Super Simple Mode120// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode. The bitmask is for flight mode switch positions121// @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6122// @User: Standard123GSCALAR(super_simple, "SUPER_SIMPLE", 0),124125// @Param: WP_YAW_BEHAVIOR126// @DisplayName: Yaw behaviour during missions127// @Description: Determines how the autopilot controls the yaw during missions and RTL128// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course129// @User: Standard130GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),131132// @Param: PILOT_SPEED_UP133// @DisplayName: Pilot maximum vertical speed ascending134// @Description: The maximum vertical ascending velocity the pilot may request in cm/s135// @Units: cm/s136// @Range: 50 500137// @Increment: 10138// @User: Standard139GSCALAR(pilot_speed_up_cms, "PILOT_SPEED_UP", PILOT_SPEED_UP_DEFAULT),140141// @Param: PILOT_ACCEL_Z142// @DisplayName: Pilot vertical acceleration143// @Description: The vertical acceleration used when pilot is controlling the altitude144// @Units: cm/s/s145// @Range: 50 500146// @Increment: 10147// @User: Standard148GSCALAR(pilot_accel_d_cmss, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),149150// @Param: FS_THR_ENABLE151// @DisplayName: Throttle Failsafe Enable152// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel153// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Removed in 4.0+),3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land,6:Enabled Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Enabled always Brake or Land154// @User: Standard155GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL),156157// @Param: FS_THR_VALUE158// @DisplayName: Throttle Failsafe Value159// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers160// @Range: 910 1100161// @Units: PWM162// @Increment: 1163// @User: Standard164GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),165166// @Param: THR_DZ167// @DisplayName: Throttle deadzone168// @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes169// @User: Standard170// @Range: 0 300171// @Units: PWM172// @Increment: 1173GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),174175// @Param: FLTMODE1176// @DisplayName: Flight Mode 1177// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230178// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL,28:Turtle179// @User: Standard180GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),181182// @Param: FLTMODE2183// @CopyFieldsFrom: FLTMODE1184// @DisplayName: Flight Mode 2185// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360186GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),187188// @Param: FLTMODE3189// @CopyFieldsFrom: FLTMODE1190// @DisplayName: Flight Mode 3191// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490192GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),193194// @Param: FLTMODE4195// @CopyFieldsFrom: FLTMODE1196// @DisplayName: Flight Mode 4197// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620198GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),199200// @Param: FLTMODE5201// @CopyFieldsFrom: FLTMODE1202// @DisplayName: Flight Mode 5203// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749204GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),205206// @Param: FLTMODE6207// @CopyFieldsFrom: FLTMODE1208// @DisplayName: Flight Mode 6209// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750210GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),211212// @Param: FLTMODE_CH213// @DisplayName: Flightmode channel214// @Description: RC Channel to use for flight mode control215// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8,9:Channel9,10:Channel 10,11:Channel 11,12:Channel 12,13:Channel 13,14:Channel 14,15:Channel 15216// @User: Advanced217GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT),218219// @Param: INITIAL_MODE220// @DisplayName: Initial flight mode221// @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver.222// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate223// @User: Advanced224GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)Mode::Number::STABILIZE),225226// @Param: SIMPLE227// @DisplayName: Simple mode bitmask228// @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode). The bitmask is for flightmode switch positions.229// @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6230// @User: Advanced231GSCALAR(simple_modes, "SIMPLE", 0),232233// @Param: LOG_BITMASK234// @DisplayName: Log bitmask235// @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basiclog types by setting this to 65535. Note that if you want to reduce log sizes you should consider using LOG_FILE_RATEMAX instead of disabling logging items with this parameter.236// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging237// @User: Standard238GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),239240// @Param: ESC_CALIBRATION241// @DisplayName: ESC Calibration242// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.243// @User: Advanced244// @Values: 0:Normal Start-up, 1:Start-up in ESC Calibration mode if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle, 3:Start-up and automatically calibrate ESCs, 9:Disabled245GSCALAR(esc_calibrate, "ESC_CALIBRATION", 0),246247#if AP_RC_TRANSMITTER_TUNING_ENABLED248// @Param: TUNE249// @DisplayName: Tuning Parameter250// @Description: Selects parameter (normally a PID gain) that is being tuned with an RC transmitter's knob. The RC input channel used is assigned by setting RCx_OPTION to 219.251// @User: Standard252// @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro Roll/Pitch deg/s,40:Acro Yaw deg/s,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,58:SysID Magnitude,59:PSC Angle Max,60:Loiter Speed253GSCALAR(rc_tuning_param, "TUNE", 0),254#endif // AP_RC_TRANSMITTER_TUNING_ENABLED255256// @Param: FRAME_TYPE257// @DisplayName: Frame Type (+, X, V, etc)258// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.259// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B, 11:Y6F, 12:BetaFlightX, 13:DJIX, 14:ClockwiseX, 15: I, 18: BetaFlightXReversed, 19:Y4260// @User: Standard261// @RebootRequired: True262GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT),263264// @Group: ARMING_265// @Path: ../libraries/AP_Arming/AP_Arming.cpp266GOBJECT(arming, "ARMING_", AP_Arming_Copter),267268// @Param: DISARM_DELAY269// @DisplayName: Disarm delay270// @Description: Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value.271// @Units: s272// @Range: 0 127273// @User: Advanced274GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),275276#if MODE_POSHOLD_ENABLED277// @Param: PHLD_BRAKE_RATE278// @DisplayName: PosHold braking rate279// @Description: PosHold flight mode's rotation rate during braking in deg/sec280// @Units: deg/s281// @Range: 4 12282// @User: Advanced283GSCALAR(poshold_brake_rate_degs, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT),284285// @Param: PHLD_BRAKE_ANGLE286// @DisplayName: PosHold braking angle max287// @Description: PosHold flight mode's max lean angle during braking in centi-degrees288// @Units: cdeg289// @Increment: 10290// @Range: 2000 4500291// @User: Advanced292GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),293#endif294295// @Param: LAND_REPOSITION296// @DisplayName: Land repositioning297// @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.298// @Values: 0:No repositioning, 1:Repositioning299// @User: Advanced300GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),301302// @Param: FS_EKF_ACTION303// @DisplayName: EKF Failsafe Action304// @Description: Controls the action that will be taken when an EKF failsafe is invoked305// @Values: 0:Report only, 1:Switch to Land mode if current mode requires position, 2:Switch to AltHold mode if current mode requires position, 3:Switch to Land mode from all modes306// @User: Advanced307GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),308309// @Param: FS_EKF_THRESH310// @DisplayName: EKF failsafe variance threshold311// @Description: Allows setting the maximum acceptable compass, velocity, position and height variances. Used in arming check and EKF failsafe.312// @Values: 0:Disabled, 0.6:Strict, 0.8:Default, 1.0:Relaxed313// @Range: 0.0 1.0314// @User: Advanced315GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),316317// @Param: FS_CRASH_CHECK318// @DisplayName: Crash check enable319// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.320// @Values: 0:Disabled, 1:Enabled321// @User: Advanced322GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 1),323324// @Param: RC_SPEED325// @DisplayName: ESC Update Speed326// @Description: This is the speed in Hertz that your ESCs will receive updates327// @Units: Hz328// @Range: 50 490329// @Increment: 1330// @User: Advanced331GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),332333#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED334// @Param: ACRO_BAL_ROLL335// @DisplayName: Acro Balance Roll336// @Description: rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude.337// @Range: 0 3338// @Increment: 0.1339// @User: Advanced340GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),341342// @Param: ACRO_BAL_PITCH343// @DisplayName: Acro Balance Pitch344// @Description: rate at which pitch angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the pitch axis. A higher value causes faster decay of desired to actual attitude.345// @Range: 0 3346// @Increment: 0.1347// @User: Advanced348GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),349#endif350351// ACRO_RP_EXPO moved to Command Model class352353#if MODE_ACRO_ENABLED354// @Param: ACRO_TRAINER355// @DisplayName: Acro Trainer356// @Description: Type of trainer used in acro mode357// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited358// @User: Advanced359GSCALAR(acro_trainer, "ACRO_TRAINER", (uint8_t)ModeAcro::Trainer::LIMITED),360#endif361362// variables not in the g class which contain EEPROM saved variables363364#if AP_CAMERA_ENABLED365// @Group: CAM366// @Path: ../libraries/AP_Camera/AP_Camera.cpp367GOBJECT(camera, "CAM", AP_Camera),368#endif369370#if AP_RELAY_ENABLED371// @Group: RELAY372// @Path: ../libraries/AP_Relay/AP_Relay.cpp373GOBJECT(relay, "RELAY", AP_Relay),374#endif375376#if HAL_PARACHUTE_ENABLED377// @Group: CHUTE_378// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp379GOBJECT(parachute, "CHUTE_", AP_Parachute),380#endif381382#if AP_LANDINGGEAR_ENABLED383// @Group: LGR_384// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp385GOBJECT(landinggear, "LGR_", AP_LandingGear),386#endif387388#if FRAME_CONFIG == HELI_FRAME389// @Group: IM_390// @Path: ../libraries/AC_InputManager/AC_InputManager_Heli.cpp391GOBJECT(input_manager, "IM_", AC_InputManager_Heli),392#endif393394// @Group: COMPASS_395// @Path: ../libraries/AP_Compass/AP_Compass.cpp396GOBJECT(compass, "COMPASS_", Compass),397398// @Group: INS399// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp400GOBJECT(ins, "INS", AP_InertialSensor),401402// @Group: WPNAV_403// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp404GOBJECTPTR(wp_nav, "WPNAV_", AC_WPNav),405406// @Group: LOIT_407// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp408GOBJECTPTR(loiter_nav, "LOIT_", AC_Loiter),409410#if MODE_CIRCLE_ENABLED411// @Group: CIRCLE_412// @Path: ../libraries/AC_WPNav/AC_Circle.cpp413GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),414#endif415416// @Group: ATC_417// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp418GOBJECTVARPTR(attitude_control, "ATC_", &copter.attitude_control_var_info),419420// @Group: PSC421// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp422GOBJECTPTR(pos_control, "PSC", AC_PosControl),423424// SR0 through SR6 was here425426// @Group: AHRS_427// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp428GOBJECT(ahrs, "AHRS_", AP_AHRS),429430#if HAL_MOUNT_ENABLED431// @Group: MNT432// @Path: ../libraries/AP_Mount/AP_Mount.cpp433GOBJECT(camera_mount, "MNT", AP_Mount),434#endif435436// @Group: BATT437// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp438GOBJECT(battery, "BATT", AP_BattMonitor),439440// @Group: BRD_441// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp442GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),443444#if HAL_MAX_CAN_PROTOCOL_DRIVERS445// @Group: CAN_446// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp447GOBJECT(can_mgr, "CAN_", AP_CANManager),448#endif449450#if HAL_SPRAYER_ENABLED451// @Group: SPRAY_452// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp453GOBJECT(sprayer, "SPRAY_", AC_Sprayer),454#endif455456#if AP_SIM_ENABLED457// @Group: SIM_458// @Path: ../libraries/SITL/SITL.cpp459GOBJECT(sitl, "SIM_", SITL::SIM),460#endif461462// @Group: BARO463// @Path: ../libraries/AP_Baro/AP_Baro.cpp464GOBJECT(barometer, "BARO", AP_Baro),465466// GPS driver467// @Group: GPS468// @Path: ../libraries/AP_GPS/AP_GPS.cpp469GOBJECT(gps, "GPS", AP_GPS),470471// @Group: SCHED_472// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp473GOBJECT(scheduler, "SCHED_", AP_Scheduler),474475// @Group: AVOID_476// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp477#if AP_AVOIDANCE_ENABLED478GOBJECT(avoid, "AVOID_", AC_Avoid),479#endif480481#if HAL_RALLY_ENABLED482// @Group: RALLY_483// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp484GOBJECT(rally, "RALLY_", AP_Rally_Copter),485#endif486487#if FRAME_CONFIG == HELI_FRAME488// @Group: H_489// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp,../libraries/AP_Motors/AP_MotorsHeli_Dual.cpp,../libraries/AP_Motors/AP_MotorsHeli.cpp490GOBJECTVARPTR(motors, "H_", &copter.motors_var_info),491#else492// @Group: MOT_493// @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp494GOBJECTVARPTR(motors, "MOT_", &copter.motors_var_info),495#endif496497// @Group: RCMAP_498// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp499GOBJECT(rcmap, "RCMAP_", RCMapper),500501#if HAL_NAVEKF2_AVAILABLE502// @Group: EK2_503// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp504GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),505#endif506507#if HAL_NAVEKF3_AVAILABLE508// @Group: EK3_509// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp510GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),511#endif512513#if MODE_AUTO_ENABLED514// @Group: MIS_515// @Path: ../libraries/AP_Mission/AP_Mission.cpp516GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),517#endif518519#if AP_RSSI_ENABLED520// @Group: RSSI_521// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp522GOBJECT(rssi, "RSSI_", AP_RSSI),523#endif524525#if AP_RANGEFINDER_ENABLED526// @Group: RNGFND527// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp528GOBJECT(rangefinder, "RNGFND", RangeFinder),529#endif530531#if AP_TERRAIN_AVAILABLE532// @Group: TERRAIN_533// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp534GOBJECT(terrain, "TERRAIN_", AP_Terrain),535#endif536537#if AP_OPTICALFLOW_ENABLED538// @Group: FLOW539// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp540GOBJECT(optflow, "FLOW", AP_OpticalFlow),541#endif542543#if AC_PRECLAND_ENABLED544// @Group: PLND_545// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp546GOBJECT(precland, "PLND_", AC_PrecLand),547#endif548549#if HAL_ADSB_ENABLED550// @Group: ADSB_551// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp552GOBJECT(adsb, "ADSB_", AP_ADSB),553#endif // HAL_ADSB_ENABLED554555#if AP_ADSB_AVOIDANCE_ENABLED556// @Group: AVD_557// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp558GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Copter),559#endif // AP_ADSB_AVOIDANCE_ENABLED560561// @Group: NTF_562// @Path: ../libraries/AP_Notify/AP_Notify.cpp563GOBJECT(notify, "NTF_", AP_Notify),564565#if MODE_THROW_ENABLED566// @Param: THROW_MOT_START567// @DisplayName: Start motors before throwing is detected568// @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.569// @Values: 0:Stopped,1:Running570// @User: Standard571GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),572573// @Param: THROW_ALT_MIN574// @DisplayName: Throw mode minimum altitude575// @Description: Minimum altitude above which Throw mode will detect a throw or a drop - 0 to disable the check576// @Units: m577// @User: Advanced578GSCALAR(throw_altitude_min, "THROW_ALT_MIN", 0),579580// @Param: THROW_ALT_MAX581// @DisplayName: Throw mode maximum altitude582// @Description: Maximum altitude under which Throw mode will detect a throw or a drop - 0 to disable the check583// @Units: m584// @User: Advanced585GSCALAR(throw_altitude_max, "THROW_ALT_MAX", 0),586587// @Param: THROW_ALT_DCSND588// @DisplayName: Throw mode target altitude to descend589// @Description: Target altitude to descend during a drop, (must be positive). This allows for rapidly clearing surrounding obstacles.590// @Units: m591// @User: Advanced592GSCALAR(throw_altitude_descend, "THROW_ALT_DCSND", 1.0),593594// @Param: THROW_ALT_ACSND595// @DisplayName: Throw mode target altitude to ascsend596// @Description: Target altitude to ascend during a throw upwards (must be positive). This allows for rapidly clearing surrounding obstacles.597// @Units: m598// @User: Advanced599GSCALAR(throw_altitude_ascend, "THROW_ALT_ACSND", 3.0),600#endif601602#if OSD_ENABLED || OSD_PARAM_ENABLED603// @Group: OSD604// @Path: ../libraries/AP_OSD/AP_OSD.cpp605GOBJECT(osd, "OSD", AP_OSD),606#endif607608#if AC_CUSTOMCONTROL_MULTI_ENABLED609// @Group: CC610// @Path: ../libraries/AC_CustomControl/AC_CustomControl.cpp611GOBJECT(custom_control, "CC", AC_CustomControl),612#endif613614// @Group:615// @Path: Parameters.cpp616GOBJECT(g2, "", ParametersG2),617618// @Group:619// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp620PARAM_VEHICLE_INFO,621622#if HAL_GCS_ENABLED623// @Group: MAV624// @Path: ../libraries/GCS_MAVLink/GCS.cpp625GOBJECT(_gcs, "MAV", GCS),626#endif627628AP_VAREND629};630631/*6322nd group of parameters633*/634const AP_Param::GroupInfo ParametersG2::var_info[] = {635636// @Param: WP_NAVALT_MIN637// @DisplayName: Waypoint navigation altitude minimum638// @Description: Altitude in meters above which navigation will begin during auto takeoff639// @Units: m640// @Range: 0 5641// @User: Standard642AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min_m, 0),643644#if HAL_BUTTON_ENABLED645// @Group: BTN_646// @Path: ../libraries/AP_Button/AP_Button.cpp647AP_SUBGROUPPTR(button_ptr, "BTN_", 2, ParametersG2, AP_Button),648#endif649650#if MODE_THROW_ENABLED651// @Param: THROW_NEXTMODE652// @DisplayName: Throw mode's follow up mode653// @Description: Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)654// @Values: 3:Auto,4:Guided,5:LOITER,6:RTL,9:Land,17:Brake,18:Throw655// @User: Standard656AP_GROUPINFO("THROW_NEXTMODE", 3, ParametersG2, throw_nextmode, 18),657658// @Param: THROW_TYPE659// @DisplayName: Type of Type660// @Description: Used by Throw mode. Specifies whether Copter is thrown upward or dropped.661// @Values: 0:Upward Throw,1:Drop662// @User: Standard663AP_GROUPINFO("THROW_TYPE", 4, ParametersG2, throw_type, (float)ModeThrow::ThrowType::Upward),664#endif665666// @Param: GND_EFFECT_COMP667// @DisplayName: Ground Effect Compensation Enable/Disable668// @Description: Ground Effect Compensation Enable/Disable669// @Values: 0:Disabled,1:Enabled670// @User: Advanced671AP_GROUPINFO("GND_EFFECT_COMP", 5, ParametersG2, gndeffect_comp_enabled, 1),672673#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED674// @Group: AFS_675// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp676AP_SUBGROUPINFO(afs, "AFS_", 6, ParametersG2, AP_AdvancedFailsafe),677#endif678679// @Param: DEV_OPTIONS680// @DisplayName: Development options681// @Description: Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning682// @Bitmask: 0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt683// @User: Advanced684AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),685686#if AP_BEACON_ENABLED687// @Group: BCN688// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp689AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon),690#endif691692#if HAL_PROXIMITY_ENABLED693// @Group: PRX694// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp695AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity),696#endif697698// ACRO_Y_EXPO (9) moved to Command Model Class699700#if MODE_ACRO_ENABLED701// @Param: ACRO_THR_MID702// @DisplayName: Acro Thr Mid703// @Description: Acro Throttle Mid704// @Range: 0 1705// @User: Advanced706AP_GROUPINFO("ACRO_THR_MID", 10, ParametersG2, acro_thr_mid, ACRO_THR_MID_DEFAULT),707#endif708709// 11 was SYSID_ENFORCE710711// 12 was AP_Stats712713// 13 was AP_Gripper714715// @Param: FRAME_CLASS716// @DisplayName: Frame Class717// @Description: Controls major frame class for multicopter component718// @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 10:BiCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad, 14:Deca, 15:Scripting Matrix, 16:6DoF Scripting, 17:Dynamic Scripting Matrix719// @User: Standard720// @RebootRequired: True721AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, DEFAULT_FRAME_CLASS),722723// @Group: SERVO724// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp725AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),726727// @Group: RC728// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h729AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter),730731// 18 was used by AP_VisualOdom732733#if AP_TEMPCALIBRATION_ENABLED734// @Group: TCAL735// @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp736AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration),737#endif738739#if TOY_MODE_ENABLED740// @Group: TMODE741// @Path: toy_mode.cpp742AP_SUBGROUPINFO(toy_mode, "TMODE", 20, ParametersG2, ToyMode),743#endif744745#if MODE_SMARTRTL_ENABLED746// @Group: SRTL_747// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp748AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL),749#endif750751#if AP_WINCH_ENABLED752// 22 was AP_WheelEncoder753754// @Group: WINCH755// @Path: ../libraries/AP_Winch/AP_Winch.cpp756AP_SUBGROUPINFO(winch, "WINCH", 23, ParametersG2, AP_Winch),757#endif758759// @Param: PILOT_SPEED_DN760// @DisplayName: Pilot maximum vertical speed descending761// @Description: The maximum vertical descending velocity the pilot may request in cm/s. If 0 PILOT_SPEED_UP value is used.762// @Units: cm/s763// @Range: 0 500764// @Increment: 10765// @User: Standard766AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn_cms, 0),767768// 25 was LAND_ALT_LOW769770#if MODE_FLOWHOLD_ENABLED771// @Group: FHLD772// @Path: mode_flowhold.cpp773AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold),774#endif775776#if MODE_FOLLOW_ENABLED777// @Group: FOLL778// @Path: ../libraries/AP_Follow/AP_Follow.cpp779AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow),780#endif781782#if USER_PARAMS_ENABLED783AP_SUBGROUPINFO(user_parameters, "USR", 28, ParametersG2, UserParameters),784#endif785786#if AUTOTUNE_ENABLED787// @Group: AUTOTUNE_788// @Path: ../libraries/AC_AutoTune/AC_AutoTune_Multi.cpp,../libraries/AC_AutoTune/AC_AutoTune_Heli.cpp789AP_SUBGROUPPTR(autotune_ptr, "AUTOTUNE_", 29, ParametersG2, AutoTune),790#endif791792// 30 was AP_Scripting793794#if AP_RC_TRANSMITTER_TUNING_ENABLED795// @Param: TUNE_MIN796// @DisplayName: Tuning minimum797// @Description: Transmitter Tuning minum value. The parameter being tuned will have its value set to this minimum value when the tuning knob is at its lowest position798// @User: Standard799AP_GROUPINFO("TUNE_MIN", 31, ParametersG2, rc_tuning_min, 0),800801// @Param: TUNE_MAX802// @DisplayName: Tuning maximum803// @Description: Transmitter Tuning maximum value. The parameter being tuned will have its value set to this maximum value when the tuning knob is at its highest position804// @User: Standard805AP_GROUPINFO("TUNE_MAX", 32, ParametersG2, rc_tuning_max, 0),806#endif // AP_RC_TRANSMITTER_TUNING_ENABLED807808#if AP_OAPATHPLANNER_ENABLED809// @Group: OA_810// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp811AP_SUBGROUPINFO(oa, "OA_", 33, ParametersG2, AP_OAPathPlanner),812#endif813814#if MODE_SYSTEMID_ENABLED815// @Group: SID816// @Path: mode_systemid.cpp817AP_SUBGROUPPTR(mode_systemid_ptr, "SID", 34, ParametersG2, ModeSystemId),818#endif819820// @Param: FS_VIBE_ENABLE821// @DisplayName: Vibration Failsafe enable822// @Description: This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations823// @Values: 0:Disabled, 1:Enabled824// @User: Standard825AP_GROUPINFO("FS_VIBE_ENABLE", 35, ParametersG2, fs_vibe_enabled, 1),826827// @Param: FS_OPTIONS828// @DisplayName: Failsafe options bitmask829// @Description: Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.830// @Bitmask: 0:Continue if in Auto on RC failsafe, 1:Continue if in Auto on GCS failsafe, 2:Continue if in Guided on RC failsafe, 3:Continue if landing on any failsafe, 4:Continue if in pilot controlled modes on GCS failsafe, 5:Release Gripper831// @User: Advanced832AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Copter::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL),833834#if MODE_AUTOROTATE_ENABLED835// @Group: AROT_836// @Path: ../libraries/AC_Autorotation/AC_Autorotation.cpp837AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation),838#endif839840#if MODE_ZIGZAG_ENABLED841// @Group: ZIGZ_842// @Path: mode_zigzag.cpp843AP_SUBGROUPPTR(mode_zigzag_ptr, "ZIGZ_", 38, ParametersG2, ModeZigZag),844#endif845846#if MODE_ACRO_ENABLED847// @Param: ACRO_OPTIONS848// @DisplayName: Acro mode options849// @Description: A range of options that can be applied to change acro mode behaviour. Air-mode enables ATC_THR_MIX_MAN at all times (air-mode has no effect on helicopters). Rate Loop Only disables the use of angle stabilization and uses angular rate stabilization only.850// @Bitmask: 0:Air-mode,1:Rate Loop Only851// @User: Advanced852AP_GROUPINFO("ACRO_OPTIONS", 39, ParametersG2, acro_options, 0),853#endif854855#if MODE_AUTO_ENABLED856// @Param: AUTO_OPTIONS857// @DisplayName: Auto mode options858// @Description: A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle. Ignore pilot yaw overrides the pilot's yaw stick being used while in auto.859// @Bitmask: 0:Allow Arming,1:Allow Takeoff Without Raising Throttle,2:Ignore pilot yaw,7:Allow weathervaning860// @User: Advanced861AP_GROUPINFO("AUTO_OPTIONS", 40, ParametersG2, auto_options, 0),862#endif863864#if MODE_GUIDED_ENABLED865// @Param: GUID_OPTIONS866// @DisplayName: Guided mode options867// @Description: Options that can be applied to change guided mode behaviour868// @Bitmask: 0:Allow Arming from Transmitter,2:Ignore pilot yaw,3:SetAttitudeTarget interprets Thrust As Thrust,4:Do not stabilize PositionXY,5:Do not stabilize VelocityXY,6:Waypoint navigation used for position targets,7:Allow weathervaning869// @User: Advanced870AP_GROUPINFO("GUID_OPTIONS", 41, ParametersG2, guided_options, 0),871#endif872873// @Param: FS_GCS_TIMEOUT874// @DisplayName: GCS failsafe timeout875// @Description: Timeout before triggering the GCS failsafe876// @Units: s877// @Range: 2 120878// @Increment: 1879// @User: Standard880AP_GROUPINFO("FS_GCS_TIMEOUT", 42, ParametersG2, fs_gcs_timeout, 5),881882#if MODE_RTL_ENABLED883// @Param: RTL_OPTIONS884// @DisplayName: RTL mode options885// @Description: Options that can be applied to change RTL mode behaviour886// @Bitmask: 2:Ignore pilot yaw887// @User: Advanced888AP_GROUPINFO("RTL_OPTIONS", 43, ParametersG2, rtl_options, 0),889#endif890891// @Param: FLIGHT_OPTIONS892// @DisplayName: Flight mode options893// @Description: Flight mode specific options894// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss895// @User: Advanced896AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),897898#if AP_RANGEFINDER_ENABLED899// @Param: RNGFND_FILT900// @DisplayName: Rangefinder filter901// @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering902// @Units: Hz903// @Range: 0 5904// @Increment: 0.05905// @User: Standard906// @RebootRequired: True907AP_GROUPINFO("RNGFND_FILT", 45, ParametersG2, rangefinder_filt, RANGEFINDER_FILT_DEFAULT),908#endif909910#if MODE_GUIDED_ENABLED911// @Param: GUID_TIMEOUT912// @DisplayName: Guided mode timeout913// @Description: Guided mode timeout after which vehicle will stop or return to level if no updates are received from caller. Only applicable during any combination of velocity, acceleration, angle control, and/or angular rate control914// @Units: s915// @Range: 0.1 5916// @User: Advanced917AP_GROUPINFO("GUID_TIMEOUT", 46, ParametersG2, guided_timeout, 3.0),918#endif919920// ACRO_PR_RATE (47), ACRO_Y_RATE (48), PILOT_Y_RATE (49) and PILOT_Y_EXPO (50) moved to command model class921922#if AP_RANGEFINDER_ENABLED923// @Param: SURFTRAK_MODE924// @DisplayName: Surface Tracking Mode925// @Description: set which surface to track in surface tracking926// @Values: 0:Do not track, 1:Ground, 2:Ceiling927// @User: Advanced928// @RebootRequired: True929AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND),930#endif931932// @Param: FS_DR_ENABLE933// @DisplayName: DeadReckon Failsafe Action934// @Description: Failsafe action taken immediately as deadreckoning starts. Deadreckoning starts when EKF loses position and velocity source and relies only on wind estimates935// @Values: 0:Disabled/NoAction,1:Land, 2:RTL, 3:SmartRTL or RTL, 4:SmartRTL or Land, 6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL936// @User: Standard937AP_GROUPINFO("FS_DR_ENABLE", 52, ParametersG2, failsafe_dr_enable, (uint8_t)Copter::FailsafeAction::RTL),938939// @Param: FS_DR_TIMEOUT940// @DisplayName: DeadReckon Failsafe Timeout941// @Description: DeadReckoning is available for this many seconds after losing position and/or velocity source. After this timeout elapses the EKF failsafe will trigger in modes requiring a position estimate942// @Range: 0 120943// @User: Standard944AP_GROUPINFO("FS_DR_TIMEOUT", 53, ParametersG2, failsafe_dr_timeout, 30),945946#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED947// @Param: ACRO_RP_RATE948// @DisplayName: Acro Roll and Pitch Rate949// @Description: Acro mode maximum roll and pitch rate. Higher values mean faster rate of rotation950// @Units: deg/s951// @Range: 1 1080952// @User: Standard953954// @Param: ACRO_RP_EXPO955// @DisplayName: Acro Roll/Pitch Expo956// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges957// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High958// @Range: -0.5 0.95959// @User: Advanced960961// @Param: ACRO_RP_RATE_TC962// @DisplayName: Acro roll/pitch rate control input time constant963// @Description: Acro roll and pitch rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response964// @Units: s965// @Range: 0 1966// @Increment: 0.01967// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp968// @User: Standard969AP_SUBGROUPINFO(command_model_acro_rp, "ACRO_RP_", 54, ParametersG2, AC_CommandModel),970#endif971972#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED973// @Param: ACRO_Y_RATE974// @DisplayName: Acro Yaw Rate975// @Description: Acro mode maximum yaw rate. Higher value means faster rate of rotation976// @Units: deg/s977// @Range: 1 360978// @User: Standard979980// @Param: ACRO_Y_EXPO981// @DisplayName: Acro Yaw Expo982// @Description: Acro yaw expo to allow faster rotation when stick at edges983// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High984// @Range: -1.0 0.95985// @User: Advanced986987// @Param: ACRO_Y_RATE_TC988// @DisplayName: Acro yaw rate control input time constant989// @Description: Acro yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response990// @Units: s991// @Range: 0 1992// @Increment: 0.01993// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp994// @User: Standard995AP_SUBGROUPINFO(command_model_acro_y, "ACRO_Y_", 55, ParametersG2, AC_CommandModel),996#endif997998// @Param: PILOT_Y_RATE999// @DisplayName: Pilot controlled yaw rate1000// @Description: Pilot controlled yaw rate max. Used in all pilot controlled modes except Acro1001// @Units: deg/s1002// @Range: 1 3601003// @User: Standard10041005// @Param: PILOT_Y_EXPO1006// @DisplayName: Pilot controlled yaw expo1007// @Description: Pilot controlled yaw expo to allow faster rotation when stick at edges1008// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High1009// @Range: -0.5 1.01010// @User: Advanced10111012// @Param: PILOT_Y_RATE_TC1013// @DisplayName: Pilot yaw rate control input time constant1014// @Description: Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response1015// @Units: s1016// @Range: 0 11017// @Increment: 0.011018// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp1019// @User: Standard1020AP_SUBGROUPINFO(command_model_pilot_y, "PILOT_Y_", 56, ParametersG2, AC_CommandModel),10211022// @Param: TKOFF_SLEW_TIME1023// @DisplayName: Slew time of throttle during take-off1024// @Description: Time to slew the throttle from minimum to maximum while checking for a successful takeoff.1025// @Units: s1026// @Range: 0.25 5.01027// @User: Standard1028AP_GROUPINFO("TKOFF_SLEW_TIME", 57, ParametersG2, takeoff_throttle_slew_time, 2.0),10291030#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME1031// @Param: TKOFF_RPM_MIN1032// @DisplayName: Takeoff Check RPM minimum1033// @Description: Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check1034// @Range: 0 100001035// @User: Standard1036AP_GROUPINFO("TKOFF_RPM_MIN", 58, ParametersG2, takeoff_rpm_min, 0),1037#endif10381039#if WEATHERVANE_ENABLED1040// @Group: WVANE_1041// @Path: ../libraries/AC_AttitudeControl/AC_WeatherVane.cpp1042AP_SUBGROUPINFO(weathervane, "WVANE_", 59, ParametersG2, AC_WeatherVane),1043#endif10441045// ID 60 is reserved for the SHIP_OPS10461047// extend to a new group1048AP_SUBGROUPEXTENSION("", 61, ParametersG2, var_info2),10491050// ID 62 is reserved for the SHOW_... parameters from the Skybrush fork at1051// https://github.com/skybrush-io/ardupilot10521053AP_GROUPEND1054};10551056/*1057extension to g2 parameters1058*/1059const AP_Param::GroupInfo ParametersG2::var_info2[] = {10601061#if AC_PAYLOAD_PLACE_ENABLED1062// @Param: PLDP_THRESH1063// @DisplayName: Payload Place thrust ratio threshold1064// @Description: Ratio of vertical thrust during decent below which payload touchdown will trigger.1065// @Range: 0.5 0.91066// @User: Standard1067AP_GROUPINFO("PLDP_THRESH", 1, ParametersG2, pldp_thrust_placed_fraction, 0.9),10681069// @Param: PLDP_RNG_MAX1070// @DisplayName: Payload Place maximum range finder altitude1071// @Description: Maximum range finder altitude in m to trigger payload touchdown, set to zero to disable.1072// @Units: m1073// @Range: 0 1001074// @User: Standard1075AP_GROUPINFO("PLDP_RNG_MAX", 2, ParametersG2, pldp_range_finder_maximum_m, 0.0),10761077// @Param: PLDP_DELAY1078// @DisplayName: Payload Place climb delay1079// @Description: Delay after release, in seconds, before aircraft starts to climb back to starting altitude.1080// @Units: s1081// @Range: 0 1201082// @User: Standard1083AP_GROUPINFO("PLDP_DELAY", 3, ParametersG2, pldp_delay_s, 0.0),10841085// @Param: PLDP_SPEED_DN1086// @DisplayName: Payload Place decent speed1087// @Description: The maximum vertical decent velocity in m/s. If 0 LAND_SPD_MS value is used.1088// @Units: m/s1089// @Range: 0 51090// @User: Standard1091AP_GROUPINFO("PLDP_SPEED_DN", 4, ParametersG2, pldp_descent_speed_ms, 0.0),1092#endif // AC_PAYLOAD_PLACE_ENABLED10931094// @Param: SURFTRAK_TC1095// @DisplayName: Surface Tracking Filter Time Constant1096// @Description: Time to achieve 63.2% of the surface altitude measurement change. If 0 filtering is disabled1097// @Units: s1098// @Range: 0 51099// @User: Advanced1100AP_GROUPINFO("SURFTRAK_TC", 5, ParametersG2, surftrak_tc, 1.0),11011102// @Param: TKOFF_THR_MAX1103// @DisplayName: Takeoff maximum throttle during take-off ramp up1104// @Description: Takeoff maximum throttle allowed before controllers assume the aircraft is airborne during the takeoff process.1105// @Range: 0.0 0.91106// @User: Advanced1107AP_GROUPINFO("TKOFF_THR_MAX", 6, ParametersG2, takeoff_throttle_max, 0.9),11081109#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME1110// @Param: TKOFF_RPM_MAX1111// @DisplayName: Takeoff Check RPM maximum1112// @Description: Takeoff is not permitted until motors report no more than this RPM. Set to zero to disable check1113// @Range: 0 100001114// @User: Standard1115AP_GROUPINFO("TKOFF_RPM_MAX", 7, ParametersG2, takeoff_rpm_max, 0),1116#endif11171118// @Param: FS_EKF_FILT1119// @DisplayName: EKF Failsafe filter cutoff1120// @Description: EKF Failsafe filter cutoff frequency. EKF variances are filtered using this value to avoid spurious failsafes from transient high variances. A higher value means the failsafe is more likely to trigger.1121// @Range: 0 101122// @Units: Hz1123// @User: Advanced1124AP_GROUPINFO("FS_EKF_FILT", 8, ParametersG2, fs_ekf_filt_hz, FS_EKF_FILT_DEFAULT),11251126#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED1127// @Param: FSTRATE_ENABLE1128// @DisplayName: Enable the fast Rate thread1129// @Description: Enable the fast Rate thread. In the default case the fast rate divisor, which controls the update frequency of the thread, is dynamically scaled from FSTRATE_DIV to avoid overrun in the gyro sample buffer and main loop slow-downs. Other values can be selected to fix the divisor to FSTRATE_DIV on arming or always.1130// @User: Advanced1131// @Values: 0:Disabled,1:Enabled-Dynamic,2:Enabled-FixedWhenArmed,3:Enabled-Fixed1132AP_GROUPINFO("FSTRATE_ENABLE", 9, ParametersG2, att_enable, 0),11331134// @Param: FSTRATE_DIV1135// @DisplayName: Fast rate thread divisor1136// @Description: Fast rate thread divisor used to control the maximum fast rate update rate. The actual rate is the gyro rate in Hz divided by this value. This value is scaled depending on the configuration of FSTRATE_ENABLE.1137// @User: Advanced1138// @Range: 1 101139AP_GROUPINFO("FSTRATE_DIV", 10, ParametersG2, att_decimation, 1),1140#endif11411142#if AP_RC_TRANSMITTER_TUNING_ENABLED1143// @Param: TUNE2_MIN1144// @DisplayName: Tuning minimum1145// @Description: Minimum value that the parameter currently being tuned with the transmitter's TRANSMITTER_TUNING2 knob will be set to1146// @User: Standard1147AP_GROUPINFO("TUNE2_MIN", 11, ParametersG2, rc_tuning2_min, 0),11481149// @Param: TUNE2_MAX1150// @DisplayName: Tuning maximum1151// @Description: Maximum value that the parameter currently being tuned with the transmitter's TRANSMITTER2_TUNING knob will be set to1152// @User: Standard1153AP_GROUPINFO("TUNE2_MAX", 12, ParametersG2, rc_tuning2_max, 0),11541155// @Param: TUNE21156// @CopyFieldsFrom: TUNE1157// @DisplayName: Tuning Parameter for TRANSMITTER_TUNE21158// @Description: Selects parameter (normally a PID gain) that is being tuned with an RC transmitter's knob. The RC input channel used is assigned by setting RCx_OPTION to 220.1159AP_GROUPINFO("TUNE2", 13, ParametersG2, rc_tuning2_param, 0),1160#endif // AP_RC_TRANSMITTER_TUNING_ENABLED11611162#if MODE_RTL_ENABLED1163// @Group: RTL_1164// @Path: mode_rtl.cpp1165AP_SUBGROUPPTR(mode_rtl_ptr, "RTL_", 14, ParametersG2, ModeRTL),1166#endif11671168// @Group: LAND_1169// @Path: mode_land.cpp1170AP_SUBGROUPPTR(mode_land_ptr, "LAND_", 15, ParametersG2, ModeLand),11711172// ID 62 is reserved for the AP_SUBGROUPEXTENSION11731174AP_GROUPEND1175};11761177/*1178constructor for g2 object1179*/1180ParametersG2::ParametersG2(void) :1181unused_integer{17}1182#if HAL_BUTTON_ENABLED1183,button_ptr(&copter.button)1184#endif1185#if AP_TEMPCALIBRATION_ENABLED1186, temp_calibration()1187#endif1188#if AP_BEACON_ENABLED1189, beacon()1190#endif1191#if HAL_PROXIMITY_ENABLED1192, proximity()1193#endif1194#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED1195,afs()1196#endif1197#if MODE_SMARTRTL_ENABLED1198,smart_rtl()1199#endif1200#if USER_PARAMS_ENABLED1201,user_parameters()1202#endif1203#if MODE_FLOWHOLD_ENABLED1204,mode_flowhold_ptr(&copter.mode_flowhold)1205#endif1206#if MODE_FOLLOW_ENABLED1207,follow()1208#endif1209#if AUTOTUNE_ENABLED1210,autotune_ptr(&copter.mode_autotune.autotune)1211#endif1212#if MODE_SYSTEMID_ENABLED1213,mode_systemid_ptr(&copter.mode_systemid)1214#endif1215#if MODE_AUTOROTATE_ENABLED1216,arot(copter.motors, copter.attitude_control)1217#endif1218#if MODE_ZIGZAG_ENABLED1219,mode_zigzag_ptr(&copter.mode_zigzag)1220#endif1221#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED1222,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f)1223#endif12241225#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED1226,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f)1227#endif12281229,command_model_pilot_y(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)12301231#if WEATHERVANE_ENABLED1232,weathervane()1233#endif1234#if MODE_RTL_ENABLED1235,mode_rtl_ptr(&copter.mode_rtl)1236#endif1237,mode_land_ptr(&copter.mode_land)1238{1239AP_Param::setup_object_defaults(this, var_info);1240AP_Param::setup_object_defaults(this, var_info2);1241}12421243void Copter::load_parameters(void)1244{1245AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);12461247// PARAMETER_CONVERSION - Added: Mar-20221248#if AP_FENCE_ENABLED1249AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true);1250#endif12511252// PARAMETER_CONVERSION - Added: July-2025 for ArduPilot-4.71253#if AP_RPM_ENABLED1254AP_Param::convert_class(g.k_param_rpm_sensor_old, &rpm_sensor, rpm_sensor.var_info, 0, true, true);1255#endif12561257static const AP_Param::G2ObjectConversion g2_conversions[] {1258#if AP_STATS_ENABLED1259// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.61260{ &stats, stats.var_info, 12 },1261#endif1262#if AP_SCRIPTING_ENABLED1263// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.61264{ &scripting, scripting.var_info, 30 },1265#endif1266#if AP_GRIPPER_ENABLED1267// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.61268{ &gripper, gripper.var_info, 13 },1269#endif1270};12711272AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));12731274// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.61275#if HAL_LOGGING_ENABLED1276AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);1277#endif12781279static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {1280#if AP_SERIALMANAGER_ENABLED1281// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.61282{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },1283#endif1284};12851286AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));12871288#if HAL_GCS_ENABLED1289// Move parameters into new MAV_ parameter namespace1290// PARAMETER_CONVERSION - Added: Mar-2025 for ArduPilot-4.71291{1292const AP_Param::ConversionInfo gcs_conversion_info[] {1293{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },1294{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },1295{ Parameters::k_param_g2, 11, AP_PARAM_INT8, "MAV_OPTIONS" },1296{ Parameters::k_param_telem_delay_old, 0, AP_PARAM_INT8, "MAV_TELEM_DELAY" },1297};1298AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));1299}1300#endif // HAL_GCS_ENABLED13011302#if MODE_RTL_ENABLED1303// convert RTL parameters1304copter.mode_rtl.convert_params();1305#endif13061307// convert LAND parameters1308copter.mode_land.convert_params();13091310// setup AP_Param frame type flags1311AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);1312}13131314// handle conversion of PID gains1315void Copter::convert_pid_parameters(void)1316{1317const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {1318// PARAMETER_CONVERSION - Added: Aug-20211319{ Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_NE_VEL_FLTE" },1320};13211322// convert angle controller gain and filter without scaling1323for (const auto &info : angle_and_filt_conversion_info) {1324AP_Param::convert_old_parameter(&info, 1.0f);1325}13261327// TradHeli default parameters1328#if FRAME_CONFIG == HELI_FRAME1329static const struct AP_Param::defaults_table_struct heli_defaults_table[] = {1330{ "LOIT_ACC_MAX_M", 5.0f },1331{ "LOIT_BRK_ACC_M", 1.25f },1332{ "LOIT_BRK_DELAY", 1.0f },1333{ "LOIT_BRK_JRK_M", 2.5f },1334{ "LOIT_SPEED_MS", 30.0f },1335{ "PHLD_BRAKE_ANGLE", 800.0f },1336{ "PHLD_BRAKE_RATE", 4.0f },1337{ "PSC_D_ACC_P", 0.028f },1338{ "PSC_NE_VEL_D", 0.0f },1339{ "PSC_NE_VEL_I", 0.5f },1340{ "PSC_NE_VEL_P", 1.0f },1341{ "RC8_OPTION", 32 },1342{ "RC_OPTIONS", 0 },1343{ "ATC_RAT_RLL_ILMI", 0.05},1344{ "ATC_RAT_PIT_ILMI", 0.05},1345};1346AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table));1347#endif // FRAME_CONFIG == HELI_FRAME13481349#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED1350#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 11351if (!ins.harmonic_notches[1].params.enabled()) {1352// notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch1353const AP_Param::ConversionInfo notchfilt_conversion_info[] {1354// PARAMETER_CONVERSION - Added: Apr 20221355{ Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" },1356{ Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" },1357{ Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" },1358{ Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" },1359};1360AP_Param::convert_old_parameters(¬chfilt_conversion_info[0], ARRAY_SIZE(notchfilt_conversion_info));1361AP_Param::set_default_by_name("INS_HNTC2_MODE", 0);1362AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);1363}1364#endif1365#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED13661367// ACRO_RP_P and ACRO_Y_P replaced with ACRO_RP_RATE and ACRO_Y_RATE for Copter-4.21368// PARAMETER_CONVERSION - Added: Sep-20211369const AP_Param::ConversionInfo acro_rpy_conversion_info[] = {1370{ Parameters::k_param_acro_rp_p, 0, AP_PARAM_FLOAT, "ACRO_RP_RATE" },1371{ Parameters::k_param_acro_yaw_p, 0, AP_PARAM_FLOAT, "ACRO_Y_RATE" }1372};1373for (const auto &info : acro_rpy_conversion_info) {1374AP_Param::convert_old_parameter(&info, 45.0);1375}13761377// convert rate and expo command model parameters for Copter-4.31378// PARAMETER_CONVERSION - Added: June-20221379const AP_Param::ConversionInfo cmd_mdl_conversion_info[] = {1380{ Parameters::k_param_g2, 47, AP_PARAM_FLOAT, "ACRO_RP_RATE" },1381{ Parameters::k_param_acro_rp_expo, 0, AP_PARAM_FLOAT, "ACRO_RP_EXPO" },1382{ Parameters::k_param_g2, 48, AP_PARAM_FLOAT, "ACRO_Y_RATE" },1383{ Parameters::k_param_g2, 9, AP_PARAM_FLOAT, "ACRO_Y_EXPO" },1384{ Parameters::k_param_g2, 49, AP_PARAM_FLOAT, "PILOT_Y_RATE" },1385{ Parameters::k_param_g2, 50, AP_PARAM_FLOAT, "PILOT_Y_EXPO" },1386};1387for (const auto &info : cmd_mdl_conversion_info) {1388AP_Param::convert_old_parameter(&info, 1.0);1389}13901391// make any SRV_Channel upgrades needed1392SRV_Channels::upgrade_parameters();1393}13941395#if HAL_PROXIMITY_ENABLED1396void Copter::convert_prx_parameters()1397{1398// convert PRX to PRX1_ parameters for Copter-4.31399// PARAMETER_CONVERSION - Added: Aug-20221400static const AP_Param::ConversionInfo prx_conversion_info[] = {1401{ Parameters::k_param_g2, 72, AP_PARAM_INT8, "PRX1_TYPE" },1402{ Parameters::k_param_g2, 136, AP_PARAM_INT8, "PRX1_ORIENT" },1403{ Parameters::k_param_g2, 200, AP_PARAM_INT16, "PRX1_YAW_CORR" },1404{ Parameters::k_param_g2, 264, AP_PARAM_INT16, "PRX1_IGN_ANG1" },1405{ Parameters::k_param_g2, 328, AP_PARAM_INT8, "PRX1_IGN_WID1" },1406{ Parameters::k_param_g2, 392, AP_PARAM_INT16, "PRX1_IGN_ANG2" },1407{ Parameters::k_param_g2, 456, AP_PARAM_INT8, "PRX1_IGN_WID2" },1408{ Parameters::k_param_g2, 520, AP_PARAM_INT16, "PRX1_IGN_ANG3" },1409{ Parameters::k_param_g2, 584, AP_PARAM_INT8, "PRX1_IGN_WID3" },1410{ Parameters::k_param_g2, 648, AP_PARAM_INT16, "PRX1_IGN_ANG4" },1411{ Parameters::k_param_g2, 712, AP_PARAM_INT8, "PRX1_IGN_WID4" },1412{ Parameters::k_param_g2, 1224, AP_PARAM_FLOAT, "PRX1_MIN" },1413{ Parameters::k_param_g2, 1288, AP_PARAM_FLOAT, "PRX1_MAX" },1414};1415for (const auto &info : prx_conversion_info) {1416AP_Param::convert_old_parameter(&info, 1.0);1417}1418}1419#endif142014211422