diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm index 73408de761..10843d3209 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm @@ -99,8 +99,8 @@ PTCH2SRV_RMAX_UP,75 Q_A_ACCEL_P_MAX,30000 Q_A_ACCEL_R_MAX,30000 Q_A_ACCEL_Y_MAX,4500 -Q_A_ANG_PIT_P,1.2 # DISABLE_CHECKS: AP limits are based on small quadcopters -Q_A_ANG_RLL_P,2 # DISABLE_CHECKS: AP limits are based on small quadcopters +Q_A_ANG_PIT_P,5.5 +Q_A_ANG_RLL_P,5 Q_A_ANG_YAW_P,2.4 # DISABLE_CHECKS: AP limits are based on small quadcopters Q_A_RAT_PIT_D,0.00448 Q_A_RAT_PIT_FLTD,15