Skip to content

Commit

Permalink
CubeOrange-Ottano: suppress checks on params
Browse files Browse the repository at this point in the history
SW-330
  • Loading branch information
robertlong13 committed Sep 16, 2024
1 parent 817ac36 commit 20420c6
Showing 1 changed file with 10 additions and 10 deletions.
20 changes: 10 additions & 10 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm
Original file line number Diff line number Diff line change
Expand Up @@ -66,14 +66,14 @@ ICE_STARTCHN_MIN,950
ICE_STARTER_TIME,5
INS_ACCEL_FILTER,10
INS_GYRO_FILTER,22
INS_HNTC2_ATT,60
INS_HNTC2_ATT,60 # DISABLE_CHECKS: AP recommended max is 50
INS_HNTC2_BW,12
INS_HNTC2_ENABLE,1
INS_HNTC2_FREQ,35
INS_HNTC2_MODE,2
INS_HNTC2_OPTS,1
INS_HNTC2_REF,1
INS_HNTCH_ATT,60
INS_HNTCH_ATT,60 # DISABLE_CHECKS: AP recommended max is 50
INS_HNTCH_BW,15
INS_HNTCH_ENABLE,1
INS_HNTCH_FREQ,60
Expand All @@ -93,7 +93,7 @@ PTCH_RATE_D,0.0065
PTCH_RATE_FF,0.7402687
PTCH_RATE_FLTD,11
PTCH_RATE_FLTT,3.183099
PTCH_RATE_I,0.7402687
PTCH_RATE_I,0.7402687 # DISABLE_CHECKS: it is recommended for RATE_I to match RATE_FF on planes, but the metadata gives a limit of 0.6 for this and 3.0 for FF
PTCH_RATE_IMAX,0.4
PTCH_RATE_P,0.2194594
PTCH_RATE_SMAX,110
Expand All @@ -104,7 +104,7 @@ PTCH2SRV_RMAX_UP,75
Q_A_ACCEL_P_MAX,8800
Q_A_ACCEL_R_MAX,9000
Q_A_ACCEL_Y_MAX,4000
Q_A_ANG_YAW_P,2
Q_A_ANG_YAW_P,2 # DISABLE_CHECKS: AP limits are based on small quadcopters
Q_A_RAT_PIT_D,0.03447478
Q_A_RAT_PIT_FLTD,11
Q_A_RAT_PIT_FLTE,8
Expand All @@ -118,7 +118,7 @@ Q_A_RAT_RLL_FLTD,11
Q_A_RAT_RLL_FLTE,8
Q_A_RAT_RLL_FLTT,11
Q_A_RAT_RLL_I,0.8448284
Q_A_RAT_RLL_P,0.8448284
Q_A_RAT_RLL_P,0.8448284 # DISABLE_CHECKS: AP limits are based on small quadcopters
Q_A_RAT_RLL_SMAX,15
Q_A_RAT_YAW_D,0.002
Q_A_RAT_YAW_FLTD,11
Expand All @@ -137,12 +137,12 @@ Q_ASSIST_SPEED,18
Q_LOIT_ACC_MAX,100
Q_LOIT_ANG_MAX,10
Q_LOIT_BRK_ACCEL,25
Q_LOIT_BRK_JERK,175
Q_LOIT_BRK_JERK,175 # DISABLE_CHECKS: AP limits are based on small quadcopters
Q_LOIT_SPEED,300
Q_M_BAT_VOLT_MAX,50.4
Q_M_BAT_VOLT_MIN,39.6
Q_M_SPIN_ARM,0.07
Q_M_SPIN_MIN,0.1
Q_M_SPIN_MIN,0.1 # DISABLE_CHECKS: this parameter should be a range restriction, but only values are defined
Q_M_THST_EXPO,0.582
Q_M_THST_HOVER,0.554629
Q_M_YAW_HEADROOM,100
Expand All @@ -169,8 +169,8 @@ Q_PILOT_ACCEL_Z,1
Q_PLT_Y_RATE,25
Q_TRANS_DECEL,0.9
Q_VFWD_GAIN,0.1
Q_WP_ACCEL_Z,30
Q_WP_JERK,0.7
Q_WP_ACCEL_Z,30 # DISABLE_CHECKS: AP limits are based on small quadcopters
Q_WP_JERK,0.7 # DISABLE_CHECKS: AP limits are based on small quadcopters
Q_WP_SPEED_DN,200
Q_WP_SPEED_UP,220
Q_WVANE_GAIN,1
Expand All @@ -181,7 +181,7 @@ RLL_RATE_D,0.001917198
RLL_RATE_FF,0.7728607
RLL_RATE_FLTD,11
RLL_RATE_FLTT,3.183099
RLL_RATE_I,0.7728607
RLL_RATE_I,0.7728607 # DISABLE_CHECKS: it is recommended for RATE_I to match RATE_FF on planes, but the metadata gives a limit of 0.6 for this and 3.0 for FF
RLL_RATE_IMAX,0.4
RLL_RATE_P,0.09429314
RLL_RATE_SMAX,125
Expand Down

0 comments on commit 20420c6

Please sign in to comment.