#include "Sub.h"12#include <AP_Gripper/AP_Gripper.h>34/*5This program is free software: you can redistribute it and/or modify6it under the terms of the GNU General Public License as published by7the Free Software Foundation, either version 3 of the License, or8(at your option) any later version.910This program is distributed in the hope that it will be useful,11but WITHOUT ANY WARRANTY; without even the implied warranty of12MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the13GNU General Public License for more details.1415You should have received a copy of the GNU General Public License16along with this program. If not, see <http://www.gnu.org/licenses/>.17*/1819/*20* ArduSub parameter definitions21*22*/2324const AP_Param::Info Sub::var_info[] = {2526// @Param: SURFACE_DEPTH27// @DisplayName: Depth reading at surface28// @Description: The depth the external pressure sensor will read when the vehicle is considered at the surface (in centimeters)29// @Units: cm30// @Range: -100 031// @User: Standard32GSCALAR(surface_depth, "SURFACE_DEPTH", SURFACE_DEPTH_DEFAULT),3334// @Param: FORMAT_VERSION35// @DisplayName: Eeprom format version number36// @Description: This value is incremented when changes are made to the eeprom format37// @User: Advanced38GSCALAR(format_version, "FORMAT_VERSION", 0),3940// SYSID_THISMAV was here4142// SYSID_MYGCS was here4344// @Param: PILOT_THR_FILT45// @DisplayName: Throttle filter cutoff46// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable47// @User: Advanced48// @Units: Hz49// @Range: 0 1050// @Increment: 0.551GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),5253// AP_SerialManager was here5455// @Param: GCS_PID_MASK56// @DisplayName: GCS PID tuning mask57// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for58// @User: Advanced59// @Bitmask: 0:Roll,1:Pitch,2:Yaw60GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),6162// @Param: FS_GCS_ENABLE63// @DisplayName: Ground Station Failsafe Enable64// @Description: Controls what action to take when GCS heartbeat is lost.65// @Values: 0:Disabled,1:Warn only,2:Disarm,3:Enter depth hold mode,4:Enter surface mode66// @User: Standard67GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISARM),6869// @Param: FS_GCS_TIMEOUT70// @DisplayName: GCS failsafe timeout71// @Description: Timeout before triggering the GCS failsafe72// @Units: s73// @Increment: 174// @User: Standard75GSCALAR(failsafe_gcs_timeout, "FS_GCS_TIMEOUT", FS_GCS_TIMEOUT_S),7677// @Param: FS_LEAK_ENABLE78// @DisplayName: Leak Failsafe Enable79// @Description: Controls what action to take if a leak is detected.80// @Values: 0:Disabled,1:Warn only,2:Enter surface mode81// @User: Standard82GSCALAR(failsafe_leak, "FS_LEAK_ENABLE", FS_LEAK_WARN_ONLY),8384// @Param: FS_PRESS_ENABLE85// @DisplayName: Internal Pressure Failsafe Enable86// @Description: Controls what action to take if internal pressure exceeds FS_PRESS_MAX parameter.87// @Values: 0:Disabled,1:Warn only88// @User: Standard89GSCALAR(failsafe_pressure, "FS_PRESS_ENABLE", FS_PRESS_DISABLED),9091// @Param: FS_TEMP_ENABLE92// @DisplayName: Internal Temperature Failsafe Enable93// @Description: Controls what action to take if internal temperature exceeds FS_TEMP_MAX parameter.94// @Values: 0:Disabled,1:Warn only95// @User: Standard96GSCALAR(failsafe_temperature, "FS_TEMP_ENABLE", FS_TEMP_DISABLED),9798#if AP_SUB_RC_ENABLED99// @Param: FS_THR_ENABLE100// @DisplayName: Throttle Failsafe Enable101// @Description: The throttle failsafe allows you to configure a software RC failsafe activated by a setting on the throttle input channel. It also enables RC failsafe on absence of RC signals being recieved.102// @Values: 0:Disabled,1: Force effective control inputs to trim positions and prevent arming,2:Surface and hold on surface on failsafe103// @User: Standard104GSCALAR(failsafe_throttle, "FS_THR_ENABLE", 0),105106// @Param: FS_THR_VALUE107// @DisplayName: Throttle Failsafe Value108// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers109// @Range: 910 1100110// @Units: PWM111// @Increment: 1112// @User: Standard113GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),114115// @Param: FLTMODE1116// @DisplayName: Flight Mode 1117// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230118// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,7:Circle,9:Surface,16:PosHold,19:Manual,20:Motor Detect,21:SurfTrak119// @User: Standard120GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),121122// @Param: FLTMODE2123// @CopyFieldsFrom: FLTMODE1124// @DisplayName: Flight Mode 2125// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360126GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),127128// @Param: FLTMODE3129// @CopyFieldsFrom: FLTMODE1130// @DisplayName: Flight Mode 3131// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490132GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),133134// @Param: FLTMODE4135// @CopyFieldsFrom: FLTMODE1136// @DisplayName: Flight Mode 4137// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620138GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),139140// @Param: FLTMODE5141// @CopyFieldsFrom: FLTMODE1142// @DisplayName: Flight Mode 5143// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749144GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),145146// @Param: FLTMODE6147// @CopyFieldsFrom: FLTMODE1148// @DisplayName: Flight Mode 6149// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750150GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),151152// @Param: FLTMODE_CH153// @DisplayName: Flightmode channel154// @Description: RC Channel to use for flight mode control155// @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 15156// @User: Advanced157GSCALAR(flight_mode_chan, "FLTMODE_CH", 0),158159// @Param: THR_ARM_POS160// @DisplayName: Throttle arming position161// @Description: Determines if throttle must be at min or within trim value to arm, if RC checks and RC_OPTION for "0" throttle are enabled.162// @User: Standard163// @Bitmask: 0:Throttle at or below min, 1: Throttle within a dead zone of RC trim value164GSCALAR(thr_arming_position, "THR_ARM_POS", 1),165#endif166// @Param: FS_PRESS_MAX167// @DisplayName: Internal Pressure Failsafe Threshold168// @Description: The maximum internal pressure allowed before triggering failsafe. Failsafe action is determined by FS_PRESS_ENABLE parameter169// @Units: Pa170// @User: Standard171GSCALAR(failsafe_pressure_max, "FS_PRESS_MAX", FS_PRESS_MAX_DEFAULT),172173// @Param: FS_TEMP_MAX174// @DisplayName: Internal Temperature Failsafe Threshold175// @Description: The maximum internal temperature allowed before triggering failsafe. Failsafe action is determined by FS_TEMP_ENABLE parameter.176// @Units: degC177// @User: Standard178GSCALAR(failsafe_temperature_max, "FS_TEMP_MAX", FS_TEMP_MAX_DEFAULT),179180// @Param: SURFACE_MAX_THR181// @DisplayName: Surface Maximum Throttle182// @Description: Maximum throttle value when the vehicle is at the surface. This value is used to scale throttle linearly from 1. (full) to min as the vehicle approaches the surface. The attenuation starts at 1 meter from surface. Only upwards throttle is limited.183// @Range: 0.0 1.0184// @User: Standard185// @Increment: 0.01186GSCALAR(surface_max_throttle, "SURFACE_MAX_THR", 0.1f),187188// @Param: FS_TERRAIN_ENAB189// @DisplayName: Terrain Failsafe Enable190// @Description: Controls what action to take if terrain information is lost during AUTO mode191// @Values: 0:Disarm, 1:Hold Position, 2:Surface192// @User: Standard193GSCALAR(failsafe_terrain, "FS_TERRAIN_ENAB", FS_TERRAIN_DISARM),194195// @Param: FS_PILOT_INPUT196// @DisplayName: Pilot input failsafe action197// @Description: Controls what action to take if no pilot input has been received after the timeout period specified by the FS_PILOT_TIMEOUT parameter198// @Values: 0:Disabled, 1:Warn Only, 2:Disarm199// @User: Standard200GSCALAR(failsafe_pilot_input, "FS_PILOT_INPUT", FS_PILOT_INPUT_DISARM),201202// @Param: FS_PILOT_TIMEOUT203// @DisplayName: Timeout for activation of pilot input failsafe204// @Description: Controls the maximum interval between received pilot inputs before the failsafe action is triggered205// @Units: s206// @Range: 0.1 3.0207// @User: Standard208GSCALAR(failsafe_pilot_input_timeout, "FS_PILOT_TIMEOUT", 3.0f),209210// @Param: XTRACK_ANG_LIM211// @DisplayName: Crosstrack correction angle limit212// @Description: Maximum allowed angle (in degrees) between current track and desired heading during waypoint navigation213// @Range: 10 90214// @User: Standard215GSCALAR(xtrack_angle_limit,"XTRACK_ANG_LIM", 45),216217// @Param: WP_YAW_BEHAVIOR218// @DisplayName: Yaw behaviour during missions219// @Description: Determines how the autopilot controls the yaw during missions and RTL220// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course, 4:Correct crosstrack error221// @User: Standard222GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),223224// @Param: PILOT_SPEED_UP225// @DisplayName: Pilot maximum vertical ascending speed226// @Description: The maximum vertical ascending velocity the pilot may request in cm/s227// @Units: cm/s228// @Range: 20 500229// @Increment: 10230// @User: Standard231GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX),232233// @Param: PILOT_SPEED_DN234// @DisplayName: Pilot maximum vertical descending speed235// @Description: The maximum vertical descending velocity the pilot may request in cm/s236// @Units: cm/s237// @Range: 20 500238// @Increment: 10239// @User: Standard240GSCALAR(pilot_speed_dn, "PILOT_SPEED_DN", 0),241242// @Param: PILOT_SPEED243// @DisplayName: Pilot maximum horizontal speed244// @Description: The maximum horizontal velocity the pilot may request in cm/s245// @Units: cm/s246// @Range: 10 500247// @Increment: 10248// @User: Standard249GSCALAR(pilot_speed, "PILOT_SPEED", PILOT_SPEED_DEFAULT),250251// @Param: PILOT_ACCEL_Z252// @DisplayName: Pilot vertical acceleration253// @Description: The vertical acceleration used when pilot is controlling the altitude254// @Units: cm/s/s255// @Range: 50 500256// @Increment: 10257// @User: Standard258GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),259260// @Param: THR_DZ261// @DisplayName: Throttle deadzone262// @Description: The PWM deadzone in microseconds above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes263// @User: Standard264// @Range: 0 300265// @Units: PWM266// @Increment: 1267GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),268269// @Param: LOG_BITMASK270// @DisplayName: Log bitmask271// @Description: 4 byte bitmap of log types to enable272// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW273// @User: Standard274GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),275276// @Param: FS_EKF_ACTION277// @DisplayName: EKF Failsafe Action278// @Description: Controls the action that will be taken when an EKF failsafe is invoked279// @Values: 0:Disabled, 1:Warn only, 2:Disarm280// @User: Advanced281GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),282283// @Param: FS_EKF_THRESH284// @DisplayName: EKF failsafe variance threshold285// @Description: Allows setting the maximum acceptable compass and velocity variance286// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed287// @Range: 0.6 1.0288// @User: Advanced289GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),290291// @Param: FS_CRASH_CHECK292// @DisplayName: Crash check enable293// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.294// @Values: 0:Disabled,1:Warn only,2:Disarm295// @User: Advanced296GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLED),297298// @Param: JS_GAIN_DEFAULT299// @DisplayName: Default gain at boot300// @Description: Default gain at boot, must be in range [JS_GAIN_MIN , JS_GAIN_MAX]. Current gain value is accessible via NAMED_VALUE_FLOAT MAVLink message with name 'PilotGain'.301// @User: Standard302// @Range: 0.1 1.0303GSCALAR(gain_default, "JS_GAIN_DEFAULT", 0.5),304305// @Param: JS_GAIN_MAX306// @DisplayName: Maximum joystick gain307// @Description: Maximum joystick gain308// @User: Standard309// @Range: 0.2 1.0310GSCALAR(maxGain, "JS_GAIN_MAX", 1.0),311312// @Param: JS_GAIN_MIN313// @DisplayName: Minimum joystick gain314// @Description: Minimum joystick gain315// @User: Standard316// @Range: 0.1 0.8317GSCALAR(minGain, "JS_GAIN_MIN", 0.25),318319// @Param: JS_GAIN_STEPS320// @DisplayName: Gain steps321// @Description: Controls the number of steps between minimum and maximum joystick gain when the gain is adjusted using buttons. Set to 1 to always use JS_GAIN_DEFAULT.322// @User: Standard323// @Range: 1 10324GSCALAR(numGainSettings, "JS_GAIN_STEPS", 4),325326// @Param: JS_LIGHTS_STEPS327// @DisplayName: Lights brightness steps328// @Description: Number of steps in brightness between minimum and maximum brightness329// @User: Standard330// @Range: 1 10331// @Units: PWM332GSCALAR(lights_steps, "JS_LIGHTS_STEPS", 8),333334// @Param: JS_THR_GAIN335// @DisplayName: Throttle gain scalar336// @Description: Scalar for gain on the throttle channel. Gets scaled with the current JS gain337// @User: Standard338// @Range: 0.5 4.0339GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f),340341// @Param: FRAME_CONFIG342// @DisplayName: Frame configuration343// @Description: Set this parameter according to your vehicle/motor configuration344// @User: Standard345// @RebootRequired: True346// @Values: 0:BlueROV1, 1:Vectored, 2:Vectored_6DOF, 3:Vectored_6DOF_90, 4:SimpleROV-3, 5:SimpleROV-4, 6:SimpleROV-5, 7:Custom347GSCALAR(frame_configuration, "FRAME_CONFIG", AP_Motors6DOF::SUB_FRAME_VECTORED),348349// @Group: BTN0_350// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp351GGROUP(jbtn_0, "BTN0_", JSButton),352353// @Group: BTN1_354// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp355GGROUP(jbtn_1, "BTN1_", JSButton),356357// @Group: BTN2_358// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp359GGROUP(jbtn_2, "BTN2_", JSButton),360361// @Group: BTN3_362// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp363GGROUP(jbtn_3, "BTN3_", JSButton),364365// @Group: BTN4_366// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp367GGROUP(jbtn_4, "BTN4_", JSButton),368369// @Group: BTN5_370// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp371GGROUP(jbtn_5, "BTN5_", JSButton),372373// @Group: BTN6_374// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp375GGROUP(jbtn_6, "BTN6_", JSButton),376377// @Group: BTN7_378// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp379GGROUP(jbtn_7, "BTN7_", JSButton),380381// @Group: BTN8_382// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp383GGROUP(jbtn_8, "BTN8_", JSButton),384385// @Group: BTN9_386// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp387GGROUP(jbtn_9, "BTN9_", JSButton),388389// @Group: BTN10_390// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp391GGROUP(jbtn_10, "BTN10_", JSButton),392393// @Group: BTN11_394// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp395GGROUP(jbtn_11, "BTN11_", JSButton),396397// @Group: BTN12_398// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp399GGROUP(jbtn_12, "BTN12_", JSButton),400401// @Group: BTN13_402// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp403GGROUP(jbtn_13, "BTN13_", JSButton),404405// @Group: BTN14_406// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp407GGROUP(jbtn_14, "BTN14_", JSButton),408409// @Group: BTN15_410// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp411GGROUP(jbtn_15, "BTN15_", JSButton),412413// @Group: BTN16_414// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp415GGROUP(jbtn_16, "BTN16_", JSButton),416417// @Group: BTN17_418// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp419GGROUP(jbtn_17, "BTN17_", JSButton),420421// @Group: BTN18_422// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp423GGROUP(jbtn_18, "BTN18_", JSButton),424425// @Group: BTN19_426// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp427GGROUP(jbtn_19, "BTN19_", JSButton),428429// @Group: BTN20_430// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp431GGROUP(jbtn_20, "BTN20_", JSButton),432433// @Group: BTN21_434// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp435GGROUP(jbtn_21, "BTN21_", JSButton),436437// @Group: BTN22_438// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp439GGROUP(jbtn_22, "BTN22_", JSButton),440441// @Group: BTN23_442// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp443GGROUP(jbtn_23, "BTN23_", JSButton),444445// @Group: BTN24_446// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp447GGROUP(jbtn_24, "BTN24_", JSButton),448449// @Group: BTN25_450// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp451GGROUP(jbtn_25, "BTN25_", JSButton),452453// @Group: BTN26_454// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp455GGROUP(jbtn_26, "BTN26_", JSButton),456457// @Group: BTN27_458// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp459GGROUP(jbtn_27, "BTN27_", JSButton),460461// @Group: BTN28_462// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp463GGROUP(jbtn_28, "BTN28_", JSButton),464465// @Group: BTN29_466// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp467GGROUP(jbtn_29, "BTN29_", JSButton),468469// @Group: BTN30_470// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp471GGROUP(jbtn_30, "BTN30_", JSButton),472473// @Group: BTN31_474// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp475GGROUP(jbtn_31, "BTN31_", JSButton),476477// @Param: RC_SPEED478// @DisplayName: ESC Update Speed479// @Description: This is the speed in Hertz that your ESCs will receive updates480// @Units: Hz481// @Range: 50 490482// @Increment: 1483// @User: Advanced484GSCALAR(rc_speed, "RC_SPEED", RC_SPEED_DEFAULT),485486// @Param: ACRO_RP_P487// @DisplayName: Acro Roll and Pitch P gain488// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.489// @Range: 1 10490// @User: Standard491GSCALAR(acro_rp_p, "ACRO_RP_P", ACRO_RP_P),492493// @Param: ACRO_YAW_P494// @DisplayName: Acro Yaw P gain495// @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.496// @Range: 1 10497// @User: Standard498GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),499500// @Param: ACRO_BAL_ROLL501// @DisplayName: Acro Balance Roll502// @Description: rate at which roll angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.503// @Range: 0 3504// @Increment: 0.1505// @User: Advanced506GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),507508// @Param: ACRO_BAL_PITCH509// @DisplayName: Acro Balance Pitch510// @Description: rate at which pitch angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.511// @Range: 0 3512// @Increment: 0.1513// @User: Advanced514GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),515516// @Param: ACRO_TRAINER517// @DisplayName: Acro Trainer518// @Description: Type of trainer used in acro mode519// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited520// @User: Advanced521GSCALAR(acro_trainer, "ACRO_TRAINER", ACRO_TRAINER_LIMITED),522523// @Param: ACRO_EXPO524// @DisplayName: Acro Expo525// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges526// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High527// @Range: -0.5 0.95528// @User: Advanced529GSCALAR(acro_expo, "ACRO_EXPO", ACRO_EXPO_DEFAULT),530531// variables not in the g class which contain EEPROM saved variables532533#if AP_CAMERA_ENABLED534// @Group: CAM535// @Path: ../libraries/AP_Camera/AP_Camera.cpp536GOBJECT(camera, "CAM", AP_Camera),537#endif538539#if AP_RELAY_ENABLED540// @Group: RELAY541// @Path: ../libraries/AP_Relay/AP_Relay.cpp542GOBJECT(relay, "RELAY", AP_Relay),543#endif544545// @Group: COMPASS_546// @Path: ../libraries/AP_Compass/AP_Compass.cpp547GOBJECT(compass, "COMPASS_", Compass),548549// @Group: INS550// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp551GOBJECT(ins, "INS", AP_InertialSensor),552553// @Group: WPNAV_554// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp555GOBJECT(wp_nav, "WPNAV_", AC_WPNav),556557// @Group: LOIT_558// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp559GOBJECT(loiter_nav, "LOIT_", AC_Loiter),560561#if CIRCLE_NAV_ENABLED562// @Group: CIRCLE_563// @Path: ../libraries/AC_WPNav/AC_Circle.cpp564GOBJECT(circle_nav, "CIRCLE_", AC_Circle),565#endif566567// @Group: ATC_568// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp569GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Sub),570571// @Group: PSC572// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp573GOBJECT(pos_control, "PSC", AC_PosControl),574575// @Group: AHRS_576// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp577GOBJECT(ahrs, "AHRS_", AP_AHRS),578579#if HAL_MOUNT_ENABLED580// @Group: MNT581// @Path: ../libraries/AP_Mount/AP_Mount.cpp582GOBJECT(camera_mount, "MNT", AP_Mount),583#endif584585// @Group: BATT586// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp587GOBJECT(battery, "BATT", AP_BattMonitor),588589// @Group: ARMING_590// @Path: AP_Arming_Sub.cpp,../libraries/AP_Arming/AP_Arming.cpp591GOBJECT(arming, "ARMING_", AP_Arming_Sub),592593// @Group: BRD_594// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp595GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),596597#if HAL_MAX_CAN_PROTOCOL_DRIVERS598// @Group: CAN_599// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp600GOBJECT(can_mgr, "CAN_", AP_CANManager),601#endif602603#if AP_SIM_ENABLED604// @Group: SIM_605// @Path: ../libraries/SITL/SITL.cpp606GOBJECT(sitl, "SIM_", SITL::SIM),607#endif608609// @Group: BARO610// @Path: ../libraries/AP_Baro/AP_Baro.cpp611GOBJECT(barometer, "BARO", AP_Baro),612613// GPS driver614// @Group: GPS615// @Path: ../libraries/AP_GPS/AP_GPS.cpp616GOBJECT(gps, "GPS", AP_GPS),617618// Leak detector619// @Group: LEAK620// @Path: ../libraries/AP_LeakDetector/AP_LeakDetector.cpp621GOBJECT(leak_detector, "LEAK", AP_LeakDetector),622623// @Group: SCHED_624// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp625GOBJECT(scheduler, "SCHED_", AP_Scheduler),626627#if AVOIDANCE_ENABLED628// @Group: AVOID_629// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp630GOBJECT(avoid, "AVOID_", AC_Avoid),631#endif632633#if HAL_RALLY_ENABLED634// @Group: RALLY_635// @Path: ../libraries/AP_Rally/AP_Rally.cpp636GOBJECT(rally, "RALLY_", AP_Rally),637#endif638639// @Group: MOT_640// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp,../libraries/AP_Motors/AP_MotorsMulticopter.cpp641GOBJECT(motors, "MOT_", AP_Motors6DOF),642643#if RCMAP_ENABLED644// @Group: RCMAP_645// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp646GOBJECT(rcmap, "RCMAP_", RCMapper),647#endif648649#if HAL_NAVEKF2_AVAILABLE650// @Group: EK2_651// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp652GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),653#endif654655#if HAL_NAVEKF3_AVAILABLE656// @Group: EK3_657// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp658GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),659#endif660661// @Group: MIS_662// @Path: ../libraries/AP_Mission/AP_Mission.cpp663GOBJECT(mission, "MIS_", AP_Mission),664665#if AP_RANGEFINDER_ENABLED666// @Group: RNGFND667// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp668GOBJECT(rangefinder, "RNGFND", RangeFinder),669670// @Param: RNGFND_SQ_MIN671// @DisplayName: Rangefinder signal quality minimum672// @Description: Minimum signal quality for good rangefinder readings673// @Range: 0 100674// @User: Advanced675GSCALAR(rangefinder_signal_min, "RNGFND_SQ_MIN", RANGEFINDER_SIGNAL_MIN_DEFAULT),676677// @Param: SURFTRAK_DEPTH678// @DisplayName: SURFTRAK minimum depth679// @Description: Minimum depth to engage SURFTRAK mode680// @Units: cm681// @User: Standard682GSCALAR(surftrak_depth, "SURFTRAK_DEPTH", SURFTRAK_DEPTH_DEFAULT),683#endif684685#if AP_TERRAIN_AVAILABLE686// @Group: TERRAIN_687// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp688GOBJECT(terrain, "TERRAIN_", AP_Terrain),689#endif690691#if AP_OPTICALFLOW_ENABLED692// @Group: FLOW693// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp694GOBJECT(optflow, "FLOW", AP_OpticalFlow),695#endif696697#if OSD_ENABLED || OSD_PARAM_ENABLED698// @Group: OSD699// @Path: ../libraries/AP_OSD/AP_OSD.cpp700GOBJECT(osd, "OSD", AP_OSD),701#endif702703#if AP_RSSI_ENABLED704// @Group: RSSI_705// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp706GOBJECT(rssi, "RSSI_", AP_RSSI),707#endif708709// @Group: NTF_710// @Path: ../libraries/AP_Notify/AP_Notify.cpp711GOBJECT(notify, "NTF_", AP_Notify),712713// @Group:714// @Path: Parameters.cpp715GOBJECT(g2, "", ParametersG2),716717// @Group:718// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp719PARAM_VEHICLE_INFO,720721#if HAL_GCS_ENABLED722// @Group: MAV723// @Path: ../libraries/GCS_MAVLink/GCS.cpp724GOBJECT(_gcs, "MAV", GCS),725#endif726727AP_VAREND728};729730/*7312nd group of parameters732*/733const AP_Param::GroupInfo ParametersG2::var_info[] = {734735// 1 was AP_Stats736737#if HAL_PROXIMITY_ENABLED738// @Group: PRX739// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp740AP_SUBGROUPINFO(proximity, "PRX", 2, ParametersG2, AP_Proximity),741#endif742743// 3 was AP_Gripper744745// @Group: SERVO746// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp747AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),748749// @Group: RC750// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h751AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),752753// 18 was scripting754// 19 was ORIGIN_LAT755// 20 was ORIGIN_LON756// 21 was ORIGIN_ALT757758// @Param: SFC_NOBARO_THST759// @DisplayName: Surface mode throttle output when no barometer is available760// @Description: Surface mode throttle output when no borometer is available. 100% is full throttle. -100% is maximum throttle downwards761// @Units: %762// @User: Standard763// @Range: -100 100764AP_GROUPINFO("SFC_NOBARO_THST", 22, ParametersG2, surface_nobaro_thrust, 10),765766// @Group: ACTUATOR767// @Path: ../ArduSub/actuators.cpp768AP_SUBGROUPINFO(actuators, "ACTUATOR", 23, ParametersG2, Actuators),769770AP_GROUPEND771};772773/*774constructor for g2 object775*/776ParametersG2::ParametersG2()777{778AP_Param::setup_object_defaults(this, var_info);779}780781const AP_Param::ConversionInfo conversion_table[] = {782{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" },783{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" },784{ Parameters::k_param_failsafe_battery_enabled, 0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },785{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },786};787788void Sub::load_parameters()789{790AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);791792AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));793794AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB);795796convert_old_parameters();797AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table));798// We should ignore this parameter since ROVs are neutral buoyancy799AP_Param::set_by_name("MOT_THST_HOVER", 0.5);800801// PARAMETER_CONVERSION - Added: Mar-2022802#if AP_FENCE_ENABLED803AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true);804#endif805806// PARAMETER_CONVERSION - Added: July-2025 for ArduPilot-4.7807#if AP_RPM_ENABLED808AP_Param::convert_class(g.k_param_rpm_sensor_old, &rpm_sensor, rpm_sensor.var_info, 0, true, true);809#endif810811static const AP_Param::G2ObjectConversion g2_conversions[] {812#if AP_AIRSPEED_ENABLED813// PARAMETER_CONVERSION - Added: JAN-2022814{ &airspeed, airspeed.var_info, 19 },815#endif816#if AP_STATS_ENABLED817// PARAMETER_CONVERSION - Added: Jan-2024818{ &stats, stats.var_info, 1 },819#endif820#if AP_SCRIPTING_ENABLED821// PARAMETER_CONVERSION - Added: Jan-2024822{ &scripting, scripting.var_info, 18 },823#endif824#if AP_GRIPPER_ENABLED825// PARAMETER_CONVERSION - Added: Feb-2024826{ &gripper, gripper.var_info, 3 },827#endif828};829830AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));831832// PARAMETER_CONVERSION - Added: Feb-2024833#if HAL_LOGGING_ENABLED834AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);835#endif836837static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {838#if AP_SERIALMANAGER_ENABLED839// PARAMETER_CONVERSION - Added: Feb-2024840{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },841#endif842};843844AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));845846#if HAL_GCS_ENABLED847// Move parameters into new MAV_ parameter namespace848// PARAMETER_CONVERSION - Added: Mar-2025849{850static const AP_Param::ConversionInfo gcs_conversion_info[] {851{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },852{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },853};854AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));855}856#endif // HAL_GCS_ENABLED857858// upgrade attitude controller parameters859sub.attitude_control.convert_parameters();860861// upgrade loiter navigation parameters862loiter_nav.convert_parameters();863864#if CIRCLE_NAV_ENABLED865circle_nav.convert_parameters();866#endif867868// PARAMETER_CONVERSION - Added: Jan-2026869// move ORIGIN_LAT, ORIGIN_LON, ORIGIN_ALT to AHRS870static const AP_Param::ConversionInfo gcs_conversion_info[] {871{ 2, 19, AP_PARAM_FLOAT, "AHRS_ORIGIN_LAT" }, // ORIGIN_LAT moved to AHRS_ORIGIN_LAT872{ 2, 20, AP_PARAM_FLOAT, "AHRS_ORIGIN_LON" }, // ORIGIN_LON moved to AHRS_ORIGIN_LON873{ 2, 21, AP_PARAM_FLOAT, "AHRS_ORIGIN_ALT" }, // ORIGIN_ALT moved to AHRS_ORIGIN_ALT874};875AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));876}877878void Sub::convert_old_parameters()879{880// attitude control filter parameter changes from _FILT to FLTE or FLTD881const AP_Param::ConversionInfo filt_conversion_info[] = {882// move ATC_RAT_RLL/PIT_FILT to FLTD, move ATC_RAT_YAW_FILT to FLTE883{ Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" },884{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" },885{ Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" },886};887AP_Param::convert_old_parameters(&filt_conversion_info[0], ARRAY_SIZE(filt_conversion_info));888889SRV_Channels::upgrade_parameters();890}891892#if LEAKDETECTOR_MAX_INSTANCES > 0893// PARAMETER_CONVERSION - Added: Dec-2025894// Deals with leak detector getting misconfigured when updating from Sub 4.1895void Sub::update_leak_pins()896{897for (uint8_t instance = 0; instance < LEAKDETECTOR_MAX_INSTANCES; instance++) {898if (leak_detector.get_pin(instance) <= 0) {899// leak detector does not use pin900continue;901}902uint8_t servo_channel;903if (!hal.gpio->pin_to_servo_channel(leak_detector.get_pin(instance), servo_channel)) {904// leak detector pin does not map to a servo channel905continue;906}907if (SRV_Channels::is_GPIO(servo_channel)) {908// servo channel is already set to GPIO909continue;910}911if (SRV_Channels::channel_function(servo_channel) != SRV_Channel::Function::k_none) {912// servo channel is already set to a function913gcs().send_text(MAV_SEVERITY_WARNING, "Leak detector %u error. Please set SERVO%u_FUNCTION to GPIO", instance + 1, servo_channel + 1);914continue;915}916// servo channel is disabled, let's set it to GPIO for the user917gcs().send_text(MAV_SEVERITY_INFO, "Leak detector %u pin (servo %u) auto-set to GPIO", instance + 1, servo_channel + 1);918char param_name[20];919snprintf(param_name, sizeof(param_name), "SERVO%u_FUNCTION", servo_channel + 1);920AP_Param::set_and_save_by_name(param_name, static_cast<int>(SRV_Channel::Function::k_GPIO));921}922}923#endif924925#if AP_RELAY_ENABLED926// PARAMETER_CONVERSION - Added: Dec-2025927// Deals with relay getting misconfigured when updating from Sub 4.1928void Sub::update_relay_pins()929{930for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) {931uint8_t servo_channel;932uint8_t pin;933if (!relay.get_pin_by_instance(instance, pin) || !hal.gpio->pin_to_servo_channel(pin, servo_channel)) {934// instance does not use pin or pin does not map to a servo channel935continue;936}937if (!relay.enabled(instance) || SRV_Channels::is_GPIO(servo_channel)) {938// instance is not enabled or servo channel is already set to GPIO939continue;940}941if (SRV_Channels::channel_function(servo_channel) != SRV_Channel::Function::k_none) {942// servo channel is already set to a function943gcs().send_text(MAV_SEVERITY_WARNING, "Relay %u error. Please set SERVO%u_FUNCTION to GPIO", instance + 1, servo_channel + 1);944continue;945}946// servo channel is disabled, let's set it to GPIO for the user947gcs().send_text(MAV_SEVERITY_INFO, "Relay %u pin (servo %u) auto-set to GPIO", instance + 1, servo_channel + 1);948char param_name[20];949snprintf(param_name, sizeof(param_name), "SERVO%u_FUNCTION", servo_channel + 1);950AP_Param::set_and_save_by_name(param_name, static_cast<int>(SRV_Channel::Function::k_GPIO));951}952}953#endif954955956