2021-03-18 00:12:54 -03:00
# include "Blimp.h"
/*
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/>.
*/
/*
* Blimp parameter definitions
*
*/
# define DEFAULT_FRAME_CLASS 0
const AP_Param : : Info Blimp : : var_info [ ] = {
// @Param: FORMAT_VERSION
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
// @ReadOnly: True
GSCALAR ( format_version , " FORMAT_VERSION " , 0 ) ,
// @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
// @Range: 1 255
2023-11-25 00:53:34 -04:00
// @Increment: 1
2021-03-18 00:12:54 -03: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 ) ,
// @Param: PILOT_THR_BHV
// @DisplayName: Throttle stick behavior
// @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.
// @User: Standard
// @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
GSCALAR ( throttle_behavior , " PILOT_THR_BHV " , 0 ) ,
// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
GOBJECT ( serial_manager , " SERIAL " , AP_SerialManager ) ,
// @Param: TELEM_DELAY
// @DisplayName: Telemetry startup delay
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
// @User: Advanced
// @Units: s
// @Range: 0 30
// @Increment: 1
2021-06-17 04:03:49 -03:00
GSCALAR ( telem_delay , " TELEM_DELAY " , 0 ) ,
2021-03-18 00:12:54 -03:00
// @Param: GCS_PID_MASK
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
2021-06-23 23:26:56 -03:00
// @Values: 0:None,1:VELX,2:VELY,4:VELZ,8:VELYAW,16:POSX,32:POSY,64:POSZ,128:POSYAW,15:Vel only,51:XY only,204:ZYaw only,240:Pos only,255:All
2021-10-18 11:06:51 -03:00
// @Bitmask: 0:VELX,1:VELY,2:VELZ,3:VELYAW,4:POSX,5:POSY,6:POZ,7:POSYAW
2021-06-23 23:26:56 -03:00
GSCALAR ( gcs_pid_mask , " GCS_PID_MASK " , 0 ) ,
2021-03-18 00:12:54 -03:00
// @Param: FS_GCS_ENABLE
// @DisplayName: Ground Station Failsafe Enable
// @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.
2022-03-26 19:15:21 -03:00
// @Values: 0:Disabled/NoAction,5:Land
2021-03-18 00:12:54 -03:00
// @User: Standard
GSCALAR ( failsafe_gcs , " FS_GCS_ENABLE " , FS_GCS_DISABLED ) ,
// @Param: GPS_HDOP_GOOD
// @DisplayName: GPS Hdop Good
// @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks
// @Range: 100 900
// @User: Advanced
GSCALAR ( gps_hdop_good , " GPS_HDOP_GOOD " , GPS_HDOP_GOOD_DEFAULT ) ,
// @Param: FS_THR_ENABLE
// @DisplayName: Throttle Failsafe Enable
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
2022-03-26 19:15:21 -03:00
// @Values: 0:Disabled,3:Enabled always Land
2021-03-18 00:12:54 -03:00
// @User: Standard
GSCALAR ( failsafe_throttle , " FS_THR_ENABLE " , FS_THR_ENABLED_ALWAYS_RTL ) ,
// @Param: FS_THR_VALUE
// @DisplayName: Throttle Failsafe Value
// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers
// @Range: 910 1100
// @Units: PWM
// @Increment: 1
// @User: Standard
GSCALAR ( failsafe_throttle_value , " FS_THR_VALUE " , FS_THR_VALUE_DEFAULT ) ,
// @Param: THR_DZ
// @DisplayName: Throttle deadzone
// @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
// @User: Standard
// @Range: 0 300
// @Units: PWM
// @Increment: 1
GSCALAR ( throttle_deadzone , " THR_DZ " , THR_DZ_DEFAULT ) ,
// @Param: FLTMODE1
// @DisplayName: Flight Mode 1
// @Description: Flight mode when Channel 5 pwm is <= 1230
2022-03-26 19:15:21 -03:00
// @Values: 0:LAND,1:MANUAL,2:VELOCITY,3:LOITER
2021-03-18 00:12:54 -03:00
// @User: Standard
GSCALAR ( flight_mode1 , " FLTMODE1 " , ( uint8_t ) FLIGHT_MODE_1 ) ,
// @Param: FLTMODE2
2022-12-29 22:10:57 -04:00
// @CopyFieldsFrom: FLTMODE1
2021-03-18 00:12:54 -03:00
// @DisplayName: Flight Mode 2
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
GSCALAR ( flight_mode2 , " FLTMODE2 " , ( uint8_t ) FLIGHT_MODE_2 ) ,
// @Param: FLTMODE3
2022-12-29 22:10:57 -04:00
// @CopyFieldsFrom: FLTMODE1
2021-03-18 00:12:54 -03:00
// @DisplayName: Flight Mode 3
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
GSCALAR ( flight_mode3 , " FLTMODE3 " , ( uint8_t ) FLIGHT_MODE_3 ) ,
// @Param: FLTMODE4
2022-12-29 22:10:57 -04:00
// @CopyFieldsFrom: FLTMODE1
2021-03-18 00:12:54 -03:00
// @DisplayName: Flight Mode 4
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
GSCALAR ( flight_mode4 , " FLTMODE4 " , ( uint8_t ) FLIGHT_MODE_4 ) ,
// @Param: FLTMODE5
2022-12-29 22:10:57 -04:00
// @CopyFieldsFrom: FLTMODE1
2021-03-18 00:12:54 -03:00
// @DisplayName: Flight Mode 5
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
GSCALAR ( flight_mode5 , " FLTMODE5 " , ( uint8_t ) FLIGHT_MODE_5 ) ,
// @Param: FLTMODE6
2022-12-29 22:10:57 -04:00
// @CopyFieldsFrom: FLTMODE1
2021-03-18 00:12:54 -03:00
// @DisplayName: Flight Mode 6
// @Description: Flight mode when Channel 5 pwm is >=1750
GSCALAR ( flight_mode6 , " FLTMODE6 " , ( uint8_t ) FLIGHT_MODE_6 ) ,
// @Param: FLTMODE_CH
// @DisplayName: Flightmode channel
// @Description: RC Channel to use for flight mode control
// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8
// @User: Advanced
GSCALAR ( flight_mode_chan , " FLTMODE_CH " , CH_MODE_DEFAULT ) ,
// @Param: INITIAL_MODE
// @DisplayName: Initial flight mode
2022-03-26 19:15:21 -03:00
// @Description: This selects the mode to start in on boot.
2021-12-14 00:57:22 -04:00
// @CopyValuesFrom: FLTMODE1
2021-03-18 00:12:54 -03:00
// @User: Advanced
GSCALAR ( initial_mode , " INITIAL_MODE " , ( uint8_t ) Mode : : Number : : MANUAL ) ,
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
2022-08-08 12:45:14 -03:00
// @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.
2023-07-27 02:06:32 -03:00
// @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:Compass
2021-03-18 00:12:54 -03:00
// @User: Standard
GSCALAR ( log_bitmask , " LOG_BITMASK " , DEFAULT_LOG_BITMASK ) ,
// @Group: ARMING_
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
GOBJECT ( arming , " ARMING_ " , AP_Arming_Blimp ) ,
// @Param: DISARM_DELAY
// @DisplayName: Disarm delay
// @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm.
// @Units: s
// @Range: 0 127
// @User: Advanced
GSCALAR ( disarm_delay , " DISARM_DELAY " , AUTO_DISARMING_DELAY ) ,
// @Param: FS_EKF_ACTION
// @DisplayName: EKF Failsafe Action
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
2022-03-26 19:15:21 -03:00
// @Values: 1:Land, 3:Land even in MANUAL
2021-03-18 00:12:54 -03: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.
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
GSCALAR ( fs_crash_check , " FS_CRASH_CHECK " , 1 ) ,
2021-06-18 01:40:01 -03:00
// @Param: MAX_VEL_XY
// @DisplayName: Max XY Velocity
// @Description: Sets the maximum XY velocity, in m/s
2021-06-22 03:36:11 -03:00
// @Range: 0.2 5
2021-06-18 01:40:01 -03:00
// @User: Standard
GSCALAR ( max_vel_xy , " MAX_VEL_XY " , 0.5 ) ,
// @Param: MAX_VEL_Z
// @DisplayName: Max Z Velocity
// @Description: Sets the maximum Z velocity, in m/s
2021-06-22 03:36:11 -03:00
// @Range: 0.2 5
2021-06-18 01:40:01 -03:00
// @User: Standard
GSCALAR ( max_vel_z , " MAX_VEL_Z " , 0.4 ) ,
2021-06-22 03:36:11 -03:00
2021-06-18 01:40:01 -03:00
// @Param: MAX_VEL_YAW
// @DisplayName: Max yaw Velocity
// @Description: Sets the maximum yaw velocity, in rad/s
2021-06-22 03:36:11 -03:00
// @Range: 0.2 5
2021-06-18 01:40:01 -03:00
// @User: Standard
GSCALAR ( max_vel_yaw , " MAX_VEL_YAW " , 0.5 ) ,
// @Param: MAX_POS_XY
// @DisplayName: Max XY Position change
// @Description: Sets the maximum XY position change, in m/s
2021-06-22 03:36:11 -03:00
// @Range: 0.1 5
2021-06-18 01:40:01 -03:00
// @User: Standard
GSCALAR ( max_pos_xy , " MAX_POS_XY " , 0.2 ) ,
// @Param: MAX_POS_Z
// @DisplayName: Max Z Position change
// @Description: Sets the maximum Z position change, in m/s
2021-06-22 03:36:11 -03:00
// @Range: 0.1 5
2021-06-18 01:40:01 -03:00
// @User: Standard
GSCALAR ( max_pos_z , " MAX_POS_Z " , 0.15 ) ,
// @Param: MAX_POS_YAW
// @DisplayName: Max Yaw Position change
// @Description: Sets the maximum Yaw position change, in rad/s
2021-06-22 03:36:11 -03:00
// @Range: 0.1 5
2021-06-18 01:40:01 -03:00
// @User: Standard
GSCALAR ( max_pos_yaw , " MAX_POS_YAW " , 0.3 ) ,
// @Param: SIMPLE_MODE
// @DisplayName: Simple mode
// @Description: Simple mode for Position control - "forward" moves blimp in +ve X direction world-frame
// @Values: 0:Disabled, 1:Enabled
// @User: Standard
GSCALAR ( simple_mode , " SIMPLE_MODE " , 0 ) ,
// @Param: DIS_MASK
// @DisplayName: Disable output mask
2023-07-27 02:06:32 -03:00
// @Description: Mask for disabling (setting to zero) one or more of the 4 output axis in mode Velocity or Loiter
2021-06-18 01:40:01 -03:00
// @Values: 0:All enabled,1:Right,2:Front,4:Down,8:Yaw,3:Down and Yaw only,12:Front & Right only
// @Bitmask: 0:Right,1:Front,2:Down,3:Yaw
// @User: Standard
GSCALAR ( dis_mask , " DIS_MASK " , 0 ) ,
2023-07-27 02:03:08 -03:00
// @Param: PID_DZ
// @DisplayName: Deadzone for the position PIDs
// @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.
// @Units: m
// @Range: 0.1 1
// @User: Standard
GSCALAR ( pid_dz , " PID_DZ " , 0 ) ,
2021-03-18 00:12:54 -03: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
GSCALAR ( rc_speed , " RC_SPEED " , RC_FAST_SPEED ) ,
// variables not in the g class which contain EEPROM saved variables
2021-12-04 00:22:56 -04:00
// @Group: COMPASS_
2021-03-18 00:12:54 -03:00
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
2021-12-04 00:22:56 -04:00
GOBJECT ( compass , " COMPASS_ " , Compass ) ,
2021-03-18 00:12:54 -03:00
2023-03-08 06:39:51 -04:00
// @Group: INS
2021-03-18 00:12:54 -03:00
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
2023-03-08 06:39:51 -04:00
GOBJECT ( ins , " INS " , AP_InertialSensor ) ,
2021-03-18 00:12:54 -03:00
// @Group: SR0_
// @Path: GCS_Mavlink.cpp
GOBJECTN ( _gcs . chan_parameters [ 0 ] , gcs0 , " SR0_ " , GCS_MAVLINK_Parameters ) ,
# if MAVLINK_COMM_NUM_BUFFERS >= 2
// @Group: SR1_
// @Path: GCS_Mavlink.cpp
GOBJECTN ( _gcs . chan_parameters [ 1 ] , gcs1 , " SR1_ " , GCS_MAVLINK_Parameters ) ,
# endif
# if MAVLINK_COMM_NUM_BUFFERS >= 3
// @Group: SR2_
// @Path: GCS_Mavlink.cpp
GOBJECTN ( _gcs . chan_parameters [ 2 ] , gcs2 , " SR2_ " , GCS_MAVLINK_Parameters ) ,
# endif
# if MAVLINK_COMM_NUM_BUFFERS >= 4
// @Group: SR3_
// @Path: GCS_Mavlink.cpp
GOBJECTN ( _gcs . chan_parameters [ 3 ] , gcs3 , " SR3_ " , GCS_MAVLINK_Parameters ) ,
# 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
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT ( ahrs , " AHRS_ " , AP_AHRS ) ,
// @Group: LOG
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
GOBJECT ( logger , " LOG " , AP_Logger ) ,
// @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT ( battery , " BATT " , AP_BattMonitor ) ,
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT ( BoardConfig , " BRD_ " , AP_BoardConfig ) ,
# if HAL_MAX_CAN_PROTOCOL_DRIVERS
// @Group: CAN_
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
GOBJECT ( can_mgr , " CAN_ " , AP_CANManager ) ,
# endif
2021-10-29 21:37:05 -03:00
# if AP_SIM_ENABLED
2021-07-30 07:09:57 -03:00
GOBJECT ( sitl , " SIM_ " , SITL : : SIM ) ,
2021-03-18 00:12:54 -03:00
# endif
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT ( barometer , " BARO " , AP_Baro ) ,
// GPS driver
2021-06-17 04:03:49 -03:00
// @Group: GPS
2021-03-18 00:12:54 -03:00
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
2021-06-17 04:03:49 -03:00
GOBJECT ( gps , " GPS " , AP_GPS ) ,
2021-03-18 00:12:54 -03:00
// @Group: SCHED_
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
GOBJECT ( scheduler , " SCHED_ " , AP_Scheduler ) ,
// @Group: RCMAP_
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
GOBJECT ( rcmap , " RCMAP_ " , RCMapper ) ,
# if HAL_NAVEKF2_AVAILABLE
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN ( ahrs . EKF2 , NavEKF2 , " EK2_ " , NavEKF2 ) ,
# endif
# if HAL_NAVEKF3_AVAILABLE
// @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
GOBJECTN ( ahrs . EKF3 , NavEKF3 , " EK3_ " , NavEKF3 ) ,
# endif
// @Group: RSSI_
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
GOBJECT ( rssi , " RSSI_ " , AP_RSSI ) ,
// @Group: NTF_
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT ( notify , " NTF_ " , AP_Notify ) ,
// @Group:
// @Path: Parameters.cpp
GOBJECT ( g2 , " " , ParametersG2 ) ,
// @Group: FINS_
// @Path: Fins.cpp
GOBJECTPTR ( motors , " FINS_ " , Fins ) ,
2021-06-18 01:40:01 -03:00
// @Param: VELXY_P
// @DisplayName: Velocity (horizontal) P gain
// @Description: Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration
// @Range: 0.1 6.0
// @Increment: 0.1
// @User: Advanced
// @Param: VELXY_I
// @DisplayName: Velocity (horizontal) I gain
// @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
// @Range: 0.02 1.00
// @Increment: 0.01
// @User: Advanced
// @Param: VELXY_D
// @DisplayName: Velocity (horizontal) D gain
// @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity
// @Range: 0.00 1.00
// @Increment: 0.001
// @User: Advanced
// @Param: VELXY_IMAX
// @DisplayName: Velocity (horizontal) integrator maximum
// @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
// @Range: 0 4500
// @Increment: 10
// @Units: cm/s/s
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: VELXY_FLTE
2021-06-18 01:40:01 -03:00
// @DisplayName: Velocity (horizontal) input filter
// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100
// @Units: Hz
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: VELXY_FLTD
2021-06-18 01:40:01 -03:00
// @DisplayName: Velocity (horizontal) input filter
// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100
// @Units: Hz
// @User: Advanced
// @Param: VELXY_FF
// @DisplayName: Velocity (horizontal) feed forward gain
// @Description: Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration
// @Range: 0 6
// @Increment: 0.01
// @User: Advanced
GOBJECT ( pid_vel_xy , " VELXY_ " , AC_PID_2D ) ,
// @Param: VELZ_P
// @DisplayName: Velocity (vertical) P gain
// @Description: Velocity (vertical) P gain. Converts the difference between desired and actual velocity to a target acceleration
// @Range: 0.1 6.0
// @Increment: 0.1
// @User: Advanced
// @Param: VELZ_I
// @DisplayName: Velocity (vertical) I gain
// @Description: Velocity (vertical) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
// @Range: 0.02 1.00
// @Increment: 0.01
// @User: Advanced
// @Param: VELZ_D
// @DisplayName: Velocity (vertical) D gain
// @Description: Velocity (vertical) D gain. Corrects short-term changes in velocity
// @Range: 0.00 1.00
// @Increment: 0.001
// @User: Advanced
// @Param: VELZ_IMAX
// @DisplayName: Velocity (vertical) integrator maximum
// @Description: Velocity (vertical) integrator maximum. Constrains the target acceleration that the I gain will output
// @Range: 0 4500
// @Increment: 10
// @Units: cm/s/s
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: VELZ_FLTE
2021-06-18 01:40:01 -03:00
// @DisplayName: Velocity (vertical) input filter
// @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100
// @Units: Hz
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: VELZ_FLTD
2021-06-18 01:40:01 -03:00
// @DisplayName: Velocity (vertical) input filter
// @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100
// @Units: Hz
// @User: Advanced
// @Param: VELZ_FF
// @DisplayName: Velocity (vertical) feed forward gain
// @Description: Velocity (vertical) feed forward gain. Converts the difference between desired velocity to a target acceleration
// @Range: 0 6
// @Increment: 0.01
// @User: Advanced
GOBJECT ( pid_vel_z , " VELZ_ " , AC_PID_Basic ) ,
// @Param: VELYAW_P
// @DisplayName: Velocity (yaw) P gain
// @Description: Velocity (yaw) P gain. Converts the difference between desired and actual velocity to a target acceleration
// @Range: 0.1 6.0
// @Increment: 0.1
// @User: Advanced
// @Param: VELYAW_I
// @DisplayName: Velocity (yaw) I gain
// @Description: Velocity (yaw) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
// @Range: 0.02 1.00
// @Increment: 0.01
// @User: Advanced
// @Param: VELYAW_D
// @DisplayName: Velocity (yaw) D gain
// @Description: Velocity (yaw) D gain. Corrects short-term changes in velocity
// @Range: 0.00 1.00
// @Increment: 0.001
// @User: Advanced
// @Param: VELYAW_IMAX
// @DisplayName: Velocity (yaw) integrator maximum
// @Description: Velocity (yaw) integrator maximum. Constrains the target acceleration that the I gain will output
// @Range: 0 4500
// @Increment: 10
// @Units: cm/s/s
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: VELYAW_FLTE
2021-06-18 01:40:01 -03:00
// @DisplayName: Velocity (yaw) input filter
// @Description: Velocity (yaw) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100
// @Units: Hz
// @User: Advanced
// @Param: VELYAW_FF
// @DisplayName: Velocity (yaw) feed forward gain
// @Description: Velocity (yaw) feed forward gain. Converts the difference between desired velocity to a target acceleration
// @Range: 0 6
// @Increment: 0.01
// @User: Advanced
GOBJECT ( pid_vel_yaw , " VELYAW_ " , AC_PID_Basic ) ,
// @Param: POSXY_P
// @DisplayName: Position (horizontal) P gain
// @Description: Position (horizontal) P gain. Converts the difference between desired and actual position to a target velocity
// @Range: 0.1 6.0
// @Increment: 0.1
// @User: Advanced
// @Param: POSXY_I
// @DisplayName: Position (horizontal) I gain
// @Description: Position (horizontal) I gain. Corrects long-term difference between desired and actual position to a target velocity
// @Range: 0.02 1.00
// @Increment: 0.01
// @User: Advanced
// @Param: POSXY_D
// @DisplayName: Position (horizontal) D gain
// @Description: Position (horizontal) D gain. Corrects short-term changes in position
// @Range: 0.00 1.00
// @Increment: 0.001
// @User: Advanced
// @Param: POSXY_IMAX
// @DisplayName: Position (horizontal) integrator maximum
// @Description: Position (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
// @Range: 0 4500
// @Increment: 10
// @Units: cm/s/s
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: POSXY_FLTE
2021-06-18 01:40:01 -03:00
// @DisplayName: Position (horizontal) input filter
// @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100
// @Units: Hz
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: POSXY_FLTD
2021-06-18 01:40:01 -03:00
// @DisplayName: Position (horizontal) input filter
// @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100
// @Units: Hz
// @User: Advanced
// @Param: POSXY_FF
// @DisplayName: Position (horizontal) feed forward gain
// @Description: Position (horizontal) feed forward gain. Converts the difference between desired position to a target velocity
// @Range: 0 6
// @Increment: 0.01
// @User: Advanced
GOBJECT ( pid_pos_xy , " POSXY_ " , AC_PID_2D ) ,
// @Param: POSZ_P
// @DisplayName: Position (vertical) P gain
// @Description: Position (vertical) P gain. Converts the difference between desired and actual position to a target velocity
// @Range: 0.1 6.0
// @Increment: 0.1
// @User: Advanced
// @Param: POSZ_I
// @DisplayName: Position (vertical) I gain
// @Description: Position (vertical) I gain. Corrects long-term difference between desired and actual position to a target velocity
// @Range: 0.02 1.00
// @Increment: 0.01
// @User: Advanced
// @Param: POSZ_D
// @DisplayName: Position (vertical) D gain
// @Description: Position (vertical) D gain. Corrects short-term changes in position
// @Range: 0.00 1.00
// @Increment: 0.001
// @User: Advanced
// @Param: POSZ_IMAX
// @DisplayName: Position (vertical) integrator maximum
// @Description: Position (vertical) integrator maximum. Constrains the target acceleration that the I gain will output
// @Range: 0 4500
// @Increment: 10
// @Units: cm/s/s
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: POSZ_FLTE
2021-06-18 01:40:01 -03:00
// @DisplayName: Position (vertical) input filter
// @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100
// @Units: Hz
// @User: Advanced
2021-08-03 01:05:50 -03:00
// @Param: POSZ_FLTD
2021-06-18 01:40:01 -03:00
// @DisplayName: Position (vertical) input filter
// @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100
// @Units: Hz
// @User: Advanced
// @Param: POSZ_FF
// @DisplayName: Position (vertical) feed forward gain
// @Description: Position (vertical) feed forward gain. Converts the difference between desired position to a target velocity
// @Range: 0 6
// @Increment: 0.01
// @User: Advanced
GOBJECT ( pid_pos_z , " POSZ_ " , AC_PID_Basic ) ,
// @Param: POSYAW_P
// @DisplayName: Position (yaw) axis controller P gain
// @Description: Position (yaw) axis controller P gain.
// @Range: 0.0 3.0
// @Increment: 0.01
// @User: Standard
// @Param: POSYAW_I
// @DisplayName: Position (yaw) axis controller I gain
// @Description: Position (yaw) axis controller I gain.
// @Range: 0.0 3.0
// @Increment: 0.01
// @User: Standard
// @Param: POSYAW_IMAX
// @DisplayName: Position (yaw) axis controller I gain maximum
// @Description: Position (yaw) axis controller I gain maximum.
// @Range: 0 4000
// @Increment: 10
// @Units: d%
// @User: Standard
// @Param: POSYAW_D
// @DisplayName: Position (yaw) axis controller D gain
// @Description: Position (yaw) axis controller D gain.
// @Range: 0.001 0.1
// @Increment: 0.001
// @User: Standard
// @Param: POSYAW_FF
// @DisplayName: Position (yaw) axis controller feed forward
// @Description: Position (yaw) axis controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
// @Param: POSYAW_FLTT
// @DisplayName: Position (yaw) target frequency filter in Hz
// @Description: Position (yaw) target frequency filter in Hz
// @Range: 1 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: POSYAW_FLTE
// @DisplayName: Position (yaw) error frequency filter in Hz
// @Description: Position (yaw) error frequency filter in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: POSYAW_FLTD
// @DisplayName: Position (yaw) derivative input filter in Hz
// @Description: Position (yaw) derivative input filter in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: POSYAW_SMAX
// @DisplayName: Yaw slew rate limit
2021-06-22 03:36:11 -03:00
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains.
2021-06-18 01:40:01 -03:00
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced
2023-09-18 22:44:34 -03:00
// @Param: POSYAW_PDMX
// @DisplayName: Position (yaw) axis controller PD sum maximum
// @Description: Position (yaw) axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 4000
// @Increment: 10
// @Units: d%
// @User: Advanced
2023-08-10 08:09:12 -03:00
// @Param: POSYAW_D_FF
// @DisplayName: Position (yaw) Derivative FeedForward Gain
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
2023-10-01 14:21:01 -03:00
// @Range: 0 0.1
2023-08-10 08:09:12 -03:00
// @Increment: 0.001
// @User: Advanced
// @Param: POSYAW_NTF
2023-10-01 14:21:01 -03:00
// @DisplayName: Position (yaw) Target notch filter index
// @Description: Position (yaw) Target notch filter index
// @Range: 1 8
2023-08-10 08:09:12 -03:00
// @User: Advanced
// @Param: POSYAW_NEF
2023-10-01 14:21:01 -03:00
// @DisplayName: Position (yaw) Error notch filter index
// @Description: Position (yaw) Error notch filter index
// @Range: 1 8
2023-08-10 08:09:12 -03:00
// @User: Advanced
2021-06-18 01:40:01 -03:00
GOBJECT ( pid_pos_yaw , " POSYAW_ " , AC_PID ) ,
2021-03-18 00:12:54 -03:00
// @Group:
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
2023-01-03 21:39:14 -04:00
PARAM_VEHICLE_INFO ,
2021-03-18 00:12:54 -03:00
AP_VAREND
} ;
/*
2 nd group of parameters
*/
const AP_Param : : GroupInfo ParametersG2 : : var_info [ ] = {
// @Param: DEV_OPTIONS
// @DisplayName: Development options
// @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 meaning
2021-06-17 04:03:49 -03:00
// @Bitmask: 0:Unknown
2021-03-18 00:12:54 -03:00
// @User: Advanced
AP_GROUPINFO ( " DEV_OPTIONS " , 7 , ParametersG2 , dev_options , 0 ) ,
// @Param: SYSID_ENFORCE
// @DisplayName: GCS sysid enforcement
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
// @Values: 0:NotEnforced,1:Enforced
// @User: Advanced
AP_GROUPINFO ( " SYSID_ENFORCE " , 11 , ParametersG2 , sysid_enforce , 0 ) ,
# if STATS_ENABLED == ENABLED
// @Group: STAT
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
AP_SUBGROUPINFO ( stats , " STAT " , 12 , ParametersG2 , AP_Stats ) ,
# endif
// @Param: FRAME_CLASS
// @DisplayName: Frame Class
2021-06-17 04:03:49 -03:00
// @Description: Controls major frame class for blimp.
// @Values: 0:Finnedblimp
2021-03-18 00:12:54 -03:00
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " FRAME_CLASS " , 15 , ParametersG2 , frame_class , DEFAULT_FRAME_CLASS ) ,
// @Group: SERVO
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
AP_SUBGROUPINFO ( servo_channels , " SERVO " , 16 , ParametersG2 , SRV_Channels ) ,
// @Group: RC
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
AP_SUBGROUPINFO ( rc_channels , " RC " , 17 , ParametersG2 , RC_Channels_Blimp ) ,
// @Param: PILOT_SPEED_DN
// @DisplayName: Pilot maximum vertical speed descending
// @Description: The maximum vertical descending velocity the pilot may request in cm/s
// @Units: cm/s
// @Range: 50 500
// @Increment: 10
// @User: Standard
AP_GROUPINFO ( " PILOT_SPEED_DN " , 24 , ParametersG2 , pilot_speed_dn , 0 ) ,
2021-11-15 01:08:35 -04:00
# if AP_SCRIPTING_ENABLED
2021-03-18 00:12:54 -03:00
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO ( scripting , " SCR_ " , 30 , ParametersG2 , AP_Scripting ) ,
# endif
// @Param: FS_VIBE_ENABLE
// @DisplayName: Vibration Failsafe enable
// @Description: This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations
// @Values: 0:Disabled, 1:Enabled
// @User: Standard
AP_GROUPINFO ( " FS_VIBE_ENABLE " , 35 , ParametersG2 , fs_vibe_enabled , 1 ) ,
// @Param: FS_OPTIONS
// @DisplayName: Failsafe options bitmask
// @Description: Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.
2022-03-26 19:15:21 -03:00
// @Values: 0:Disabled, 16:Continue if in pilot controlled modes on GCS failsafe
// @Bitmask: 4:Continue if in pilot controlled modes on GCS failsafe
2021-03-18 00:12:54 -03:00
// @User: Advanced
AP_GROUPINFO ( " FS_OPTIONS " , 36 , ParametersG2 , fs_options , ( float ) Blimp : : FailsafeOption : : GCS_CONTINUE_IF_PILOT_CONTROL ) ,
// @Param: FS_GCS_TIMEOUT
// @DisplayName: GCS failsafe timeout
// @Description: Timeout before triggering the GCS failsafe
// @Units: s
// @Range: 2 120
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " FS_GCS_TIMEOUT " , 42 , ParametersG2 , fs_gcs_timeout , 5 ) ,
AP_GROUPEND
} ;
/*
constructor for g2 object
*/
ParametersG2 : : ParametersG2 ( void )
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
void Blimp : : load_parameters ( void )
{
hal . util - > set_soft_armed ( false ) ;
if ( ! g . format_version . load ( ) | |
g . format_version ! = Parameters : : k_format_version ) {
// erase all parameters
hal . console - > printf ( " Firmware change: erasing EEPROM... \n " ) ;
StorageManager : : erase ( ) ;
AP_Param : : erase_all ( ) ;
// save the current format version
g . format_version . set_and_save ( Parameters : : k_format_version ) ;
hal . console - > printf ( " done. \n " ) ;
}
2022-07-04 22:57:43 -03:00
g . format_version . set_default ( Parameters : : k_format_version ) ;
2021-03-18 00:12:54 -03:00
uint32_t before = micros ( ) ;
// Load all auto-loaded EEPROM variables
AP_Param : : load_all ( ) ;
hal . console - > printf ( " load_all took %uus \n " , ( unsigned ) ( micros ( ) - before ) ) ;
// setup AP_Param frame type flags
2021-06-23 23:26:56 -03:00
AP_Param : : set_frame_type_flags ( AP_PARAM_FRAME_BLIMP ) ;
2021-03-18 00:12:54 -03:00
}