mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 08:04:14 -03:00
autotest: fix usage of tabs instead of space
Python 3 is stricter with regard to using tabs instead of space (PEP8): Spaces are the preferred indentation method. Tabs should be used solely to remain consistent with code that is already indented with tabs. Python 3 disallows mixing the use of tabs and spaces for indentation. Python 2 code indented with a mixture of tabs and spaces should be converted to using spaces exclusively.
This commit is contained in:
parent
c89530a97c
commit
35b550f03d
@ -143,21 +143,21 @@ class Matrix3:
|
|||||||
def from_euler(self, roll, pitch, yaw):
|
def from_euler(self, roll, pitch, yaw):
|
||||||
'''fill the matrix from Euler angles in radians'''
|
'''fill the matrix from Euler angles in radians'''
|
||||||
cp = cos(pitch)
|
cp = cos(pitch)
|
||||||
sp = sin(pitch)
|
sp = sin(pitch)
|
||||||
sr = sin(roll)
|
sr = sin(roll)
|
||||||
cr = cos(roll)
|
cr = cos(roll)
|
||||||
sy = sin(yaw)
|
sy = sin(yaw)
|
||||||
cy = cos(yaw)
|
cy = cos(yaw)
|
||||||
|
|
||||||
self.a.x = cp * cy
|
self.a.x = cp * cy
|
||||||
self.a.y = (sr * sp * cy) - (cr * sy)
|
self.a.y = (sr * sp * cy) - (cr * sy)
|
||||||
self.a.z = (cr * sp * cy) + (sr * sy)
|
self.a.z = (cr * sp * cy) + (sr * sy)
|
||||||
self.b.x = cp * sy
|
self.b.x = cp * sy
|
||||||
self.b.y = (sr * sp * sy) + (cr * cy)
|
self.b.y = (sr * sp * sy) + (cr * cy)
|
||||||
self.b.z = (cr * sp * sy) - (sr * cy)
|
self.b.z = (cr * sp * sy) - (sr * cy)
|
||||||
self.c.x = -sp
|
self.c.x = -sp
|
||||||
self.c.y = sr * cp
|
self.c.y = sr * cp
|
||||||
self.c.z = cr * cp
|
self.c.z = cr * cp
|
||||||
|
|
||||||
|
|
||||||
def to_euler(self):
|
def to_euler(self):
|
||||||
@ -190,11 +190,11 @@ class Matrix3:
|
|||||||
def from_euler312(self, roll, pitch, yaw):
|
def from_euler312(self, roll, pitch, yaw):
|
||||||
'''fill the matrix from Euler angles in radians in 312 convention'''
|
'''fill the matrix from Euler angles in radians in 312 convention'''
|
||||||
c3 = cos(pitch)
|
c3 = cos(pitch)
|
||||||
s3 = sin(pitch)
|
s3 = sin(pitch)
|
||||||
s2 = sin(roll)
|
s2 = sin(roll)
|
||||||
c2 = cos(roll)
|
c2 = cos(roll)
|
||||||
s1 = sin(yaw)
|
s1 = sin(yaw)
|
||||||
c1 = cos(yaw)
|
c1 = cos(yaw)
|
||||||
|
|
||||||
self.a.x = c1 * c3 - s1 * s2 * s3
|
self.a.x = c1 * c3 - s1 * s2 * s3
|
||||||
self.b.y = c1 * c2
|
self.b.y = c1 * c2
|
||||||
@ -250,29 +250,29 @@ class Matrix3:
|
|||||||
|
|
||||||
def rotate(self, g):
|
def rotate(self, g):
|
||||||
'''rotate the matrix by a given amount on 3 axes'''
|
'''rotate the matrix by a given amount on 3 axes'''
|
||||||
temp_matrix = Matrix3()
|
temp_matrix = Matrix3()
|
||||||
a = self.a
|
a = self.a
|
||||||
b = self.b
|
b = self.b
|
||||||
c = self.c
|
c = self.c
|
||||||
temp_matrix.a.x = a.y * g.z - a.z * g.y
|
temp_matrix.a.x = a.y * g.z - a.z * g.y
|
||||||
temp_matrix.a.y = a.z * g.x - a.x * g.z
|
temp_matrix.a.y = a.z * g.x - a.x * g.z
|
||||||
temp_matrix.a.z = a.x * g.y - a.y * g.x
|
temp_matrix.a.z = a.x * g.y - a.y * g.x
|
||||||
temp_matrix.b.x = b.y * g.z - b.z * g.y
|
temp_matrix.b.x = b.y * g.z - b.z * g.y
|
||||||
temp_matrix.b.y = b.z * g.x - b.x * g.z
|
temp_matrix.b.y = b.z * g.x - b.x * g.z
|
||||||
temp_matrix.b.z = b.x * g.y - b.y * g.x
|
temp_matrix.b.z = b.x * g.y - b.y * g.x
|
||||||
temp_matrix.c.x = c.y * g.z - c.z * g.y
|
temp_matrix.c.x = c.y * g.z - c.z * g.y
|
||||||
temp_matrix.c.y = c.z * g.x - c.x * g.z
|
temp_matrix.c.y = c.z * g.x - c.x * g.z
|
||||||
temp_matrix.c.z = c.x * g.y - c.y * g.x
|
temp_matrix.c.z = c.x * g.y - c.y * g.x
|
||||||
self.a += temp_matrix.a
|
self.a += temp_matrix.a
|
||||||
self.b += temp_matrix.b
|
self.b += temp_matrix.b
|
||||||
self.c += temp_matrix.c
|
self.c += temp_matrix.c
|
||||||
|
|
||||||
def normalize(self):
|
def normalize(self):
|
||||||
'''re-normalise a rotation matrix'''
|
'''re-normalise a rotation matrix'''
|
||||||
error = self.a * self.b
|
error = self.a * self.b
|
||||||
t0 = self.a - (self.b * (0.5 * error))
|
t0 = self.a - (self.b * (0.5 * error))
|
||||||
t1 = self.b - (self.a * (0.5 * error))
|
t1 = self.b - (self.a * (0.5 * error))
|
||||||
t2 = t0 % t1
|
t2 = t0 % t1
|
||||||
self.a = t0 * (1.0 / t0.length())
|
self.a = t0 * (1.0 / t0.length())
|
||||||
self.b = t1 * (1.0 / t1.length())
|
self.b = t1 * (1.0 / t1.length())
|
||||||
self.c = t2 * (1.0 / t2.length())
|
self.c = t2 * (1.0 / t2.length())
|
||||||
|
Loading…
Reference in New Issue
Block a user