diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/defaults.parm index dc5fb95bf1..1078b74cf1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/defaults.parm @@ -42,7 +42,7 @@ RTL_ALTITUDE 30.00 AIRSPEED_MAX 25 AIRSPEED_MIN 8 ARSPD_RATIO 1.9 -LIM_ROLL_CD 4000 +ROLL_LIMIT_DEG 40.00 # the HWing can become unstable at high speeds. Limit pitch angle # to prevent overspeed