Browse Source

Copter: reduce alt hold defaults

Throttle Rate P to 5.0 (was 6.0)
Throttle Accel P to 0.5 (was 0.75)
Throttle Accel I to 1.0 (was 1.5)
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
9c613cd1ec
  1. 30
      ArduCopter/config.h

30
ArduCopter/config.h

@ -680,7 +680,21 @@ @@ -680,7 +680,21 @@
// RATE control
#ifndef THROTTLE_RATE_P
# define THROTTLE_RATE_P 6.0f
# define THROTTLE_RATE_P 5.0f
#endif
// Throttle Accel control
#ifndef THROTTLE_ACCEL_P
# define THROTTLE_ACCEL_P 0.50f
#endif
#ifndef THROTTLE_ACCEL_I
# define THROTTLE_ACCEL_I 1.00f
#endif
#ifndef THROTTLE_ACCEL_D
# define THROTTLE_ACCEL_D 0.0f
#endif
#ifndef THROTTLE_ACCEL_IMAX
# define THROTTLE_ACCEL_IMAX 500
#endif
// default maximum vertical velocity and acceleration the pilot may request
@ -700,20 +714,6 @@ @@ -700,20 +714,6 @@
# define ALT_HOLD_ACCEL_MAX 250 // if you change this you must also update the duplicate declaration in AC_WPNav.h
#endif
// Throttle Accel control
#ifndef THROTTLE_ACCEL_P
# define THROTTLE_ACCEL_P 0.75f
#endif
#ifndef THROTTLE_ACCEL_I
# define THROTTLE_ACCEL_I 1.50f
#endif
#ifndef THROTTLE_ACCEL_D
# define THROTTLE_ACCEL_D 0.0f
#endif
#ifndef THROTTLE_ACCEL_IMAX
# define THROTTLE_ACCEL_IMAX 500
#endif
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//

Loading…
Cancel
Save