Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduSub/Parameters.cpp
Views: 1798
#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// @Param: SYSID_THISMAV41// @DisplayName: MAVLink system ID of this vehicle42// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network43// @Range: 1 25544// @User: Advanced45GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),4647// @Param: SYSID_MYGCS48// @DisplayName: My ground station number49// @Description: Allows restricting radio overrides to only come from my ground station50// @Range: 1 25551// @Increment: 152// @User: Advanced53GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),5455// @Param: PILOT_THR_FILT56// @DisplayName: Throttle filter cutoff57// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable58// @User: Advanced59// @Units: Hz60// @Range: 0 1061// @Increment: 0.562GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),6364// AP_SerialManager was here6566// @Param: GCS_PID_MASK67// @DisplayName: GCS PID tuning mask68// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for69// @User: Advanced70// @Bitmask: 0:Roll,1:Pitch,2:Yaw71GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),7273// @Param: FS_GCS_ENABLE74// @DisplayName: Ground Station Failsafe Enable75// @Description: Controls what action to take when GCS heartbeat is lost.76// @Values: 0:Disabled,1:Warn only,2:Disarm,3:Enter depth hold mode,4:Enter surface mode77// @User: Standard78GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISARM),7980// @Param: FS_GCS_TIMEOUT81// @DisplayName: GCS failsafe timeout82// @Description: Timeout before triggering the GCS failsafe83// @Units: s84// @Increment: 185// @User: Standard86GSCALAR(failsafe_gcs_timeout, "FS_GCS_TIMEOUT", FS_GCS_TIMEOUT_S),8788// @Param: FS_LEAK_ENABLE89// @DisplayName: Leak Failsafe Enable90// @Description: Controls what action to take if a leak is detected.91// @Values: 0:Disabled,1:Warn only,2:Enter surface mode92// @User: Standard93GSCALAR(failsafe_leak, "FS_LEAK_ENABLE", FS_LEAK_WARN_ONLY),9495// @Param: FS_PRESS_ENABLE96// @DisplayName: Internal Pressure Failsafe Enable97// @Description: Controls what action to take if internal pressure exceeds FS_PRESS_MAX parameter.98// @Values: 0:Disabled,1:Warn only99// @User: Standard100GSCALAR(failsafe_pressure, "FS_PRESS_ENABLE", FS_PRESS_DISABLED),101102// @Param: FS_TEMP_ENABLE103// @DisplayName: Internal Temperature Failsafe Enable104// @Description: Controls what action to take if internal temperature exceeds FS_TEMP_MAX parameter.105// @Values: 0:Disabled,1:Warn only106// @User: Standard107GSCALAR(failsafe_temperature, "FS_TEMP_ENABLE", FS_TEMP_DISABLED),108109// @Param: FS_PRESS_MAX110// @DisplayName: Internal Pressure Failsafe Threshold111// @Description: The maximum internal pressure allowed before triggering failsafe. Failsafe action is determined by FS_PRESS_ENABLE parameter112// @Units: Pa113// @User: Standard114GSCALAR(failsafe_pressure_max, "FS_PRESS_MAX", FS_PRESS_MAX_DEFAULT),115116// @Param: FS_TEMP_MAX117// @DisplayName: Internal Temperature Failsafe Threshold118// @Description: The maximum internal temperature allowed before triggering failsafe. Failsafe action is determined by FS_TEMP_ENABLE parameter.119// @Units: degC120// @User: Standard121GSCALAR(failsafe_temperature_max, "FS_TEMP_MAX", FS_TEMP_MAX_DEFAULT),122123// @Param: FS_TERRAIN_ENAB124// @DisplayName: Terrain Failsafe Enable125// @Description: Controls what action to take if terrain information is lost during AUTO mode126// @Values: 0:Disarm, 1:Hold Position, 2:Surface127// @User: Standard128GSCALAR(failsafe_terrain, "FS_TERRAIN_ENAB", FS_TERRAIN_DISARM),129130// @Param: FS_PILOT_INPUT131// @DisplayName: Pilot input failsafe action132// @Description: Controls what action to take if no pilot input has been received after the timeout period specified by the FS_PILOT_TIMEOUT parameter133// @Values: 0:Disabled, 1:Warn Only, 2:Disarm134// @User: Standard135GSCALAR(failsafe_pilot_input, "FS_PILOT_INPUT", FS_PILOT_INPUT_DISARM),136137// @Param: FS_PILOT_TIMEOUT138// @DisplayName: Timeout for activation of pilot input failsafe139// @Description: Controls the maximum interval between received pilot inputs before the failsafe action is triggered140// @Units: s141// @Range: 0.1 3.0142// @User: Standard143GSCALAR(failsafe_pilot_input_timeout, "FS_PILOT_TIMEOUT", 3.0f),144145// @Param: XTRACK_ANG_LIM146// @DisplayName: Crosstrack correction angle limit147// @Description: Maximum allowed angle (in degrees) between current track and desired heading during waypoint navigation148// @Range: 10 90149// @User: Standard150GSCALAR(xtrack_angle_limit,"XTRACK_ANG_LIM", 45),151152// @Param: WP_YAW_BEHAVIOR153// @DisplayName: Yaw behaviour during missions154// @Description: Determines how the autopilot controls the yaw during missions and RTL155// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course, 4:Correct crosstrack error156// @User: Standard157GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),158159// @Param: PILOT_SPEED_UP160// @DisplayName: Pilot maximum vertical ascending speed161// @Description: The maximum vertical ascending velocity the pilot may request in cm/s162// @Units: cm/s163// @Range: 20 500164// @Increment: 10165// @User: Standard166GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX),167168// @Param: PILOT_SPEED_DN169// @DisplayName: Pilot maximum vertical descending speed170// @Description: The maximum vertical descending velocity the pilot may request in cm/s171// @Units: cm/s172// @Range: 20 500173// @Increment: 10174// @User: Standard175GSCALAR(pilot_speed_dn, "PILOT_SPEED_DN", 0),176177// @Param: PILOT_ACCEL_Z178// @DisplayName: Pilot vertical acceleration179// @Description: The vertical acceleration used when pilot is controlling the altitude180// @Units: cm/s/s181// @Range: 50 500182// @Increment: 10183// @User: Standard184GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),185186// @Param: THR_DZ187// @DisplayName: Throttle deadzone188// @Description: The PWM deadzone in microseconds above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes189// @User: Standard190// @Range: 0 300191// @Units: PWM192// @Increment: 1193GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),194195// @Param: LOG_BITMASK196// @DisplayName: Log bitmask197// @Description: 4 byte bitmap of log types to enable198// @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_RAW199// @User: Standard200GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),201202// @Param: ANGLE_MAX203// @DisplayName: Angle Max204// @Description: Maximum lean angle in all flight modes205// @Units: cdeg206// @Increment: 10207// @Range: 1000 8000208// @User: Advanced209ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),210211// @Param: FS_EKF_ACTION212// @DisplayName: EKF Failsafe Action213// @Description: Controls the action that will be taken when an EKF failsafe is invoked214// @Values: 0:Disabled, 1:Warn only, 2:Disarm215// @User: Advanced216GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),217218// @Param: FS_EKF_THRESH219// @DisplayName: EKF failsafe variance threshold220// @Description: Allows setting the maximum acceptable compass and velocity variance221// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed222// @User: Advanced223GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),224225// @Param: FS_CRASH_CHECK226// @DisplayName: Crash check enable227// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.228// @Values: 0:Disabled,1:Warn only,2:Disarm229// @User: Advanced230GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLED),231232// @Param: JS_GAIN_DEFAULT233// @DisplayName: Default gain at boot234// @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'.235// @User: Standard236// @Range: 0.1 1.0237GSCALAR(gain_default, "JS_GAIN_DEFAULT", 0.5),238239// @Param: JS_GAIN_MAX240// @DisplayName: Maximum joystick gain241// @Description: Maximum joystick gain242// @User: Standard243// @Range: 0.2 1.0244GSCALAR(maxGain, "JS_GAIN_MAX", 1.0),245246// @Param: JS_GAIN_MIN247// @DisplayName: Minimum joystick gain248// @Description: Minimum joystick gain249// @User: Standard250// @Range: 0.1 0.8251GSCALAR(minGain, "JS_GAIN_MIN", 0.25),252253// @Param: JS_GAIN_STEPS254// @DisplayName: Gain steps255// @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.256// @User: Standard257// @Range: 1 10258GSCALAR(numGainSettings, "JS_GAIN_STEPS", 4),259260// @Param: JS_LIGHTS_STEPS261// @DisplayName: Lights brightness steps262// @Description: Number of steps in brightness between minimum and maximum brightness263// @User: Standard264// @Range: 1 10265// @Units: PWM266GSCALAR(lights_steps, "JS_LIGHTS_STEPS", 8),267268// @Param: JS_THR_GAIN269// @DisplayName: Throttle gain scalar270// @Description: Scalar for gain on the throttle channel. Gets scaled with the current JS gain271// @User: Standard272// @Range: 0.5 4.0273GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f),274275// @Param: FRAME_CONFIG276// @DisplayName: Frame configuration277// @Description: Set this parameter according to your vehicle/motor configuration278// @User: Standard279// @RebootRequired: True280// @Values: 0:BlueROV1, 1:Vectored, 2:Vectored_6DOF, 3:Vectored_6DOF_90, 4:SimpleROV-3, 5:SimpleROV-4, 6:SimpleROV-5, 7:Custom281GSCALAR(frame_configuration, "FRAME_CONFIG", AP_Motors6DOF::SUB_FRAME_VECTORED),282283// @Group: BTN0_284// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp285GGROUP(jbtn_0, "BTN0_", JSButton),286287// @Group: BTN1_288// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp289GGROUP(jbtn_1, "BTN1_", JSButton),290291// @Group: BTN2_292// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp293GGROUP(jbtn_2, "BTN2_", JSButton),294295// @Group: BTN3_296// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp297GGROUP(jbtn_3, "BTN3_", JSButton),298299// @Group: BTN4_300// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp301GGROUP(jbtn_4, "BTN4_", JSButton),302303// @Group: BTN5_304// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp305GGROUP(jbtn_5, "BTN5_", JSButton),306307// @Group: BTN6_308// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp309GGROUP(jbtn_6, "BTN6_", JSButton),310311// @Group: BTN7_312// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp313GGROUP(jbtn_7, "BTN7_", JSButton),314315// @Group: BTN8_316// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp317GGROUP(jbtn_8, "BTN8_", JSButton),318319// @Group: BTN9_320// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp321GGROUP(jbtn_9, "BTN9_", JSButton),322323// @Group: BTN10_324// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp325GGROUP(jbtn_10, "BTN10_", JSButton),326327// @Group: BTN11_328// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp329GGROUP(jbtn_11, "BTN11_", JSButton),330331// @Group: BTN12_332// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp333GGROUP(jbtn_12, "BTN12_", JSButton),334335// @Group: BTN13_336// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp337GGROUP(jbtn_13, "BTN13_", JSButton),338339// @Group: BTN14_340// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp341GGROUP(jbtn_14, "BTN14_", JSButton),342343// @Group: BTN15_344// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp345GGROUP(jbtn_15, "BTN15_", JSButton),346347// @Group: BTN16_348// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp349GGROUP(jbtn_16, "BTN16_", JSButton),350351// @Group: BTN17_352// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp353GGROUP(jbtn_17, "BTN17_", JSButton),354355// @Group: BTN18_356// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp357GGROUP(jbtn_18, "BTN18_", JSButton),358359// @Group: BTN19_360// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp361GGROUP(jbtn_19, "BTN19_", JSButton),362363// @Group: BTN20_364// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp365GGROUP(jbtn_20, "BTN20_", JSButton),366367// @Group: BTN21_368// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp369GGROUP(jbtn_21, "BTN21_", JSButton),370371// @Group: BTN22_372// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp373GGROUP(jbtn_22, "BTN22_", JSButton),374375// @Group: BTN23_376// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp377GGROUP(jbtn_23, "BTN23_", JSButton),378379// @Group: BTN24_380// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp381GGROUP(jbtn_24, "BTN24_", JSButton),382383// @Group: BTN25_384// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp385GGROUP(jbtn_25, "BTN25_", JSButton),386387// @Group: BTN26_388// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp389GGROUP(jbtn_26, "BTN26_", JSButton),390391// @Group: BTN27_392// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp393GGROUP(jbtn_27, "BTN27_", JSButton),394395// @Group: BTN28_396// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp397GGROUP(jbtn_28, "BTN28_", JSButton),398399// @Group: BTN29_400// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp401GGROUP(jbtn_29, "BTN29_", JSButton),402403// @Group: BTN30_404// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp405GGROUP(jbtn_30, "BTN30_", JSButton),406407// @Group: BTN31_408// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp409GGROUP(jbtn_31, "BTN31_", JSButton),410411// @Param: RC_SPEED412// @DisplayName: ESC Update Speed413// @Description: This is the speed in Hertz that your ESCs will receive updates414// @Units: Hz415// @Range: 50 490416// @Increment: 1417// @User: Advanced418GSCALAR(rc_speed, "RC_SPEED", RC_SPEED_DEFAULT),419420// @Param: ACRO_RP_P421// @DisplayName: Acro Roll and Pitch P gain422// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.423// @Range: 1 10424// @User: Standard425GSCALAR(acro_rp_p, "ACRO_RP_P", ACRO_RP_P),426427// @Param: ACRO_YAW_P428// @DisplayName: Acro Yaw P gain429// @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.430// @Range: 1 10431// @User: Standard432GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),433434// @Param: ACRO_BAL_ROLL435// @DisplayName: Acro Balance Roll436// @Description: rate at which roll angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.437// @Range: 0 3438// @Increment: 0.1439// @User: Advanced440GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),441442// @Param: ACRO_BAL_PITCH443// @DisplayName: Acro Balance Pitch444// @Description: rate at which pitch angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.445// @Range: 0 3446// @Increment: 0.1447// @User: Advanced448GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),449450// @Param: ACRO_TRAINER451// @DisplayName: Acro Trainer452// @Description: Type of trainer used in acro mode453// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited454// @User: Advanced455GSCALAR(acro_trainer, "ACRO_TRAINER", ACRO_TRAINER_LIMITED),456457// @Param: ACRO_EXPO458// @DisplayName: Acro Expo459// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges460// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High461// @User: Advanced462GSCALAR(acro_expo, "ACRO_EXPO", ACRO_EXPO_DEFAULT),463464// variables not in the g class which contain EEPROM saved variables465466#if AP_CAMERA_ENABLED467// @Group: CAM468// @Path: ../libraries/AP_Camera/AP_Camera.cpp469GOBJECT(camera, "CAM", AP_Camera),470#endif471472#if AP_RELAY_ENABLED473// @Group: RELAY474// @Path: ../libraries/AP_Relay/AP_Relay.cpp475GOBJECT(relay, "RELAY", AP_Relay),476#endif477478// @Group: COMPASS_479// @Path: ../libraries/AP_Compass/AP_Compass.cpp480GOBJECT(compass, "COMPASS_", Compass),481482// @Group: INS483// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp484GOBJECT(ins, "INS", AP_InertialSensor),485486// @Group: WPNAV_487// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp488GOBJECT(wp_nav, "WPNAV_", AC_WPNav),489490// @Group: LOIT_491// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp492GOBJECT(loiter_nav, "LOIT_", AC_Loiter),493494#if CIRCLE_NAV_ENABLED495// @Group: CIRCLE_496// @Path: ../libraries/AC_WPNav/AC_Circle.cpp497GOBJECT(circle_nav, "CIRCLE_", AC_Circle),498#endif499500// @Group: ATC_501// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp502GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Sub),503504// @Group: PSC505// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp506GOBJECT(pos_control, "PSC", AC_PosControl),507508// @Group: SR0_509// @Path: GCS_MAVLink_Sub.cpp510GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),511512#if MAVLINK_COMM_NUM_BUFFERS >= 2513// @Group: SR1_514// @Path: GCS_MAVLink_Sub.cpp515GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),516#endif517518#if MAVLINK_COMM_NUM_BUFFERS >= 3519// @Group: SR2_520// @Path: GCS_MAVLink_Sub.cpp521GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),522#endif523524#if MAVLINK_COMM_NUM_BUFFERS >= 4525// @Group: SR3_526// @Path: GCS_MAVLink_Sub.cpp527GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),528#endif529530#if MAVLINK_COMM_NUM_BUFFERS >= 5531// @Group: SR4_532// @Path: GCS_MAVLink_Sub.cpp533GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),534#endif535536#if MAVLINK_COMM_NUM_BUFFERS >= 6537// @Group: SR5_538// @Path: GCS_MAVLink_Sub.cpp539GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),540#endif541542#if MAVLINK_COMM_NUM_BUFFERS >= 7543// @Group: SR6_544// @Path: GCS_MAVLink_Sub.cpp545GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),546#endif547548// @Group: AHRS_549// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp550GOBJECT(ahrs, "AHRS_", AP_AHRS),551552#if HAL_MOUNT_ENABLED553// @Group: MNT554// @Path: ../libraries/AP_Mount/AP_Mount.cpp555GOBJECT(camera_mount, "MNT", AP_Mount),556#endif557558// @Group: BATT559// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp560GOBJECT(battery, "BATT", AP_BattMonitor),561562// @Group: ARMING_563// @Path: AP_Arming_Sub.cpp,../libraries/AP_Arming/AP_Arming.cpp564GOBJECT(arming, "ARMING_", AP_Arming_Sub),565566// @Group: BRD_567// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp568GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),569570#if HAL_MAX_CAN_PROTOCOL_DRIVERS571// @Group: CAN_572// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp573GOBJECT(can_mgr, "CAN_", AP_CANManager),574#endif575576#if AP_SIM_ENABLED577// @Group: SIM_578// @Path: ../libraries/SITL/SITL.cpp579GOBJECT(sitl, "SIM_", SITL::SIM),580#endif581582// @Group: BARO583// @Path: ../libraries/AP_Baro/AP_Baro.cpp584GOBJECT(barometer, "BARO", AP_Baro),585586// GPS driver587// @Group: GPS588// @Path: ../libraries/AP_GPS/AP_GPS.cpp589GOBJECT(gps, "GPS", AP_GPS),590591// Leak detector592// @Group: LEAK593// @Path: ../libraries/AP_LeakDetector/AP_LeakDetector.cpp594GOBJECT(leak_detector, "LEAK", AP_LeakDetector),595596// @Group: SCHED_597// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp598GOBJECT(scheduler, "SCHED_", AP_Scheduler),599600#if AVOIDANCE_ENABLED601// @Group: AVOID_602// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp603GOBJECT(avoid, "AVOID_", AC_Avoid),604#endif605606#if HAL_RALLY_ENABLED607// @Group: RALLY_608// @Path: ../libraries/AP_Rally/AP_Rally.cpp609GOBJECT(rally, "RALLY_", AP_Rally),610#endif611612// @Group: MOT_613// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp,../libraries/AP_Motors/AP_MotorsMulticopter.cpp614GOBJECT(motors, "MOT_", AP_Motors6DOF),615616#if RCMAP_ENABLED617// @Group: RCMAP_618// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp619GOBJECT(rcmap, "RCMAP_", RCMapper),620#endif621622#if HAL_NAVEKF2_AVAILABLE623// @Group: EK2_624// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp625GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),626#endif627628#if HAL_NAVEKF3_AVAILABLE629// @Group: EK3_630// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp631GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),632#endif633634// @Group: MIS_635// @Path: ../libraries/AP_Mission/AP_Mission.cpp636GOBJECT(mission, "MIS_", AP_Mission),637638#if AP_RANGEFINDER_ENABLED639// @Group: RNGFND640// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp641GOBJECT(rangefinder, "RNGFND", RangeFinder),642643// @Param: RNGFND_SQ_MIN644// @DisplayName: Rangefinder signal quality minimum645// @Description: Minimum signal quality for good rangefinder readings646// @Range: 0 100647// @User: Advanced648GSCALAR(rangefinder_signal_min, "RNGFND_SQ_MIN", RANGEFINDER_SIGNAL_MIN_DEFAULT),649650// @Param: SURFTRAK_DEPTH651// @DisplayName: SURFTRAK minimum depth652// @Description: Minimum depth to engage SURFTRAK mode653// @Units: cm654// @User: Standard655GSCALAR(surftrak_depth, "SURFTRAK_DEPTH", SURFTRAK_DEPTH_DEFAULT),656#endif657658#if AP_TERRAIN_AVAILABLE659// @Group: TERRAIN_660// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp661GOBJECT(terrain, "TERRAIN_", AP_Terrain),662#endif663664#if AP_OPTICALFLOW_ENABLED665// @Group: FLOW666// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp667GOBJECT(optflow, "FLOW", AP_OpticalFlow),668#endif669670#if AP_RPM_ENABLED671// @Group: RPM672// @Path: ../libraries/AP_RPM/AP_RPM.cpp673GOBJECT(rpm_sensor, "RPM", AP_RPM),674#endif675676// @Group: NTF_677// @Path: ../libraries/AP_Notify/AP_Notify.cpp678GOBJECT(notify, "NTF_", AP_Notify),679680// @Group:681// @Path: Parameters.cpp682GOBJECT(g2, "", ParametersG2),683684// @Group:685// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp686PARAM_VEHICLE_INFO,687688AP_VAREND689};690691/*6922nd group of parameters693*/694const AP_Param::GroupInfo ParametersG2::var_info[] = {695696// 1 was AP_Stats697698#if HAL_PROXIMITY_ENABLED699// @Group: PRX700// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp701AP_SUBGROUPINFO(proximity, "PRX", 2, ParametersG2, AP_Proximity),702#endif703704// 3 was AP_Gripper705706// @Group: SERVO707// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp708AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),709710// @Group: RC711// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h712AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),713714// 18 was scripting715716// @Param: ORIGIN_LAT717// @DisplayName: Backup latitude for EKF origin718// @Description: Backup EKF origin latitude used when not using a positioning system.719// @Units: deg720// @User: Standard721AP_GROUPINFO("ORIGIN_LAT", 19, ParametersG2, backup_origin_lat, 0),722723// @Param: ORIGIN_LON724// @DisplayName: Backup longitude for EKF origin725// @Description: Backup EKF origin longitude used when not using a positioning system.726// @Units: deg727// @User: Standard728AP_GROUPINFO("ORIGIN_LON", 20, ParametersG2, backup_origin_lon, 0),729730// @Param: ORIGIN_ALT731// @DisplayName: Backup altitude (MSL) for EKF origin732// @Description: Backup EKF origin altitude (MSL) used when not using a positioning system.733// @Units: m734// @User: Standard735AP_GROUPINFO("ORIGIN_ALT", 21, ParametersG2, backup_origin_alt, 0),736737AP_GROUPEND738};739740/*741constructor for g2 object742*/743ParametersG2::ParametersG2()744{745AP_Param::setup_object_defaults(this, var_info);746}747748const AP_Param::ConversionInfo conversion_table[] = {749{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" },750{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" },751{ Parameters::k_param_failsafe_battery_enabled, 0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },752{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },753{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },754};755756void Sub::load_parameters()757{758AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);759760AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));761762AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB);763764convert_old_parameters();765AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table));766// We should ignore this parameter since ROVs are neutral buoyancy767AP_Param::set_by_name("MOT_THST_HOVER", 0.5);768769// PARAMETER_CONVERSION - Added: Mar-2022770#if AP_FENCE_ENABLED771AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true);772#endif773774static const AP_Param::G2ObjectConversion g2_conversions[] {775#if AP_AIRSPEED_ENABLED776// PARAMETER_CONVERSION - Added: JAN-2022777{ &airspeed, airspeed.var_info, 19 },778#endif779#if AP_STATS_ENABLED780// PARAMETER_CONVERSION - Added: Jan-2024781{ &stats, stats.var_info, 1 },782#endif783#if AP_SCRIPTING_ENABLED784// PARAMETER_CONVERSION - Added: Jan-2024785{ &scripting, scripting.var_info, 18 },786#endif787#if AP_GRIPPER_ENABLED788// PARAMETER_CONVERSION - Added: Feb-2024789{ &gripper, gripper.var_info, 3 },790#endif791};792793AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));794795// PARAMETER_CONVERSION - Added: Feb-2024796#if HAL_LOGGING_ENABLED797AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);798#endif799800static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {801#if AP_SERIALMANAGER_ENABLED802// PARAMETER_CONVERSION - Added: Feb-2024803{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },804#endif805};806807AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));808}809810void Sub::convert_old_parameters()811{812// attitude control filter parameter changes from _FILT to FLTE or FLTD813const AP_Param::ConversionInfo filt_conversion_info[] = {814// move ATC_RAT_RLL/PIT_FILT to FLTD, move ATC_RAT_YAW_FILT to FLTE815{ Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" },816{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" },817{ Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" },818};819AP_Param::convert_old_parameters(&filt_conversion_info[0], ARRAY_SIZE(filt_conversion_info));820821SRV_Channels::upgrade_parameters();822}823824825