#include "Blimp.h"12/*3This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/1617/*18* Blimp parameter definitions19*20*/2122#define DEFAULT_FRAME_CLASS 02324const AP_Param::Info Blimp::var_info[] = {25// @Param: FORMAT_VERSION26// @DisplayName: Eeprom format version number27// @Description: This value is incremented when changes are made to the eeprom format28// @User: Advanced29GSCALAR(format_version, "FORMAT_VERSION", 0),3031// SYSID_THISMAV was here3233// SYSID_MYGCS was here3435// @Param: PILOT_THR_FILT36// @DisplayName: Throttle filter cutoff37// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable38// @User: Advanced39// @Units: Hz40// @Range: 0 1041// @Increment: 0.542GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),4344// @Param: PILOT_THR_BHV45// @DisplayName: Throttle stick behavior46// @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.47// @User: Standard48// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection49GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),5051// SerialManager was here5253// @Param: GCS_PID_MASK54// @DisplayName: GCS PID tuning mask55// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for56// @User: Advanced57// @Bitmask: 0:VELX,1:VELY,2:VELZ,3:VELYAW,4:POSX,5:POSY,6:POZ,7:POSYAW58GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),5960// @Param: FS_GCS_ENABLE61// @DisplayName: Ground Station Failsafe Enable62// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.63// @Values: 0:Disabled/NoAction,5:Land64// @User: Standard65GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),6667// @Param: GPS_HDOP_GOOD68// @DisplayName: GPS Hdop Good69// @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks70// @Range: 100 90071// @User: Advanced72GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),7374// @Param: FS_THR_ENABLE75// @DisplayName: Throttle Failsafe Enable76// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel77// @Values: 0:Disabled,3:Enabled always Land78// @User: Standard79GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL),8081// @Param: FS_THR_VALUE82// @DisplayName: Throttle Failsafe Value83// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers84// @Range: 910 110085// @Units: PWM86// @Increment: 187// @User: Standard88GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),8990// @Param: THR_DZ91// @DisplayName: Throttle deadzone92// @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes93// @User: Standard94// @Range: 0 30095// @Units: PWM96// @Increment: 197GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),9899// @Param: FLTMODE1100// @DisplayName: Flight Mode 1101// @Description: Flight mode when Channel 5 pwm is <= 1230102// @Values: 0:LAND,1:MANUAL,2:VELOCITY,3:LOITER103// @User: Standard104GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),105106// @Param: FLTMODE2107// @CopyFieldsFrom: FLTMODE1108// @DisplayName: Flight Mode 2109// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360110GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),111112// @Param: FLTMODE3113// @CopyFieldsFrom: FLTMODE1114// @DisplayName: Flight Mode 3115// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490116GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),117118// @Param: FLTMODE4119// @CopyFieldsFrom: FLTMODE1120// @DisplayName: Flight Mode 4121// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620122GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),123124// @Param: FLTMODE5125// @CopyFieldsFrom: FLTMODE1126// @DisplayName: Flight Mode 5127// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749128GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),129130// @Param: FLTMODE6131// @CopyFieldsFrom: FLTMODE1132// @DisplayName: Flight Mode 6133// @Description: Flight mode when Channel 5 pwm is >=1750134GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),135136// @Param: FLTMODE_CH137// @DisplayName: Flightmode channel138// @Description: RC Channel to use for flight mode control139// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8140// @User: Advanced141GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT),142143// @Param: INITIAL_MODE144// @DisplayName: Initial flight mode145// @Description: This selects the mode to start in on boot.146// @CopyValuesFrom: FLTMODE1147// @User: Advanced148GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)Mode::Number::MANUAL),149150// @Param: LOG_BITMASK151// @DisplayName: Log bitmask152// @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535.153// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,6:RC Input,7:IMU,9:Battery Monitor,10:RC Output,12:PID,13:Compass154// @User: Standard155GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),156157// @Group: ARMING_158// @Path: ../libraries/AP_Arming/AP_Arming.cpp159GOBJECT(arming, "ARMING_", AP_Arming_Blimp),160161// @Param: DISARM_DELAY162// @DisplayName: Disarm delay163// @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm.164// @Units: s165// @Range: 0 127166// @User: Advanced167GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),168169// @Param: FS_EKF_ACTION170// @DisplayName: EKF Failsafe Action171// @Description: Controls the action that will be taken when an EKF failsafe is invoked172// @Values: 1:Land, 3:Land even in MANUAL173// @User: Advanced174GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),175176// @Param: FS_EKF_THRESH177// @DisplayName: EKF failsafe variance threshold178// @Description: Allows setting the maximum acceptable compass and velocity variance179// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed180// @Range: 0.6 1.0181// @User: Advanced182GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),183184// @Param: FS_CRASH_CHECK185// @DisplayName: Crash check enable186// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.187// @Values: 0:Disabled, 1:Enabled188// @User: Advanced189GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 1),190191// @Param: MAX_VEL_XY192// @DisplayName: Max XY Velocity193// @Description: Sets the maximum XY velocity, in m/s194// @Range: 0.2 5195// @User: Standard196GSCALAR(max_vel_xy, "MAX_VEL_XY", 0.5),197198// @Param: MAX_VEL_Z199// @DisplayName: Max Z Velocity200// @Description: Sets the maximum Z velocity, in m/s201// @Range: 0.2 5202// @User: Standard203GSCALAR(max_vel_z, "MAX_VEL_Z", 0.4),204205// @Param: MAX_VEL_YAW206// @DisplayName: Max yaw Velocity207// @Description: Sets the maximum yaw velocity, in rad/s208// @Range: 0.2 5209// @User: Standard210GSCALAR(max_vel_yaw, "MAX_VEL_YAW", 0.5),211212// @Param: MAX_POS_XY213// @DisplayName: Max XY Position change214// @Description: Sets the maximum XY position change, in m/s215// @Range: 0.1 5216// @User: Standard217GSCALAR(max_pos_xy, "MAX_POS_XY", 0.2),218219// @Param: MAX_POS_Z220// @DisplayName: Max Z Position change221// @Description: Sets the maximum Z position change, in m/s222// @Range: 0.1 5223// @User: Standard224GSCALAR(max_pos_z, "MAX_POS_Z", 0.15),225226// @Param: MAX_POS_YAW227// @DisplayName: Max Yaw Position change228// @Description: Sets the maximum Yaw position change, in rad/s229// @Range: 0.1 5230// @User: Standard231GSCALAR(max_pos_yaw, "MAX_POS_YAW", 0.3),232233// @Param: SIMPLE_MODE234// @DisplayName: Simple mode235// @Description: Simple mode for Position control - "forward" moves blimp in +ve X direction world-frame236// @Values: 0:Disabled, 1:Enabled237// @User: Standard238GSCALAR(simple_mode, "SIMPLE_MODE", 0),239240// @Param: DIS_MASK241// @DisplayName: Disable output mask242// @Description: Mask for disabling (setting to zero) one or more of the 4 output axis in mode Velocity or Loiter243// @Bitmask: 0:Right,1:Front,2:Down,3:Yaw244// @User: Standard245GSCALAR(dis_mask, "DIS_MASK", 0),246247// @Param: PID_DZ248// @DisplayName: Deadzone for the position PIDs249// @Description: Output 0 thrust signal when blimp is within this distance (in meters) of the target position. Warning: If this param is greater than MAX_POS_XY param then the blimp won't move at all in the XY plane in Loiter mode as it does not allow more than a second's lag. Same for the other axes.250// @Units: m251// @Range: 0.1 1252// @User: Standard253GSCALAR(pid_dz, "PID_DZ", 0),254255// @Param: RC_SPEED256// @DisplayName: ESC Update Speed257// @Description: This is the speed in Hertz that your ESCs will receive updates258// @Units: Hz259// @Range: 50 490260// @Increment: 1261// @User: Advanced262GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),263264// variables not in the g class which contain EEPROM saved variables265266// @Group: COMPASS_267// @Path: ../libraries/AP_Compass/AP_Compass.cpp268GOBJECT(compass, "COMPASS_", Compass),269270// @Group: INS271// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp272GOBJECT(ins, "INS", AP_InertialSensor),273274// SR0 through SR6 was here275276// @Group: AHRS_277// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp278GOBJECT(ahrs, "AHRS_", AP_AHRS),279280// @Group: BATT281// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp282GOBJECT(battery, "BATT", AP_BattMonitor),283284// @Group: BRD_285// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp286GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),287288#if HAL_MAX_CAN_PROTOCOL_DRIVERS289// @Group: CAN_290// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp291GOBJECT(can_mgr, "CAN_", AP_CANManager),292#endif293294#if AP_SIM_ENABLED295GOBJECT(sitl, "SIM_", SITL::SIM),296#endif297298// @Group: BARO299// @Path: ../libraries/AP_Baro/AP_Baro.cpp300GOBJECT(barometer, "BARO", AP_Baro),301302// GPS driver303// @Group: GPS304// @Path: ../libraries/AP_GPS/AP_GPS.cpp305GOBJECT(gps, "GPS", AP_GPS),306307// @Group: SCHED_308// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp309GOBJECT(scheduler, "SCHED_", AP_Scheduler),310311// @Group: RCMAP_312// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp313GOBJECT(rcmap, "RCMAP_", RCMapper),314315#if HAL_NAVEKF2_AVAILABLE316// @Group: EK2_317// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp318GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),319#endif320321#if HAL_NAVEKF3_AVAILABLE322// @Group: EK3_323// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp324GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),325#endif326327#if AP_RSSI_ENABLED328// @Group: RSSI_329// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp330GOBJECT(rssi, "RSSI_", AP_RSSI),331#endif332333// @Group: NTF_334// @Path: ../libraries/AP_Notify/AP_Notify.cpp335GOBJECT(notify, "NTF_", AP_Notify),336337// @Group:338// @Path: Parameters.cpp339GOBJECT(g2, "", ParametersG2),340341// @Group: FINS_342// @Path: Fins.cpp343GOBJECTPTR(motors, "FINS_", Fins),344345// @Param: VELXY_P346// @DisplayName: Velocity (horizontal) P gain347// @Description: Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration348// @Range: 0.1 6.0349// @Increment: 0.1350// @User: Advanced351352// @Param: VELXY_I353// @DisplayName: Velocity (horizontal) I gain354// @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration355// @Range: 0.02 1.00356// @Increment: 0.01357// @User: Advanced358359// @Param: VELXY_D360// @DisplayName: Velocity (horizontal) D gain361// @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity362// @Range: 0.00 1.00363// @Increment: 0.001364// @User: Advanced365366// @Param: VELXY_IMAX367// @DisplayName: Velocity (horizontal) integrator maximum368// @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output369// @Range: 0 4500370// @Increment: 10371// @Units: cm/s/s372// @User: Advanced373374// @Param: VELXY_FLTE375// @DisplayName: Velocity (horizontal) input filter376// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms377// @Range: 0 100378// @Units: Hz379// @User: Advanced380381// @Param: VELXY_FLTD382// @DisplayName: Velocity (horizontal) input filter383// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term384// @Range: 0 100385// @Units: Hz386// @User: Advanced387388// @Param: VELXY_FF389// @DisplayName: Velocity (horizontal) feed forward gain390// @Description: Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration391// @Range: 0 6392// @Increment: 0.01393// @User: Advanced394GOBJECT(pid_vel_xy, "VELXY_", AC_PID_2D),395396// @Param: VELZ_P397// @DisplayName: Velocity (vertical) P gain398// @Description: Velocity (vertical) P gain. Converts the difference between desired and actual velocity to a target acceleration399// @Range: 0.1 6.0400// @Increment: 0.1401// @User: Advanced402403// @Param: VELZ_I404// @DisplayName: Velocity (vertical) I gain405// @Description: Velocity (vertical) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration406// @Range: 0.02 1.00407// @Increment: 0.01408// @User: Advanced409410// @Param: VELZ_D411// @DisplayName: Velocity (vertical) D gain412// @Description: Velocity (vertical) D gain. Corrects short-term changes in velocity413// @Range: 0.00 1.00414// @Increment: 0.001415// @User: Advanced416417// @Param: VELZ_IMAX418// @DisplayName: Velocity (vertical) integrator maximum419// @Description: Velocity (vertical) integrator maximum. Constrains the target acceleration that the I gain will output420// @Range: 0 4500421// @Increment: 10422// @Units: cm/s/s423// @User: Advanced424425// @Param: VELZ_FLTE426// @DisplayName: Velocity (vertical) input filter427// @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms428// @Range: 0 100429// @Units: Hz430// @User: Advanced431432// @Param: VELZ_FLTD433// @DisplayName: Velocity (vertical) input filter434// @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for D term435// @Range: 0 100436// @Units: Hz437// @User: Advanced438439// @Param: VELZ_FF440// @DisplayName: Velocity (vertical) feed forward gain441// @Description: Velocity (vertical) feed forward gain. Converts the difference between desired velocity to a target acceleration442// @Range: 0 6443// @Increment: 0.01444// @User: Advanced445GOBJECT(pid_vel_z, "VELZ_", AC_PID_Basic),446447// @Param: VELYAW_P448// @DisplayName: Velocity (yaw) P gain449// @Description: Velocity (yaw) P gain. Converts the difference between desired and actual velocity to a target acceleration450// @Range: 0.1 6.0451// @Increment: 0.1452// @User: Advanced453454// @Param: VELYAW_I455// @DisplayName: Velocity (yaw) I gain456// @Description: Velocity (yaw) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration457// @Range: 0.02 1.00458// @Increment: 0.01459// @User: Advanced460461// @Param: VELYAW_D462// @DisplayName: Velocity (yaw) D gain463// @Description: Velocity (yaw) D gain. Corrects short-term changes in velocity464// @Range: 0.00 1.00465// @Increment: 0.001466// @User: Advanced467468// @Param: VELYAW_IMAX469// @DisplayName: Velocity (yaw) integrator maximum470// @Description: Velocity (yaw) integrator maximum. Constrains the target acceleration that the I gain will output471// @Range: 0 4500472// @Increment: 10473// @Units: cm/s/s474// @User: Advanced475476// @Param: VELYAW_FLTE477// @DisplayName: Velocity (yaw) input filter478// @Description: Velocity (yaw) input filter. This filter (in Hz) is applied to the input for P and I terms479// @Range: 0 100480// @Units: Hz481// @User: Advanced482483// @Param: VELYAW_FF484// @DisplayName: Velocity (yaw) feed forward gain485// @Description: Velocity (yaw) feed forward gain. Converts the difference between desired velocity to a target acceleration486// @Range: 0 6487// @Increment: 0.01488// @User: Advanced489GOBJECT(pid_vel_yaw, "VELYAW_", AC_PID_Basic),490491// @Param: POSXY_P492// @DisplayName: Position (horizontal) P gain493// @Description: Position (horizontal) P gain. Converts the difference between desired and actual position to a target velocity494// @Range: 0.1 6.0495// @Increment: 0.1496// @User: Advanced497498// @Param: POSXY_I499// @DisplayName: Position (horizontal) I gain500// @Description: Position (horizontal) I gain. Corrects long-term difference between desired and actual position to a target velocity501// @Range: 0.02 1.00502// @Increment: 0.01503// @User: Advanced504505// @Param: POSXY_D506// @DisplayName: Position (horizontal) D gain507// @Description: Position (horizontal) D gain. Corrects short-term changes in position508// @Range: 0.00 1.00509// @Increment: 0.001510// @User: Advanced511512// @Param: POSXY_IMAX513// @DisplayName: Position (horizontal) integrator maximum514// @Description: Position (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output515// @Range: 0 4500516// @Increment: 10517// @Units: cm/s/s518// @User: Advanced519520// @Param: POSXY_FLTE521// @DisplayName: Position (horizontal) input filter522// @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms523// @Range: 0 100524// @Units: Hz525// @User: Advanced526527// @Param: POSXY_FLTD528// @DisplayName: Position (horizontal) input filter529// @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for D term530// @Range: 0 100531// @Units: Hz532// @User: Advanced533534// @Param: POSXY_FF535// @DisplayName: Position (horizontal) feed forward gain536// @Description: Position (horizontal) feed forward gain. Converts the difference between desired position to a target velocity537// @Range: 0 6538// @Increment: 0.01539// @User: Advanced540GOBJECT(pid_pos_xy, "POSXY_", AC_PID_2D),541542// @Param: POSZ_P543// @DisplayName: Position (vertical) P gain544// @Description: Position (vertical) P gain. Converts the difference between desired and actual position to a target velocity545// @Range: 0.1 6.0546// @Increment: 0.1547// @User: Advanced548549// @Param: POSZ_I550// @DisplayName: Position (vertical) I gain551// @Description: Position (vertical) I gain. Corrects long-term difference between desired and actual position to a target velocity552// @Range: 0.02 1.00553// @Increment: 0.01554// @User: Advanced555556// @Param: POSZ_D557// @DisplayName: Position (vertical) D gain558// @Description: Position (vertical) D gain. Corrects short-term changes in position559// @Range: 0.00 1.00560// @Increment: 0.001561// @User: Advanced562563// @Param: POSZ_IMAX564// @DisplayName: Position (vertical) integrator maximum565// @Description: Position (vertical) integrator maximum. Constrains the target acceleration that the I gain will output566// @Range: 0 4500567// @Increment: 10568// @Units: cm/s/s569// @User: Advanced570571// @Param: POSZ_FLTE572// @DisplayName: Position (vertical) input filter573// @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms574// @Range: 0 100575// @Units: Hz576// @User: Advanced577578// @Param: POSZ_FLTD579// @DisplayName: Position (vertical) input filter580// @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for D term581// @Range: 0 100582// @Units: Hz583// @User: Advanced584585// @Param: POSZ_FF586// @DisplayName: Position (vertical) feed forward gain587// @Description: Position (vertical) feed forward gain. Converts the difference between desired position to a target velocity588// @Range: 0 6589// @Increment: 0.01590// @User: Advanced591GOBJECT(pid_pos_z, "POSZ_", AC_PID_Basic),592593// @Param: POSYAW_P594// @DisplayName: Position (yaw) axis controller P gain595// @Description: Position (yaw) axis controller P gain.596// @Range: 0.0 3.0597// @Increment: 0.01598// @User: Standard599600// @Param: POSYAW_I601// @DisplayName: Position (yaw) axis controller I gain602// @Description: Position (yaw) axis controller I gain.603// @Range: 0.0 3.0604// @Increment: 0.01605// @User: Standard606607// @Param: POSYAW_IMAX608// @DisplayName: Position (yaw) axis controller I gain maximum609// @Description: Position (yaw) axis controller I gain maximum.610// @Range: 0 4000611// @Increment: 10612// @Units: d%613// @User: Standard614615// @Param: POSYAW_D616// @DisplayName: Position (yaw) axis controller D gain617// @Description: Position (yaw) axis controller D gain.618// @Range: 0.001 0.1619// @Increment: 0.001620// @User: Standard621622// @Param: POSYAW_FF623// @DisplayName: Position (yaw) axis controller feed forward624// @Description: Position (yaw) axis controller feed forward625// @Range: 0 0.5626// @Increment: 0.001627// @User: Standard628629// @Param: POSYAW_FLTT630// @DisplayName: Position (yaw) target frequency filter in Hz631// @Description: Position (yaw) target frequency filter in Hz632// @Range: 1 50633// @Increment: 1634// @Units: Hz635// @User: Standard636637// @Param: POSYAW_FLTE638// @DisplayName: Position (yaw) error frequency filter in Hz639// @Description: Position (yaw) error frequency filter in Hz640// @Range: 1 100641// @Increment: 1642// @Units: Hz643// @User: Standard644645// @Param: POSYAW_FLTD646// @DisplayName: Position (yaw) derivative input filter in Hz647// @Description: Position (yaw) derivative input filter in Hz648// @Range: 1 100649// @Increment: 1650// @Units: Hz651// @User: Standard652653// @Param: POSYAW_SMAX654// @DisplayName: Yaw slew rate limit655// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains.656// @Range: 0 200657// @Increment: 0.5658// @User: Advanced659660// @Param: POSYAW_PDMX661// @DisplayName: Position (yaw) axis controller PD sum maximum662// @Description: Position (yaw) axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output663// @Range: 0 4000664// @Increment: 10665// @Units: d%666// @User: Advanced667668// @Param: POSYAW_D_FF669// @DisplayName: Position (yaw) Derivative FeedForward Gain670// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target671// @Range: 0 0.1672// @Increment: 0.001673// @User: Advanced674675// @Param: POSYAW_NTF676// @DisplayName: Position (yaw) Target notch filter index677// @Description: Position (yaw) Target notch filter index678// @Range: 1 8679// @User: Advanced680681// @Param: POSYAW_NEF682// @DisplayName: Position (yaw) Error notch filter index683// @Description: Position (yaw) Error notch filter index684// @Range: 1 8685// @User: Advanced686687GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID),688689// @Group:690// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp691PARAM_VEHICLE_INFO,692693#if HAL_GCS_ENABLED694// @Group: MAV695// @Path: ../libraries/GCS_MAVLink/GCS.cpp696GOBJECT(_gcs, "MAV", GCS),697#endif698699AP_VAREND700};701702/*7032nd group of parameters704*/705const AP_Param::GroupInfo ParametersG2::var_info[] = {706707// @Param: DEV_OPTIONS708// @DisplayName: Development options709// @Description: Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning710// @Bitmask: 0:Unknown711// @User: Advanced712AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),713714// 11 was SYSID_ENFORCE715716// 12 was AP_Stats717718// @Param: FRAME_CLASS719// @DisplayName: Frame Class720// @Description: Controls major frame class for blimp.721// @Values: 0:Finnedblimp722// @User: Standard723// @RebootRequired: True724AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, DEFAULT_FRAME_CLASS),725726// @Group: SERVO727// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp728AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),729730// @Group: RC731// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h732AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Blimp),733734// @Param: PILOT_SPEED_DN735// @DisplayName: Pilot maximum vertical speed descending736// @Description: The maximum vertical descending velocity the pilot may request in cm/s737// @Units: cm/s738// @Range: 50 500739// @Increment: 10740// @User: Standard741AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn, 0),742743// 30 was AP_Scripting744745// @Param: FS_VIBE_ENABLE746// @DisplayName: Vibration Failsafe enable747// @Description: This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations748// @Values: 0:Disabled, 1:Enabled749// @User: Standard750AP_GROUPINFO("FS_VIBE_ENABLE", 35, ParametersG2, fs_vibe_enabled, 1),751752// @Param: FS_OPTIONS753// @DisplayName: Failsafe options bitmask754// @Description: Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.755// @Bitmask: 4:Continue if in pilot controlled modes on GCS failsafe756// @User: Advanced757AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Blimp::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL),758759// @Param: FS_GCS_TIMEOUT760// @DisplayName: GCS failsafe timeout761// @Description: Timeout before triggering the GCS failsafe762// @Units: s763// @Range: 2 120764// @Increment: 1765// @User: Standard766AP_GROUPINFO("FS_GCS_TIMEOUT", 42, ParametersG2, fs_gcs_timeout, 5),767768AP_GROUPEND769};770771/*772constructor for g2 object773*/774ParametersG2::ParametersG2(void)775{776AP_Param::setup_object_defaults(this, var_info);777}778779void Blimp::load_parameters(void)780{781AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);782783static const AP_Param::G2ObjectConversion g2_conversions[] {784#if AP_STATS_ENABLED785// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6786{ &stats, stats.var_info, 12 },787#endif788#if AP_SCRIPTING_ENABLED789// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6790{ &scripting, scripting.var_info, 30 },791#endif792};793AP_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));808809// setup AP_Param frame type flags810AP_Param::set_frame_type_flags(AP_PARAM_FRAME_BLIMP);811812#if HAL_GCS_ENABLED813// Move parameters into new MAV_ parameter namespace814// PARAMETER_CONVERSION - Added: Mar-2025 for ArduPilot-4.7815{816static const AP_Param::ConversionInfo gcs_conversion_info[] {817{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },818{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },819{ Parameters::k_param_g2, 11, AP_PARAM_INT8, "MAV_OPTIONS" },820{ Parameters::k_param_telem_delay_old, 0, AP_PARAM_INT8, "MAV_TELEM_DELAY" },821};822AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));823}824#endif // HAL_GCS_ENABLED825826}827828829