mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: adjust default quadplane tune
This commit is contained in:
parent
c379310d11
commit
8c249a39b2
@ -70,10 +70,16 @@ Q_M_PWM_MIN 1000
|
|||||||
Q_M_PWM_MAX 2000
|
Q_M_PWM_MAX 2000
|
||||||
Q_M_BAT_VOLT_MAX 12.8
|
Q_M_BAT_VOLT_MAX 12.8
|
||||||
Q_M_BAT_VOLT_MIN 9.6
|
Q_M_BAT_VOLT_MIN 9.6
|
||||||
Q_A_RAT_RLL_P 0.15
|
Q_A_RAT_RLL_P 0.108
|
||||||
Q_A_RAT_PIT_P 0.15
|
Q_A_RAT_RLL_I 0.108
|
||||||
Q_A_RAT_RLL_D 0.002
|
Q_A_RAT_RLL_D 0.001
|
||||||
Q_A_RAT_PIT_D 0.002
|
Q_A_RAT_PIT_P 0.103
|
||||||
|
Q_A_RAT_PIT_I 0.103
|
||||||
|
Q_A_RAT_PIT_D 0.001
|
||||||
|
Q_A_RAT_YAW_P 0.4
|
||||||
|
Q_A_RAT_YAW_P 0.04
|
||||||
|
Q_A_ANG_RLL_P 6
|
||||||
|
Q_A_ANG_PIT_P 6
|
||||||
RTL_ALTITUDE 20.00
|
RTL_ALTITUDE 20.00
|
||||||
PTCH_RATE_FF 1.407055
|
PTCH_RATE_FF 1.407055
|
||||||
RLL_RATE_FF 0.552741
|
RLL_RATE_FF 0.552741
|
||||||
|
Loading…
Reference in New Issue
Block a user