quaternion.py
Go to the documentation of this file.
1 import numpy as np
2 from dynamic_graph.sot.tools.se3 import SO3
3 from numpy import linalg
4 
5 
6 class Quaternion(object):
7  """
8  Quaternion class :
9  ------------------
10 
11  A quaternion has a scalar part and a vector part.
12  In this class the quaternion is represented as an array of 4 elements :
13  - the first element is the scalar part
14  - the next 3 elements represents the vector part
15 
16  One can acces to the array directly with the attribute "array"
17  e.g. q1=Quaternion(1,0,0,0) --> q1.array
18 
19  A quaternion can be instanciated with 1, 2 or 4 elements
20  (see : __init__() for more information).
21 
22  It can also return a rotation vector, a rotation matrix, or a SO3
23  (see the methods : to...() for more information).
24  """
25 
26  def __init__(self, *args):
27  """
28  Instanciation of the quaternion with 1, 2 or 4 arguments :
29  -----------------------------------------------------------
30  This creates a 4-sized array (self.array) representing the quaternion
31  with the first element representing the scalar part
32  and the 3 others the vector part.
33 
34  With 4 arguments :
35  ------------------
36  - the first one is used as the scalar part,
37  the other three as the vector part.
38 
39  With 2 arguments :
40  ------------------
41  - the 1-sized argument is used as the scalar part,
42  the 3-sized argument is used as the vector part.
43 
44  With 1 argument :
45  -----------------
46  - if it is a quaternion it will create a copy of this quaternion.
47  - if it is a scalar, the scalar will be used as the scalar part
48  and the vector part will be set at (0,0,0).
49  - if it is an array, matrix, tuple or list of 4 elements,
50  the first element is used as the scalar part
51  and the rest as the vector part.
52  - if it is an array, matrix, tuple or list of 3 elements,
53  the 3 elements are interpreted as a rotation vector,
54  this creates a quaternion representing the same rotation.
55  - if it is a to 2 dimension array convertible array, matrix, tuple
56  or list with at least (3*3) elements,
57  the upper left (3*3) elements are interpreted as a rotation matrix,
58  this creates a quaternion representing the same rotation.
59 
60  With 0 arguments :
61  ------------------
62  If no argument is given, than the quaternion will be set by default
63  to with the scalar part set to 1 and the vector part to (0,0,0).
64  (this is the neutral element for multiplication in quaternion space)
65 
66  To create a quaternion from Roll, Pitch, Yaw angles :
67  -----------------------------------------------------
68  first instanciate a quaternion and than use the method fromRPY()
69  to change the values of it to the dezired ones.
70  e.g. : quat().fromRPY(R,P,Y)
71  """
72 
73  error = False
74  if len(args) == 0: # By default, if no argument is given
75  self.array = np.array([1.0, 0.0, 0.0, 0.0])
76  elif len(args) == 4: # From 4 elements
77  if np.array(args).size == 4:
78  self.array = np.double(np.array(args))
79  else:
80  error = True
81  elif len(args) == 1:
82  if type(args[0]) == Quaternion: # From a Quaternion
83  self.array = args[0].array.copy()
84  elif np.array(args[0]).size == 1:
85  # From one sized element, this element will be the scalar part,
86  # the vector part will be set at (0,0,0)
87  self.array = np.double(
88  np.hstack([np.array(args[0]), np.array([0, 0, 0])])
89  )
90  elif np.array(args[0]).size == 4 and max(np.array(args[0]).shape) == 4:
91  # From an array, matrix, tuple or list of 4 elements
92  self.array = np.double(np.array(args[0])).reshape(
93  4,
94  )
95  elif np.array(args[0]).size == 3 and max(np.array(args[0]).shape) == 3:
96  # From an array, matrix, tuple or list of 3 elements interpreted
97  # as a rotation vector
98  rV = np.double(np.array(args[0])).reshape(
99  3,
100  )
101  alpha = np.double(linalg.norm(rV))
102  if alpha != 0:
103  e = rV / alpha
104  else:
105  e = rV
106  self.array = np.hstack([np.cos(alpha / 2.0), np.sin(alpha / 2.0) * e])
107  elif (
108  len(np.array(args[0]).shape) == 2
109  and np.array(args[0]).shape[0] >= 3
110  and np.array(args[0]).shape[1] >= 3
111  ):
112  # From a to 2 dimension array convertible array, matrix, tuple or list
113  # with at least (3*3) elements interpreted as a rotation matrix
114  rM = np.double(np.array(args[0])[:3, :3])
115  selec = np.zeros(4)
116  selec[0] = 1 + rM[0, 0] + rM[1, 1] + rM[2, 2]
117  selec[1] = 1 + rM[0, 0] - rM[1, 1] - rM[2, 2]
118  selec[2] = 1 - rM[0, 0] + rM[1, 1] - rM[2, 2]
119  selec[3] = 1 - rM[0, 0] - rM[1, 1] + rM[2, 2]
120  param = selec.argmax()
121  if selec[param] > 0:
122  q = np.zeros(4)
123  if param == 0:
124  q[0] = np.sqrt(selec[param])
125  q[1] = (rM[2, 1] - rM[1, 2]) / q[0]
126  q[2] = (rM[0, 2] - rM[2, 0]) / q[0]
127  q[3] = (rM[1, 0] - rM[0, 1]) / q[0]
128  self.array = q * 0.5
129  # print '--1--V3'
130  elif param == 1:
131  q[1] = np.sqrt(selec[param])
132  q[0] = (rM[2, 1] - rM[1, 2]) / q[1]
133  q[2] = (rM[1, 0] + rM[0, 1]) / q[1]
134  q[3] = (rM[0, 2] + rM[2, 0]) / q[1]
135  self.array = q * 0.5
136  # print '--2--V3'
137  elif param == 2:
138  q[2] = np.sqrt(selec[param])
139  q[0] = (rM[0, 2] - rM[2, 0]) / q[2]
140  q[1] = (rM[1, 0] + rM[0, 1]) / q[2]
141  q[3] = (rM[2, 1] + rM[1, 2]) / q[2]
142  self.array = q * 0.5
143  # print '--3--V3'
144  elif param == 3:
145  q[3] = np.sqrt(selec[param])
146  q[0] = (rM[1, 0] - rM[0, 1]) / q[3]
147  q[1] = (rM[0, 2] + rM[2, 0]) / q[3]
148  q[2] = (rM[2, 1] + rM[1, 2]) / q[3]
149  self.array = q * 0.5
150  # print '--4--V3'
151  else:
152  error = True
153  else:
154  error = True
155  elif (
156  len(args) == 2
157  ): # From a scalar part (1 element) and a vector part (3 elements)
158  arg0 = np.double(np.array(args[0]))
159  arg1 = np.double(np.array(args[1]))
160  if arg0.size == 1 and arg1.size == 3:
161  self.array = np.zeros(4)
162  self.array[0] = arg0
163  self.array[1:4] = arg1[:]
164  elif arg0.size == 3 and arg1.size == 1:
165  self.array = np.zeros(4)
166  self.array[0] = arg1
167  self.array[1:4] = arg0[:]
168  else:
169  error = True
170 
171  else:
172  error = True
173 
174  if not error and self.array.shape != (4,):
175  del self.array
176  error = True
177  if error:
178  raise TypeError(
179  "Impossible to instanciate the Quaternion object "
180  "with the given arguments"
181  )
182 
183  def __str__(self):
184  """
185  String representation of the quaternion.
186  """
187  aff = "[ "
188  aff += str(self.array[0]) + " + "
189  aff += str(self.array[1]) + " i + "
190  aff += str(self.array[2]) + " j + "
191  aff += str(self.array[3]) + " k ]"
192  return aff
193 
194  def __neg__(self):
195  """
196  Returns a quaternion which elements are the opposite of the original,
197  (this opposite quaternion represents the same rotation).
198  """
199  return Quaternion(-self.array)
200 
201  def __add__(self, other):
202  """
203  If other is not a quaternion it is casted to a quaternion,
204  the elements are added one to one.
205  """
206  if type(other) != Quaternion:
207  q2 = Quaternion(other)
208  else:
209  q2 = other
210  return Quaternion(self.array + q2.array)
211 
212  def __sub__(self, other):
213  """
214  If other is not a quaternion it is casted to a quaternion,
215  the elements are substracted one to one.
216  """
217  if type(other) != Quaternion:
218  q2 = Quaternion(other)
219  else:
220  q2 = other
221  return Quaternion(self.array - q2.array)
222 
223  def __mul__(self, other):
224  """
225  If other is not a quaternion it is casted to a quaternion,
226  the result of the quaternion multiplication is returned.
227  """
228  if type(other) != Quaternion:
229  q2 = Quaternion(other)
230  else:
231  q2 = other
232  qr = np.zeros(4)
233  qr[0] = self.array[0] * q2.array[0] - np.vdot(self.array[1:], q2.array[1:])
234  qr[1:4] = (
235  np.cross(self.array[1:4], q2.array[1:4])
236  + self.array[0] * q2.array[1:4]
237  + q2.array[0] * self.array[1:4]
238  )
239  return Quaternion(qr)
240 
241  def __rmul__(self, other):
242  """
243  other is casted to a quaternion,
244  the result of the quaternion multiplication is returned.
245  """
246  return Quaternion(other) * self
247 
248  def __abs__(self):
249  """
250  Returns the norm of the quaternion.
251  """
252  return np.double(linalg.norm(self.array))
253 
254  def conjugate(self):
255  """
256  Returns the conjugate of the quaternion.
257  """
258  return Quaternion(self.array[0], -self.array[1:4])
259 
260  def inv(self):
261  """
262  Returns the inverse of the quaternion.
263  """
264  return Quaternion(self.conjugate().array / (abs(self) ** 2))
265 
266  def __div__(self, other):
267  """
268  If other is not a quaternion it is casted to a quaternion,
269  the result of the quaternion multiplication with the inverse of other
270  is returned.
271  """
272  if type(other) != Quaternion:
273  q2 = Quaternion(other)
274  else:
275  q2 = other
276  return self * q2.inv()
277 
278  def __pow__(self, n):
279  """
280  Returns quaternion**n with quaternion**0 = Quaternion(1,0,0,0).
281  """
282  r = Quaternion()
283  for i in range(n):
284  r = r * self
285  return r
286 
287  def normalize(self):
288  """
289  Changes the values of the quaternion to make it a unit quaternion
290  representing the same rotation as the original one
291  and returns the updated version.
292  """
293  self.array /= abs(self)
294  return self
295 
296  def normalized(self):
297  """
298  Returns the unit quaternion representation of the quaternion
299  without changing the original.
300  """
301  qr = Quaternion(self)
302  qr.normalize()
303  return qr
304 
305  def toSO3(self):
306  """
307  Returns the corresponding SO3.
308  """
309  return SO3(self.toRotationMatrix())
310 
311  def toRotationMatrix(self):
312  """
313  Returns a (3*3) array (rotation matrix)
314  representing the same rotation as the (normalized) quaternion.
315  """
316  q = self.normalized().array
317  rm = np.zeros((3, 3))
318  rm[0, 0] = 1 - 2 * (q[2] ** 2 + q[3] ** 2)
319  rm[0, 1] = 2 * q[1] * q[2] - 2 * q[0] * q[3]
320  rm[0, 2] = 2 * q[1] * q[3] + 2 * q[0] * q[2]
321  rm[1, 0] = 2 * q[1] * q[2] + 2 * q[0] * q[3]
322  rm[1, 1] = 1 - 2 * (q[1] ** 2 + q[3] ** 2)
323  rm[1, 2] = 2 * q[2] * q[3] - 2 * q[0] * q[1]
324  rm[2, 0] = 2 * q[1] * q[3] - 2 * q[0] * q[2]
325  rm[2, 1] = 2 * q[2] * q[3] + 2 * q[0] * q[1]
326  rm[2, 2] = 1 - 2 * (q[1] ** 2 + q[2] ** 2)
327  return rm
328 
329  def toRotationVector(self):
330  """
331  Returns a 3-sized array (rotation vector)
332  representing the same rotation as the (normalized) quaternion.
333  """
334  q = self.normalized().array
335  rV = np.zeros(3)
336  alpha = 2 * np.arccos(q[0])
337  if linalg.norm(q[1:4]) != 0:
338  rV = alpha * q[1:4] / linalg.norm(q[1:4])
339  return rV
340 
341  def copy(self):
342  """
343  Returns a copy of the quaternion.
344  """
345  return Quaternion(self)
346 
347  def toRPY(self):
348  """
349  Returns a 3-sized array with representing the same rotation
350  as the (normalized) quaternion. With :
351  - the first element representing the Roll,
352  - the second the Pitch
353  - the third the Yaw
354  Where Roll Pitch and Yaw are the angles so that the rotation
355  with the quaternion represents the same rotation as :
356  - A rotation of R (Roll) about the original x-axis,
357  followed by a rotation of P (Pitch) about the original y-axis,
358  followed by a rotation of Y (Yaw) about the original z-axis.
359  - Or otherwise a rotation of Y about the original z-axis,
360  followed by a rotation of P about the new y-axis,
361  followed by a rotation of R about the new x-axis.
362  """
363  q = self.normalized().array
364  r = np.arctan2(2 * (q[0] * q[1] + q[2] * q[3]), 1 - 2 * (q[1] ** 2 + q[2] ** 2))
365  p = np.arctan2(
366  2 * (q[0] * q[2] - q[3] * q[1]),
367  np.sqrt(
368  (2 * (q[0] * q[1] + q[2] * q[3])) ** 2
369  + (1 - 2 * (q[1] ** 2 + q[2] ** 2)) ** 2
370  ),
371  ) # We cas use arcsin but arctan2 is more robust
372  y = np.arctan2(2 * (q[0] * q[3] + q[1] * q[2]), 1 - 2 * (q[2] ** 2 + q[3] ** 2))
373  return np.array([r, p, y])
374 
375  def fromRPY(self, R, P, Y):
376  """
377  Set the values of the quaternion to the values of a unit quaternion
378  representing the same rotation as the one performed by Roll Pitch Yaw :
379  - A rotation of R (Roll) about the original x-axis,
380  followed by a rotation of P (Pitch) about the original y-axis,
381  followed by a rotation of Y (Yaw) about the original z-axis.
382  - Or otherwise a rotation of Y about the original z-axis,
383  followed by a rotation of P about the new y-axis,
384  followed by a rotation of R about the new x-axis.
385  """
386  r = R / 2.0
387  p = P / 2.0
388  y = Y / 2.0
389  self.array[0] = np.cos(r) * np.cos(p) * np.cos(y) + np.sin(r) * np.sin(
390  p
391  ) * np.sin(y)
392  self.array[1] = np.sin(r) * np.cos(p) * np.cos(y) - np.cos(r) * np.sin(
393  p
394  ) * np.sin(y)
395  self.array[2] = np.cos(r) * np.sin(p) * np.cos(y) + np.sin(r) * np.cos(
396  p
397  ) * np.sin(y)
398  self.array[3] = np.cos(r) * np.cos(p) * np.sin(y) - np.sin(r) * np.sin(
399  p
400  ) * np.cos(y)
401  return self.normalize()
quaternion.Quaternion.toSO3
def toSO3(self)
Definition: quaternion.py:305
quaternion.Quaternion.__pow__
def __pow__(self, n)
Definition: quaternion.py:278
quaternion.Quaternion.toRPY
def toRPY(self)
Definition: quaternion.py:347
quaternion.Quaternion.normalized
def normalized(self)
Definition: quaternion.py:296
quaternion.Quaternion.__sub__
def __sub__(self, other)
Definition: quaternion.py:212
quaternion.Quaternion.normalize
def normalize(self)
Definition: quaternion.py:287
quaternion.Quaternion.__init__
def __init__(self, *args)
Definition: quaternion.py:26
quaternion.Quaternion.__add__
def __add__(self, other)
Definition: quaternion.py:201
quaternion.Quaternion.array
array
Definition: quaternion.py:75
quaternion.Quaternion.toRotationVector
def toRotationVector(self)
Definition: quaternion.py:329
quaternion.Quaternion.conjugate
def conjugate(self)
Definition: quaternion.py:254
quaternion.Quaternion
Definition: quaternion.py:6
quaternion.Quaternion.copy
def copy(self)
Definition: quaternion.py:341
quaternion.Quaternion.toRotationMatrix
def toRotationMatrix(self)
Definition: quaternion.py:311
quaternion.Quaternion.__mul__
def __mul__(self, other)
Definition: quaternion.py:223
quaternion.Quaternion.__str__
def __str__(self)
Definition: quaternion.py:183
quaternion.Quaternion.__rmul__
def __rmul__(self, other)
Definition: quaternion.py:241
quaternion.Quaternion.__neg__
def __neg__(self)
Definition: quaternion.py:194
quaternion.Quaternion.inv
def inv(self)
Definition: quaternion.py:260
quaternion.Quaternion.fromRPY
def fromRPY(self, R, P, Y)
Definition: quaternion.py:375
quaternion.Quaternion.__div__
def __div__(self, other)
Definition: quaternion.py:266
quaternion.Quaternion.__abs__
def __abs__(self)
Definition: quaternion.py:248


sot-tools
Author(s): Mehdi Benallegue, Francois Keith, Florent Lamiraux, Thomas Moulard, Olivier Stasse, Jorrit T'Hooft
autogenerated on Wed Aug 2 2023 02:35:13