rotmat.py 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369
  1. #!/usr/bin/env python
  2. #
  3. # vector3 and rotation matrix classes
  4. # This follows the conventions in the ArduPilot code,
  5. # and is essentially a python version of the AP_Math library
  6. #
  7. # Andrew Tridgell, March 2012
  8. #
  9. # This library is free software; you can redistribute it and/or modify it
  10. # under the terms of the GNU Lesser General Public License as published by the
  11. # Free Software Foundation; either version 2.1 of the License, or (at your
  12. # option) any later version.
  13. #
  14. # This library is distributed in the hope that it will be useful, but WITHOUT
  15. # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
  16. # FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License
  17. # for more details.
  18. #
  19. # You should have received a copy of the GNU Lesser General Public License
  20. # along with this library; if not, write to the Free Software Foundation,
  21. # Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
  22. '''rotation matrix class
  23. '''
  24. from __future__ import print_function
  25. from builtins import range
  26. from builtins import object
  27. from math import sin, cos, sqrt, asin, atan2, pi, radians, acos, degrees
  28. class Vector3(object):
  29. '''a vector'''
  30. def __init__(self, x=None, y=None, z=None):
  31. if x is not None and y is not None and z is not None:
  32. self.x = float(x)
  33. self.y = float(y)
  34. self.z = float(z)
  35. elif x is not None and len(x) == 3:
  36. self.x = float(x[0])
  37. self.y = float(x[1])
  38. self.z = float(x[2])
  39. elif x is not None:
  40. raise ValueError('bad initialiser')
  41. else:
  42. self.x = float(0)
  43. self.y = float(0)
  44. self.z = float(0)
  45. def __repr__(self):
  46. return 'Vector3(%.2f, %.2f, %.2f)' % (self.x,
  47. self.y,
  48. self.z)
  49. def __eq__(self, v):
  50. return self.x == v.x and self.y == v.y and self.z == v.z
  51. def __ne__(self, v):
  52. return not self == v
  53. def close(self, v, tol=1e-7):
  54. return abs(self.x - v.x) < tol and \
  55. abs(self.y - v.y) < tol and \
  56. abs(self.z - v.z) < tol
  57. def __add__(self, v):
  58. return Vector3(self.x + v.x,
  59. self.y + v.y,
  60. self.z + v.z)
  61. __radd__ = __add__
  62. def __sub__(self, v):
  63. return Vector3(self.x - v.x,
  64. self.y - v.y,
  65. self.z - v.z)
  66. def __neg__(self):
  67. return Vector3(-self.x, -self.y, -self.z)
  68. def __rsub__(self, v):
  69. return Vector3(v.x - self.x,
  70. v.y - self.y,
  71. v.z - self.z)
  72. def __mul__(self, v):
  73. if isinstance(v, Vector3):
  74. '''dot product'''
  75. return self.x*v.x + self.y*v.y + self.z*v.z
  76. return Vector3(self.x * v,
  77. self.y * v,
  78. self.z * v)
  79. __rmul__ = __mul__
  80. def __div__(self, v):
  81. return Vector3(self.x / v,
  82. self.y / v,
  83. self.z / v)
  84. def __mod__(self, v):
  85. '''cross product'''
  86. return Vector3(self.y*v.z - self.z*v.y,
  87. self.z*v.x - self.x*v.z,
  88. self.x*v.y - self.y*v.x)
  89. def __copy__(self):
  90. return Vector3(self.x, self.y, self.z)
  91. copy = __copy__
  92. def length(self):
  93. return sqrt(self.x**2 + self.y**2 + self.z**2)
  94. def zero(self):
  95. self.x = self.y = self.z = 0
  96. def angle(self, v):
  97. '''return the angle between this vector and another vector'''
  98. return acos((self * v) / (self.length() * v.length()))
  99. def normalized(self):
  100. return self.__div__(self.length())
  101. def normalize(self):
  102. v = self.normalized()
  103. self.x = v.x
  104. self.y = v.y
  105. self.z = v.z
  106. class Matrix3(object):
  107. '''a 3x3 matrix, intended as a rotation matrix'''
  108. def __init__(self, a=None, b=None, c=None):
  109. if a is not None and b is not None and c is not None:
  110. self.a = a.copy()
  111. self.b = b.copy()
  112. self.c = c.copy()
  113. else:
  114. self.identity()
  115. def __repr__(self):
  116. return 'Matrix3((%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f))' % (
  117. self.a.x, self.a.y, self.a.z,
  118. self.b.x, self.b.y, self.b.z,
  119. self.c.x, self.c.y, self.c.z)
  120. def identity(self):
  121. self.a = Vector3(1,0,0)
  122. self.b = Vector3(0,1,0)
  123. self.c = Vector3(0,0,1)
  124. def transposed(self):
  125. return Matrix3(Vector3(self.a.x, self.b.x, self.c.x),
  126. Vector3(self.a.y, self.b.y, self.c.y),
  127. Vector3(self.a.z, self.b.z, self.c.z))
  128. def from_euler(self, roll, pitch, yaw):
  129. '''fill the matrix from Euler angles in radians'''
  130. cp = cos(pitch)
  131. sp = sin(pitch)
  132. sr = sin(roll)
  133. cr = cos(roll)
  134. sy = sin(yaw)
  135. cy = cos(yaw)
  136. self.a.x = cp * cy
  137. self.a.y = (sr * sp * cy) - (cr * sy)
  138. self.a.z = (cr * sp * cy) + (sr * sy)
  139. self.b.x = cp * sy
  140. self.b.y = (sr * sp * sy) + (cr * cy)
  141. self.b.z = (cr * sp * sy) - (sr * cy)
  142. self.c.x = -sp
  143. self.c.y = sr * cp
  144. self.c.z = cr * cp
  145. def to_euler(self):
  146. '''find Euler angles (321 convention) for the matrix'''
  147. if self.c.x >= 1.0:
  148. pitch = pi
  149. elif self.c.x <= -1.0:
  150. pitch = -pi
  151. else:
  152. pitch = -asin(self.c.x)
  153. roll = atan2(self.c.y, self.c.z)
  154. yaw = atan2(self.b.x, self.a.x)
  155. return (roll, pitch, yaw)
  156. def to_euler312(self):
  157. '''find Euler angles (312 convention) for the matrix.
  158. See http://www.atacolorado.com/eulersequences.doc
  159. '''
  160. T21 = self.a.y
  161. T22 = self.b.y
  162. T23 = self.c.y
  163. T13 = self.c.x
  164. T33 = self.c.z
  165. yaw = atan2(-T21, T22)
  166. roll = asin(T23)
  167. pitch = atan2(-T13, T33)
  168. return (roll, pitch, yaw)
  169. def from_euler312(self, roll, pitch, yaw):
  170. '''fill the matrix from Euler angles in radians in 312 convention'''
  171. c3 = cos(pitch)
  172. s3 = sin(pitch)
  173. s2 = sin(roll)
  174. c2 = cos(roll)
  175. s1 = sin(yaw)
  176. c1 = cos(yaw)
  177. self.a.x = c1 * c3 - s1 * s2 * s3
  178. self.b.y = c1 * c2
  179. self.c.z = c3 * c2
  180. self.a.y = -c2*s1
  181. self.a.z = s3*c1 + c3*s2*s1
  182. self.b.x = c3*s1 + s3*s2*c1
  183. self.b.z = s1*s3 - s2*c1*c3
  184. self.c.x = -s3*c2
  185. self.c.y = s2
  186. def __add__(self, m):
  187. return Matrix3(self.a + m.a, self.b + m.b, self.c + m.c)
  188. __radd__ = __add__
  189. def __sub__(self, m):
  190. return Matrix3(self.a - m.a, self.b - m.b, self.c - m.c)
  191. def __rsub__(self, m):
  192. return Matrix3(m.a - self.a, m.b - self.b, m.c - self.c)
  193. def __eq__(self, m):
  194. return self.a == m.a and self.b == m.b and self.c == m.c
  195. def __ne__(self, m):
  196. return not self == m
  197. def __mul__(self, other):
  198. if isinstance(other, Vector3):
  199. v = other
  200. return Vector3(self.a.x * v.x + self.a.y * v.y + self.a.z * v.z,
  201. self.b.x * v.x + self.b.y * v.y + self.b.z * v.z,
  202. self.c.x * v.x + self.c.y * v.y + self.c.z * v.z)
  203. elif isinstance(other, Matrix3):
  204. m = other
  205. return Matrix3(Vector3(self.a.x * m.a.x + self.a.y * m.b.x + self.a.z * m.c.x,
  206. self.a.x * m.a.y + self.a.y * m.b.y + self.a.z * m.c.y,
  207. self.a.x * m.a.z + self.a.y * m.b.z + self.a.z * m.c.z),
  208. Vector3(self.b.x * m.a.x + self.b.y * m.b.x + self.b.z * m.c.x,
  209. self.b.x * m.a.y + self.b.y * m.b.y + self.b.z * m.c.y,
  210. self.b.x * m.a.z + self.b.y * m.b.z + self.b.z * m.c.z),
  211. Vector3(self.c.x * m.a.x + self.c.y * m.b.x + self.c.z * m.c.x,
  212. self.c.x * m.a.y + self.c.y * m.b.y + self.c.z * m.c.y,
  213. self.c.x * m.a.z + self.c.y * m.b.z + self.c.z * m.c.z))
  214. v = other
  215. return Matrix3(self.a * v, self.b * v, self.c * v)
  216. def __div__(self, v):
  217. return Matrix3(self.a / v, self.b / v, self.c / v)
  218. def __neg__(self):
  219. return Matrix3(-self.a, -self.b, -self.c)
  220. def __copy__(self):
  221. return Matrix3(self.a, self.b, self.c)
  222. copy = __copy__
  223. def rotate(self, g):
  224. '''rotate the matrix by a given amount on 3 axes,
  225. where g is a vector of delta angles. Used
  226. with DCM updates in mavextra.py'''
  227. temp_matrix = Matrix3()
  228. a = self.a
  229. b = self.b
  230. c = self.c
  231. temp_matrix.a.x = a.y * g.z - a.z * g.y
  232. temp_matrix.a.y = a.z * g.x - a.x * g.z
  233. temp_matrix.a.z = a.x * g.y - a.y * g.x
  234. temp_matrix.b.x = b.y * g.z - b.z * g.y
  235. temp_matrix.b.y = b.z * g.x - b.x * g.z
  236. temp_matrix.b.z = b.x * g.y - b.y * g.x
  237. temp_matrix.c.x = c.y * g.z - c.z * g.y
  238. temp_matrix.c.y = c.z * g.x - c.x * g.z
  239. temp_matrix.c.z = c.x * g.y - c.y * g.x
  240. self.a += temp_matrix.a
  241. self.b += temp_matrix.b
  242. self.c += temp_matrix.c
  243. def normalize(self):
  244. '''re-normalise a rotation matrix'''
  245. error = self.a * self.b
  246. t0 = self.a - (self.b * (0.5 * error))
  247. t1 = self.b - (self.a * (0.5 * error))
  248. t2 = t0 % t1
  249. self.a = t0 * (1.0 / t0.length())
  250. self.b = t1 * (1.0 / t1.length())
  251. self.c = t2 * (1.0 / t2.length())
  252. def trace(self):
  253. '''the trace of the matrix'''
  254. return self.a.x + self.b.y + self.c.z
  255. def from_axis_angle(self, axis, angle):
  256. '''create a rotation matrix from axis and angle'''
  257. ux = axis.x
  258. uy = axis.y
  259. uz = axis.z
  260. ct = cos(angle)
  261. st = sin(angle)
  262. self.a.x = ct + (1-ct) * ux**2
  263. self.a.y = ux*uy*(1-ct) - uz*st
  264. self.a.z = ux*uz*(1-ct) + uy*st
  265. self.b.x = uy*ux*(1-ct) + uz*st
  266. self.b.y = ct + (1-ct) * uy**2
  267. self.b.z = uy*uz*(1-ct) - ux*st
  268. self.c.x = uz*ux*(1-ct) - uy*st
  269. self.c.y = uz*uy*(1-ct) + ux*st
  270. self.c.z = ct + (1-ct) * uz**2
  271. def from_two_vectors(self, vec1, vec2):
  272. '''get a rotation matrix from two vectors.
  273. This returns a rotation matrix which when applied to vec1
  274. will produce a vector pointing in the same direction as vec2'''
  275. angle = vec1.angle(vec2)
  276. cross = vec1 % vec2
  277. if cross.length() == 0:
  278. # the two vectors are colinear
  279. return self.from_euler(0,0,angle)
  280. cross.normalize()
  281. return self.from_axis_angle(cross, angle)
  282. def close(self, m, tol=1e-7):
  283. return self.a.close(m.a, tol) and self.b.close(m.b, tol) and self.c.close(m.c, tol)
  284. class Plane(object):
  285. '''a plane in 3 space, defined by a point and a vector normal'''
  286. def __init__(self, point=None, normal=None):
  287. if point is None:
  288. point = Vector3(0,0,0)
  289. if normal is None:
  290. normal = Vector3(0, 0, 1)
  291. self.point = point
  292. self.normal = normal
  293. class Line(object):
  294. '''a line in 3 space, defined by a point and a vector'''
  295. def __init__(self, point=None, vector=None):
  296. if point is None:
  297. point = Vector3(0,0,0)
  298. if vector is None:
  299. vector = Vector3(0, 0, 1)
  300. self.point = point
  301. self.vector = vector
  302. def plane_intersection(self, plane, forward_only=False):
  303. '''return point where line intersects with a plane'''
  304. l_dot_n = self.vector * plane.normal
  305. if l_dot_n == 0.0:
  306. # line is parallel to the plane
  307. return None
  308. d = ((plane.point - self.point) * plane.normal) / l_dot_n
  309. if forward_only and d < 0:
  310. return None
  311. return (self.vector * d) + self.point