From 64289d436a3f1279ce356d5c42a29afc42c96ee3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 20 Feb 2021 10:21:01 +0900 Subject: [PATCH] Copter: reduce ANGLE_MAX default to 30deg --- ArduCopter/config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index d4ab508115..88701c79d8 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -559,7 +559,7 @@ # define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range #endif #ifndef DEFAULT_ANGLE_MAX - # define DEFAULT_ANGLE_MAX 4500 // ANGLE_MAX parameters default value + # define DEFAULT_ANGLE_MAX 3000 // ANGLE_MAX parameters default value #endif #ifndef ANGLE_RATE_MAX # define ANGLE_RATE_MAX 18000 // default maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes