2016-01-14 15:30:56 -04:00
# include "Sub.h"
2015-12-30 18:57:56 -04:00
2024-02-21 02:40:36 -04:00
# include <AP_Gripper/AP_Gripper.h>
2015-12-30 18:57:56 -04:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
/*
2016-12-20 16:20:15 -04:00
* ArduSub parameter definitions
2015-12-30 18:57:56 -04:00
*
*/
2016-01-14 15:30:56 -04:00
const AP_Param : : Info Sub : : var_info [ ] = {
2016-03-01 21:39:23 -04:00
2017-02-03 17:33:27 -04:00
// @Param: SURFACE_DEPTH
// @DisplayName: Depth reading at surface
// @Description: The depth the external pressure sensor will read when the vehicle is considered at the surface (in centimeters)
2017-08-20 14:40:27 -03:00
// @Units: cm
2017-02-03 17:33:27 -04:00
// @Range: -100 0
2016-05-03 23:24:15 -03:00
// @User: Standard
2017-02-03 17:33:27 -04:00
GSCALAR ( surface_depth , " SURFACE_DEPTH " , SURFACE_DEPTH_DEFAULT ) ,
2016-03-01 21:39:23 -04:00
2020-02-18 01:52:54 -04:00
// @Param: FORMAT_VERSION
2015-12-30 18:57:56 -04:00
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
2020-02-18 01:52:54 -04:00
GSCALAR ( format_version , " FORMAT_VERSION " , 0 ) ,
2015-12-30 18:57:56 -04:00
// @Param: SYSID_THISMAV
// @DisplayName: MAVLink system ID of this vehicle
// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
// @Range: 1 255
// @User: Advanced
GSCALAR ( sysid_this_mav , " SYSID_THISMAV " , MAV_SYSTEM_ID ) ,
// @Param: SYSID_MYGCS
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
2023-11-25 00:53:48 -04:00
// @Range: 1 255
// @Increment: 1
2015-12-30 18:57:56 -04:00
// @User: Advanced
GSCALAR ( sysid_my_gcs , " SYSID_MYGCS " , 255 ) ,
// @Param: PILOT_THR_FILT
// @DisplayName: Throttle filter cutoff
// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
// @User: Advanced
// @Units: Hz
// @Range: 0 10
// @Increment: .5
GSCALAR ( throttle_filt , " PILOT_THR_FILT " , 0 ) ,
2024-02-28 00:57:47 -04:00
// AP_SerialManager was here
2015-12-30 18:57:56 -04:00
// @Param: GCS_PID_MASK
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
GSCALAR ( gcs_pid_mask , " GCS_PID_MASK " , 0 ) ,
// @Param: FS_GCS_ENABLE
// @DisplayName: Ground Station Failsafe Enable
2016-08-26 16:27:28 -03:00
// @Description: Controls what action to take when GCS heartbeat is lost.
// @Values: 0:Disabled,1:Warn only,2:Disarm,3:Enter depth hold mode,4:Enter surface mode
2015-12-30 18:57:56 -04:00
// @User: Standard
2016-12-07 15:10:04 -04:00
GSCALAR ( failsafe_gcs , " FS_GCS_ENABLE " , FS_GCS_DISARM ) ,
2016-08-26 16:27:28 -03:00
// @Param: FS_LEAK_ENABLE
// @DisplayName: Leak Failsafe Enable
// @Description: Controls what action to take if a leak is detected.
// @Values: 0:Disabled,1:Warn only,2:Enter surface mode
// @User: Standard
2017-02-17 15:03:19 -04:00
GSCALAR ( failsafe_leak , " FS_LEAK_ENABLE " , FS_LEAK_WARN_ONLY ) ,
2015-12-30 18:57:56 -04:00
2016-09-11 18:49:19 -03:00
// @Param: FS_PRESS_ENABLE
// @DisplayName: Internal Pressure Failsafe Enable
// @Description: Controls what action to take if internal pressure exceeds FS_PRESS_MAX parameter.
// @Values: 0:Disabled,1:Warn only
// @User: Standard
GSCALAR ( failsafe_pressure , " FS_PRESS_ENABLE " , FS_PRESS_DISABLED ) ,
// @Param: FS_TEMP_ENABLE
// @DisplayName: Internal Temperature Failsafe Enable
// @Description: Controls what action to take if internal temperature exceeds FS_TEMP_MAX parameter.
// @Values: 0:Disabled,1:Warn only
// @User: Standard
GSCALAR ( failsafe_temperature , " FS_TEMP_ENABLE " , FS_TEMP_DISABLED ) ,
// @Param: FS_PRESS_MAX
// @DisplayName: Internal Pressure Failsafe Threshold
// @Description: The maximum internal pressure allowed before triggering failsafe. Failsafe action is determined by FS_PRESS_ENABLE parameter
2017-05-02 10:36:52 -03:00
// @Units: Pa
2016-09-11 18:49:19 -03:00
// @User: Standard
GSCALAR ( failsafe_pressure_max , " FS_PRESS_MAX " , FS_PRESS_MAX_DEFAULT ) ,
// @Param: FS_TEMP_MAX
// @DisplayName: Internal Temperature Failsafe Threshold
// @Description: The maximum internal temperature allowed before triggering failsafe. Failsafe action is determined by FS_TEMP_ENABLE parameter.
2017-05-02 10:36:52 -03:00
// @Units: degC
2016-09-11 18:49:19 -03:00
// @User: Standard
GSCALAR ( failsafe_temperature_max , " FS_TEMP_MAX " , FS_TEMP_MAX_DEFAULT ) ,
2017-02-07 20:42:28 -04:00
// @Param: FS_TERRAIN_ENAB
// @DisplayName: Terrain Failsafe Enable
// @Description: Controls what action to take if terrain information is lost during AUTO mode
// @Values: 0:Disarm, 1:Hold Position, 2:Surface
// @User: Standard
GSCALAR ( failsafe_terrain , " FS_TERRAIN_ENAB " , FS_TERRAIN_DISARM ) ,
2017-04-14 18:23:59 -03:00
// @Param: FS_PILOT_INPUT
// @DisplayName: Pilot input failsafe action
// @Description: Controls what action to take if no pilot input has been received after the timeout period specified by the FS_PILOT_TIMEOUT parameter
// @Values: 0:Disabled, 1:Warn Only, 2:Disarm
// @User: Standard
GSCALAR ( failsafe_pilot_input , " FS_PILOT_INPUT " , FS_PILOT_INPUT_DISARM ) ,
// @Param: FS_PILOT_TIMEOUT
// @DisplayName: Timeout for activation of pilot input failsafe
// @Description: Controls the maximum interval between received pilot inputs before the failsafe action is triggered
2017-05-02 10:36:52 -03:00
// @Units: s
2017-05-12 18:16:12 -03:00
// @Range: 0.1 3.0
2017-04-14 18:23:59 -03:00
// @User: Standard
2017-08-20 14:42:31 -03:00
GSCALAR ( failsafe_pilot_input_timeout , " FS_PILOT_TIMEOUT " , 3.0f ) ,
2017-04-14 18:23:59 -03:00
2017-02-07 20:42:28 -04:00
// @Param: XTRACK_ANG_LIM
// @DisplayName: Crosstrack correction angle limit
// @Description: Maximum allowed angle (in degrees) between current track and desired heading during waypoint navigation
// @Range: 10 90
// @User: Standard
2017-02-03 17:33:27 -04:00
GSCALAR ( xtrack_angle_limit , " XTRACK_ANG_LIM " , 45 ) ,
2017-02-07 20:42:28 -04:00
2015-12-30 18:57:56 -04:00
// @Param: WP_YAW_BEHAVIOR
// @DisplayName: Yaw behaviour during missions
// @Description: Determines how the autopilot controls the yaw during missions and RTL
2017-08-19 20:52:38 -03:00
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course, 4:Correct crosstrack error
2015-12-30 18:57:56 -04:00
// @User: Standard
GSCALAR ( wp_yaw_behavior , " WP_YAW_BEHAVIOR " , WP_YAW_BEHAVIOR_DEFAULT ) ,
2017-11-19 08:29:09 -04:00
// @Param: PILOT_SPEED_UP
// @DisplayName: Pilot maximum vertical ascending speed
// @Description: The maximum vertical ascending velocity the pilot may request in cm/s
2017-05-02 10:36:52 -03:00
// @Units: cm/s
2015-12-30 18:57:56 -04:00
// @Range: 50 500
// @Increment: 10
// @User: Standard
2017-11-19 08:29:09 -04:00
GSCALAR ( pilot_speed_up , " PILOT_SPEED_UP " , PILOT_VELZ_MAX ) ,
// @Param: PILOT_SPEED_DN
// @DisplayName: Pilot maximum vertical descending speed
// @Description: The maximum vertical descending velocity the pilot may request in cm/s
// @Units: cm/s
// @Range: 50 500
// @Increment: 10
// @User: Standard
GSCALAR ( pilot_speed_dn , " PILOT_SPEED_DN " , 0 ) ,
2015-12-30 18:57:56 -04:00
// @Param: PILOT_ACCEL_Z
// @DisplayName: Pilot vertical acceleration
// @Description: The vertical acceleration used when pilot is controlling the altitude
// @Units: cm/s/s
// @Range: 50 500
// @Increment: 10
// @User: Standard
GSCALAR ( pilot_accel_z , " PILOT_ACCEL_Z " , PILOT_ACCEL_Z_DEFAULT ) ,
// @Param: THR_DZ
// @DisplayName: Throttle deadzone
2017-05-15 20:17:22 -03:00
// @Description: The PWM deadzone in microseconds above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
2015-12-30 18:57:56 -04:00
// @User: Standard
// @Range: 0 300
2017-05-02 10:36:52 -03:00
// @Units: PWM
2015-12-30 18:57:56 -04:00
// @Increment: 1
GSCALAR ( throttle_deadzone , " THR_DZ " , THR_DZ_DEFAULT ) ,
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: 4 byte bitmap of log types to enable
2017-02-03 00:18:27 -04:00
// @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_RAW
2015-12-30 18:57:56 -04:00
// @User: Standard
GSCALAR ( log_bitmask , " LOG_BITMASK " , DEFAULT_LOG_BITMASK ) ,
// @Param: ANGLE_MAX
// @DisplayName: Angle Max
// @Description: Maximum lean angle in all flight modes
2017-05-02 10:36:52 -03:00
// @Units: cdeg
2021-05-20 10:08:46 -03:00
// @Increment: 10
2015-12-30 18:57:56 -04:00
// @Range: 1000 8000
// @User: Advanced
ASCALAR ( angle_max , " ANGLE_MAX " , DEFAULT_ANGLE_MAX ) ,
// @Param: FS_EKF_ACTION
// @DisplayName: EKF Failsafe Action
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
2017-05-12 17:15:58 -03:00
// @Values: 0:Disabled, 1:Warn only, 2:Disarm
2015-12-30 18:57:56 -04:00
// @User: Advanced
GSCALAR ( fs_ekf_action , " FS_EKF_ACTION " , FS_EKF_ACTION_DEFAULT ) ,
// @Param: FS_EKF_THRESH
// @DisplayName: EKF failsafe variance threshold
// @Description: Allows setting the maximum acceptable compass and velocity variance
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
// @User: Advanced
GSCALAR ( fs_ekf_thresh , " FS_EKF_THRESH " , FS_EKF_THRESHOLD_DEFAULT ) ,
// @Param: FS_CRASH_CHECK
// @DisplayName: Crash check enable
// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
2017-03-24 17:30:28 -03:00
// @Values: 0:Disabled,1:Warn only,2:Disarm
2015-12-30 18:57:56 -04:00
// @User: Advanced
2017-03-24 17:30:28 -03:00
GSCALAR ( fs_crash_check , " FS_CRASH_CHECK " , FS_CRASH_DISABLED ) ,
2015-12-30 18:57:56 -04:00
2017-02-03 17:33:27 -04:00
// @Param: JS_GAIN_DEFAULT
// @DisplayName: Default gain at boot
2022-11-11 15:00:11 -04:00
// @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'.
2017-02-03 17:33:27 -04:00
// @User: Standard
// @Range: 0.1 1.0
GSCALAR ( gain_default , " JS_GAIN_DEFAULT " , 0.5 ) ,
// @Param: JS_GAIN_MAX
// @DisplayName: Maximum joystick gain
// @Description: Maximum joystick gain
// @User: Standard
// @Range: 0.2 1.0
GSCALAR ( maxGain , " JS_GAIN_MAX " , 1.0 ) ,
// @Param: JS_GAIN_MIN
// @DisplayName: Minimum joystick gain
// @Description: Minimum joystick gain
// @User: Standard
// @Range: 0.1 0.8
GSCALAR ( minGain , " JS_GAIN_MIN " , 0.25 ) ,
// @Param: JS_GAIN_STEPS
// @DisplayName: Gain steps
// @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.
// @User: Standard
// @Range: 1 10
GSCALAR ( numGainSettings , " JS_GAIN_STEPS " , 4 ) ,
2017-10-26 16:42:56 -03:00
// @Param: JS_LIGHTS_STEPS
// @DisplayName: Lights brightness steps
// @Description: Number of steps in brightness between minimum and maximum brightness
2017-02-03 17:33:27 -04:00
// @User: Standard
2017-10-26 16:42:56 -03:00
// @Range: 1 10
2017-05-02 10:36:52 -03:00
// @Units: PWM
2017-10-26 16:42:56 -03:00
GSCALAR ( lights_steps , " JS_LIGHTS_STEPS " , 8 ) ,
2017-02-03 17:33:27 -04:00
// @Param: JS_THR_GAIN
// @DisplayName: Throttle gain scalar
2023-10-31 17:59:34 -03:00
// @Description: Scalar for gain on the throttle channel. Gets scaled with the current JS gain
2017-02-03 17:33:27 -04:00
// @User: Standard
// @Range: 0.5 4.0
GSCALAR ( throttle_gain , " JS_THR_GAIN " , 1.0f ) ,
// @Param: FRAME_CONFIG
// @DisplayName: Frame configuration
// @Description: Set this parameter according to your vehicle/motor configuration
// @User: Standard
2016-12-13 21:15:37 -04:00
// @RebootRequired: True
2017-02-03 17:33:27 -04:00
// @Values: 0:BlueROV1, 1:Vectored, 2:Vectored_6DOF, 3:Vectored_6DOF_90, 4:SimpleROV-3, 5:SimpleROV-4, 6:SimpleROV-5, 7:Custom
GSCALAR ( frame_configuration , " FRAME_CONFIG " , AP_Motors6DOF : : SUB_FRAME_VECTORED ) ,
2016-12-13 21:15:37 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN0_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_0 , " BTN0_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN1_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_1 , " BTN1_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN2_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_2 , " BTN2_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN3_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_3 , " BTN3_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN4_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_4 , " BTN4_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN5_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_5 , " BTN5_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN6_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_6 , " BTN6_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN7_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_7 , " BTN7_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN8_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_8 , " BTN8_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN9_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_9 , " BTN9_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN10_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_10 , " BTN10_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN11_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_11 , " BTN11_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN12_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_12 , " BTN12_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN13_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_13 , " BTN13_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN14_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_14 , " BTN14_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2017-02-03 17:33:27 -04:00
// @Group: BTN15_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_15 , " BTN15_ " , JSButton ) ,
2016-03-12 11:15:18 -04:00
2023-10-30 15:02:07 -03:00
// @Group: BTN16_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_16 , " BTN16_ " , JSButton ) ,
// @Group: BTN17_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_17 , " BTN17_ " , JSButton ) ,
// @Group: BTN18_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_18 , " BTN18_ " , JSButton ) ,
// @Group: BTN19_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_19 , " BTN19_ " , JSButton ) ,
// @Group: BTN20_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_20 , " BTN20_ " , JSButton ) ,
// @Group: BTN21_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_21 , " BTN21_ " , JSButton ) ,
// @Group: BTN22_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_22 , " BTN22_ " , JSButton ) ,
// @Group: BTN23_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_23 , " BTN23_ " , JSButton ) ,
// @Group: BTN24_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_24 , " BTN24_ " , JSButton ) ,
// @Group: BTN25_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_25 , " BTN25_ " , JSButton ) ,
// @Group: BTN26_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_26 , " BTN26_ " , JSButton ) ,
// @Group: BTN27_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_27 , " BTN27_ " , JSButton ) ,
// @Group: BTN28_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_28 , " BTN28_ " , JSButton ) ,
// @Group: BTN29_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_29 , " BTN29_ " , JSButton ) ,
// @Group: BTN30_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_30 , " BTN30_ " , JSButton ) ,
// @Group: BTN31_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
GGROUP ( jbtn_31 , " BTN31_ " , JSButton ) ,
2015-12-30 18:57:56 -04:00
// @Param: RC_SPEED
// @DisplayName: ESC Update Speed
// @Description: This is the speed in Hertz that your ESCs will receive updates
// @Units: Hz
// @Range: 50 490
// @Increment: 1
// @User: Advanced
2016-12-07 12:43:30 -04:00
GSCALAR ( rc_speed , " RC_SPEED " , RC_SPEED_DEFAULT ) ,
2015-12-30 18:57:56 -04:00
// @Param: ACRO_RP_P
// @DisplayName: Acro Roll and Pitch P gain
// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
// @Range: 1 10
// @User: Standard
GSCALAR ( acro_rp_p , " ACRO_RP_P " , ACRO_RP_P ) ,
// @Param: ACRO_YAW_P
// @DisplayName: Acro Yaw P gain
2016-12-20 16:20:15 -04:00
// @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.
2015-12-30 18:57:56 -04:00
// @Range: 1 10
// @User: Standard
GSCALAR ( acro_yaw_p , " ACRO_YAW_P " , ACRO_YAW_P ) ,
// @Param: ACRO_BAL_ROLL
// @DisplayName: Acro Balance Roll
// @Description: rate at which roll angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
// @Range: 0 3
// @Increment: 0.1
// @User: Advanced
GSCALAR ( acro_balance_roll , " ACRO_BAL_ROLL " , ACRO_BALANCE_ROLL ) ,
// @Param: ACRO_BAL_PITCH
// @DisplayName: Acro Balance Pitch
// @Description: rate at which pitch angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
// @Range: 0 3
// @Increment: 0.1
// @User: Advanced
GSCALAR ( acro_balance_pitch , " ACRO_BAL_PITCH " , ACRO_BALANCE_PITCH ) ,
// @Param: ACRO_TRAINER
// @DisplayName: Acro Trainer
// @Description: Type of trainer used in acro mode
// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
// @User: Advanced
GSCALAR ( acro_trainer , " ACRO_TRAINER " , ACRO_TRAINER_LIMITED ) ,
// @Param: ACRO_EXPO
// @DisplayName: Acro Expo
// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
// @User: Advanced
GSCALAR ( acro_expo , " ACRO_EXPO " , ACRO_EXPO_DEFAULT ) ,
// variables not in the g class which contain EEPROM saved variables
2022-06-02 05:28:26 -03:00
# if AP_CAMERA_ENABLED
2023-02-14 00:04:04 -04:00
// @Group: CAM
2015-12-30 18:57:56 -04:00
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
2023-02-14 00:04:04 -04:00
GOBJECT ( camera , " CAM " , AP_Camera ) ,
2015-12-30 18:57:56 -04:00
# endif
2023-06-06 05:05:07 -03:00
# if AP_RELAY_ENABLED
2023-10-03 21:17:55 -03:00
// @Group: RELAY
2015-12-30 18:57:56 -04:00
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
2023-10-03 21:17:55 -03:00
GOBJECT ( relay , " RELAY " , AP_Relay ) ,
2023-06-06 05:05:07 -03:00
# endif
2015-12-30 18:57:56 -04:00
2021-12-04 00:22:56 -04:00
// @Group: COMPASS_
2016-04-03 14:19:09 -03:00
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
2021-12-04 00:22:56 -04:00
GOBJECT ( compass , " COMPASS_ " , Compass ) ,
2015-12-30 18:57:56 -04:00
2023-03-08 06:39:29 -04:00
// @Group: INS
2015-12-30 18:57:56 -04:00
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
2023-03-08 06:39:29 -04:00
GOBJECT ( ins , " INS " , AP_InertialSensor ) ,
2015-12-30 18:57:56 -04:00
// @Group: WPNAV_
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
GOBJECT ( wp_nav , " WPNAV_ " , AC_WPNav ) ,
2018-03-28 01:54:24 -03:00
// @Group: LOIT_
// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
2019-07-10 22:51:03 -03:00
GOBJECT ( loiter_nav , " LOIT_ " , AC_Loiter ) ,
2018-03-28 01:54:24 -03:00
2016-11-29 12:53:48 -04:00
# if CIRCLE_NAV_ENABLED == ENABLED
2015-12-30 18:57:56 -04:00
// @Group: CIRCLE_
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
GOBJECT ( circle_nav , " CIRCLE_ " , AC_Circle ) ,
2016-11-29 12:53:48 -04:00
# endif
2015-12-30 18:57:56 -04:00
// @Group: ATC_
2017-02-02 23:17:44 -04:00
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp
GOBJECT ( attitude_control , " ATC_ " , AC_AttitudeControl_Sub ) ,
2015-12-30 18:57:56 -04:00
2016-12-06 19:35:12 -04:00
// @Group: PSC
2015-12-30 18:57:56 -04:00
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
GOBJECT ( pos_control , " PSC " , AC_PosControl ) ,
// @Group: SR0_
// @Path: GCS_Mavlink.cpp
2019-06-19 07:32:27 -03:00
GOBJECTN ( _gcs . chan_parameters [ 0 ] , gcs0 , " SR0_ " , GCS_MAVLINK_Parameters ) ,
2015-12-30 18:57:56 -04:00
2020-12-22 15:43:53 -04:00
# if MAVLINK_COMM_NUM_BUFFERS >= 2
2015-12-30 18:57:56 -04:00
// @Group: SR1_
// @Path: GCS_Mavlink.cpp
2019-06-19 07:32:27 -03:00
GOBJECTN ( _gcs . chan_parameters [ 1 ] , gcs1 , " SR1_ " , GCS_MAVLINK_Parameters ) ,
2020-12-22 15:43:53 -04:00
# endif
2015-12-30 18:57:56 -04:00
2020-12-22 15:43:53 -04:00
# if MAVLINK_COMM_NUM_BUFFERS >= 3
2015-12-30 18:57:56 -04:00
// @Group: SR2_
// @Path: GCS_Mavlink.cpp
2019-06-19 07:32:27 -03:00
GOBJECTN ( _gcs . chan_parameters [ 2 ] , gcs2 , " SR2_ " , GCS_MAVLINK_Parameters ) ,
2020-12-22 15:43:53 -04:00
# endif
2015-12-30 18:57:56 -04:00
2020-12-22 15:43:53 -04:00
# if MAVLINK_COMM_NUM_BUFFERS >= 4
2015-12-30 18:57:56 -04:00
// @Group: SR3_
// @Path: GCS_Mavlink.cpp
2019-06-19 07:32:27 -03:00
GOBJECTN ( _gcs . chan_parameters [ 3 ] , gcs3 , " SR3_ " , GCS_MAVLINK_Parameters ) ,
2020-12-22 15:43:53 -04:00
# endif
# if MAVLINK_COMM_NUM_BUFFERS >= 5
// @Group: SR4_
// @Path: GCS_Mavlink.cpp
GOBJECTN ( _gcs . chan_parameters [ 4 ] , gcs4 , " SR4_ " , GCS_MAVLINK_Parameters ) ,
# endif
# if MAVLINK_COMM_NUM_BUFFERS >= 6
// @Group: SR5_
// @Path: GCS_Mavlink.cpp
GOBJECTN ( _gcs . chan_parameters [ 5 ] , gcs5 , " SR5_ " , GCS_MAVLINK_Parameters ) ,
# endif
# if MAVLINK_COMM_NUM_BUFFERS >= 7
// @Group: SR6_
// @Path: GCS_Mavlink.cpp
GOBJECTN ( _gcs . chan_parameters [ 6 ] , gcs6 , " SR6_ " , GCS_MAVLINK_Parameters ) ,
# endif
2015-12-30 18:57:56 -04:00
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT ( ahrs , " AHRS_ " , AP_AHRS ) ,
2020-07-24 14:30:21 -03:00
# if HAL_MOUNT_ENABLED
2015-12-30 18:57:56 -04:00
// @Group: MNT
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
GOBJECT ( camera_mount , " MNT " , AP_Mount ) ,
# endif
// @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT ( battery , " BATT " , AP_BattMonitor ) ,
2017-02-27 17:12:56 -04:00
// @Group: ARMING_
// @Path: AP_Arming_Sub.cpp,../libraries/AP_Arming/AP_Arming.cpp
GOBJECT ( arming , " ARMING_ " , AP_Arming_Sub ) ,
2015-12-30 18:57:56 -04:00
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT ( BoardConfig , " BRD_ " , AP_BoardConfig ) ,
2020-05-31 08:49:45 -03:00
# if HAL_MAX_CAN_PROTOCOL_DRIVERS
2017-05-06 06:12:08 -03:00
// @Group: CAN_
2020-05-31 08:49:45 -03:00
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
GOBJECT ( can_mgr , " CAN_ " , AP_CANManager ) ,
2017-05-06 06:12:08 -03:00
# endif
2021-10-29 21:37:05 -03:00
# if AP_SIM_ENABLED
2023-01-15 07:20:38 -04:00
// @Group: SIM_
// @Path: ../libraries/SITL/SITL.cpp
2021-07-30 07:09:44 -03:00
GOBJECT ( sitl , " SIM_ " , SITL : : SIM ) ,
2015-12-30 18:57:56 -04:00
# endif
2020-12-03 04:13:33 -04:00
// @Group: BARO
2015-12-30 18:57:56 -04:00
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
2020-12-03 04:13:33 -04:00
GOBJECT ( barometer , " BARO " , AP_Baro ) ,
2015-12-30 18:57:56 -04:00
// GPS driver
2020-12-30 11:01:53 -04:00
// @Group: GPS
2015-12-30 18:57:56 -04:00
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
2020-12-30 11:01:53 -04:00
GOBJECT ( gps , " GPS " , AP_GPS ) ,
2015-12-30 18:57:56 -04:00
2017-02-07 15:43:41 -04:00
// Leak detector
2017-02-07 16:55:11 -04:00
// @Group: LEAK
2017-02-07 15:43:41 -04:00
// @Path: ../libraries/AP_LeakDetector/AP_LeakDetector.cpp
2017-02-03 17:33:27 -04:00
GOBJECT ( leak_detector , " LEAK " , AP_LeakDetector ) ,
2017-02-07 19:47:30 -04:00
2015-12-30 18:57:56 -04:00
// @Group: SCHED_
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
GOBJECT ( scheduler , " SCHED_ " , AP_Scheduler ) ,
2016-12-04 12:49:46 -04:00
# if AVOIDANCE_ENABLED == ENABLED
2017-02-03 17:33:27 -04:00
// @Group: AVOID_
2016-07-05 21:18:58 -03:00
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
GOBJECT ( avoid , " AVOID_ " , AC_Avoid ) ,
2016-12-04 12:49:46 -04:00
# endif
2016-07-05 21:18:58 -03:00
2022-09-21 10:13:20 -03:00
# if HAL_RALLY_ENABLED
2015-12-30 18:57:56 -04:00
// @Group: RALLY_
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
GOBJECT ( rally , " RALLY_ " , AP_Rally ) ,
# endif
2017-02-03 17:33:27 -04:00
// @Group: MOT_
// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp,../libraries/AP_Motors/AP_MotorsMulticopter.cpp
GOBJECT ( motors , " MOT_ " , AP_Motors6DOF ) ,
2017-02-07 18:32:21 -04:00
2016-11-25 19:26:28 -04:00
# if RCMAP_ENABLED == ENABLED
2015-12-30 18:57:56 -04:00
// @Group: RCMAP_
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
GOBJECT ( rcmap , " RCMAP_ " , RCMapper ) ,
2016-11-25 19:26:28 -04:00
# endif
2015-12-30 18:57:56 -04:00
2020-01-15 08:05:58 -04:00
# if HAL_NAVEKF2_AVAILABLE
2015-12-30 18:57:56 -04:00
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
2019-12-10 06:46:02 -04:00
GOBJECTN ( ahrs . EKF2 , NavEKF2 , " EK2_ " , NavEKF2 ) ,
2020-01-15 08:05:58 -04:00
# endif
2017-02-03 17:33:27 -04:00
2020-01-15 08:05:58 -04:00
# if HAL_NAVEKF3_AVAILABLE
2017-01-31 13:06:55 -04:00
// @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
2019-12-10 06:46:02 -04:00
GOBJECTN ( ahrs . EKF3 , NavEKF3 , " EK3_ " , NavEKF3 ) ,
2020-01-15 08:05:58 -04:00
# endif
2017-01-31 13:06:55 -04:00
2015-12-30 18:57:56 -04:00
// @Group: MIS_
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
GOBJECT ( mission , " MIS_ " , AP_Mission ) ,
2017-02-03 17:33:27 -04:00
2023-11-07 18:23:41 -04:00
# if AP_RANGEFINDER_ENABLED
2015-12-30 18:57:56 -04:00
// @Group: RNGFND
2019-11-11 02:41:07 -04:00
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
2016-05-22 21:50:44 -03:00
GOBJECT ( rangefinder , " RNGFND " , RangeFinder ) ,
2024-02-21 16:12:34 -04:00
// @Param: RNGFND_SQ_MIN
// @DisplayName: Rangefinder signal quality minimum
// @Description: Minimum signal quality for good rangefinder readings
// @Range: 0 100
// @User: Advanced
GSCALAR ( rangefinder_signal_min , " RNGFND_SQ_MIN " , RANGEFINDER_SIGNAL_MIN_DEFAULT ) ,
// @Param: SURFTRAK_DEPTH
// @DisplayName: SURFTRAK minimum depth
// @Description: Minimum depth to engage SURFTRAK mode
// @Units: cm
// @User: Standard
GSCALAR ( surftrak_depth , " SURFTRAK_DEPTH " , SURFTRAK_DEPTH_DEFAULT ) ,
2015-12-30 18:57:56 -04:00
# endif
2021-02-12 23:40:10 -04:00
# if AP_TERRAIN_AVAILABLE
2015-12-30 18:57:56 -04:00
// @Group: TERRAIN_
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
GOBJECT ( terrain , " TERRAIN_ " , AP_Terrain ) ,
# endif
2021-12-24 18:05:23 -04:00
# if AP_OPTICALFLOW_ENABLED
2015-12-30 18:57:56 -04:00
// @Group: FLOW
2021-12-23 23:59:00 -04:00
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
2022-08-14 22:31:15 -03:00
GOBJECT ( optflow , " FLOW " , AP_OpticalFlow ) ,
2015-12-30 18:57:56 -04:00
# endif
2022-07-15 20:59:13 -03:00
# if AP_RPM_ENABLED
2015-12-30 18:57:56 -04:00
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT ( rpm_sensor , " RPM " , AP_RPM ) ,
2016-11-25 18:58:31 -04:00
# endif
2015-12-30 18:57:56 -04:00
2017-02-03 17:33:27 -04:00
// @Group: NTF_
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT ( notify , " NTF_ " , AP_Notify ) ,
2016-03-03 02:36:13 -04:00
2017-02-03 17:33:27 -04:00
// @Group:
2016-07-23 02:50:24 -03:00
// @Path: Parameters.cpp
GOBJECT ( g2 , " " , ParametersG2 ) ,
2019-12-19 18:59:38 -04:00
// @Group:
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
2023-01-03 21:39:14 -04:00
PARAM_VEHICLE_INFO ,
2019-12-19 18:59:38 -04:00
2015-12-30 18:57:56 -04:00
AP_VAREND
} ;
2016-07-23 02:50:24 -03:00
/*
2 nd group of parameters
*/
const AP_Param : : GroupInfo ParametersG2 : : var_info [ ] = {
2024-01-30 00:15:47 -04:00
// 1 was AP_Stats
2021-03-25 05:09:38 -03:00
# if HAL_PROXIMITY_ENABLED
2016-11-17 01:12:06 -04:00
// @Group: PRX
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
AP_SUBGROUPINFO ( proximity , " PRX " , 2 , ParametersG2 , AP_Proximity ) ,
# endif
2024-02-21 02:40:36 -04:00
// 3 was AP_Gripper
2016-07-23 02:50:24 -03:00
2017-01-31 13:06:55 -04:00
// @Group: SERVO
2017-02-09 12:14:00 -04:00
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
2017-01-31 13:06:55 -04:00
AP_SUBGROUPINFO ( servo_channels , " SERVO " , 16 , ParametersG2 , SRV_Channels ) ,
// @Group: RC
2018-08-03 23:28:09 -03:00
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
2017-01-31 13:06:55 -04:00
AP_SUBGROUPINFO ( rc_channels , " RC " , 17 , ParametersG2 , RC_Channels ) ,
2024-01-30 00:06:21 -04:00
// 18 was scripting
2019-03-01 02:41:05 -04:00
2022-01-09 21:36:53 -04:00
// 19 was airspeed
2020-07-18 19:01:36 -03:00
2016-07-23 02:50:24 -03:00
AP_GROUPEND
} ;
2016-11-17 01:12:06 -04:00
/*
constructor for g2 object
*/
2022-01-09 21:36:53 -04:00
ParametersG2 : : ParametersG2 ( )
2016-11-17 01:12:06 -04:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
2018-03-01 14:44:02 -04:00
const AP_Param : : ConversionInfo conversion_table [ ] = {
2018-11-05 17:44:37 -04:00
{ Parameters : : k_param_fs_batt_voltage , 0 , AP_PARAM_FLOAT , " BATT_LOW_VOLT " } ,
{ Parameters : : k_param_fs_batt_mah , 0 , AP_PARAM_FLOAT , " BATT_LOW_MAH " } ,
2018-03-01 14:44:02 -04:00
{ Parameters : : k_param_failsafe_battery_enabled , 0 , AP_PARAM_INT8 , " BATT_FS_LOW_ACT " } ,
2019-03-25 05:35:03 -03:00
{ Parameters : : k_param_compass_enabled_deprecated , 0 , AP_PARAM_INT8 , " COMPASS_ENABLE " } ,
2019-04-10 22:58:32 -03:00
{ Parameters : : k_param_arming , 2 , AP_PARAM_INT16 , " ARMING_CHECK " } ,
2018-03-01 14:44:02 -04:00
} ;
2018-06-28 08:09:40 -03:00
void Sub : : load_parameters ( )
2015-12-30 18:57:56 -04:00
{
2024-02-10 00:38:51 -04:00
AP_Vehicle : : load_parameters ( g . format_version , Parameters : : k_format_version ) ;
2018-03-01 14:44:02 -04:00
AP_Param : : convert_old_parameters ( & conversion_table [ 0 ] , ARRAY_SIZE ( conversion_table ) ) ;
2017-01-31 13:06:55 -04:00
2017-02-15 20:06:12 -04:00
AP_Param : : set_frame_type_flags ( AP_PARAM_FRAME_SUB ) ;
2017-01-31 13:06:55 -04:00
convert_old_parameters ( ) ;
2023-07-27 11:07:27 -03:00
AP_Param : : set_defaults_from_table ( defaults_table , ARRAY_SIZE ( defaults_table ) ) ;
2020-01-27 12:07:07 -04:00
// We should ignore this parameter since ROVs are neutral buoyancy
AP_Param : : set_by_name ( " MOT_THST_HOVER " , 0.5 ) ;
2022-01-09 21:36:53 -04:00
2022-03-04 12:36:54 -04:00
// PARAMETER_CONVERSION - Added: Mar-2022
# if AP_FENCE_ENABLED
2024-02-21 17:32:00 -04:00
AP_Param : : convert_class ( g . k_param_fence_old , & fence , fence . var_info , 0 , true ) ;
2022-03-04 12:36:54 -04:00
# endif
2024-01-25 23:05:58 -04:00
2024-02-21 07:32:35 -04:00
static const AP_Param : : G2ObjectConversion g2_conversions [ ] {
# if AP_AIRSPEED_ENABLED
// PARAMETER_CONVERSION - Added: JAN-2022
2024-02-21 17:32:00 -04:00
{ & airspeed , airspeed . var_info , 19 } ,
2024-01-30 00:06:21 -04:00
# endif
2024-02-21 07:32:35 -04:00
# if AP_STATS_ENABLED
2024-01-30 00:06:21 -04:00
// PARAMETER_CONVERSION - Added: Jan-2024
2024-02-21 17:32:00 -04:00
{ & stats , stats . var_info , 1 } ,
2024-02-21 07:32:35 -04:00
# endif
2024-01-30 00:06:21 -04:00
# if AP_SCRIPTING_ENABLED
2024-02-21 07:32:35 -04:00
// PARAMETER_CONVERSION - Added: Jan-2024
2024-02-21 17:32:00 -04:00
{ & scripting , scripting . var_info , 18 } ,
2024-01-25 23:05:58 -04:00
# endif
2024-02-21 02:40:36 -04:00
# if AP_GRIPPER_ENABLED
2024-02-21 07:32:35 -04:00
// PARAMETER_CONVERSION - Added: Feb-2024
2024-02-21 17:32:00 -04:00
{ & gripper , gripper . var_info , 3 } ,
2024-02-21 02:40:36 -04:00
# endif
2024-02-21 07:32:35 -04:00
} ;
AP_Param : : convert_g2_objects ( & g2 , g2_conversions , ARRAY_SIZE ( g2_conversions ) ) ;
2024-02-21 02:40:36 -04:00
2024-02-07 07:21:25 -04:00
// PARAMETER_CONVERSION - Added: Feb-2024
# if HAL_LOGGING_ENABLED
2024-02-21 17:32:00 -04:00
AP_Param : : convert_class ( g . k_param_logger , & logger , logger . var_info , 0 , true ) ;
2024-02-07 07:21:25 -04:00
# endif
2024-02-28 00:57:47 -04:00
static const AP_Param : : TopLevelObjectConversion toplevel_conversions [ ] {
# if AP_SERIALMANAGER_ENABLED
// PARAMETER_CONVERSION - Added: Feb-2024
{ & serial_manager , serial_manager . var_info , Parameters : : k_param_serial_manager_old } ,
# endif
} ;
AP_Param : : convert_toplevel_objects ( toplevel_conversions , ARRAY_SIZE ( toplevel_conversions ) ) ;
2017-01-31 13:06:55 -04:00
}
2018-06-28 08:09:40 -03:00
void Sub : : convert_old_parameters ( )
2017-02-03 17:33:27 -04:00
{
2019-07-16 02:13:36 -03:00
// attitude control filter parameter changes from _FILT to FLTE or FLTD
const AP_Param : : ConversionInfo filt_conversion_info [ ] = {
// move ATC_RAT_RLL/PIT_FILT to FLTD, move ATC_RAT_YAW_FILT to FLTE
{ Parameters : : k_param_attitude_control , 385 , AP_PARAM_FLOAT , " ATC_RAT_RLL_FLTE " } ,
{ Parameters : : k_param_attitude_control , 386 , AP_PARAM_FLOAT , " ATC_RAT_PIT_FLTE " } ,
{ Parameters : : k_param_attitude_control , 387 , AP_PARAM_FLOAT , " ATC_RAT_YAW_FLTE " } ,
} ;
2022-11-20 10:03:23 -04:00
AP_Param : : convert_old_parameters ( & filt_conversion_info [ 0 ] , ARRAY_SIZE ( filt_conversion_info ) ) ;
2019-07-16 02:13:36 -03:00
2020-01-13 00:46:05 -04:00
SRV_Channels : : upgrade_parameters ( ) ;
2015-12-30 18:57:56 -04:00
}