mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: added notch params for quadplanes
This commit is contained in:
parent
ab9d13f5dd
commit
6bfaa3ef62
@ -44,6 +44,15 @@ SERVO2_REVERSED 1
|
||||
SERVO_AUTO_TRIM 1
|
||||
SERVO_RATE 150
|
||||
|
||||
# harmonic notch filter
|
||||
INS_HNTCH_ENABLE 1
|
||||
INS_HNTCH_ATT 40
|
||||
INS_HNTCH_BW 40
|
||||
INS_HNTCH_FREQ 81
|
||||
INS_HNTCH_HMNCS 3
|
||||
INS_HNTCH_MODE 1
|
||||
INS_HNTCH_REF 0.39
|
||||
|
||||
# quadplane parameters
|
||||
Q_ENABLE 1
|
||||
Q_FRAME_CLASS 1
|
||||
|
@ -32,6 +32,15 @@ PTCH_RATE_I 0.627938
|
||||
PTCH_RATE_P 0.076867
|
||||
PTCH_RATE_SMAX 100
|
||||
|
||||
# notch filter
|
||||
INS_HNTCH_ENABLE 1
|
||||
INS_HNTCH_ATT 60
|
||||
INS_HNTCH_BW 50
|
||||
INS_HNTCH_FREQ 100
|
||||
INS_HNTCH_HMNCS 7
|
||||
INS_HNTCH_MODE 1
|
||||
INS_HNTCH_REF 0.21
|
||||
|
||||
# quadplane setup
|
||||
Q_ENABLE 1
|
||||
Q_FRAME_CLASS 1
|
||||
|
Loading…
Reference in New Issue
Block a user