From 42f553626e55b5f8c2c475b0ef197730d4688b80 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 31 May 2022 13:13:38 +1000 Subject: [PATCH] Plane: adjust down default quadplane gains make it better for a typical quadplane, the defaults were more suitable on smaller aircraft --- ArduPlane/quadplane.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 9ed1623712..b8b60cdf1a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -478,6 +478,10 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "Q_WP_SPEED", 500 }, { "Q_WP_ACCEL", 100 }, { "Q_P_JERK_XY", 2 }, + // lower rotational accel limits + { "Q_A_ACCEL_R_MAX", 40000 }, + { "Q_A_ACCEL_P_MAX", 40000 }, + { "Q_A_ACCEL_Y_MAX", 10000 }, }; /*