mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AR_AttitudeControl: lengthen timeout to 200ms
This is required because occasionally the turn rate controller can be disabled for just over 100ms as new navigation commands are loaded
This commit is contained in:
parent
a2b1807ca0
commit
9930550cfc
@ -18,7 +18,7 @@
|
||||
#define AR_ATTCONTROL_THR_SPEED_D 0.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_FILT 5.00f
|
||||
#define AR_ATTCONTROL_DT 0.02f
|
||||
#define AR_ATTCONTROL_TIMEOUT_MS 100
|
||||
#define AR_ATTCONTROL_TIMEOUT_MS 200
|
||||
|
||||
// throttle/speed control maximum acceleration/deceleration (in m/s) (_ACCEL_MAX parameter default)
|
||||
#define AR_ATTCONTROL_THR_ACCEL_MAX 5.00f
|
||||
|
Loading…
Reference in New Issue
Block a user