mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
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)
This commit is contained in:
parent
62a4e66481
commit
4b47a618a4
@ -685,7 +685,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
|
||||
@ -705,20 +719,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…
Reference in New Issue
Block a user