diff --git a/Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt b/Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt new file mode 100644 index 00000000000000..ab2be0d1a45470 --- /dev/null +++ b/Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt @@ -0,0 +1,7 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.090027 1 +1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.361553 149.163956 20.000000 1 +2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364540 149.162857 50.000000 1 +3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.367333 149.163164 28.000000 1 +4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.366814 149.165878 28.000000 1 +5 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.362947 149.165179 0.000000 1 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 31a127f3e01170..ff92fedef82d57 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -3275,6 +3275,10 @@ def MicroStrainEAHRS5(self): '''Test MicroStrain EAHRS series 5 support''' self.fly_external_AHRS("MicroStrain5", 2, "ap1.txt") + def InertialLabsEAHRS(self): + '''Test InertialLabs EAHRS support''' + self.fly_external_AHRS("ILabs", 5, "ap1.txt") + def get_accelvec(self, m): return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81 @@ -5353,6 +5357,7 @@ def tests(self): self.TerrainLoiter, self.VectorNavEAHRS, self.MicroStrainEAHRS5, + self.InertialLabsEAHRS, self.Deadreckoning, self.DeadreckoningNoAirSpeed, self.EKFlaneswitch,