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.
This commit is contained in:
Randy Mackay 2021-09-16 20:10:08 +09:00 committed by Andrew Tridgell
parent 9c54b3d252
commit e85a95f21c

View File

@ -20,15 +20,15 @@
#include <AP_GPS/AP_GPS.h>
// 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