5 Unit tests for the quaternion library 8 from __future__
import absolute_import, division, print_function
14 __author__ =
"Thomas Gubler" 15 __copyright__ =
"Copyright (C) 2014 Thomas Gubler" 16 __license__ =
"GNU Lesser General Public License v3" 17 __email__ =
"thomasgubler@gmail.com" 23 Class to test QuaternionBase 27 """Constructor, set up some data that is reused in many tests""" 28 super(QuaternionBaseTest, self).
__init__(*args, **kwargs)
32 """Test the constructor functionality""" 40 q = [0.707106781186547, 0, 0.707106781186547, 0]
41 euler = [np.radians(90), np.radians(90), np.radians(90)]
46 q = [0.774519052838329, 0.158493649053890, 0.591506350946110,
48 euler = [np.radians(60), np.radians(60), np.radians(60)]
49 dcm = [[0.25, -0.058012701892219, 0.966506350946110],
50 [0.433012701892219, 0.899519052838329, -0.058012701892219],
51 [-0.866025403784439, 0.433012701892219, 0.25]]
55 q = [0.754971823897152, 0.102564313848771, -0.324261369073765,
57 euler = [np.radians(34), np.radians(-22), np.radians(-80)]
58 dcm = [[0.161003786707723, 0.780067269138261, -0.604626195500121],
59 [-0.913097848445116, 0.350255780704370, 0.208741963313735],
60 [0.374606593415912, 0.518474631686401, 0.768670252102276]]
65 Helper function for constructor test 67 Calls constructor for the quaternion from q euler and dcm and checks 68 if the resulting converions are equivalent to the arguments. 69 The test for the euler angles is weak as the solution is not unique 71 :param q: quaternion 4x1, [w, x, y, z] 72 :param euler: [roll, pitch, yaw], needs to be equivalent to q 73 :param q: dcm 3x3, needs to be equivalent to q 78 np.testing.assert_almost_equal(q_test.q, q)
80 np.testing.assert_almost_equal(q_test.dcm, dcm)
83 assert(np.allclose(q_test.euler, euler)
or 84 np.allclose(q_test.q, q_euler.q))
88 np.testing.assert_almost_equal(q_test.q, q)
90 np.testing.assert_almost_equal(q_test.dcm, dcm)
93 assert(np.allclose(q_test.euler, euler)
or 94 np.allclose(q_test.q, q_euler.q))
98 np.testing.assert_almost_equal(q_test.q, q)
100 np.testing.assert_almost_equal(q_test.dcm, dcm)
103 assert(np.allclose(q_test.euler, euler)
or 104 np.allclose(q_test.q, q_euler.q))
108 np.testing.assert_almost_equal(q_test.q, q)
110 np.testing.assert_almost_equal(q_test.dcm, dcm)
113 assert(np.allclose(q_test.euler, euler)
or 114 np.allclose(q_test.q, q_euler.q))
120 n = np.sqrt(np.dot(qa, qa))
123 self.assertAlmostEqual(n, QuaternionBase.norm_array(qa))
124 np.testing.assert_almost_equal(qan, QuaternionBase.normalize_array(qa))
125 np.testing.assert_almost_equal(n, q.norm)
127 np.testing.assert_almost_equal(qan, q.q)
128 self.assertAlmostEqual(1, q.norm)
132 Creates a list of all euler angles 134 :param step: stepsixe in radians 135 :returns: euler angles [[phi, thea, psi], [phi, theta, psi], ...] 138 r_phi = np.arange(-np.pi + e, np.pi - e, step)
139 r_theta = np.arange(-np.pi/2 + e, np.pi/2 - e, step)
140 r_psi = np.arange(-np.pi + e, np.pi - e, step)
141 return [[phi, theta, psi]
for phi
in r_phi
for theta
in r_theta
145 """Generate quaternions from all euler angles""" 150 Tests forward and backward conversions 169 q_inv_inv = q_inv.inversed
170 assert q.close(q_inv_inv)
173 """Test multiplication""" 176 assert q.close(p * p.inversed * q)
178 r_dcm = np.dot(p.dcm, q.dcm)
179 np.testing.assert_almost_equal(r_dcm, r.dcm)
187 assert mul.close(div)
193 v = np.array([1, 2, 3])
195 v1_dcm = np.dot(q.dcm, v)
196 np.testing.assert_almost_equal(v1, v1_dcm)
199 np.testing.assert_almost_equal(v1, v1_mul[1:4])
200 v2 = q_inv.transform(v1)
201 np.testing.assert_almost_equal(v, v2)
206 Class to test Quaternion 210 """Constructor, set up some data that is reused in many tests""" 211 super(QuaternionTest, self).
__init__(*args, **kwargs)
215 """Generate quaternions from all euler angles""" 219 """Test the constructor functionality""" 227 q = [0.774519052838329, 0.158493649053890, 0.591506350946110,
229 euler = [np.radians(60), np.radians(60), np.radians(60)]
230 dcm =
Matrix3(
Vector3(0.25, -0.058012701892219, 0.966506350946110),
231 Vector3(0.433012701892219, 0.899519052838329,
233 Vector3(-0.866025403784439, 0.433012701892219, 0.25))
239 Helper function for constructor test 241 Calls constructor for the quaternion from q euler and dcm and checks 242 if the resulting converions are equivalent to the arguments. 243 The test for the euler angles is weak as the solution is not unique 245 :param q: quaternion 4x1, [w, x, y, z] 246 :param euler: Vector3(roll, pitch, yaw), needs to be equivalent to q 247 :param q: Matrix3, needs to be equivalent to q 252 np.testing.assert_almost_equal(q_test.q, q)
254 assert q_test.dcm.close(dcm)
257 assert(np.allclose(q_test.euler, euler)
or 258 np.allclose(q_test.q, q_euler.q))
263 np.testing.assert_almost_equal(q_test.q, q)
265 assert q_test.dcm.close(dcm)
268 assert(np.allclose(q_test.euler, euler)
or 269 np.allclose(q_test.q, q_euler.q))
273 np.testing.assert_almost_equal(q_test.q, q)
275 assert q_test.dcm.close(dcm)
278 assert(np.allclose(q_test.euler, euler)
or 279 np.allclose(q_test.q, q_euler.q))
283 np.testing.assert_almost_equal(q_test.q, q)
285 assert q_test.dcm.close(dcm)
288 assert(np.allclose(q_test.euler, euler)
or 289 np.allclose(q_test.q, q_euler.q))
293 np.testing.assert_almost_equal(q_test.q, q)
295 assert q_test.dcm.close(dcm)
298 assert(np.allclose(q_test.euler, euler)
or 299 np.allclose(q_test.q, q_euler.q))
303 Tests forward and backward conversions 325 assert v1.close(v1_dcm)
326 v2 = q_inv.transform(v1)
330 """Test multiplication""" 333 assert q.close(p * p.inversed * q)
335 r_dcm = p.dcm * q.dcm
336 assert r_dcm.close(r.dcm)
339 if __name__ ==
'__main__':
def _all_angles(self, step=np.radians(45))
def _helper_test_constructor(self, q, euler, dcm)
def _all_quaternions(self)
def test_constructor(self)
def test_constructor(self)
def test_conversion(self)
def test_conversion(self)
def __init__(self, args, kwargs)
def _helper_test_constructor(self, q, euler, dcm)
def __init__(self, args, kwargs)
def _all_quaternions(self)