mirror of https://github.com/ArduPilot/ardupilot
Autotest:Copter test fix for tri
fixed excessive yaw rate for 'tri' frame
This commit is contained in:
parent
a58e808af8
commit
6095992f14
|
@ -6985,7 +6985,6 @@ class AutoTestCopter(AutoTest):
|
|||
'heli-dual': "wrong binary, different takeoff regime",
|
||||
'heli': "wrong binary, different takeoff regime",
|
||||
'heli-blade360': "wrong binary, different takeoff regime",
|
||||
'tri': "bad yaw rate",
|
||||
}
|
||||
for frame in sorted(copter_vinfo_options["frames"].keys()):
|
||||
self.start_subtest("Testing frame (%s)" % str(frame))
|
||||
|
|
|
@ -2,7 +2,5 @@ SERVO7_MIN 1000
|
|||
SERVO7_MAX 2000
|
||||
SERVO7_TRIM 1360
|
||||
FRAME_CLASS 7
|
||||
ATC_RAT_YAW_I 0.09
|
||||
ATC_RAT_YAW_I 0.11
|
||||
ATC_RAT_YAW_FLTE 5.0
|
||||
MOT_YAW_SV_ANGLE 60
|
||||
|
|
Loading…
Reference in New Issue