23 '''rotation matrix class 25 from __future__
import print_function
26 from builtins
import range
27 from builtins
import object
29 from math
import sin, cos, sqrt, asin, atan2, pi, radians, acos, degrees
34 if x
is not None and y
is not None and z
is not None:
38 elif x
is not None and len(x) == 3:
43 raise ValueError(
'bad initialiser')
50 return 'Vector3(%.2f, %.2f, %.2f)' % (self.
x,
55 return self.
x == v.x
and self.
y == v.y
and self.
z == v.z
61 return abs(self.
x - v.x) < tol
and \
62 abs(self.
y - v.y) < tol
and \
63 abs(self.
z - v.z) < tol
86 if isinstance(v, Vector3):
88 return self.
x*v.x + self.
y*v.y + self.
z*v.z
103 self.
z*v.x - self.
x*v.z,
104 self.
x*v.y - self.
y*v.x)
112 return sqrt(self.
x**2 + self.
y**2 + self.
z**2)
115 self.
x = self.
y = self.
z = 0
118 '''return the angle between this vector and another vector''' 119 return acos((self * v) / (self.
length() * v.length()))
131 '''a 3x3 matrix, intended as a rotation matrix''' 133 if a
is not None and b
is not None and c
is not None:
141 return 'Matrix3((%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f))' % (
142 self.a.x, self.a.y, self.a.z,
143 self.b.x, self.b.y, self.b.z,
144 self.c.x, self.c.y, self.c.z)
153 Vector3(self.a.y, self.b.y, self.c.y),
154 Vector3(self.a.z, self.b.z, self.c.z))
158 '''fill the matrix from Euler angles in radians''' 167 self.a.y = (sr * sp * cy) - (cr * sy)
168 self.a.z = (cr * sp * cy) + (sr * sy)
170 self.b.y = (sr * sp * sy) + (cr * cy)
171 self.b.z = (cr * sp * sy) - (sr * cy)
178 '''find Euler angles (321 convention) for the matrix''' 181 elif self.c.x <= -1.0:
184 pitch = -asin(self.c.x)
185 roll = atan2(self.c.y, self.c.z)
186 yaw = atan2(self.b.x, self.a.x)
187 return (roll, pitch, yaw)
191 '''find Euler angles (312 convention) for the matrix. 192 See http://www.atacolorado.com/eulersequences.doc 199 yaw = atan2(-T21, T22)
201 pitch = atan2(-T13, T33)
202 return (roll, pitch, yaw)
205 '''fill the matrix from Euler angles in radians in 312 convention''' 213 self.a.x = c1 * c3 - s1 * s2 * s3
217 self.a.z = s3*c1 + c3*s2*s1
218 self.b.x = c3*s1 + s3*s2*c1
219 self.b.z = s1*s3 - s2*c1*c3
224 return Matrix3(self.
a + m.a, self.
b + m.b, self.
c + m.c)
229 return Matrix3(self.
a - m.a, self.
b - m.b, self.
c - m.c)
232 return Matrix3(m.a - self.
a, m.b - self.
b, m.c - self.
c)
235 return self.
a == m.a
and self.
b == m.b
and self.
c == m.c
241 if isinstance(other, Vector3):
243 return Vector3(self.a.x * v.x + self.a.y * v.y + self.a.z * v.z,
244 self.b.x * v.x + self.b.y * v.y + self.b.z * v.z,
245 self.c.x * v.x + self.c.y * v.y + self.c.z * v.z)
246 elif isinstance(other, Matrix3):
248 return Matrix3(
Vector3(self.a.x * m.a.x + self.a.y * m.b.x + self.a.z * m.c.x,
249 self.a.x * m.a.y + self.a.y * m.b.y + self.a.z * m.c.y,
250 self.a.x * m.a.z + self.a.y * m.b.z + self.a.z * m.c.z),
251 Vector3(self.b.x * m.a.x + self.b.y * m.b.x + self.b.z * m.c.x,
252 self.b.x * m.a.y + self.b.y * m.b.y + self.b.z * m.c.y,
253 self.b.x * m.a.z + self.b.y * m.b.z + self.b.z * m.c.z),
254 Vector3(self.c.x * m.a.x + self.c.y * m.b.x + self.c.z * m.c.x,
255 self.c.x * m.a.y + self.c.y * m.b.y + self.c.z * m.c.y,
256 self.c.x * m.a.z + self.c.y * m.b.z + self.c.z * m.c.z))
258 return Matrix3(self.
a * v, self.
b * v, self.
c * v)
261 return Matrix3(self.
a / v, self.
b / v, self.
c / v)
272 '''rotate the matrix by a given amount on 3 axes, 273 where g is a vector of delta angles. Used 274 with DCM updates in mavextra.py''' 279 temp_matrix.a.x = a.y * g.z - a.z * g.y
280 temp_matrix.a.y = a.z * g.x - a.x * g.z
281 temp_matrix.a.z = a.x * g.y - a.y * g.x
282 temp_matrix.b.x = b.y * g.z - b.z * g.y
283 temp_matrix.b.y = b.z * g.x - b.x * g.z
284 temp_matrix.b.z = b.x * g.y - b.y * g.x
285 temp_matrix.c.x = c.y * g.z - c.z * g.y
286 temp_matrix.c.y = c.z * g.x - c.x * g.z
287 temp_matrix.c.z = c.x * g.y - c.y * g.x
288 self.
a += temp_matrix.a
289 self.
b += temp_matrix.b
290 self.
c += temp_matrix.c
293 '''re-normalise a rotation matrix''' 294 error = self.
a * self.
b 295 t0 = self.
a - (self.
b * (0.5 * error))
296 t1 = self.
b - (self.
a * (0.5 * error))
298 self.
a = t0 * (1.0 / t0.length())
299 self.
b = t1 * (1.0 / t1.length())
300 self.
c = t2 * (1.0 / t2.length())
303 '''the trace of the matrix''' 304 return self.a.x + self.b.y + self.c.z
307 '''create a rotation matrix from axis and angle''' 313 self.a.x = ct + (1-ct) * ux**2
314 self.a.y = ux*uy*(1-ct) - uz*st
315 self.a.z = ux*uz*(1-ct) + uy*st
316 self.b.x = uy*ux*(1-ct) + uz*st
317 self.b.y = ct + (1-ct) * uy**2
318 self.b.z = uy*uz*(1-ct) - ux*st
319 self.c.x = uz*ux*(1-ct) - uy*st
320 self.c.y = uz*uy*(1-ct) + ux*st
321 self.c.z = ct + (1-ct) * uz**2
325 '''get a rotation matrix from two vectors. 326 This returns a rotation matrix which when applied to vec1 327 will produce a vector pointing in the same direction as vec2''' 328 angle = vec1.angle(vec2)
330 if cross.length() == 0:
337 return self.a.close(m.a, tol)
and self.b.close(m.b, tol)
and self.c.close(m.c, tol)
340 '''a plane in 3 space, defined by a point and a vector normal''' 350 '''a line in 3 space, defined by a point and a vector''' 360 '''return point where line intersects with a plane''' 361 l_dot_n = self.
vector * plane.normal
365 d = ((plane.point - self.
point) * plane.normal) / l_dot_n
366 if forward_only
and d < 0:
def from_euler312(self, roll, pitch, yaw)
def from_two_vectors(self, vec1, vec2)
def __init__(self, point=None, normal=None)
def close(self, m, tol=1e-7)
def from_euler(self, roll, pitch, yaw)
def close(self, v, tol=1e-7)
def __init__(self, a=None, b=None, c=None)
def __init__(self, x=None, y=None, z=None)
def __init__(self, point=None, vector=None)
def from_axis_angle(self, axis, angle)
def plane_intersection(self, plane, forward_only=False)