$search
00001 # -*- coding: utf-8 -*- 00002 # transformations.py 00003 00004 # Copyright (c) 2006-2012, Christoph Gohlke 00005 # Copyright (c) 2006-2012, The Regents of the University of California 00006 # Produced at the Laboratory for Fluorescence Dynamics 00007 # All rights reserved. 00008 # 00009 # Redistribution and use in source and binary forms, with or without 00010 # modification, are permitted provided that the following conditions are met: 00011 # 00012 # * Redistributions of source code must retain the above copyright 00013 # notice, this list of conditions and the following disclaimer. 00014 # * Redistributions in binary form must reproduce the above copyright 00015 # notice, this list of conditions and the following disclaimer in the 00016 # documentation and/or other materials provided with the distribution. 00017 # * Neither the name of the copyright holders nor the names of any 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00022 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00023 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00024 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00025 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00026 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00027 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00028 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00029 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00030 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 00033 """Homogeneous Transformation Matrices and Quaternions. 00034 00035 A library for calculating 4x4 matrices for translating, rotating, reflecting, 00036 scaling, shearing, projecting, orthogonalizing, and superimposing arrays of 00037 3D homogeneous coordinates as well as for converting between rotation matrices, 00038 Euler angles, and quaternions. Also includes an Arcball control object and 00039 functions to decompose transformation matrices. 00040 00041 :Authors: 00042 `Christoph Gohlke <http://www.lfd.uci.edu/~gohlke/>`__, 00043 Laboratory for Fluorescence Dynamics, University of California, Irvine 00044 00045 :Version: 2012.01.01 00046 00047 Requirements 00048 ------------ 00049 00050 * `Python 2.7 or 3.2 <http://www.python.org>`__ 00051 * `Numpy 1.6 <http://numpy.scipy.org>`__ 00052 * `transformations.c 2012.01.01 <http://www.lfd.uci.edu/~gohlke/>`__ 00053 (optional implementation of some functions in C) 00054 00055 Notes 00056 ----- 00057 00058 The API is not stable yet and is expected to change between revisions. 00059 00060 This Python code is not optimized for speed. Refer to the transformations.c 00061 module for a faster implementation of some functions. 00062 00063 Documentation in HTML format can be generated with epydoc. 00064 00065 Matrices (M) can be inverted using numpy.linalg.inv(M), be concatenated using 00066 numpy.dot(M0, M1), or transform homogeneous coordinate arrays (v) using 00067 numpy.dot(M, v) for shape (4, \*) column vectors, respectively 00068 numpy.dot(v, M.T) for shape (\*, 4) row vectors ("array of points"). 00069 00070 This module follows the "column vectors on the right" convention. Use the 00071 transpose of the transformation matrices for OpenGL glMultMatrixd(), which 00072 assumes "row vectors on the left" convention. 00073 00074 Calculations are carried out with numpy.float64 precision. 00075 00076 Vector, point, quaternion, and matrix function arguments are expected to be 00077 "array like", i.e. tuple, list, or numpy arrays. 00078 00079 Return types are numpy arrays unless specified otherwise. 00080 00081 Angles are in radians unless specified otherwise. 00082 00083 Quaternions w+ix+jy+kz are represented as [w, x, y, z]. 00084 00085 A triple of Euler angles can be applied/interpreted in 24 ways, which can 00086 be specified using a 4 character string or encoded 4-tuple: 00087 00088 *Axes 4-string*: e.g. 'sxyz' or 'ryxy' 00089 00090 - first character : rotations are applied to 's'tatic or 'r'otating frame 00091 - remaining characters : successive rotation axis 'x', 'y', or 'z' 00092 00093 *Axes 4-tuple*: e.g. (0, 0, 0, 0) or (1, 1, 1, 1) 00094 00095 - inner axis: code of axis ('x':0, 'y':1, 'z':2) of rightmost matrix. 00096 - parity : even (0) if inner axis 'x' is followed by 'y', 'y' is followed 00097 by 'z', or 'z' is followed by 'x'. Otherwise odd (1). 00098 - repetition : first and last axis are same (1) or different (0). 00099 - frame : rotations are applied to static (0) or rotating (1) frame. 00100 00101 References 00102 ---------- 00103 00104 (1) Matrices and transformations. Ronald Goldman. 00105 In "Graphics Gems I", pp 472-475. Morgan Kaufmann, 1990. 00106 (2) More matrices and transformations: shear and pseudo-perspective. 00107 Ronald Goldman. In "Graphics Gems II", pp 320-323. Morgan Kaufmann, 1991. 00108 (3) Decomposing a matrix into simple transformations. Spencer Thomas. 00109 In "Graphics Gems II", pp 320-323. Morgan Kaufmann, 1991. 00110 (4) Recovering the data from the transformation matrix. Ronald Goldman. 00111 In "Graphics Gems II", pp 324-331. Morgan Kaufmann, 1991. 00112 (5) Euler angle conversion. Ken Shoemake. 00113 In "Graphics Gems IV", pp 222-229. Morgan Kaufmann, 1994. 00114 (6) Arcball rotation control. Ken Shoemake. 00115 In "Graphics Gems IV", pp 175-192. Morgan Kaufmann, 1994. 00116 (7) Representing attitude: Euler angles, unit quaternions, and rotation 00117 vectors. James Diebel. 2006. 00118 (8) A discussion of the solution for the best rotation to relate two sets 00119 of vectors. W Kabsch. Acta Cryst. 1978. A34, 827-828. 00120 (9) Closed-form solution of absolute orientation using unit quaternions. 00121 BKP Horn. J Opt Soc Am A. 1987. 4(4):629-642. 00122 (10) Quaternions. Ken Shoemake. 00123 http://www.sfu.ca/~jwa3/cmpt461/files/quatut.pdf 00124 (11) From quaternion to matrix and back. JMP van Waveren. 2005. 00125 http://www.intel.com/cd/ids/developer/asmo-na/eng/293748.htm 00126 (12) Uniform random rotations. Ken Shoemake. 00127 In "Graphics Gems III", pp 124-132. Morgan Kaufmann, 1992. 00128 (13) Quaternion in molecular modeling. CFF Karney. 00129 J Mol Graph Mod, 25(5):595-604 00130 (14) New method for extracting the quaternion from a rotation matrix. 00131 Itzhack Y Bar-Itzhack, J Guid Contr Dynam. 2000. 23(6): 1085-1087. 00132 (15) Multiple View Geometry in Computer Vision. Hartley and Zissermann. 00133 Cambridge University Press; 2nd Ed. 2004. Chapter 4, Algorithm 4.7, p 130. 00134 00135 Examples 00136 -------- 00137 00138 >>> alpha, beta, gamma = 0.123, -1.234, 2.345 00139 >>> origin, xaxis, yaxis, zaxis = [0, 0, 0], [1, 0, 0], [0, 1, 0], [0, 0, 1] 00140 >>> I = identity_matrix() 00141 >>> Rx = rotation_matrix(alpha, xaxis) 00142 >>> Ry = rotation_matrix(beta, yaxis) 00143 >>> Rz = rotation_matrix(gamma, zaxis) 00144 >>> R = concatenate_matrices(Rx, Ry, Rz) 00145 >>> euler = euler_from_matrix(R, 'rxyz') 00146 >>> numpy.allclose([alpha, beta, gamma], euler) 00147 True 00148 >>> Re = euler_matrix(alpha, beta, gamma, 'rxyz') 00149 >>> is_same_transform(R, Re) 00150 True 00151 >>> al, be, ga = euler_from_matrix(Re, 'rxyz') 00152 >>> is_same_transform(Re, euler_matrix(al, be, ga, 'rxyz')) 00153 True 00154 >>> qx = quaternion_about_axis(alpha, xaxis) 00155 >>> qy = quaternion_about_axis(beta, yaxis) 00156 >>> qz = quaternion_about_axis(gamma, zaxis) 00157 >>> q = quaternion_multiply(qx, qy) 00158 >>> q = quaternion_multiply(q, qz) 00159 >>> Rq = quaternion_matrix(q) 00160 >>> is_same_transform(R, Rq) 00161 True 00162 >>> S = scale_matrix(1.23, origin) 00163 >>> T = translation_matrix([1, 2, 3]) 00164 >>> Z = shear_matrix(beta, xaxis, origin, zaxis) 00165 >>> R = random_rotation_matrix(numpy.random.rand(3)) 00166 >>> M = concatenate_matrices(T, R, Z, S) 00167 >>> scale, shear, angles, trans, persp = decompose_matrix(M) 00168 >>> numpy.allclose(scale, 1.23) 00169 True 00170 >>> numpy.allclose(trans, [1, 2, 3]) 00171 True 00172 >>> numpy.allclose(shear, [0, math.tan(beta), 0]) 00173 True 00174 >>> is_same_transform(R, euler_matrix(axes='sxyz', *angles)) 00175 True 00176 >>> M1 = compose_matrix(scale, shear, angles, trans, persp) 00177 >>> is_same_transform(M, M1) 00178 True 00179 >>> v0, v1 = random_vector(3), random_vector(3) 00180 >>> M = rotation_matrix(angle_between_vectors(v0, v1), vector_product(v0, v1)) 00181 >>> v2 = numpy.dot(v0, M[:3,:3].T) 00182 >>> numpy.allclose(unit_vector(v1), unit_vector(v2)) 00183 True 00184 00185 """ 00186 00187 from __future__ import division, print_function 00188 00189 import sys 00190 import os 00191 import warnings 00192 import math 00193 00194 import numpy 00195 00196 00197 def identity_matrix(): 00198 """Return 4x4 identity/unit matrix. 00199 00200 >>> I = identity_matrix() 00201 >>> numpy.allclose(I, numpy.dot(I, I)) 00202 True 00203 >>> numpy.sum(I), numpy.trace(I) 00204 (4.0, 4.0) 00205 >>> numpy.allclose(I, numpy.identity(4)) 00206 True 00207 00208 """ 00209 return numpy.identity(4) 00210 00211 00212 def translation_matrix(direction): 00213 """Return matrix to translate by direction vector. 00214 00215 >>> v = numpy.random.random(3) - 0.5 00216 >>> numpy.allclose(v, translation_matrix(v)[:3, 3]) 00217 True 00218 00219 """ 00220 M = numpy.identity(4) 00221 M[:3, 3] = direction[:3] 00222 return M 00223 00224 00225 def translation_from_matrix(matrix): 00226 """Return translation vector from translation matrix. 00227 00228 >>> v0 = numpy.random.random(3) - 0.5 00229 >>> v1 = translation_from_matrix(translation_matrix(v0)) 00230 >>> numpy.allclose(v0, v1) 00231 True 00232 00233 """ 00234 return numpy.array(matrix, copy=False)[:3, 3].copy() 00235 00236 00237 def reflection_matrix(point, normal): 00238 """Return matrix to mirror at plane defined by point and normal vector. 00239 00240 >>> v0 = numpy.random.random(4) - 0.5 00241 >>> v0[3] = 1. 00242 >>> v1 = numpy.random.random(3) - 0.5 00243 >>> R = reflection_matrix(v0, v1) 00244 >>> numpy.allclose(2, numpy.trace(R)) 00245 True 00246 >>> numpy.allclose(v0, numpy.dot(R, v0)) 00247 True 00248 >>> v2 = v0.copy() 00249 >>> v2[:3] += v1 00250 >>> v3 = v0.copy() 00251 >>> v2[:3] -= v1 00252 >>> numpy.allclose(v2, numpy.dot(R, v3)) 00253 True 00254 00255 """ 00256 normal = unit_vector(normal[:3]) 00257 M = numpy.identity(4) 00258 M[:3, :3] -= 2.0 * numpy.outer(normal, normal) 00259 M[:3, 3] = (2.0 * numpy.dot(point[:3], normal)) * normal 00260 return M 00261 00262 00263 def reflection_from_matrix(matrix): 00264 """Return mirror plane point and normal vector from reflection matrix. 00265 00266 >>> v0 = numpy.random.random(3) - 0.5 00267 >>> v1 = numpy.random.random(3) - 0.5 00268 >>> M0 = reflection_matrix(v0, v1) 00269 >>> point, normal = reflection_from_matrix(M0) 00270 >>> M1 = reflection_matrix(point, normal) 00271 >>> is_same_transform(M0, M1) 00272 True 00273 00274 """ 00275 M = numpy.array(matrix, dtype=numpy.float64, copy=False) 00276 # normal: unit eigenvector corresponding to eigenvalue -1 00277 w, V = numpy.linalg.eig(M[:3, :3]) 00278 i = numpy.where(abs(numpy.real(w) + 1.0) < 1e-8)[0] 00279 if not len(i): 00280 raise ValueError("no unit eigenvector corresponding to eigenvalue -1") 00281 normal = numpy.real(V[:, i[0]]).squeeze() 00282 # point: any unit eigenvector corresponding to eigenvalue 1 00283 w, V = numpy.linalg.eig(M) 00284 i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] 00285 if not len(i): 00286 raise ValueError("no unit eigenvector corresponding to eigenvalue 1") 00287 point = numpy.real(V[:, i[-1]]).squeeze() 00288 point /= point[3] 00289 return point, normal 00290 00291 00292 def rotation_matrix(angle, direction, point=None): 00293 """Return matrix to rotate about axis defined by point and direction. 00294 00295 >>> R = rotation_matrix(math.pi/2, [0, 0, 1], [1, 0, 0]) 00296 >>> numpy.allclose(numpy.dot(R, [0, 0, 0, 1]), [1, -1, 0, 1]) 00297 True 00298 >>> angle = (random.random() - 0.5) * (2*math.pi) 00299 >>> direc = numpy.random.random(3) - 0.5 00300 >>> point = numpy.random.random(3) - 0.5 00301 >>> R0 = rotation_matrix(angle, direc, point) 00302 >>> R1 = rotation_matrix(angle-2*math.pi, direc, point) 00303 >>> is_same_transform(R0, R1) 00304 True 00305 >>> R0 = rotation_matrix(angle, direc, point) 00306 >>> R1 = rotation_matrix(-angle, -direc, point) 00307 >>> is_same_transform(R0, R1) 00308 True 00309 >>> I = numpy.identity(4, numpy.float64) 00310 >>> numpy.allclose(I, rotation_matrix(math.pi*2, direc)) 00311 True 00312 >>> numpy.allclose(2, numpy.trace(rotation_matrix(math.pi/2, 00313 ... direc, point))) 00314 True 00315 00316 """ 00317 sina = math.sin(angle) 00318 cosa = math.cos(angle) 00319 direction = unit_vector(direction[:3]) 00320 # rotation matrix around unit vector 00321 R = numpy.diag([cosa, cosa, cosa]) 00322 R += numpy.outer(direction, direction) * (1.0 - cosa) 00323 direction *= sina 00324 R += numpy.array([[ 0.0, -direction[2], direction[1]], 00325 [ direction[2], 0.0, -direction[0]], 00326 [-direction[1], direction[0], 0.0]]) 00327 M = numpy.identity(4) 00328 M[:3, :3] = R 00329 if point is not None: 00330 # rotation not around origin 00331 point = numpy.array(point[:3], dtype=numpy.float64, copy=False) 00332 M[:3, 3] = point - numpy.dot(R, point) 00333 return M 00334 00335 00336 def rotation_from_matrix(matrix): 00337 """Return rotation angle and axis from rotation matrix. 00338 00339 >>> angle = (random.random() - 0.5) * (2*math.pi) 00340 >>> direc = numpy.random.random(3) - 0.5 00341 >>> point = numpy.random.random(3) - 0.5 00342 >>> R0 = rotation_matrix(angle, direc, point) 00343 >>> angle, direc, point = rotation_from_matrix(R0) 00344 >>> R1 = rotation_matrix(angle, direc, point) 00345 >>> is_same_transform(R0, R1) 00346 True 00347 00348 """ 00349 R = numpy.array(matrix, dtype=numpy.float64, copy=False) 00350 R33 = R[:3, :3] 00351 # direction: unit eigenvector of R33 corresponding to eigenvalue of 1 00352 w, W = numpy.linalg.eig(R33.T) 00353 i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] 00354 if not len(i): 00355 raise ValueError("no unit eigenvector corresponding to eigenvalue 1") 00356 direction = numpy.real(W[:, i[-1]]).squeeze() 00357 # point: unit eigenvector of R33 corresponding to eigenvalue of 1 00358 w, Q = numpy.linalg.eig(R) 00359 i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] 00360 if not len(i): 00361 raise ValueError("no unit eigenvector corresponding to eigenvalue 1") 00362 point = numpy.real(Q[:, i[-1]]).squeeze() 00363 point /= point[3] 00364 # rotation angle depending on direction 00365 cosa = (numpy.trace(R33) - 1.0) / 2.0 00366 if abs(direction[2]) > 1e-8: 00367 sina = (R[1, 0] + (cosa-1.0)*direction[0]*direction[1]) / direction[2] 00368 elif abs(direction[1]) > 1e-8: 00369 sina = (R[0, 2] + (cosa-1.0)*direction[0]*direction[2]) / direction[1] 00370 else: 00371 sina = (R[2, 1] + (cosa-1.0)*direction[1]*direction[2]) / direction[0] 00372 angle = math.atan2(sina, cosa) 00373 return angle, direction, point 00374 00375 00376 def scale_matrix(factor, origin=None, direction=None): 00377 """Return matrix to scale by factor around origin in direction. 00378 00379 Use factor -1 for point symmetry. 00380 00381 >>> v = (numpy.random.rand(4, 5) - 0.5) * 20 00382 >>> v[3] = 1 00383 >>> S = scale_matrix(-1.234) 00384 >>> numpy.allclose(numpy.dot(S, v)[:3], -1.234*v[:3]) 00385 True 00386 >>> factor = random.random() * 10 - 5 00387 >>> origin = numpy.random.random(3) - 0.5 00388 >>> direct = numpy.random.random(3) - 0.5 00389 >>> S = scale_matrix(factor, origin) 00390 >>> S = scale_matrix(factor, origin, direct) 00391 00392 """ 00393 if direction is None: 00394 # uniform scaling 00395 M = numpy.diag([factor, factor, factor, 1.0]) 00396 if origin is not None: 00397 M[:3, 3] = origin[:3] 00398 M[:3, 3] *= 1.0 - factor 00399 else: 00400 # nonuniform scaling 00401 direction = unit_vector(direction[:3]) 00402 factor = 1.0 - factor 00403 M = numpy.identity(4) 00404 M[:3, :3] -= factor * numpy.outer(direction, direction) 00405 if origin is not None: 00406 M[:3, 3] = (factor * numpy.dot(origin[:3], direction)) * direction 00407 return M 00408 00409 00410 def scale_from_matrix(matrix): 00411 """Return scaling factor, origin and direction from scaling matrix. 00412 00413 >>> factor = random.random() * 10 - 5 00414 >>> origin = numpy.random.random(3) - 0.5 00415 >>> direct = numpy.random.random(3) - 0.5 00416 >>> S0 = scale_matrix(factor, origin) 00417 >>> factor, origin, direction = scale_from_matrix(S0) 00418 >>> S1 = scale_matrix(factor, origin, direction) 00419 >>> is_same_transform(S0, S1) 00420 True 00421 >>> S0 = scale_matrix(factor, origin, direct) 00422 >>> factor, origin, direction = scale_from_matrix(S0) 00423 >>> S1 = scale_matrix(factor, origin, direction) 00424 >>> is_same_transform(S0, S1) 00425 True 00426 00427 """ 00428 M = numpy.array(matrix, dtype=numpy.float64, copy=False) 00429 M33 = M[:3, :3] 00430 factor = numpy.trace(M33) - 2.0 00431 try: 00432 # direction: unit eigenvector corresponding to eigenvalue factor 00433 w, V = numpy.linalg.eig(M33) 00434 i = numpy.where(abs(numpy.real(w) - factor) < 1e-8)[0][0] 00435 direction = numpy.real(V[:, i]).squeeze() 00436 direction /= vector_norm(direction) 00437 except IndexError: 00438 # uniform scaling 00439 factor = (factor + 2.0) / 3.0 00440 direction = None 00441 # origin: any eigenvector corresponding to eigenvalue 1 00442 w, V = numpy.linalg.eig(M) 00443 i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] 00444 if not len(i): 00445 raise ValueError("no eigenvector corresponding to eigenvalue 1") 00446 origin = numpy.real(V[:, i[-1]]).squeeze() 00447 origin /= origin[3] 00448 return factor, origin, direction 00449 00450 00451 def projection_matrix(point, normal, direction=None, 00452 perspective=None, pseudo=False): 00453 """Return matrix to project onto plane defined by point and normal. 00454 00455 Using either perspective point, projection direction, or none of both. 00456 00457 If pseudo is True, perspective projections will preserve relative depth 00458 such that Perspective = dot(Orthogonal, PseudoPerspective). 00459 00460 >>> P = projection_matrix([0, 0, 0], [1, 0, 0]) 00461 >>> numpy.allclose(P[1:, 1:], numpy.identity(4)[1:, 1:]) 00462 True 00463 >>> point = numpy.random.random(3) - 0.5 00464 >>> normal = numpy.random.random(3) - 0.5 00465 >>> direct = numpy.random.random(3) - 0.5 00466 >>> persp = numpy.random.random(3) - 0.5 00467 >>> P0 = projection_matrix(point, normal) 00468 >>> P1 = projection_matrix(point, normal, direction=direct) 00469 >>> P2 = projection_matrix(point, normal, perspective=persp) 00470 >>> P3 = projection_matrix(point, normal, perspective=persp, pseudo=True) 00471 >>> is_same_transform(P2, numpy.dot(P0, P3)) 00472 True 00473 >>> P = projection_matrix([3, 0, 0], [1, 1, 0], [1, 0, 0]) 00474 >>> v0 = (numpy.random.rand(4, 5) - 0.5) * 20 00475 >>> v0[3] = 1 00476 >>> v1 = numpy.dot(P, v0) 00477 >>> numpy.allclose(v1[1], v0[1]) 00478 True 00479 >>> numpy.allclose(v1[0], 3-v1[1]) 00480 True 00481 00482 """ 00483 M = numpy.identity(4) 00484 point = numpy.array(point[:3], dtype=numpy.float64, copy=False) 00485 normal = unit_vector(normal[:3]) 00486 if perspective is not None: 00487 # perspective projection 00488 perspective = numpy.array(perspective[:3], dtype=numpy.float64, 00489 copy=False) 00490 M[0, 0] = M[1, 1] = M[2, 2] = numpy.dot(perspective-point, normal) 00491 M[:3, :3] -= numpy.outer(perspective, normal) 00492 if pseudo: 00493 # preserve relative depth 00494 M[:3, :3] -= numpy.outer(normal, normal) 00495 M[:3, 3] = numpy.dot(point, normal) * (perspective+normal) 00496 else: 00497 M[:3, 3] = numpy.dot(point, normal) * perspective 00498 M[3, :3] = -normal 00499 M[3, 3] = numpy.dot(perspective, normal) 00500 elif direction is not None: 00501 # parallel projection 00502 direction = numpy.array(direction[:3], dtype=numpy.float64, copy=False) 00503 scale = numpy.dot(direction, normal) 00504 M[:3, :3] -= numpy.outer(direction, normal) / scale 00505 M[:3, 3] = direction * (numpy.dot(point, normal) / scale) 00506 else: 00507 # orthogonal projection 00508 M[:3, :3] -= numpy.outer(normal, normal) 00509 M[:3, 3] = numpy.dot(point, normal) * normal 00510 return M 00511 00512 00513 def projection_from_matrix(matrix, pseudo=False): 00514 """Return projection plane and perspective point from projection matrix. 00515 00516 Return values are same as arguments for projection_matrix function: 00517 point, normal, direction, perspective, and pseudo. 00518 00519 >>> point = numpy.random.random(3) - 0.5 00520 >>> normal = numpy.random.random(3) - 0.5 00521 >>> direct = numpy.random.random(3) - 0.5 00522 >>> persp = numpy.random.random(3) - 0.5 00523 >>> P0 = projection_matrix(point, normal) 00524 >>> result = projection_from_matrix(P0) 00525 >>> P1 = projection_matrix(*result) 00526 >>> is_same_transform(P0, P1) 00527 True 00528 >>> P0 = projection_matrix(point, normal, direct) 00529 >>> result = projection_from_matrix(P0) 00530 >>> P1 = projection_matrix(*result) 00531 >>> is_same_transform(P0, P1) 00532 True 00533 >>> P0 = projection_matrix(point, normal, perspective=persp, pseudo=False) 00534 >>> result = projection_from_matrix(P0, pseudo=False) 00535 >>> P1 = projection_matrix(*result) 00536 >>> is_same_transform(P0, P1) 00537 True 00538 >>> P0 = projection_matrix(point, normal, perspective=persp, pseudo=True) 00539 >>> result = projection_from_matrix(P0, pseudo=True) 00540 >>> P1 = projection_matrix(*result) 00541 >>> is_same_transform(P0, P1) 00542 True 00543 00544 """ 00545 M = numpy.array(matrix, dtype=numpy.float64, copy=False) 00546 M33 = M[:3, :3] 00547 w, V = numpy.linalg.eig(M) 00548 i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] 00549 if not pseudo and len(i): 00550 # point: any eigenvector corresponding to eigenvalue 1 00551 point = numpy.real(V[:, i[-1]]).squeeze() 00552 point /= point[3] 00553 # direction: unit eigenvector corresponding to eigenvalue 0 00554 w, V = numpy.linalg.eig(M33) 00555 i = numpy.where(abs(numpy.real(w)) < 1e-8)[0] 00556 if not len(i): 00557 raise ValueError("no eigenvector corresponding to eigenvalue 0") 00558 direction = numpy.real(V[:, i[0]]).squeeze() 00559 direction /= vector_norm(direction) 00560 # normal: unit eigenvector of M33.T corresponding to eigenvalue 0 00561 w, V = numpy.linalg.eig(M33.T) 00562 i = numpy.where(abs(numpy.real(w)) < 1e-8)[0] 00563 if len(i): 00564 # parallel projection 00565 normal = numpy.real(V[:, i[0]]).squeeze() 00566 normal /= vector_norm(normal) 00567 return point, normal, direction, None, False 00568 else: 00569 # orthogonal projection, where normal equals direction vector 00570 return point, direction, None, None, False 00571 else: 00572 # perspective projection 00573 i = numpy.where(abs(numpy.real(w)) > 1e-8)[0] 00574 if not len(i): 00575 raise ValueError( 00576 "no eigenvector not corresponding to eigenvalue 0") 00577 point = numpy.real(V[:, i[-1]]).squeeze() 00578 point /= point[3] 00579 normal = - M[3, :3] 00580 perspective = M[:3, 3] / numpy.dot(point[:3], normal) 00581 if pseudo: 00582 perspective -= normal 00583 return point, normal, None, perspective, pseudo 00584 00585 00586 def clip_matrix(left, right, bottom, top, near, far, perspective=False): 00587 """Return matrix to obtain normalized device coordinates from frustrum. 00588 00589 The frustrum bounds are axis-aligned along x (left, right), 00590 y (bottom, top) and z (near, far). 00591 00592 Normalized device coordinates are in range [-1, 1] if coordinates are 00593 inside the frustrum. 00594 00595 If perspective is True the frustrum is a truncated pyramid with the 00596 perspective point at origin and direction along z axis, otherwise an 00597 orthographic canonical view volume (a box). 00598 00599 Homogeneous coordinates transformed by the perspective clip matrix 00600 need to be dehomogenized (devided by w coordinate). 00601 00602 >>> frustrum = numpy.random.rand(6) 00603 >>> frustrum[1] += frustrum[0] 00604 >>> frustrum[3] += frustrum[2] 00605 >>> frustrum[5] += frustrum[4] 00606 >>> M = clip_matrix(perspective=False, *frustrum) 00607 >>> numpy.dot(M, [frustrum[0], frustrum[2], frustrum[4], 1]) 00608 array([-1., -1., -1., 1.]) 00609 >>> numpy.dot(M, [frustrum[1], frustrum[3], frustrum[5], 1]) 00610 array([ 1., 1., 1., 1.]) 00611 >>> M = clip_matrix(perspective=True, *frustrum) 00612 >>> v = numpy.dot(M, [frustrum[0], frustrum[2], frustrum[4], 1]) 00613 >>> v / v[3] 00614 array([-1., -1., -1., 1.]) 00615 >>> v = numpy.dot(M, [frustrum[1], frustrum[3], frustrum[4], 1]) 00616 >>> v / v[3] 00617 array([ 1., 1., -1., 1.]) 00618 00619 """ 00620 if left >= right or bottom >= top or near >= far: 00621 raise ValueError("invalid frustrum") 00622 if perspective: 00623 if near <= _EPS: 00624 raise ValueError("invalid frustrum: near <= 0") 00625 t = 2.0 * near 00626 M = [[t/(left-right), 0.0, (right+left)/(right-left), 0.0], 00627 [0.0, t/(bottom-top), (top+bottom)/(top-bottom), 0.0], 00628 [0.0, 0.0, (far+near)/(near-far), t*far/(far-near)], 00629 [0.0, 0.0, -1.0, 0.0]] 00630 else: 00631 M = [[2.0/(right-left), 0.0, 0.0, (right+left)/(left-right)], 00632 [0.0, 2.0/(top-bottom), 0.0, (top+bottom)/(bottom-top)], 00633 [0.0, 0.0, 2.0/(far-near), (far+near)/(near-far)], 00634 [0.0, 0.0, 0.0, 1.0]] 00635 return numpy.array(M) 00636 00637 00638 def shear_matrix(angle, direction, point, normal): 00639 """Return matrix to shear by angle along direction vector on shear plane. 00640 00641 The shear plane is defined by a point and normal vector. The direction 00642 vector must be orthogonal to the plane's normal vector. 00643 00644 A point P is transformed by the shear matrix into P2 such that 00645 the vector P-P2 is parallel to the direction vector and its extent is 00646 given by the angle of P-P'-P2, where P' is the orthogonal projection 00647 of P onto the shear plane. 00648 00649 >>> angle = (random.random() - 0.5) * 4*math.pi 00650 >>> direct = numpy.random.random(3) - 0.5 00651 >>> point = numpy.random.random(3) - 0.5 00652 >>> normal = numpy.cross(direct, numpy.random.random(3)) 00653 >>> S = shear_matrix(angle, direct, point, normal) 00654 >>> numpy.allclose(1, numpy.linalg.det(S)) 00655 True 00656 00657 """ 00658 normal = unit_vector(normal[:3]) 00659 direction = unit_vector(direction[:3]) 00660 if abs(numpy.dot(normal, direction)) > 1e-6: 00661 raise ValueError("direction and normal vectors are not orthogonal") 00662 angle = math.tan(angle) 00663 M = numpy.identity(4) 00664 M[:3, :3] += angle * numpy.outer(direction, normal) 00665 M[:3, 3] = -angle * numpy.dot(point[:3], normal) * direction 00666 return M 00667 00668 00669 def shear_from_matrix(matrix): 00670 """Return shear angle, direction and plane from shear matrix. 00671 00672 >>> angle = (random.random() - 0.5) * 4*math.pi 00673 >>> direct = numpy.random.random(3) - 0.5 00674 >>> point = numpy.random.random(3) - 0.5 00675 >>> normal = numpy.cross(direct, numpy.random.random(3)) 00676 >>> S0 = shear_matrix(angle, direct, point, normal) 00677 >>> angle, direct, point, normal = shear_from_matrix(S0) 00678 >>> S1 = shear_matrix(angle, direct, point, normal) 00679 >>> is_same_transform(S0, S1) 00680 True 00681 00682 """ 00683 M = numpy.array(matrix, dtype=numpy.float64, copy=False) 00684 M33 = M[:3, :3] 00685 # normal: cross independent eigenvectors corresponding to the eigenvalue 1 00686 w, V = numpy.linalg.eig(M33) 00687 i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-4)[0] 00688 if len(i) < 2: 00689 raise ValueError("no two linear independent eigenvectors found %s" % w) 00690 V = numpy.real(V[:, i]).squeeze().T 00691 lenorm = -1.0 00692 for i0, i1 in ((0, 1), (0, 2), (1, 2)): 00693 n = numpy.cross(V[i0], V[i1]) 00694 w = vector_norm(n) 00695 if w > lenorm: 00696 lenorm = w 00697 normal = n 00698 normal /= lenorm 00699 # direction and angle 00700 direction = numpy.dot(M33 - numpy.identity(3), normal) 00701 angle = vector_norm(direction) 00702 direction /= angle 00703 angle = math.atan(angle) 00704 # point: eigenvector corresponding to eigenvalue 1 00705 w, V = numpy.linalg.eig(M) 00706 i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] 00707 if not len(i): 00708 raise ValueError("no eigenvector corresponding to eigenvalue 1") 00709 point = numpy.real(V[:, i[-1]]).squeeze() 00710 point /= point[3] 00711 return angle, direction, point, normal 00712 00713 00714 def decompose_matrix(matrix): 00715 """Return sequence of transformations from transformation matrix. 00716 00717 matrix : array_like 00718 Non-degenerative homogeneous transformation matrix 00719 00720 Return tuple of: 00721 scale : vector of 3 scaling factors 00722 shear : list of shear factors for x-y, x-z, y-z axes 00723 angles : list of Euler angles about static x, y, z axes 00724 translate : translation vector along x, y, z axes 00725 perspective : perspective partition of matrix 00726 00727 Raise ValueError if matrix is of wrong type or degenerative. 00728 00729 >>> T0 = translation_matrix([1, 2, 3]) 00730 >>> scale, shear, angles, trans, persp = decompose_matrix(T0) 00731 >>> T1 = translation_matrix(trans) 00732 >>> numpy.allclose(T0, T1) 00733 True 00734 >>> S = scale_matrix(0.123) 00735 >>> scale, shear, angles, trans, persp = decompose_matrix(S) 00736 >>> scale[0] 00737 0.123 00738 >>> R0 = euler_matrix(1, 2, 3) 00739 >>> scale, shear, angles, trans, persp = decompose_matrix(R0) 00740 >>> R1 = euler_matrix(*angles) 00741 >>> numpy.allclose(R0, R1) 00742 True 00743 00744 """ 00745 M = numpy.array(matrix, dtype=numpy.float64, copy=True).T 00746 if abs(M[3, 3]) < _EPS: 00747 raise ValueError("M[3, 3] is zero") 00748 M /= M[3, 3] 00749 P = M.copy() 00750 P[:, 3] = 0.0, 0.0, 0.0, 1.0 00751 if not numpy.linalg.det(P): 00752 raise ValueError("matrix is singular") 00753 00754 scale = numpy.zeros((3, )) 00755 shear = [0.0, 0.0, 0.0] 00756 angles = [0.0, 0.0, 0.0] 00757 00758 if any(abs(M[:3, 3]) > _EPS): 00759 perspective = numpy.dot(M[:, 3], numpy.linalg.inv(P.T)) 00760 M[:, 3] = 0.0, 0.0, 0.0, 1.0 00761 else: 00762 perspective = numpy.array([0.0, 0.0, 0.0, 1.0]) 00763 00764 translate = M[3, :3].copy() 00765 M[3, :3] = 0.0 00766 00767 row = M[:3, :3].copy() 00768 scale[0] = vector_norm(row[0]) 00769 row[0] /= scale[0] 00770 shear[0] = numpy.dot(row[0], row[1]) 00771 row[1] -= row[0] * shear[0] 00772 scale[1] = vector_norm(row[1]) 00773 row[1] /= scale[1] 00774 shear[0] /= scale[1] 00775 shear[1] = numpy.dot(row[0], row[2]) 00776 row[2] -= row[0] * shear[1] 00777 shear[2] = numpy.dot(row[1], row[2]) 00778 row[2] -= row[1] * shear[2] 00779 scale[2] = vector_norm(row[2]) 00780 row[2] /= scale[2] 00781 shear[1:] /= scale[2] 00782 00783 if numpy.dot(row[0], numpy.cross(row[1], row[2])) < 0: 00784 numpy.negative(scale, scale) 00785 numpy.negative(row, row) 00786 00787 angles[1] = math.asin(-row[0, 2]) 00788 if math.cos(angles[1]): 00789 angles[0] = math.atan2(row[1, 2], row[2, 2]) 00790 angles[2] = math.atan2(row[0, 1], row[0, 0]) 00791 else: 00792 #angles[0] = math.atan2(row[1, 0], row[1, 1]) 00793 angles[0] = math.atan2(-row[2, 1], row[1, 1]) 00794 angles[2] = 0.0 00795 00796 return scale, shear, angles, translate, perspective 00797 00798 00799 def compose_matrix(scale=None, shear=None, angles=None, translate=None, 00800 perspective=None): 00801 """Return transformation matrix from sequence of transformations. 00802 00803 This is the inverse of the decompose_matrix function. 00804 00805 Sequence of transformations: 00806 scale : vector of 3 scaling factors 00807 shear : list of shear factors for x-y, x-z, y-z axes 00808 angles : list of Euler angles about static x, y, z axes 00809 translate : translation vector along x, y, z axes 00810 perspective : perspective partition of matrix 00811 00812 >>> scale = numpy.random.random(3) - 0.5 00813 >>> shear = numpy.random.random(3) - 0.5 00814 >>> angles = (numpy.random.random(3) - 0.5) * (2*math.pi) 00815 >>> trans = numpy.random.random(3) - 0.5 00816 >>> persp = numpy.random.random(4) - 0.5 00817 >>> M0 = compose_matrix(scale, shear, angles, trans, persp) 00818 >>> result = decompose_matrix(M0) 00819 >>> M1 = compose_matrix(*result) 00820 >>> is_same_transform(M0, M1) 00821 True 00822 00823 """ 00824 M = numpy.identity(4) 00825 if perspective is not None: 00826 P = numpy.identity(4) 00827 P[3, :] = perspective[:4] 00828 M = numpy.dot(M, P) 00829 if translate is not None: 00830 T = numpy.identity(4) 00831 T[:3, 3] = translate[:3] 00832 M = numpy.dot(M, T) 00833 if angles is not None: 00834 R = euler_matrix(angles[0], angles[1], angles[2], 'sxyz') 00835 M = numpy.dot(M, R) 00836 if shear is not None: 00837 Z = numpy.identity(4) 00838 Z[1, 2] = shear[2] 00839 Z[0, 2] = shear[1] 00840 Z[0, 1] = shear[0] 00841 M = numpy.dot(M, Z) 00842 if scale is not None: 00843 S = numpy.identity(4) 00844 S[0, 0] = scale[0] 00845 S[1, 1] = scale[1] 00846 S[2, 2] = scale[2] 00847 M = numpy.dot(M, S) 00848 M /= M[3, 3] 00849 return M 00850 00851 00852 def orthogonalization_matrix(lengths, angles): 00853 """Return orthogonalization matrix for crystallographic cell coordinates. 00854 00855 Angles are expected in degrees. 00856 00857 The de-orthogonalization matrix is the inverse. 00858 00859 >>> O = orthogonalization_matrix([10, 10, 10], [90, 90, 90]) 00860 >>> numpy.allclose(O[:3, :3], numpy.identity(3, float) * 10) 00861 True 00862 >>> O = orthogonalization_matrix([9.8, 12.0, 15.5], [87.2, 80.7, 69.7]) 00863 >>> numpy.allclose(numpy.sum(O), 43.063229) 00864 True 00865 00866 """ 00867 a, b, c = lengths 00868 angles = numpy.radians(angles) 00869 sina, sinb, _ = numpy.sin(angles) 00870 cosa, cosb, cosg = numpy.cos(angles) 00871 co = (cosa * cosb - cosg) / (sina * sinb) 00872 return numpy.array([ 00873 [ a*sinb*math.sqrt(1.0-co*co), 0.0, 0.0, 0.0], 00874 [-a*sinb*co, b*sina, 0.0, 0.0], 00875 [ a*cosb, b*cosa, c, 0.0], 00876 [ 0.0, 0.0, 0.0, 1.0]]) 00877 00878 00879 def affine_matrix_from_points(v0, v1, shear=True, scale=True, usesvd=True): 00880 """Return affine transform matrix to register two point sets. 00881 00882 v0 and v1 are shape (ndims, \*) arrays of at least ndims non-homogeneous 00883 coordinates, where ndims is the dimensionality of the coordinate space. 00884 00885 If shear is False, a similarity transformation matrix is returned. 00886 If also scale is False, a rigid/Eucledian transformation matrix 00887 is returned. 00888 00889 By default the algorithm by Hartley and Zissermann [15] is used. 00890 If usesvd is True, similarity and Eucledian transformation matrices 00891 are calculated by minimizing the weighted sum of squared deviations 00892 (RMSD) according to the algorithm by Kabsch [8]. 00893 Otherwise, and if ndims is 3, the quaternion based algorithm by Horn [9] 00894 is used, which is slower when using this Python implementation. 00895 00896 The returned matrix performs rotation, translation and uniform scaling 00897 (if specified). 00898 00899 >>> v0 = [[0, 1031, 1031, 0], [0, 0, 1600, 1600]] 00900 >>> v1 = [[675, 826, 826, 677], [55, 52, 281, 277]] 00901 >>> affine_matrix_from_points(v0, v1) 00902 array([[ 0.14549, 0.00062, 675.50008], 00903 [ 0.00048, 0.14094, 53.24971], 00904 [ 0. , 0. , 1. ]]) 00905 >>> T = translation_matrix(numpy.random.random(3)-0.5) 00906 >>> R = random_rotation_matrix(numpy.random.random(3)) 00907 >>> S = scale_matrix(random.random()) 00908 >>> M = concatenate_matrices(T, R, S) 00909 >>> v0 = (numpy.random.rand(4, 100) - 0.5) * 20 00910 >>> v0[3] = 1 00911 >>> v1 = numpy.dot(M, v0) 00912 >>> v0[:3] += numpy.random.normal(0, 1e-8, 300).reshape(3, -1) 00913 >>> M = affine_matrix_from_points(v0[:3], v1[:3]) 00914 >>> numpy.allclose(v1, numpy.dot(M, v0)) 00915 True 00916 00917 More examples in superimposition_matrix() 00918 00919 """ 00920 v0 = numpy.array(v0, dtype=numpy.float64, copy=True) 00921 v1 = numpy.array(v1, dtype=numpy.float64, copy=True) 00922 00923 ndims = v0.shape[0] 00924 if ndims < 2 or v0.shape[1] < ndims or v0.shape != v1.shape: 00925 raise ValueError("input arrays are of wrong shape or type") 00926 00927 # move centroids to origin 00928 t0 = -numpy.mean(v0, axis=1) 00929 M0 = numpy.identity(ndims+1) 00930 M0[:ndims, ndims] = t0 00931 v0 += t0.reshape(ndims, 1) 00932 t1 = -numpy.mean(v1, axis=1) 00933 M1 = numpy.identity(ndims+1) 00934 M1[:ndims, ndims] = t1 00935 v1 += t1.reshape(ndims, 1) 00936 00937 if shear: 00938 # Affine transformation 00939 A = numpy.concatenate((v0, v1), axis=0) 00940 u, s, vh = numpy.linalg.svd(A.T) 00941 vh = vh[:ndims].T 00942 B = vh[:ndims] 00943 C = vh[ndims:2*ndims] 00944 t = numpy.dot(C, numpy.linalg.pinv(B)) 00945 t = numpy.concatenate((t, numpy.zeros((ndims, 1))), axis=1) 00946 M = numpy.vstack((t, ((0.0,)*ndims) + (1.0,))) 00947 elif usesvd or ndims != 3: 00948 # Rigid transformation via SVD of covariance matrix 00949 u, s, vh = numpy.linalg.svd(numpy.dot(v1, v0.T)) 00950 # rotation matrix from SVD orthonormal bases 00951 R = numpy.dot(u, vh) 00952 if numpy.linalg.det(R) < 0.0: 00953 # R does not constitute right handed system 00954 R -= numpy.outer(u[:, ndims-1], vh[ndims-1, :]*2.0) 00955 s[-1] *= -1.0 00956 # homogeneous transformation matrix 00957 M = numpy.identity(ndims+1) 00958 M[:ndims, :ndims] = R 00959 else: 00960 # Rigid transformation matrix via quaternion 00961 # compute symmetric matrix N 00962 xx, yy, zz = numpy.sum(v0 * v1, axis=1) 00963 xy, yz, zx = numpy.sum(v0 * numpy.roll(v1, -1, axis=0), axis=1) 00964 xz, yx, zy = numpy.sum(v0 * numpy.roll(v1, -2, axis=0), axis=1) 00965 N = [[xx+yy+zz, 0.0, 0.0, 0.0], 00966 [yz-zy, xx-yy-zz, 0.0, 0.0], 00967 [zx-xz, xy+yx, yy-xx-zz, 0.0], 00968 [xy-yx, zx+xz, yz+zy, zz-xx-yy]] 00969 # quaternion: eigenvector corresponding to most positive eigenvalue 00970 w, V = numpy.linalg.eigh(N) 00971 q = V[:, numpy.argmax(w)] 00972 q /= vector_norm(q) # unit quaternion 00973 # homogeneous transformation matrix 00974 M = quaternion_matrix(q) 00975 00976 if scale and not shear: 00977 # Affine transformation; scale is ratio of RMS deviations from centroid 00978 v0 *= v0 00979 v1 *= v1 00980 M[:ndims, :ndims] *= math.sqrt(numpy.sum(v1) / numpy.sum(v0)) 00981 00982 # move centroids back 00983 M = numpy.dot(numpy.linalg.inv(M1), numpy.dot(M, M0)) 00984 M /= M[ndims, ndims] 00985 return M 00986 00987 00988 def superimposition_matrix(v0, v1, scale=False, usesvd=True): 00989 """Return matrix to transform given 3D point set into second point set. 00990 00991 v0 and v1 are shape (3, \*) or (4, \*) arrays of at least 3 points. 00992 00993 The parameters scale and usesvd are explained in the more general 00994 affine_matrix_from_points function. 00995 00996 The returned matrix is a similarity or Eucledian transformation matrix. 00997 This function has a fast C implementation in transformations.c. 00998 00999 >>> v0 = numpy.random.rand(3, 10) 01000 >>> M = superimposition_matrix(v0, v0) 01001 >>> numpy.allclose(M, numpy.identity(4)) 01002 True 01003 >>> R = random_rotation_matrix(numpy.random.random(3)) 01004 >>> v0 = [[1,0,0], [0,1,0], [0,0,1], [1,1,1]] 01005 >>> v1 = numpy.dot(R, v0) 01006 >>> M = superimposition_matrix(v0, v1) 01007 >>> numpy.allclose(v1, numpy.dot(M, v0)) 01008 True 01009 >>> v0 = (numpy.random.rand(4, 100) - 0.5) * 20 01010 >>> v0[3] = 1 01011 >>> v1 = numpy.dot(R, v0) 01012 >>> M = superimposition_matrix(v0, v1) 01013 >>> numpy.allclose(v1, numpy.dot(M, v0)) 01014 True 01015 >>> S = scale_matrix(random.random()) 01016 >>> T = translation_matrix(numpy.random.random(3)-0.5) 01017 >>> M = concatenate_matrices(T, R, S) 01018 >>> v1 = numpy.dot(M, v0) 01019 >>> v0[:3] += numpy.random.normal(0, 1e-9, 300).reshape(3, -1) 01020 >>> M = superimposition_matrix(v0, v1, scale=True) 01021 >>> numpy.allclose(v1, numpy.dot(M, v0)) 01022 True 01023 >>> M = superimposition_matrix(v0, v1, scale=True, usesvd=False) 01024 >>> numpy.allclose(v1, numpy.dot(M, v0)) 01025 True 01026 >>> v = numpy.empty((4, 100, 3)) 01027 >>> v[:, :, 0] = v0 01028 >>> M = superimposition_matrix(v0, v1, scale=True, usesvd=False) 01029 >>> numpy.allclose(v1, numpy.dot(M, v[:, :, 0])) 01030 True 01031 01032 """ 01033 v0 = numpy.array(v0, dtype=numpy.float64, copy=False)[:3] 01034 v1 = numpy.array(v1, dtype=numpy.float64, copy=False)[:3] 01035 return affine_matrix_from_points(v0, v1, shear=False, 01036 scale=scale, usesvd=usesvd) 01037 01038 01039 def euler_matrix(ai, aj, ak, axes='sxyz'): 01040 """Return homogeneous rotation matrix from Euler angles and axis sequence. 01041 01042 ai, aj, ak : Euler's roll, pitch and yaw angles 01043 axes : One of 24 axis sequences as string or encoded tuple 01044 01045 >>> R = euler_matrix(1, 2, 3, 'syxz') 01046 >>> numpy.allclose(numpy.sum(R[0]), -1.34786452) 01047 True 01048 >>> R = euler_matrix(1, 2, 3, (0, 1, 0, 1)) 01049 >>> numpy.allclose(numpy.sum(R[0]), -0.383436184) 01050 True 01051 >>> ai, aj, ak = (4*math.pi) * (numpy.random.random(3) - 0.5) 01052 >>> for axes in _AXES2TUPLE.keys(): 01053 ... R = euler_matrix(ai, aj, ak, axes) 01054 >>> for axes in _TUPLE2AXES.keys(): 01055 ... R = euler_matrix(ai, aj, ak, axes) 01056 01057 """ 01058 try: 01059 firstaxis, parity, repetition, frame = _AXES2TUPLE[axes] 01060 except (AttributeError, KeyError): 01061 _TUPLE2AXES[axes] # validation 01062 firstaxis, parity, repetition, frame = axes 01063 01064 i = firstaxis 01065 j = _NEXT_AXIS[i+parity] 01066 k = _NEXT_AXIS[i-parity+1] 01067 01068 if frame: 01069 ai, ak = ak, ai 01070 if parity: 01071 ai, aj, ak = -ai, -aj, -ak 01072 01073 si, sj, sk = math.sin(ai), math.sin(aj), math.sin(ak) 01074 ci, cj, ck = math.cos(ai), math.cos(aj), math.cos(ak) 01075 cc, cs = ci*ck, ci*sk 01076 sc, ss = si*ck, si*sk 01077 01078 M = numpy.identity(4) 01079 if repetition: 01080 M[i, i] = cj 01081 M[i, j] = sj*si 01082 M[i, k] = sj*ci 01083 M[j, i] = sj*sk 01084 M[j, j] = -cj*ss+cc 01085 M[j, k] = -cj*cs-sc 01086 M[k, i] = -sj*ck 01087 M[k, j] = cj*sc+cs 01088 M[k, k] = cj*cc-ss 01089 else: 01090 M[i, i] = cj*ck 01091 M[i, j] = sj*sc-cs 01092 M[i, k] = sj*cc+ss 01093 M[j, i] = cj*sk 01094 M[j, j] = sj*ss+cc 01095 M[j, k] = sj*cs-sc 01096 M[k, i] = -sj 01097 M[k, j] = cj*si 01098 M[k, k] = cj*ci 01099 return M 01100 01101 01102 def euler_from_matrix(matrix, axes='sxyz'): 01103 """Return Euler angles from rotation matrix for specified axis sequence. 01104 01105 axes : One of 24 axis sequences as string or encoded tuple 01106 01107 Note that many Euler angle triplets can describe one matrix. 01108 01109 >>> R0 = euler_matrix(1, 2, 3, 'syxz') 01110 >>> al, be, ga = euler_from_matrix(R0, 'syxz') 01111 >>> R1 = euler_matrix(al, be, ga, 'syxz') 01112 >>> numpy.allclose(R0, R1) 01113 True 01114 >>> angles = (4*math.pi) * (numpy.random.random(3) - 0.5) 01115 >>> for axes in _AXES2TUPLE.keys(): 01116 ... R0 = euler_matrix(axes=axes, *angles) 01117 ... R1 = euler_matrix(axes=axes, *euler_from_matrix(R0, axes)) 01118 ... if not numpy.allclose(R0, R1): print(axes, "failed") 01119 01120 """ 01121 try: 01122 firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()] 01123 except (AttributeError, KeyError): 01124 _TUPLE2AXES[axes] # validation 01125 firstaxis, parity, repetition, frame = axes 01126 01127 i = firstaxis 01128 j = _NEXT_AXIS[i+parity] 01129 k = _NEXT_AXIS[i-parity+1] 01130 01131 M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:3, :3] 01132 if repetition: 01133 sy = math.sqrt(M[i, j]*M[i, j] + M[i, k]*M[i, k]) 01134 if sy > _EPS: 01135 ax = math.atan2( M[i, j], M[i, k]) 01136 ay = math.atan2( sy, M[i, i]) 01137 az = math.atan2( M[j, i], -M[k, i]) 01138 else: 01139 ax = math.atan2(-M[j, k], M[j, j]) 01140 ay = math.atan2( sy, M[i, i]) 01141 az = 0.0 01142 else: 01143 cy = math.sqrt(M[i, i]*M[i, i] + M[j, i]*M[j, i]) 01144 if cy > _EPS: 01145 ax = math.atan2( M[k, j], M[k, k]) 01146 ay = math.atan2(-M[k, i], cy) 01147 az = math.atan2( M[j, i], M[i, i]) 01148 else: 01149 ax = math.atan2(-M[j, k], M[j, j]) 01150 ay = math.atan2(-M[k, i], cy) 01151 az = 0.0 01152 01153 if parity: 01154 ax, ay, az = -ax, -ay, -az 01155 if frame: 01156 ax, az = az, ax 01157 return ax, ay, az 01158 01159 01160 def euler_from_quaternion(quaternion, axes='sxyz'): 01161 """Return Euler angles from quaternion for specified axis sequence. 01162 01163 >>> angles = euler_from_quaternion([0.99810947, 0.06146124, 0, 0]) 01164 >>> numpy.allclose(angles, [0.123, 0, 0]) 01165 True 01166 01167 """ 01168 return euler_from_matrix(quaternion_matrix(quaternion), axes) 01169 01170 01171 def quaternion_from_euler(ai, aj, ak, axes='sxyz'): 01172 """Return quaternion from Euler angles and axis sequence. 01173 01174 ai, aj, ak : Euler's roll, pitch and yaw angles 01175 axes : One of 24 axis sequences as string or encoded tuple 01176 01177 >>> q = quaternion_from_euler(1, 2, 3, 'ryxz') 01178 >>> numpy.allclose(q, [0.435953, 0.310622, -0.718287, 0.444435]) 01179 True 01180 01181 """ 01182 try: 01183 firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()] 01184 except (AttributeError, KeyError): 01185 _TUPLE2AXES[axes] # validation 01186 firstaxis, parity, repetition, frame = axes 01187 01188 i = firstaxis + 1 01189 j = _NEXT_AXIS[i+parity-1] + 1 01190 k = _NEXT_AXIS[i-parity] + 1 01191 01192 if frame: 01193 ai, ak = ak, ai 01194 if parity: 01195 aj = -aj 01196 01197 ai /= 2.0 01198 aj /= 2.0 01199 ak /= 2.0 01200 ci = math.cos(ai) 01201 si = math.sin(ai) 01202 cj = math.cos(aj) 01203 sj = math.sin(aj) 01204 ck = math.cos(ak) 01205 sk = math.sin(ak) 01206 cc = ci*ck 01207 cs = ci*sk 01208 sc = si*ck 01209 ss = si*sk 01210 01211 q = numpy.empty((4, )) 01212 if repetition: 01213 q[0] = cj*(cc - ss) 01214 q[i] = cj*(cs + sc) 01215 q[j] = sj*(cc + ss) 01216 q[k] = sj*(cs - sc) 01217 else: 01218 q[0] = cj*cc + sj*ss 01219 q[i] = cj*sc - sj*cs 01220 q[j] = cj*ss + sj*cc 01221 q[k] = cj*cs - sj*sc 01222 if parity: 01223 q[j] *= -1.0 01224 01225 return q 01226 01227 01228 def quaternion_about_axis(angle, axis): 01229 """Return quaternion for rotation about axis. 01230 01231 >>> q = quaternion_about_axis(0.123, [1, 0, 0]) 01232 >>> numpy.allclose(q, [0.99810947, 0.06146124, 0, 0]) 01233 True 01234 01235 """ 01236 q = numpy.array([0.0, axis[0], axis[1], axis[2]]) 01237 qlen = vector_norm(q) 01238 if qlen > _EPS: 01239 q *= math.sin(angle/2.0) / qlen 01240 q[0] = math.cos(angle/2.0) 01241 return q 01242 01243 01244 def quaternion_matrix(quaternion): 01245 """Return homogeneous rotation matrix from quaternion. 01246 01247 >>> M = quaternion_matrix([0.99810947, 0.06146124, 0, 0]) 01248 >>> numpy.allclose(M, rotation_matrix(0.123, [1, 0, 0])) 01249 True 01250 >>> M = quaternion_matrix([1, 0, 0, 0]) 01251 >>> numpy.allclose(M, numpy.identity(4)) 01252 True 01253 >>> M = quaternion_matrix([0, 1, 0, 0]) 01254 >>> numpy.allclose(M, numpy.diag([1, -1, -1, 1])) 01255 True 01256 01257 """ 01258 q = numpy.array(quaternion, dtype=numpy.float64, copy=True) 01259 n = numpy.dot(q, q) 01260 if n < _EPS: 01261 return numpy.identity(4) 01262 q *= math.sqrt(2.0 / n) 01263 q = numpy.outer(q, q) 01264 return numpy.array([ 01265 [1.0-q[2, 2]-q[3, 3], q[1, 2]-q[3, 0], q[1, 3]+q[2, 0], 0.0], 01266 [ q[1, 2]+q[3, 0], 1.0-q[1, 1]-q[3, 3], q[2, 3]-q[1, 0], 0.0], 01267 [ q[1, 3]-q[2, 0], q[2, 3]+q[1, 0], 1.0-q[1, 1]-q[2, 2], 0.0], 01268 [ 0.0, 0.0, 0.0, 1.0]]) 01269 01270 01271 def quaternion_from_matrix(matrix, isprecise=False): 01272 """Return quaternion from rotation matrix. 01273 01274 If isprecise is True, the input matrix is assumed to be a precise rotation 01275 matrix and a faster algorithm is used. 01276 01277 >>> q = quaternion_from_matrix(numpy.identity(4), True) 01278 >>> numpy.allclose(q, [1, 0, 0, 0]) 01279 True 01280 >>> q = quaternion_from_matrix(numpy.diag([1, -1, -1, 1])) 01281 >>> numpy.allclose(q, [0, 1, 0, 0]) or numpy.allclose(q, [0, -1, 0, 0]) 01282 True 01283 >>> R = rotation_matrix(0.123, (1, 2, 3)) 01284 >>> q = quaternion_from_matrix(R, True) 01285 >>> numpy.allclose(q, [0.9981095, 0.0164262, 0.0328524, 0.0492786]) 01286 True 01287 >>> R = [[-0.545, 0.797, 0.260, 0], [0.733, 0.603, -0.313, 0], 01288 ... [-0.407, 0.021, -0.913, 0], [0, 0, 0, 1]] 01289 >>> q = quaternion_from_matrix(R) 01290 >>> numpy.allclose(q, [0.19069, 0.43736, 0.87485, -0.083611]) 01291 True 01292 >>> R = [[0.395, 0.362, 0.843, 0], [-0.626, 0.796, -0.056, 0], 01293 ... [-0.677, -0.498, 0.529, 0], [0, 0, 0, 1]] 01294 >>> q = quaternion_from_matrix(R) 01295 >>> numpy.allclose(q, [0.82336615, -0.13610694, 0.46344705, -0.29792603]) 01296 True 01297 >>> R = random_rotation_matrix() 01298 >>> q = quaternion_from_matrix(R) 01299 >>> is_same_transform(R, quaternion_matrix(q)) 01300 True 01301 01302 """ 01303 M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:4, :4] 01304 if isprecise: 01305 q = numpy.empty((4, )) 01306 t = numpy.trace(M) 01307 if t > M[3, 3]: 01308 q[0] = t 01309 q[3] = M[1, 0] - M[0, 1] 01310 q[2] = M[0, 2] - M[2, 0] 01311 q[1] = M[2, 1] - M[1, 2] 01312 else: 01313 i, j, k = 1, 2, 3 01314 if M[1, 1] > M[0, 0]: 01315 i, j, k = 2, 3, 1 01316 if M[2, 2] > M[i, i]: 01317 i, j, k = 3, 1, 2 01318 t = M[i, i] - (M[j, j] + M[k, k]) + M[3, 3] 01319 q[i] = t 01320 q[j] = M[i, j] + M[j, i] 01321 q[k] = M[k, i] + M[i, k] 01322 q[3] = M[k, j] - M[j, k] 01323 q *= 0.5 / math.sqrt(t * M[3, 3]) 01324 else: 01325 m00 = M[0, 0] 01326 m01 = M[0, 1] 01327 m02 = M[0, 2] 01328 m10 = M[1, 0] 01329 m11 = M[1, 1] 01330 m12 = M[1, 2] 01331 m20 = M[2, 0] 01332 m21 = M[2, 1] 01333 m22 = M[2, 2] 01334 # symmetric matrix K 01335 K = numpy.array([[m00-m11-m22, 0.0, 0.0, 0.0], 01336 [m01+m10, m11-m00-m22, 0.0, 0.0], 01337 [m02+m20, m12+m21, m22-m00-m11, 0.0], 01338 [m21-m12, m02-m20, m10-m01, m00+m11+m22]]) 01339 K /= 3.0 01340 # quaternion is eigenvector of K that corresponds to largest eigenvalue 01341 w, V = numpy.linalg.eigh(K) 01342 q = V[[3, 0, 1, 2], numpy.argmax(w)] 01343 if q[0] < 0.0: 01344 numpy.negative(q, q) 01345 return q 01346 01347 01348 def quaternion_multiply(quaternion1, quaternion0): 01349 """Return multiplication of two quaternions. 01350 01351 >>> q = quaternion_multiply([4, 1, -2, 3], [8, -5, 6, 7]) 01352 >>> numpy.allclose(q, [28, -44, -14, 48]) 01353 True 01354 01355 """ 01356 w0, x0, y0, z0 = quaternion0 01357 w1, x1, y1, z1 = quaternion1 01358 return numpy.array([-x1*x0 - y1*y0 - z1*z0 + w1*w0, 01359 x1*w0 + y1*z0 - z1*y0 + w1*x0, 01360 -x1*z0 + y1*w0 + z1*x0 + w1*y0, 01361 x1*y0 - y1*x0 + z1*w0 + w1*z0], dtype=numpy.float64) 01362 01363 01364 def quaternion_conjugate(quaternion): 01365 """Return conjugate of quaternion. 01366 01367 >>> q0 = random_quaternion() 01368 >>> q1 = quaternion_conjugate(q0) 01369 >>> q1[0] == q0[0] and all(q1[1:] == -q0[1:]) 01370 True 01371 01372 """ 01373 q = numpy.array(quaternion, dtype=numpy.float64, copy=True) 01374 numpy.negative(q[1:], q[1:]) 01375 return q 01376 01377 01378 def quaternion_inverse(quaternion): 01379 """Return inverse of quaternion. 01380 01381 >>> q0 = random_quaternion() 01382 >>> q1 = quaternion_inverse(q0) 01383 >>> numpy.allclose(quaternion_multiply(q0, q1), [1, 0, 0, 0]) 01384 True 01385 01386 """ 01387 q = numpy.array(quaternion, dtype=numpy.float64, copy=True) 01388 numpy.negative(q[1:], q[1:]) 01389 return q / numpy.dot(q, q) 01390 01391 01392 def quaternion_real(quaternion): 01393 """Return real part of quaternion. 01394 01395 >>> quaternion_real([3, 0, 1, 2]) 01396 3.0 01397 01398 """ 01399 return float(quaternion[0]) 01400 01401 01402 def quaternion_imag(quaternion): 01403 """Return imaginary part of quaternion. 01404 01405 >>> quaternion_imag([3, 0, 1, 2]) 01406 array([ 0., 1., 2.]) 01407 01408 """ 01409 return numpy.array(quaternion[1:4], dtype=numpy.float64, copy=True) 01410 01411 01412 def quaternion_slerp(quat0, quat1, fraction, spin=0, shortestpath=True): 01413 """Return spherical linear interpolation between two quaternions. 01414 01415 >>> q0 = random_quaternion() 01416 >>> q1 = random_quaternion() 01417 >>> q = quaternion_slerp(q0, q1, 0) 01418 >>> numpy.allclose(q, q0) 01419 True 01420 >>> q = quaternion_slerp(q0, q1, 1, 1) 01421 >>> numpy.allclose(q, q1) 01422 True 01423 >>> q = quaternion_slerp(q0, q1, 0.5) 01424 >>> angle = math.acos(numpy.dot(q0, q)) 01425 >>> numpy.allclose(2, math.acos(numpy.dot(q0, q1)) / angle) or \ 01426 numpy.allclose(2, math.acos(-numpy.dot(q0, q1)) / angle) 01427 True 01428 01429 """ 01430 q0 = unit_vector(quat0[:4]) 01431 q1 = unit_vector(quat1[:4]) 01432 if fraction == 0.0: 01433 return q0 01434 elif fraction == 1.0: 01435 return q1 01436 d = numpy.dot(q0, q1) 01437 if abs(abs(d) - 1.0) < _EPS: 01438 return q0 01439 if shortestpath and d < 0.0: 01440 # invert rotation 01441 d = -d 01442 numpy.negative(q1, q1) 01443 angle = math.acos(d) + spin * math.pi 01444 if abs(angle) < _EPS: 01445 return q0 01446 isin = 1.0 / math.sin(angle) 01447 q0 *= math.sin((1.0 - fraction) * angle) * isin 01448 q1 *= math.sin(fraction * angle) * isin 01449 q0 += q1 01450 return q0 01451 01452 01453 def random_quaternion(rand=None): 01454 """Return uniform random unit quaternion. 01455 01456 rand: array like or None 01457 Three independent random variables that are uniformly distributed 01458 between 0 and 1. 01459 01460 >>> q = random_quaternion() 01461 >>> numpy.allclose(1, vector_norm(q)) 01462 True 01463 >>> q = random_quaternion(numpy.random.random(3)) 01464 >>> len(q.shape), q.shape[0]==4 01465 (1, True) 01466 01467 """ 01468 if rand is None: 01469 rand = numpy.random.rand(3) 01470 else: 01471 assert len(rand) == 3 01472 r1 = numpy.sqrt(1.0 - rand[0]) 01473 r2 = numpy.sqrt(rand[0]) 01474 pi2 = math.pi * 2.0 01475 t1 = pi2 * rand[1] 01476 t2 = pi2 * rand[2] 01477 return numpy.array([numpy.cos(t2)*r2, numpy.sin(t1)*r1, 01478 numpy.cos(t1)*r1, numpy.sin(t2)*r2]) 01479 01480 01481 def random_rotation_matrix(rand=None): 01482 """Return uniform random rotation matrix. 01483 01484 rand: array like 01485 Three independent random variables that are uniformly distributed 01486 between 0 and 1 for each returned quaternion. 01487 01488 >>> R = random_rotation_matrix() 01489 >>> numpy.allclose(numpy.dot(R.T, R), numpy.identity(4)) 01490 True 01491 01492 """ 01493 return quaternion_matrix(random_quaternion(rand)) 01494 01495 01496 class Arcball(object): 01497 """Virtual Trackball Control. 01498 01499 >>> ball = Arcball() 01500 >>> ball = Arcball(initial=numpy.identity(4)) 01501 >>> ball.place([320, 320], 320) 01502 >>> ball.down([500, 250]) 01503 >>> ball.drag([475, 275]) 01504 >>> R = ball.matrix() 01505 >>> numpy.allclose(numpy.sum(R), 3.90583455) 01506 True 01507 >>> ball = Arcball(initial=[1, 0, 0, 0]) 01508 >>> ball.place([320, 320], 320) 01509 >>> ball.setaxes([1, 1, 0], [-1, 1, 0]) 01510 >>> ball.setconstrain(True) 01511 >>> ball.down([400, 200]) 01512 >>> ball.drag([200, 400]) 01513 >>> R = ball.matrix() 01514 >>> numpy.allclose(numpy.sum(R), 0.2055924) 01515 True 01516 >>> ball.next() 01517 01518 """ 01519 01520 def __init__(self, initial=None): 01521 """Initialize virtual trackball control. 01522 01523 initial : quaternion or rotation matrix 01524 01525 """ 01526 self._axis = None 01527 self._axes = None 01528 self._radius = 1.0 01529 self._center = [0.0, 0.0] 01530 self._vdown = numpy.array([0.0, 0.0, 1.0]) 01531 self._constrain = False 01532 if initial is None: 01533 self._qdown = numpy.array([1.0, 0.0, 0.0, 0.0]) 01534 else: 01535 initial = numpy.array(initial, dtype=numpy.float64) 01536 if initial.shape == (4, 4): 01537 self._qdown = quaternion_from_matrix(initial) 01538 elif initial.shape == (4, ): 01539 initial /= vector_norm(initial) 01540 self._qdown = initial 01541 else: 01542 raise ValueError("initial not a quaternion or matrix") 01543 self._qnow = self._qpre = self._qdown 01544 01545 def place(self, center, radius): 01546 """Place Arcball, e.g. when window size changes. 01547 01548 center : sequence[2] 01549 Window coordinates of trackball center. 01550 radius : float 01551 Radius of trackball in window coordinates. 01552 01553 """ 01554 self._radius = float(radius) 01555 self._center[0] = center[0] 01556 self._center[1] = center[1] 01557 01558 def setaxes(self, *axes): 01559 """Set axes to constrain rotations.""" 01560 if axes is None: 01561 self._axes = None 01562 else: 01563 self._axes = [unit_vector(axis) for axis in axes] 01564 01565 def setconstrain(self, constrain): 01566 """Set state of constrain to axis mode.""" 01567 self._constrain = constrain == True 01568 01569 def getconstrain(self): 01570 """Return state of constrain to axis mode.""" 01571 return self._constrain 01572 01573 def down(self, point): 01574 """Set initial cursor window coordinates and pick constrain-axis.""" 01575 self._vdown = arcball_map_to_sphere(point, self._center, self._radius) 01576 self._qdown = self._qpre = self._qnow 01577 if self._constrain and self._axes is not None: 01578 self._axis = arcball_nearest_axis(self._vdown, self._axes) 01579 self._vdown = arcball_constrain_to_axis(self._vdown, self._axis) 01580 else: 01581 self._axis = None 01582 01583 def drag(self, point): 01584 """Update current cursor window coordinates.""" 01585 vnow = arcball_map_to_sphere(point, self._center, self._radius) 01586 if self._axis is not None: 01587 vnow = arcball_constrain_to_axis(vnow, self._axis) 01588 self._qpre = self._qnow 01589 t = numpy.cross(self._vdown, vnow) 01590 if numpy.dot(t, t) < _EPS: 01591 self._qnow = self._qdown 01592 else: 01593 q = [numpy.dot(self._vdown, vnow), t[0], t[1], t[2]] 01594 self._qnow = quaternion_multiply(q, self._qdown) 01595 01596 def next(self, acceleration=0.0): 01597 """Continue rotation in direction of last drag.""" 01598 q = quaternion_slerp(self._qpre, self._qnow, 2.0+acceleration, False) 01599 self._qpre, self._qnow = self._qnow, q 01600 01601 def matrix(self): 01602 """Return homogeneous rotation matrix.""" 01603 return quaternion_matrix(self._qnow) 01604 01605 01606 def arcball_map_to_sphere(point, center, radius): 01607 """Return unit sphere coordinates from window coordinates.""" 01608 v0 = (point[0] - center[0]) / radius 01609 v1 = (center[1] - point[1]) / radius 01610 n = v0*v0 + v1*v1 01611 if n > 1.0: 01612 # position outside of sphere 01613 n = math.sqrt(n) 01614 return numpy.array([v0/n, v1/n, 0.0]) 01615 else: 01616 return numpy.array([v0, v1, math.sqrt(1.0 - n)]) 01617 01618 01619 def arcball_constrain_to_axis(point, axis): 01620 """Return sphere point perpendicular to axis.""" 01621 v = numpy.array(point, dtype=numpy.float64, copy=True) 01622 a = numpy.array(axis, dtype=numpy.float64, copy=True) 01623 v -= a * numpy.dot(a, v) # on plane 01624 n = vector_norm(v) 01625 if n > _EPS: 01626 if v[2] < 0.0: 01627 numpy.negative(v, v) 01628 v /= n 01629 return v 01630 if a[2] == 1.0: 01631 return numpy.array([1.0, 0.0, 0.0]) 01632 return unit_vector([-a[1], a[0], 0.0]) 01633 01634 01635 def arcball_nearest_axis(point, axes): 01636 """Return axis, which arc is nearest to point.""" 01637 point = numpy.array(point, dtype=numpy.float64, copy=False) 01638 nearest = None 01639 mx = -1.0 01640 for axis in axes: 01641 t = numpy.dot(arcball_constrain_to_axis(point, axis), point) 01642 if t > mx: 01643 nearest = axis 01644 mx = t 01645 return nearest 01646 01647 01648 # epsilon for testing whether a number is close to zero 01649 _EPS = numpy.finfo(float).eps * 4.0 01650 01651 # axis sequences for Euler angles 01652 _NEXT_AXIS = [1, 2, 0, 1] 01653 01654 # map axes strings to/from tuples of inner axis, parity, repetition, frame 01655 _AXES2TUPLE = { 01656 'sxyz': (0, 0, 0, 0), 'sxyx': (0, 0, 1, 0), 'sxzy': (0, 1, 0, 0), 01657 'sxzx': (0, 1, 1, 0), 'syzx': (1, 0, 0, 0), 'syzy': (1, 0, 1, 0), 01658 'syxz': (1, 1, 0, 0), 'syxy': (1, 1, 1, 0), 'szxy': (2, 0, 0, 0), 01659 'szxz': (2, 0, 1, 0), 'szyx': (2, 1, 0, 0), 'szyz': (2, 1, 1, 0), 01660 'rzyx': (0, 0, 0, 1), 'rxyx': (0, 0, 1, 1), 'ryzx': (0, 1, 0, 1), 01661 'rxzx': (0, 1, 1, 1), 'rxzy': (1, 0, 0, 1), 'ryzy': (1, 0, 1, 1), 01662 'rzxy': (1, 1, 0, 1), 'ryxy': (1, 1, 1, 1), 'ryxz': (2, 0, 0, 1), 01663 'rzxz': (2, 0, 1, 1), 'rxyz': (2, 1, 0, 1), 'rzyz': (2, 1, 1, 1)} 01664 01665 _TUPLE2AXES = dict((v, k) for k, v in _AXES2TUPLE.items()) 01666 01667 01668 def vector_norm(data, axis=None, out=None): 01669 """Return length, i.e. eucledian norm, of ndarray along axis. 01670 01671 >>> v = numpy.random.random(3) 01672 >>> n = vector_norm(v) 01673 >>> numpy.allclose(n, numpy.linalg.norm(v)) 01674 True 01675 >>> v = numpy.random.rand(6, 5, 3) 01676 >>> n = vector_norm(v, axis=-1) 01677 >>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=2))) 01678 True 01679 >>> n = vector_norm(v, axis=1) 01680 >>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=1))) 01681 True 01682 >>> v = numpy.random.rand(5, 4, 3) 01683 >>> n = numpy.empty((5, 3)) 01684 >>> vector_norm(v, axis=1, out=n) 01685 >>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=1))) 01686 True 01687 >>> vector_norm([]) 01688 0.0 01689 >>> vector_norm([1]) 01690 1.0 01691 01692 """ 01693 data = numpy.array(data, dtype=numpy.float64, copy=True) 01694 if out is None: 01695 if data.ndim == 1: 01696 return math.sqrt(numpy.dot(data, data)) 01697 data *= data 01698 out = numpy.atleast_1d(numpy.sum(data, axis=axis)) 01699 numpy.sqrt(out, out) 01700 return out 01701 else: 01702 data *= data 01703 numpy.sum(data, axis=axis, out=out) 01704 numpy.sqrt(out, out) 01705 01706 01707 def unit_vector(data, axis=None, out=None): 01708 """Return ndarray normalized by length, i.e. eucledian norm, along axis. 01709 01710 >>> v0 = numpy.random.random(3) 01711 >>> v1 = unit_vector(v0) 01712 >>> numpy.allclose(v1, v0 / numpy.linalg.norm(v0)) 01713 True 01714 >>> v0 = numpy.random.rand(5, 4, 3) 01715 >>> v1 = unit_vector(v0, axis=-1) 01716 >>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=2)), 2) 01717 >>> numpy.allclose(v1, v2) 01718 True 01719 >>> v1 = unit_vector(v0, axis=1) 01720 >>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=1)), 1) 01721 >>> numpy.allclose(v1, v2) 01722 True 01723 >>> v1 = numpy.empty((5, 4, 3)) 01724 >>> unit_vector(v0, axis=1, out=v1) 01725 >>> numpy.allclose(v1, v2) 01726 True 01727 >>> list(unit_vector([])) 01728 [] 01729 >>> list(unit_vector([1])) 01730 [1.0] 01731 01732 """ 01733 if out is None: 01734 data = numpy.array(data, dtype=numpy.float64, copy=True) 01735 if data.ndim == 1: 01736 data /= math.sqrt(numpy.dot(data, data)) 01737 return data 01738 else: 01739 if out is not data: 01740 out[:] = numpy.array(data, copy=False) 01741 data = out 01742 length = numpy.atleast_1d(numpy.sum(data*data, axis)) 01743 numpy.sqrt(length, length) 01744 if axis is not None: 01745 length = numpy.expand_dims(length, axis) 01746 data /= length 01747 if out is None: 01748 return data 01749 01750 01751 def random_vector(size): 01752 """Return array of random doubles in the half-open interval [0.0, 1.0). 01753 01754 >>> v = random_vector(10000) 01755 >>> numpy.all(v >= 0) and numpy.all(v < 1) 01756 True 01757 >>> v0 = random_vector(10) 01758 >>> v1 = random_vector(10) 01759 >>> numpy.any(v0 == v1) 01760 False 01761 01762 """ 01763 return numpy.random.random(size) 01764 01765 01766 def vector_product(v0, v1, axis=0): 01767 """Return vector perpendicular to vectors. 01768 01769 >>> v = vector_product([2, 0, 0], [0, 3, 0]) 01770 >>> numpy.allclose(v, [0, 0, 6]) 01771 True 01772 >>> v0 = [[2, 0, 0, 2], [0, 2, 0, 2], [0, 0, 2, 2]] 01773 >>> v1 = [[3], [0], [0]] 01774 >>> v = vector_product(v0, v1) 01775 >>> numpy.allclose(v, [[0, 0, 0, 0], [0, 0, 6, 6], [0, -6, 0, -6]]) 01776 True 01777 >>> v0 = [[2, 0, 0], [2, 0, 0], [0, 2, 0], [2, 0, 0]] 01778 >>> v1 = [[0, 3, 0], [0, 0, 3], [0, 0, 3], [3, 3, 3]] 01779 >>> v = vector_product(v0, v1, axis=1) 01780 >>> numpy.allclose(v, [[0, 0, 6], [0, -6, 0], [6, 0, 0], [0, -6, 6]]) 01781 True 01782 01783 """ 01784 return numpy.cross(v0, v1, axis=axis) 01785 01786 01787 def angle_between_vectors(v0, v1, directed=True, axis=0): 01788 """Return angle between vectors. 01789 01790 If directed is False, the input vectors are interpreted as undirected axes, 01791 i.e. the maximum angle is pi/2. 01792 01793 >>> a = angle_between_vectors([1, -2, 3], [-1, 2, -3]) 01794 >>> numpy.allclose(a, math.pi) 01795 True 01796 >>> a = angle_between_vectors([1, -2, 3], [-1, 2, -3], directed=False) 01797 >>> numpy.allclose(a, 0) 01798 True 01799 >>> v0 = [[2, 0, 0, 2], [0, 2, 0, 2], [0, 0, 2, 2]] 01800 >>> v1 = [[3], [0], [0]] 01801 >>> a = angle_between_vectors(v0, v1) 01802 >>> numpy.allclose(a, [0, 1.5708, 1.5708, 0.95532]) 01803 True 01804 >>> v0 = [[2, 0, 0], [2, 0, 0], [0, 2, 0], [2, 0, 0]] 01805 >>> v1 = [[0, 3, 0], [0, 0, 3], [0, 0, 3], [3, 3, 3]] 01806 >>> a = angle_between_vectors(v0, v1, axis=1) 01807 >>> numpy.allclose(a, [1.5708, 1.5708, 1.5708, 0.95532]) 01808 True 01809 01810 """ 01811 v0 = numpy.array(v0, dtype=numpy.float64, copy=False) 01812 v1 = numpy.array(v1, dtype=numpy.float64, copy=False) 01813 dot = numpy.sum(v0 * v1, axis=axis) 01814 dot /= vector_norm(v0, axis=axis) * vector_norm(v1, axis=axis) 01815 return numpy.arccos(dot if directed else numpy.fabs(dot)) 01816 01817 01818 def inverse_matrix(matrix): 01819 """Return inverse of square transformation matrix. 01820 01821 >>> M0 = random_rotation_matrix() 01822 >>> M1 = inverse_matrix(M0.T) 01823 >>> numpy.allclose(M1, numpy.linalg.inv(M0.T)) 01824 True 01825 >>> for size in range(1, 7): 01826 ... M0 = numpy.random.rand(size, size) 01827 ... M1 = inverse_matrix(M0) 01828 ... if not numpy.allclose(M1, numpy.linalg.inv(M0)): print(size) 01829 01830 """ 01831 return numpy.linalg.inv(matrix) 01832 01833 01834 def concatenate_matrices(*matrices): 01835 """Return concatenation of series of transformation matrices. 01836 01837 >>> M = numpy.random.rand(16).reshape((4, 4)) - 0.5 01838 >>> numpy.allclose(M, concatenate_matrices(M)) 01839 True 01840 >>> numpy.allclose(numpy.dot(M, M.T), concatenate_matrices(M, M.T)) 01841 True 01842 01843 """ 01844 M = numpy.identity(4) 01845 for i in matrices: 01846 M = numpy.dot(M, i) 01847 return M 01848 01849 01850 def is_same_transform(matrix0, matrix1): 01851 """Return True if two matrices perform same transformation. 01852 01853 >>> is_same_transform(numpy.identity(4), numpy.identity(4)) 01854 True 01855 >>> is_same_transform(numpy.identity(4), random_rotation_matrix()) 01856 False 01857 01858 """ 01859 matrix0 = numpy.array(matrix0, dtype=numpy.float64, copy=True) 01860 matrix0 /= matrix0[3, 3] 01861 matrix1 = numpy.array(matrix1, dtype=numpy.float64, copy=True) 01862 matrix1 /= matrix1[3, 3] 01863 return numpy.allclose(matrix0, matrix1) 01864 01865 def decompose_affine(m): 01866 """ 01867 Decompose matrix into a rotation (represented as a quaternion) followed 01868 by a translation 01869 """ 01870 t = translation_from_matrix(m) 01871 tm = translation_matrix(t) 01872 q = quaternion_from_matrix(numpy.dot(numpy.linalg.inv(tm), m)) 01873 return (t,q) 01874 01875 def affine_matrix(v,q): 01876 """ 01877 Create an affine transformation matrix from a 3d vector and a 4d quaternion 01878 """ 01879 return numpy.dot(translation_matrix(v), quaternion_matrix(q)) 01880 01881 01882 # def _import_module(module_name, warn=True, prefix='_py_', ignore='_'): 01883 # """Try import all public attributes from module into global namespace. 01884 01885 # Existing attributes with name clashes are renamed with prefix. 01886 # Attributes starting with underscore are ignored by default. 01887 01888 # Return True on successful import. 01889 01890 # """ 01891 # sys.path.append(os.path.dirname(__file__)) 01892 # try: 01893 # module = __import__(module_name) 01894 # except ImportError: 01895 # sys.path.pop() 01896 # if warn: 01897 # warnings.warn("failed to import module " + module_name) 01898 # else: 01899 # sys.path.pop() 01900 # for attr in dir(module): 01901 # if ignore and attr.startswith(ignore): 01902 # continue 01903 # if prefix: 01904 # if attr in globals(): 01905 # globals()[prefix + attr] = globals()[attr] 01906 # elif warn: 01907 # warnings.warn("no Python implementation of " + attr) 01908 # globals()[attr] = getattr(module, attr) 01909 # return True 01910 01911 01912 # __version__ = '2012.01.01' 01913 # __docformat__ = 'restructuredtext en' 01914 01915 # _import_module('_transformations') 01916 01917 if __name__ == "__main__": 01918 import doctest 01919 import random # used in doctests 01920 numpy.set_printoptions(suppress=True, precision=5) 01921 doctest.testmod() 01922