mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AR_AttitudeControl: reduce default accel max to 2m/s/s
This commit is contained in:
parent
856d592b1d
commit
c032095c80
@ -24,7 +24,7 @@
|
||||
#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
|
||||
#define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f
|
||||
|
||||
// minimum speed in m/s
|
||||
#define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f
|
||||
|
Loading…
Reference in New Issue
Block a user