From e85a95f21c607aa9fb36c263e3f8273e64d3f673 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 16 Sep 2021 20:10:08 +0900 Subject: [PATCH] AR_AttitudeControl: reduce some param defaults These reductions are based on experirence helping users setup new vehicle. In the vast majority of cases the existing values are too high STEER_ANG_P is the default for the angle-to-rate controller and is used during pivot turns. This value may still be slightly too high. STEER_RATE_MAX is the maximum turn rate so the new value allows a 360 turn in 3 seconds STEER_ACCEL_MAX is the acceleration for the turn rate meaning a vehicle can get to 120 deg/sec in 1 sec THR_ACCEL_MAX is the maximum acceleration. This new value means a vehicle can accelerate to 1m/s in 1 second. --- libraries/APM_Control/AR_AttitudeControl.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index c5b9c4691f..25031c74f5 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -20,15 +20,15 @@ #include // attitude control default definition -#define AR_ATTCONTROL_STEER_ANG_P 2.50f +#define AR_ATTCONTROL_STEER_ANG_P 2.00f #define AR_ATTCONTROL_STEER_RATE_FF 0.20f #define AR_ATTCONTROL_STEER_RATE_P 0.20f #define AR_ATTCONTROL_STEER_RATE_I 0.20f #define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f #define AR_ATTCONTROL_STEER_RATE_D 0.00f #define AR_ATTCONTROL_STEER_RATE_FILT 10.00f -#define AR_ATTCONTROL_STEER_RATE_MAX 360.0f -#define AR_ATTCONTROL_STEER_ACCEL_MAX 180.0f +#define AR_ATTCONTROL_STEER_RATE_MAX 120.0f +#define AR_ATTCONTROL_STEER_ACCEL_MAX 120.0f #define AR_ATTCONTROL_THR_SPEED_P 0.20f #define AR_ATTCONTROL_THR_SPEED_I 0.20f #define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f @@ -50,7 +50,7 @@ #define AR_ATTCONTROL_DT 0.02f // throttle/speed control maximum acceleration/deceleration (in m/s) (_ACCEL_MAX parameter default) -#define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f +#define AR_ATTCONTROL_THR_ACCEL_MAX 1.00f // minimum speed in m/s #define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f