diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm index 2301497613..d2439ebdb4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm @@ -61,8 +61,6 @@ LOG_FILE_DSRMROT,1 LOG_FILE_MB_FREE,5000 # DISABLE_CHECKS: we want to reserve 5GB for logs; ArduPilot suggests max of 1GB LOG_REPLAY,1 MIN_GROUNDSPEED,8 -PTCH_LIM_MAX_DEG,16 -PTCH_LIM_MIN_DEG,-13 Q_A_THR_MIX_MAN,0.25 Q_A_THR_MIX_MAX,0.65 Q_A_THR_MIX_MIN,0.25 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 9c52e28ad9..1d823576bd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -111,6 +111,8 @@ INS_POS3_X,0.82 KFF_RDDRMIX,1 NAVL1_LIM_BANK,35 # Set to match ROLL_LIMIT_DEG NAVL1_PERIOD,27 +PTCH_LIM_MAX_DEG,16 +PTCH_LIM_MIN_DEG,-13 PTCH_RATE_D,0.0065 PTCH_RATE_FF,0.7402687 PTCH_RATE_FLTD,11 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm index 10843d3209..0fbddeb744 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm @@ -84,6 +84,8 @@ INS_POS3_Z,-0.03 KFF_RDDRMIX,0.9 NAVL1_LIM_BANK,40 # Set to match ROLL_LIMIT_DEG NAVL1_PERIOD,19 +PTCH_LIM_MAX_DEG,16 +PTCH_LIM_MIN_DEG,-13 PTCH_RATE_D,0.0029344 PTCH_RATE_FF,0.36 PTCH_RATE_FLTD,10