Merge branch 'development' into state-integration-cleaning

This commit is contained in:
Martin Diehl 2020-04-17 07:46:40 +02:00
commit 84d6521183
18 changed files with 1057 additions and 622 deletions

@ -1 +1 @@
Subproject commit aa0b9fe992ce0bfc172989ab006893ddb8939c1e Subproject commit 232a094c715bcbbd1c6652c4dc4a4a50d402b82f

View File

@ -1 +1 @@
v2.0.3-2245-gc7508d85 v2.0.3-2303-g2a6132b7

View File

@ -51,19 +51,18 @@ def cube_to_ball(cube):
https://doi.org/10.1088/0965-0393/22/7/075013 https://doi.org/10.1088/0965-0393/22/7/075013
""" """
if np.abs(np.max(cube))>np.pi**(2./3.) * 0.5: cube_ = np.clip(cube,None,np.pi**(2./3.) * 0.5) if np.isclose(np.abs(np.max(cube)),np.pi**(2./3.) * 0.5,atol=1e-6) else cube
raise ValueError
# transform to the sphere grid via the curved square, and intercept the zero point # transform to the sphere grid via the curved square, and intercept the zero point
if np.allclose(cube,0.0,rtol=0.0,atol=1.0e-300): if np.allclose(cube_,0.0,rtol=0.0,atol=1.0e-16):
ball = np.zeros(3) ball = np.zeros(3)
else: else:
# get pyramide and scale by grid parameter ratio # get pyramide and scale by grid parameter ratio
p = _get_order(cube) p = _get_order(cube_)
XYZ = cube[p] * sc XYZ = cube_[p[0]] * sc
# intercept all the points along the z-axis # intercept all the points along the z-axis
if np.allclose(XYZ[0:2],0.0,rtol=0.0,atol=1.0e-300): if np.allclose(XYZ[0:2],0.0,rtol=0.0,atol=1.0e-16):
ball = np.array([0.0, 0.0, np.sqrt(6.0/np.pi) * XYZ[2]]) ball = np.array([0.0, 0.0, np.sqrt(6.0/np.pi) * XYZ[2]])
else: else:
order = [1,0] if np.abs(XYZ[1]) <= np.abs(XYZ[0]) else [0,1] order = [1,0] if np.abs(XYZ[1]) <= np.abs(XYZ[0]) else [0,1]
@ -82,7 +81,7 @@ def cube_to_ball(cube):
ball = np.array([ T[order[1]] * q, T[order[0]] * q, np.sqrt(6.0/np.pi) * XYZ[2] - c ]) ball = np.array([ T[order[1]] * q, T[order[0]] * q, np.sqrt(6.0/np.pi) * XYZ[2] - c ])
# reverse the coordinates back to the regular order according to the original pyramid number # reverse the coordinates back to the regular order according to the original pyramid number
ball = ball[p] ball = ball[p[1]]
return ball return ball
@ -102,15 +101,14 @@ def ball_to_cube(ball):
https://doi.org/10.1088/0965-0393/22/7/075013 https://doi.org/10.1088/0965-0393/22/7/075013
""" """
rs = np.linalg.norm(ball) ball_ = ball/np.linalg.norm(ball)*R1 if np.isclose(np.linalg.norm(ball),R1,atol=1e-6) else ball
if rs > R1: rs = np.linalg.norm(ball_)
raise ValueError
if np.allclose(ball,0.0,rtol=0.0,atol=1.0e-300): if np.allclose(ball_,0.0,rtol=0.0,atol=1.0e-16):
cube = np.zeros(3) cube = np.zeros(3)
else: else:
p = _get_order(ball) p = _get_order(ball_)
xyz3 = ball[p] xyz3 = ball_[p[0]]
# inverse M_3 # inverse M_3
xyz2 = xyz3[0:2] * np.sqrt( 2.0*rs/(rs+np.abs(xyz3[2])) ) xyz2 = xyz3[0:2] * np.sqrt( 2.0*rs/(rs+np.abs(xyz3[2])) )
@ -118,7 +116,7 @@ def ball_to_cube(ball):
# inverse M_2 # inverse M_2
qxy = np.sum(xyz2**2) qxy = np.sum(xyz2**2)
if np.isclose(qxy,0.0,rtol=0.0,atol=1.0e-300): if np.isclose(qxy,0.0,rtol=0.0,atol=1.0e-16):
Tinv = np.zeros(2) Tinv = np.zeros(2)
else: else:
q2 = qxy + np.max(np.abs(xyz2))**2 q2 = qxy + np.max(np.abs(xyz2))**2
@ -132,7 +130,7 @@ def ball_to_cube(ball):
# inverse M_1 # inverse M_1
cube = np.array([ Tinv[0], Tinv[1], (-1.0 if xyz3[2] < 0.0 else 1.0) * rs / np.sqrt(6.0/np.pi) ]) /sc cube = np.array([ Tinv[0], Tinv[1], (-1.0 if xyz3[2] < 0.0 else 1.0) * rs / np.sqrt(6.0/np.pi) ]) /sc
# reverse the coordinates back to the regular order according to the original pyramid number # reverse the coordinates back to the regular order according to the original pyramid number
cube = cube[p] cube = cube[p[1]]
return cube return cube
@ -157,10 +155,10 @@ def _get_order(xyz):
""" """
if (abs(xyz[0])<= xyz[2]) and (abs(xyz[1])<= xyz[2]) or \ if (abs(xyz[0])<= xyz[2]) and (abs(xyz[1])<= xyz[2]) or \
(abs(xyz[0])<=-xyz[2]) and (abs(xyz[1])<=-xyz[2]): (abs(xyz[0])<=-xyz[2]) and (abs(xyz[1])<=-xyz[2]):
return [0,1,2] return [[0,1,2],[0,1,2]]
elif (abs(xyz[2])<= xyz[0]) and (abs(xyz[1])<= xyz[0]) or \ elif (abs(xyz[2])<= xyz[0]) and (abs(xyz[1])<= xyz[0]) or \
(abs(xyz[2])<=-xyz[0]) and (abs(xyz[1])<=-xyz[0]): (abs(xyz[2])<=-xyz[0]) and (abs(xyz[1])<=-xyz[0]):
return [1,2,0] return [[1,2,0],[2,0,1]]
elif (abs(xyz[0])<= xyz[1]) and (abs(xyz[2])<= xyz[1]) or \ elif (abs(xyz[0])<= xyz[1]) and (abs(xyz[2])<= xyz[1]) or \
(abs(xyz[0])<=-xyz[1]) and (abs(xyz[2])<=-xyz[1]): (abs(xyz[0])<=-xyz[1]) and (abs(xyz[2])<=-xyz[1]):
return [2,0,1] return [[2,0,1],[1,2,0]]

View File

@ -6,7 +6,7 @@ name = 'damask'
with open(_os.path.join(_os.path.dirname(__file__),'VERSION')) as _f: with open(_os.path.join(_os.path.dirname(__file__),'VERSION')) as _f:
version = _re.sub(r'^v','',_f.readline().strip()) version = _re.sub(r'^v','',_f.readline().strip())
# classes # make classes directly accessible as damask.Class
from ._environment import Environment # noqa from ._environment import Environment # noqa
from ._table import Table # noqa from ._table import Table # noqa
from ._vtk import VTK # noqa from ._vtk import VTK # noqa

View File

@ -291,7 +291,7 @@ class Geom:
comments = [] comments = []
for i,line in enumerate(content[:header_length]): for i,line in enumerate(content[:header_length]):
items = line.lower().strip().split() items = line.split('#')[0].lower().strip().split()
key = items[0] if items else '' key = items[0] if items else ''
if key == 'grid': if key == 'grid':
grid = np.array([ int(dict(zip(items[1::2],items[2::2]))[i]) for i in ['a','b','c']]) grid = np.array([ int(dict(zip(items[1::2],items[2::2]))[i]) for i in ['a','b','c']])
@ -307,7 +307,7 @@ class Geom:
microstructure = np.empty(grid.prod()) # initialize as flat array microstructure = np.empty(grid.prod()) # initialize as flat array
i = 0 i = 0
for line in content[header_length:]: for line in content[header_length:]:
items = line.split() items = line.split('#')[0].split()
if len(items) == 3: if len(items) == 3:
if items[1].lower() == 'of': if items[1].lower() == 'of':
items = np.ones(int(items[0]))*float(items[2]) items = np.ones(int(items[0]))*float(items[2])

View File

@ -2,7 +2,7 @@ import numpy as np
from ._Lambert import ball_to_cube, cube_to_ball from ._Lambert import ball_to_cube, cube_to_ball
P = -1 _P = -1
def iszero(a): def iszero(a):
return np.isclose(a,0.0,atol=1.0e-12,rtol=0.0) return np.isclose(a,0.0,atol=1.0e-12,rtol=0.0)
@ -89,7 +89,7 @@ class Rotation:
other_q = other.quaternion[0] other_q = other.quaternion[0]
other_p = other.quaternion[1:] other_p = other.quaternion[1:]
R = self.__class__(np.append(self_q*other_q - np.dot(self_p,other_p), R = self.__class__(np.append(self_q*other_q - np.dot(self_p,other_p),
self_q*other_p + other_q*self_p + P * np.cross(self_p,other_p))) self_q*other_p + other_q*self_p + _P * np.cross(self_p,other_p)))
return R.standardize() return R.standardize()
elif isinstance(other, (tuple,np.ndarray)): elif isinstance(other, (tuple,np.ndarray)):
if isinstance(other,tuple) or other.shape == (3,): # rotate a single (3)-vector or meshgrid if isinstance(other,tuple) or other.shape == (3,): # rotate a single (3)-vector or meshgrid
@ -97,7 +97,7 @@ class Rotation:
B = 2.0 * ( self.quaternion[1]*other[0] B = 2.0 * ( self.quaternion[1]*other[0]
+ self.quaternion[2]*other[1] + self.quaternion[2]*other[1]
+ self.quaternion[3]*other[2]) + self.quaternion[3]*other[2])
C = 2.0 * P*self.quaternion[0] C = 2.0 * _P*self.quaternion[0]
return np.array([ return np.array([
A*other[0] + B*self.quaternion[1] + C*(self.quaternion[2]*other[2] - self.quaternion[3]*other[1]), A*other[0] + B*self.quaternion[1] + C*(self.quaternion[2]*other[2] - self.quaternion[3]*other[1]),
@ -206,7 +206,7 @@ class Rotation:
""" """
ax = Rotation.qu2ax(self.quaternion) ax = Rotation.qu2ax(self.quaternion)
if degrees: ax[3] = np.degrees(ax[3]) if degrees: ax[3] = np.degrees(ax[3])
return (ax[:3],np.degrees(ax[3])) if pair else ax return (ax[:3],ax[3]) if pair else ax
def asMatrix(self): def asMatrix(self):
"""Rotation matrix.""" """Rotation matrix."""
@ -262,9 +262,9 @@ class Rotation:
if acceptHomomorph: if acceptHomomorph:
qu *= -1. qu *= -1.
else: else:
raise ValueError('Quaternion has negative first component.\n{}'.format(qu[0])) raise ValueError('Quaternion has negative first component: {}.'.format(qu[0]))
if not np.isclose(np.linalg.norm(qu), 1.0): if not np.isclose(np.linalg.norm(qu), 1.0):
raise ValueError('Quaternion is not of unit length.\n{} {} {} {}'.format(*qu)) raise ValueError('Quaternion is not of unit length: {} {} {} {}.'.format(*qu))
return Rotation(qu) return Rotation(qu)
@ -276,7 +276,7 @@ class Rotation:
else np.array(eulers,dtype=float) else np.array(eulers,dtype=float)
eu = np.radians(eu) if degrees else eu eu = np.radians(eu) if degrees else eu
if np.any(eu < 0.0) or np.any(eu > 2.0*np.pi) or eu[1] > np.pi: if np.any(eu < 0.0) or np.any(eu > 2.0*np.pi) or eu[1] > np.pi:
raise ValueError('Euler angles outside of [0..2π],[0..π],[0..2π].\n{} {} {}.'.format(*eu)) raise ValueError('Euler angles outside of [0..2π],[0..π],[0..2π]: {} {} {}.'.format(*eu))
return Rotation(Rotation.eu2qu(eu)) return Rotation(Rotation.eu2qu(eu))
@ -292,9 +292,9 @@ class Rotation:
if degrees: ax[ 3] = np.radians(ax[3]) if degrees: ax[ 3] = np.radians(ax[3])
if normalise: ax[0:3] /= np.linalg.norm(ax[0:3]) if normalise: ax[0:3] /= np.linalg.norm(ax[0:3])
if ax[3] < 0.0 or ax[3] > np.pi: if ax[3] < 0.0 or ax[3] > np.pi:
raise ValueError('Axis angle rotation angle outside of [0..π].\n{}'.format(ax[3])) raise ValueError('Axis angle rotation angle outside of [0..π]: {}.'.format(ax[3]))
if not np.isclose(np.linalg.norm(ax[0:3]), 1.0): if not np.isclose(np.linalg.norm(ax[0:3]), 1.0):
raise ValueError('Axis angle rotation axis is not of unit length.\n{} {} {}'.format(*ax[0:3])) raise ValueError('Axis angle rotation axis is not of unit length: {} {} {}.'.format(*ax[0:3]))
return Rotation(Rotation.ax2qu(ax)) return Rotation(Rotation.ax2qu(ax))
@ -312,11 +312,11 @@ class Rotation:
(U,S,Vh) = np.linalg.svd(om) # singular value decomposition (U,S,Vh) = np.linalg.svd(om) # singular value decomposition
om = np.dot(U,Vh) om = np.dot(U,Vh)
if not np.isclose(np.linalg.det(om),1.0): if not np.isclose(np.linalg.det(om),1.0):
raise ValueError('matrix is not a proper rotation.\n{}'.format(om)) raise ValueError('matrix is not a proper rotation: {}.'.format(om))
if not np.isclose(np.dot(om[0],om[1]), 0.0) \ if not np.isclose(np.dot(om[0],om[1]), 0.0) \
or not np.isclose(np.dot(om[1],om[2]), 0.0) \ or not np.isclose(np.dot(om[1],om[2]), 0.0) \
or not np.isclose(np.dot(om[2],om[0]), 0.0): or not np.isclose(np.dot(om[2],om[0]), 0.0):
raise ValueError('matrix is not orthogonal.\n{}'.format(om)) raise ValueError('matrix is not orthogonal: {}.'.format(om))
return Rotation(Rotation.om2qu(om)) return Rotation(Rotation.om2qu(om))
@ -336,9 +336,9 @@ class Rotation:
if P > 0: ro[0:3] *= -1 # convert from P=1 to P=-1 if P > 0: ro[0:3] *= -1 # convert from P=1 to P=-1
if normalise: ro[0:3] /= np.linalg.norm(ro[0:3]) if normalise: ro[0:3] /= np.linalg.norm(ro[0:3])
if not np.isclose(np.linalg.norm(ro[0:3]), 1.0): if not np.isclose(np.linalg.norm(ro[0:3]), 1.0):
raise ValueError('Rodrigues rotation axis is not of unit length.\n{} {} {}'.format(*ro[0:3])) raise ValueError('Rodrigues rotation axis is not of unit length: {} {} {}.'.format(*ro[0:3]))
if ro[3] < 0.0: if ro[3] < 0.0:
raise ValueError('Rodrigues rotation angle not positive.\n{}'.format(ro[3])) raise ValueError('Rodrigues rotation angle not positive: {}.'.format(ro[3]))
return Rotation(Rotation.ro2qu(ro)) return Rotation(Rotation.ro2qu(ro))
@ -350,6 +350,9 @@ class Rotation:
else np.array(homochoric,dtype=float) else np.array(homochoric,dtype=float)
if P > 0: ho *= -1 # convert from P=1 to P=-1 if P > 0: ho *= -1 # convert from P=1 to P=-1
if np.linalg.norm(ho) > (3.*np.pi/4.)**(1./3.)+1e-9:
raise ValueError('Coordinate outside of the sphere: {} {} {}.'.format(ho))
return Rotation(Rotation.ho2qu(ho)) return Rotation(Rotation.ho2qu(ho))
@staticmethod @staticmethod
@ -358,6 +361,10 @@ class Rotation:
cu = cubochoric if isinstance(cubochoric, np.ndarray) and cubochoric.dtype == np.dtype(float) \ cu = cubochoric if isinstance(cubochoric, np.ndarray) and cubochoric.dtype == np.dtype(float) \
else np.array(cubochoric,dtype=float) else np.array(cubochoric,dtype=float)
if np.abs(np.max(cu))>np.pi**(2./3.) * 0.5+1e-9:
raise ValueError('Coordinate outside of the cube: {} {} {}.'.format(*cu))
ho = Rotation.cu2ho(cu) ho = Rotation.cu2ho(cu)
if P > 0: ho *= -1 # convert from P=1 to P=-1 if P > 0: ho *= -1 # convert from P=1 to P=-1
@ -383,7 +390,7 @@ class Rotation:
""" """
if not all(isinstance(item, Rotation) for item in rotations): if not all(isinstance(item, Rotation) for item in rotations):
raise TypeError("Only instances of Rotation can be averaged.") raise TypeError('Only instances of Rotation can be averaged.')
N = len(rotations) N = len(rotations)
if not weights: if not weights:
@ -441,34 +448,69 @@ class Rotation:
#---------- Quaternion ---------- #---------- Quaternion ----------
@staticmethod @staticmethod
def qu2om(qu): def qu2om(qu):
if len(qu.shape) == 1:
"""Quaternion to rotation matrix.""" """Quaternion to rotation matrix."""
qq = qu[0]**2-(qu[1]**2 + qu[2]**2 + qu[3]**2) qq = qu[0]**2-(qu[1]**2 + qu[2]**2 + qu[3]**2)
om = np.diag(qq + 2.0*np.array([qu[1],qu[2],qu[3]])**2) om = np.diag(qq + 2.0*np.array([qu[1],qu[2],qu[3]])**2)
om[1,0] = 2.0*(qu[2]*qu[1]+qu[0]*qu[3]) om[0,1] = 2.0*(qu[2]*qu[1]+qu[0]*qu[3])
om[0,1] = 2.0*(qu[1]*qu[2]-qu[0]*qu[3]) om[1,0] = 2.0*(qu[1]*qu[2]-qu[0]*qu[3])
om[2,1] = 2.0*(qu[3]*qu[2]+qu[0]*qu[1]) om[1,2] = 2.0*(qu[3]*qu[2]+qu[0]*qu[1])
om[1,2] = 2.0*(qu[2]*qu[3]-qu[0]*qu[1]) om[2,1] = 2.0*(qu[2]*qu[3]-qu[0]*qu[1])
om[0,2] = 2.0*(qu[1]*qu[3]+qu[0]*qu[2]) om[2,0] = 2.0*(qu[1]*qu[3]+qu[0]*qu[2])
om[2,0] = 2.0*(qu[3]*qu[1]-qu[0]*qu[2]) om[0,2] = 2.0*(qu[3]*qu[1]-qu[0]*qu[2])
return om if P > 0.0 else om.T else:
qq = qu[...,0:1]**2-(qu[...,1:2]**2 + qu[...,2:3]**2 + qu[...,3:4]**2)
om = np.block([qq + 2.0*qu[...,1:2]**2,
2.0*(qu[...,2:3]*qu[...,1:2]+qu[...,0:1]*qu[...,3:4]),
2.0*(qu[...,3:4]*qu[...,1:2]-qu[...,0:1]*qu[...,2:3]),
2.0*(qu[...,1:2]*qu[...,2:3]-qu[...,0:1]*qu[...,3:4]),
qq + 2.0*qu[...,2:3]**2,
2.0*(qu[...,3:4]*qu[...,2:3]+qu[...,0:1]*qu[...,1:2]),
2.0*(qu[...,1:2]*qu[...,3:4]+qu[...,0:1]*qu[...,2:3]),
2.0*(qu[...,2:3]*qu[...,3:4]-qu[...,0:1]*qu[...,1:2]),
qq + 2.0*qu[...,3:4]**2,
]).reshape(qu.shape[:-1]+(3,3))
return om if _P < 0.0 else np.swapaxes(om,(-1,-2))
@staticmethod @staticmethod
def qu2eu(qu): def qu2eu(qu):
"""Quaternion to Bunge-Euler angles.""" """Quaternion to Bunge-Euler angles."""
if len(qu.shape) == 1:
q03 = qu[0]**2+qu[3]**2 q03 = qu[0]**2+qu[3]**2
q12 = qu[1]**2+qu[2]**2 q12 = qu[1]**2+qu[2]**2
chi = np.sqrt(q03*q12) chi = np.sqrt(q03*q12)
if np.abs(q12) < 1.e-8:
if iszero(chi): eu = np.array([np.arctan2(-_P*2.0*qu[0]*qu[3],qu[0]**2-qu[3]**2), 0.0, 0.0])
eu = np.array([np.arctan2(-P*2.0*qu[0]*qu[3],qu[0]**2-qu[3]**2), 0.0, 0.0]) if iszero(q12) else \ elif np.abs(q03) < 1.e-8:
np.array([np.arctan2(2.0*qu[1]*qu[2],qu[1]**2-qu[2]**2), np.pi, 0.0]) eu = np.array([np.arctan2( 2.0*qu[1]*qu[2],qu[1]**2-qu[2]**2), np.pi, 0.0])
else: else:
eu = np.array([np.arctan2((-P*qu[0]*qu[2]+qu[1]*qu[3])*chi, (-P*qu[0]*qu[1]-qu[2]*qu[3])*chi ), eu = np.array([np.arctan2((-_P*qu[0]*qu[2]+qu[1]*qu[3])*chi, (-_P*qu[0]*qu[1]-qu[2]*qu[3])*chi ),
np.arctan2( 2.0*chi, q03-q12 ), np.arctan2( 2.0*chi, q03-q12 ),
np.arctan2(( P*qu[0]*qu[2]+qu[1]*qu[3])*chi, (-P*qu[0]*qu[1]+qu[2]*qu[3])*chi )]) np.arctan2(( _P*qu[0]*qu[2]+qu[1]*qu[3])*chi, (-_P*qu[0]*qu[1]+qu[2]*qu[3])*chi )])
else:
q02 = qu[...,0:1]*qu[...,2:3]
q13 = qu[...,1:2]*qu[...,3:4]
q01 = qu[...,0:1]*qu[...,1:2]
q23 = qu[...,2:3]*qu[...,3:4]
q03_s = qu[...,0:1]**2+qu[...,3:4]**2
q12_s = qu[...,1:2]**2+qu[...,2:3]**2
chi = np.sqrt(q03_s*q12_s)
# reduce Euler angles to definition range, i.e a lower limit of 0.0 eu = np.where(np.abs(q12_s) < 1.0e-8,
np.block([np.arctan2(-_P*2.0*qu[...,0:1]*qu[...,3:4],qu[...,0:1]**2-qu[...,3:4]**2),
np.zeros(qu.shape[:-1]+(2,))]),
np.where(np.abs(q03_s) < 1.0e-8,
np.block([np.arctan2( 2.0*qu[...,1:2]*qu[...,2:3],qu[...,1:2]**2-qu[...,2:3]**2),
np.broadcast_to(np.pi,qu.shape[:-1]+(1,)),
np.zeros(qu.shape[:-1]+(1,))]),
np.block([np.arctan2((-_P*q02+q13)*chi, (-_P*q01-q23)*chi),
np.arctan2( 2.0*chi, q03_s-q12_s ),
np.arctan2(( _P*q02+q13)*chi, (-_P*q01+q23)*chi)])
)
)
# reduce Euler angles to definition range
eu[np.abs(eu)<1.e-6] = 0.0
eu = np.where(eu<0, (eu+2.0*np.pi)%np.array([2.0*np.pi,np.pi,2.0*np.pi]),eu) eu = np.where(eu<0, (eu+2.0*np.pi)%np.array([2.0*np.pi,np.pi,2.0*np.pi]),eu)
return eu return eu
@ -479,38 +521,65 @@ class Rotation:
Modified version of the original formulation, should be numerically more stable Modified version of the original formulation, should be numerically more stable
""" """
if iszero(qu[1]**2+qu[2]**2+qu[3]**2): # set axis to [001] if the angle is 0/360 if len(qu.shape) == 1:
ax = [ 0.0, 0.0, 1.0, 0.0 ] if np.abs(np.sum(qu[1:4]**2)) < 1.e-6: # set axis to [001] if the angle is 0/360
elif not iszero(qu[0]): ax = np.array([ 0.0, 0.0, 1.0, 0.0 ])
elif qu[0] > 1.e-6:
s = np.sign(qu[0])/np.sqrt(qu[1]**2+qu[2]**2+qu[3]**2) s = np.sign(qu[0])/np.sqrt(qu[1]**2+qu[2]**2+qu[3]**2)
omega = 2.0 * np.arccos(np.clip(qu[0],-1.0,1.0)) omega = 2.0 * np.arccos(np.clip(qu[0],-1.0,1.0))
ax = [ qu[1]*s, qu[2]*s, qu[3]*s, omega ] ax = ax = np.array([ qu[1]*s, qu[2]*s, qu[3]*s, omega ])
else: else:
ax = [ qu[1], qu[2], qu[3], np.pi] ax = ax = np.array([ qu[1], qu[2], qu[3], np.pi])
return np.array(ax) else:
with np.errstate(invalid='ignore',divide='ignore'):
s = np.sign(qu[...,0:1])/np.sqrt(qu[...,1:2]**2+qu[...,2:3]**2+qu[...,3:4]**2)
omega = 2.0 * np.arccos(np.clip(qu[...,0:1],-1.0,1.0))
ax = np.where(np.broadcast_to(qu[...,0:1] < 1.0e-6,qu.shape),
np.block([qu[...,1:4],np.broadcast_to(np.pi,qu.shape[:-1]+(1,))]),
np.block([qu[...,1:4]*s,omega]))
ax[np.sum(np.abs(qu[...,1:4])**2,axis=-1) < 1.0e-6,] = [0.0, 0.0, 1.0, 0.0]
return ax
@staticmethod @staticmethod
def qu2ro(qu): def qu2ro(qu):
"""Quaternion to Rodrigues-Frank vector.""" """Quaternion to Rodrigues-Frank vector."""
if len(qu.shape) == 1:
if iszero(qu[0]): if iszero(qu[0]):
ro = [qu[1], qu[2], qu[3], np.inf] ro = np.array([qu[1], qu[2], qu[3], np.inf])
else: else:
s = np.linalg.norm([qu[1],qu[2],qu[3]]) s = np.linalg.norm(qu[1:4])
ro = [0.0,0.0,P,0.0] if iszero(s) else \ ro = np.array([0.0,0.0,_P,0.0] if iszero(s) else \
[ qu[1]/s, qu[2]/s, qu[3]/s, np.tan(np.arccos(np.clip(qu[0],-1.0,1.0)))] [ qu[1]/s, qu[2]/s, qu[3]/s, np.tan(np.arccos(np.clip(qu[0],-1.0,1.0)))])
return np.array(ro) else:
with np.errstate(invalid='ignore',divide='ignore'):
s = np.linalg.norm(qu[...,1:4],axis=-1,keepdims=True)
ro = np.where(np.broadcast_to(np.abs(qu[...,0:1]) < 1.0e-12,qu.shape),
np.block([qu[...,1:2], qu[...,2:3], qu[...,3:4], np.broadcast_to(np.inf,qu.shape[:-1]+(1,))]),
np.block([qu[...,1:2]/s,qu[...,2:3]/s,qu[...,3:4]/s,
np.tan(np.arccos(np.clip(qu[...,0:1],-1.0,1.0)))
])
)
ro[np.abs(s).squeeze(-1) < 1.0e-12] = [0.0,0.0,_P,0.0]
return ro
@staticmethod @staticmethod
def qu2ho(qu): def qu2ho(qu):
"""Quaternion to homochoric vector.""" """Quaternion to homochoric vector."""
if len(qu.shape) == 1:
omega = 2.0 * np.arccos(np.clip(qu[0],-1.0,1.0)) omega = 2.0 * np.arccos(np.clip(qu[0],-1.0,1.0))
if np.abs(omega) < 1.0e-12:
if iszero(omega): ho = np.zeros(3)
ho = np.array([ 0.0, 0.0, 0.0 ])
else: else:
ho = np.array([qu[1], qu[2], qu[3]]) ho = np.array([qu[1], qu[2], qu[3]])
f = 0.75 * ( omega - np.sin(omega) ) f = 0.75 * ( omega - np.sin(omega) )
ho = ho/np.linalg.norm(ho) * f**(1./3.) ho = ho/np.linalg.norm(ho) * f**(1./3.)
else:
with np.errstate(invalid='ignore'):
omega = 2.0 * np.arccos(np.clip(qu[...,0:1],-1.0,1.0))
ho = np.where(np.abs(omega) < 1.0e-12,
np.zeros(3),
qu[...,1:4]/np.linalg.norm(qu[...,1:4],axis=-1,keepdims=True) \
* (0.75*(omega - np.sin(omega)))**(1./3.))
return ho return ho
@staticmethod @staticmethod
@ -532,37 +601,71 @@ class Rotation:
@staticmethod @staticmethod
def om2eu(om): def om2eu(om):
"""Rotation matrix to Bunge-Euler angles.""" """Rotation matrix to Bunge-Euler angles."""
if abs(om[2,2]) < 1.0: if len(om.shape) == 2:
if not np.isclose(np.abs(om[2,2]),1.0,1.e-4):
zeta = 1.0/np.sqrt(1.0-om[2,2]**2) zeta = 1.0/np.sqrt(1.0-om[2,2]**2)
eu = np.array([np.arctan2(om[2,0]*zeta,-om[2,1]*zeta), eu = np.array([np.arctan2(om[2,0]*zeta,-om[2,1]*zeta),
np.arccos(om[2,2]), np.arccos(om[2,2]),
np.arctan2(om[0,2]*zeta, om[1,2]*zeta)]) np.arctan2(om[0,2]*zeta, om[1,2]*zeta)])
else: else:
eu = np.array([np.arctan2( om[0,1],om[0,0]), np.pi*0.5*(1-om[2,2]),0.0]) # following the paper, not the reference implementation eu = np.array([np.arctan2( om[0,1],om[0,0]), np.pi*0.5*(1-om[2,2]),0.0]) # following the paper, not the reference implementation
else:
# reduce Euler angles to definition range, i.e a lower limit of 0.0 with np.errstate(invalid='ignore',divide='ignore'):
zeta = 1.0/np.sqrt(1.0-om[...,2,2:3]**2)
eu = np.where(np.isclose(np.abs(om[...,2,2:3]),1.0,1e-4),
np.block([np.arctan2(om[...,0,1:2],om[...,0,0:1]),
np.pi*0.5*(1-om[...,2,2:3]),
np.zeros(om.shape[:-2]+(1,)),
]),
np.block([np.arctan2(om[...,2,0:1]*zeta,-om[...,2,1:2]*zeta),
np.arccos(om[...,2,2:3]),
np.arctan2(om[...,0,2:3]*zeta,+om[...,1,2:3]*zeta)
])
)
eu[np.abs(eu)<1.e-6] = 0.0
eu = np.where(eu<0, (eu+2.0*np.pi)%np.array([2.0*np.pi,np.pi,2.0*np.pi]),eu) eu = np.where(eu<0, (eu+2.0*np.pi)%np.array([2.0*np.pi,np.pi,2.0*np.pi]),eu)
return eu return eu
@staticmethod @staticmethod
def om2ax(om): def om2ax(om):
"""Rotation matrix to axis angle pair.""" """Rotation matrix to axis angle pair."""
if len(om.shape) == 2:
ax=np.empty(4) ax=np.empty(4)
# first get the rotation angle # first get the rotation angle
t = 0.5*(om.trace() -1.0) t = 0.5*(om.trace() -1.0)
ax[3] = np.arccos(np.clip(t,-1.0,1.0)) ax[3] = np.arccos(np.clip(t,-1.0,1.0))
if np.abs(ax[3])<1.e-6:
if iszero(ax[3]): ax = np.array([ 0.0, 0.0, 1.0, 0.0])
ax = [ 0.0, 0.0, 1.0, 0.0]
else: else:
w,vr = np.linalg.eig(om) w,vr = np.linalg.eig(om)
# next, find the eigenvalue (1,0j) # next, find the eigenvalue (1,0j)
i = np.where(np.isclose(w,1.0+0.0j))[0][0] i = np.where(np.isclose(w,1.0+0.0j))[0][0]
ax[0:3] = np.real(vr[0:3,i]) ax[0:3] = np.real(vr[0:3,i])
diagDelta = np.array([om[1,2]-om[2,1],om[2,0]-om[0,2],om[0,1]-om[1,0]]) diagDelta = -_P*np.array([om[1,2]-om[2,1],om[2,0]-om[0,2],om[0,1]-om[1,0]])
ax[0:3] = np.where(iszero(diagDelta), ax[0:3],np.abs(ax[0:3])*np.sign(-P*diagDelta)) diagDelta[np.abs(diagDelta)<1.e-6] = 1.0
return np.array(ax) ax[0:3] = np.where(np.abs(diagDelta)<0, ax[0:3],np.abs(ax[0:3])*np.sign(diagDelta))
else:
diag_delta = -_P*np.block([om[...,1,2:3]-om[...,2,1:2],
om[...,2,0:1]-om[...,0,2:3],
om[...,0,1:2]-om[...,1,0:1]
])
diag_delta[np.abs(diag_delta)<1.e-6] = 1.0
t = 0.5*(om.trace(axis2=-2,axis1=-1) -1.0).reshape(om.shape[:-2]+(1,))
w,vr = np.linalg.eig(om)
# mask duplicated real eigenvalues
w[np.isclose(w[...,0],1.0+0.0j),1:] = 0.
w[np.isclose(w[...,1],1.0+0.0j),2:] = 0.
vr = np.swapaxes(vr,-1,-2)
ax = np.where(np.abs(diag_delta)<0,
np.real(vr[np.isclose(w,1.0+0.0j)]).reshape(om.shape[:-2]+(3,)),
np.abs(np.real(vr[np.isclose(w,1.0+0.0j)]).reshape(om.shape[:-2]+(3,))) \
*np.sign(diag_delta))
ax = np.block([ax,np.arccos(np.clip(t,-1.0,1.0))])
ax[np.abs(ax[...,3])<1.e-6] = [ 0.0, 0.0, 1.0, 0.0]
return ax
@staticmethod @staticmethod
def om2ro(om): def om2ro(om):
@ -584,32 +687,57 @@ class Rotation:
@staticmethod @staticmethod
def eu2qu(eu): def eu2qu(eu):
"""Bunge-Euler angles to quaternion.""" """Bunge-Euler angles to quaternion."""
if len(eu.shape) == 1:
ee = 0.5*eu ee = 0.5*eu
cPhi = np.cos(ee[1]) cPhi = np.cos(ee[1])
sPhi = np.sin(ee[1]) sPhi = np.sin(ee[1])
qu = np.array([ cPhi*np.cos(ee[0]+ee[2]), qu = np.array([ cPhi*np.cos(ee[0]+ee[2]),
-P*sPhi*np.cos(ee[0]-ee[2]), -_P*sPhi*np.cos(ee[0]-ee[2]),
-P*sPhi*np.sin(ee[0]-ee[2]), -_P*sPhi*np.sin(ee[0]-ee[2]),
-P*cPhi*np.sin(ee[0]+ee[2]) ]) -_P*cPhi*np.sin(ee[0]+ee[2]) ])
if qu[0] < 0.0: qu*=-1 if qu[0] < 0.0: qu*=-1
else:
ee = 0.5*eu
cPhi = np.cos(ee[...,1:2])
sPhi = np.sin(ee[...,1:2])
qu = np.block([ cPhi*np.cos(ee[...,0:1]+ee[...,2:3]),
-_P*sPhi*np.cos(ee[...,0:1]-ee[...,2:3]),
-_P*sPhi*np.sin(ee[...,0:1]-ee[...,2:3]),
-_P*cPhi*np.sin(ee[...,0:1]+ee[...,2:3])])
qu[qu[...,0]<0.0]*=-1
return qu return qu
@staticmethod @staticmethod
def eu2om(eu): def eu2om(eu):
"""Bunge-Euler angles to rotation matrix.""" """Bunge-Euler angles to rotation matrix."""
if len(eu.shape) == 1:
c = np.cos(eu) c = np.cos(eu)
s = np.sin(eu) s = np.sin(eu)
om = np.array([[+c[0]*c[2]-s[0]*s[2]*c[1], +s[0]*c[2]+c[0]*s[2]*c[1], +s[2]*s[1]], om = np.array([[+c[0]*c[2]-s[0]*s[2]*c[1], +s[0]*c[2]+c[0]*s[2]*c[1], +s[2]*s[1]],
[-c[0]*s[2]-s[0]*c[2]*c[1], -s[0]*s[2]+c[0]*c[2]*c[1], +c[2]*s[1]], [-c[0]*s[2]-s[0]*c[2]*c[1], -s[0]*s[2]+c[0]*c[2]*c[1], +c[2]*s[1]],
[+s[0]*s[1], -c[0]*s[1], +c[1] ]]) [+s[0]*s[1], -c[0]*s[1], +c[1] ]])
else:
om[np.where(iszero(om))] = 0.0 c = np.cos(eu)
s = np.sin(eu)
om = np.block([+c[...,0:1]*c[...,2:3]-s[...,0:1]*s[...,2:3]*c[...,1:2],
+s[...,0:1]*c[...,2:3]+c[...,0:1]*s[...,2:3]*c[...,1:2],
+s[...,2:3]*s[...,1:2],
-c[...,0:1]*s[...,2:3]-s[...,0:1]*c[...,2:3]*c[...,1:2],
-s[...,0:1]*s[...,2:3]+c[...,0:1]*c[...,2:3]*c[...,1:2],
+c[...,2:3]*s[...,1:2],
+s[...,0:1]*s[...,1:2],
-c[...,0:1]*s[...,1:2],
+c[...,1:2]
]).reshape(eu.shape[:-1]+(3,3))
om[np.abs(om)<1.e-12] = 0.0
return om return om
@staticmethod @staticmethod
def eu2ax(eu): def eu2ax(eu):
"""Bunge-Euler angles to axis angle pair.""" """Bunge-Euler angles to axis angle pair."""
if len(eu.shape) == 1:
t = np.tan(eu[1]*0.5) t = np.tan(eu[1]*0.5)
sigma = 0.5*(eu[0]+eu[2]) sigma = 0.5*(eu[0]+eu[2])
delta = 0.5*(eu[0]-eu[2]) delta = 0.5*(eu[0]-eu[2])
@ -617,24 +745,45 @@ class Rotation:
alpha = np.pi if iszero(np.cos(sigma)) else \ alpha = np.pi if iszero(np.cos(sigma)) else \
2.0*np.arctan(tau/np.cos(sigma)) 2.0*np.arctan(tau/np.cos(sigma))
if iszero(alpha): if np.abs(alpha)<1.e-6:
ax = np.array([ 0.0, 0.0, 1.0, 0.0 ]) ax = np.array([ 0.0, 0.0, 1.0, 0.0 ])
else: else:
ax = -P/tau * np.array([ t*np.cos(delta), t*np.sin(delta), np.sin(sigma) ]) # passive axis angle pair so a minus sign in front ax = -_P/tau * np.array([ t*np.cos(delta), t*np.sin(delta), np.sin(sigma) ]) # passive axis angle pair so a minus sign in front
ax = np.append(ax,alpha) ax = np.append(ax,alpha)
if alpha < 0.0: ax *= -1.0 # ensure alpha is positive if alpha < 0.0: ax *= -1.0 # ensure alpha is positive
else:
t = np.tan(eu[...,1:2]*0.5)
sigma = 0.5*(eu[...,0:1]+eu[...,2:3])
delta = 0.5*(eu[...,0:1]-eu[...,2:3])
tau = np.linalg.norm(np.block([t,np.sin(sigma)]),axis=-1,keepdims=True)
alpha = np.where(np.abs(np.cos(sigma))<1.e-12,np.pi,2.0*np.arctan(tau/np.cos(sigma)))
with np.errstate(invalid='ignore',divide='ignore'):
ax = np.where(np.broadcast_to(np.abs(alpha)<1.0e-12,eu.shape[:-1]+(4,)),
[0.0,0.0,1.0,0.0],
np.block([-_P/tau*t*np.cos(delta),
-_P/tau*t*np.sin(delta),
-_P/tau* np.sin(sigma),
alpha
]))
ax[(alpha<0.0).squeeze()] *=-1
return ax return ax
@staticmethod @staticmethod
def eu2ro(eu): def eu2ro(eu):
"""Bunge-Euler angles to Rodrigues-Frank vector.""" """Bunge-Euler angles to Rodrigues-Frank vector."""
if len(eu.shape) == 1:
ro = Rotation.eu2ax(eu) # convert to axis angle pair representation ro = Rotation.eu2ax(eu) # convert to axis angle pair representation
if ro[3] >= np.pi: # Differs from original implementation. check convention 5 if ro[3] >= np.pi: # Differs from original implementation. check convention 5
ro[3] = np.inf ro[3] = np.inf
elif iszero(ro[3]): elif iszero(ro[3]):
ro = np.array([ 0.0, 0.0, P, 0.0 ]) ro = np.array([ 0.0, 0.0, _P, 0.0 ])
else: else:
ro[3] = np.tan(ro[3]*0.5) ro[3] = np.tan(ro[3]*0.5)
else:
ax = Rotation.eu2ax(eu)
ro = np.block([ax[...,:3],np.tan(ax[...,3:4]*.5)])
ro[ax[...,3]>=np.pi,3] = np.inf
ro[np.abs(ax[...,3])<1.e-16] = [ 0.0, 0.0, _P, 0.0 ]
return ro return ro
@staticmethod @staticmethod
@ -652,17 +801,24 @@ class Rotation:
@staticmethod @staticmethod
def ax2qu(ax): def ax2qu(ax):
"""Axis angle pair to quaternion.""" """Axis angle pair to quaternion."""
if iszero(ax[3]): if len(ax.shape) == 1:
if np.abs(ax[3])<1.e-6:
qu = np.array([ 1.0, 0.0, 0.0, 0.0 ]) qu = np.array([ 1.0, 0.0, 0.0, 0.0 ])
else: else:
c = np.cos(ax[3]*0.5) c = np.cos(ax[3]*0.5)
s = np.sin(ax[3]*0.5) s = np.sin(ax[3]*0.5)
qu = np.array([ c, ax[0]*s, ax[1]*s, ax[2]*s ]) qu = np.array([ c, ax[0]*s, ax[1]*s, ax[2]*s ])
return qu return qu
else:
c = np.cos(ax[...,3:4]*.5)
s = np.sin(ax[...,3:4]*.5)
qu = np.where(np.abs(ax[...,3:4])<1.e-6,[1.0, 0.0, 0.0, 0.0],np.block([c, ax[...,:3]*s]))
return qu
@staticmethod @staticmethod
def ax2om(ax): def ax2om(ax):
"""Axis angle pair to rotation matrix.""" """Axis angle pair to rotation matrix."""
if len(ax.shape) == 1:
c = np.cos(ax[3]) c = np.cos(ax[3])
s = np.sin(ax[3]) s = np.sin(ax[3])
omc = 1.0-c omc = 1.0-c
@ -672,7 +828,20 @@ class Rotation:
q = omc*ax[idx[0]] * ax[idx[1]] q = omc*ax[idx[0]] * ax[idx[1]]
om[idx[0],idx[1]] = q + s*ax[idx[2]] om[idx[0],idx[1]] = q + s*ax[idx[2]]
om[idx[1],idx[0]] = q - s*ax[idx[2]] om[idx[1],idx[0]] = q - s*ax[idx[2]]
return om if P < 0.0 else om.T else:
c = np.cos(ax[...,3:4])
s = np.sin(ax[...,3:4])
omc = 1. -c
om = np.block([c+omc*ax[...,0:1]**2,
omc*ax[...,0:1]*ax[...,1:2] + s*ax[...,2:3],
omc*ax[...,0:1]*ax[...,2:3] - s*ax[...,1:2],
omc*ax[...,0:1]*ax[...,1:2] - s*ax[...,2:3],
c+omc*ax[...,1:2]**2,
omc*ax[...,1:2]*ax[...,2:3] + s*ax[...,0:1],
omc*ax[...,0:1]*ax[...,2:3] + s*ax[...,1:2],
omc*ax[...,1:2]*ax[...,2:3] - s*ax[...,0:1],
c+omc*ax[...,2:3]**2]).reshape(ax.shape[:-1]+(3,3))
return om if _P < 0.0 else np.swapaxes(om,(-1,-2))
@staticmethod @staticmethod
def ax2eu(ax): def ax2eu(ax):
@ -682,21 +851,35 @@ class Rotation:
@staticmethod @staticmethod
def ax2ro(ax): def ax2ro(ax):
"""Axis angle pair to Rodrigues-Frank vector.""" """Axis angle pair to Rodrigues-Frank vector."""
if iszero(ax[3]): if len(ax.shape) == 1:
ro = [ 0.0, 0.0, P, 0.0 ] if np.abs(ax[3])<1.e-6:
ro = [ 0.0, 0.0, _P, 0.0 ]
else: else:
ro = [ax[0], ax[1], ax[2]] ro = [ax[0], ax[1], ax[2]]
# 180 degree case # 180 degree case
ro += [np.inf] if np.isclose(ax[3],np.pi,atol=1.0e-15,rtol=0.0) else \ ro += [np.inf] if np.isclose(ax[3],np.pi,atol=1.0e-15,rtol=0.0) else \
[np.tan(ax[3]*0.5)] [np.tan(ax[3]*0.5)]
return np.array(ro) return np.array(ro)
else:
ro = np.block([ax[...,:3],
np.where(np.isclose(ax[...,3:4],np.pi,atol=1.e-15,rtol=.0),
np.inf,
np.tan(ax[...,3:4]*0.5))
])
ro[np.abs(ax[...,3])<1.e-6] = [.0,.0,_P,.0]
return ro
@staticmethod @staticmethod
def ax2ho(ax): def ax2ho(ax):
"""Axis angle pair to homochoric vector.""" """Axis angle pair to homochoric vector."""
if len(ax.shape) == 1:
f = (0.75 * ( ax[3] - np.sin(ax[3]) ))**(1.0/3.0) f = (0.75 * ( ax[3] - np.sin(ax[3]) ))**(1.0/3.0)
ho = ax[0:3] * f ho = ax[0:3] * f
return ho return ho
else:
f = (0.75 * ( ax[...,3:4] - np.sin(ax[...,3:4]) ))**(1.0/3.0)
ho = ax[...,:3] * f
return ho
@staticmethod @staticmethod
def ax2cu(ax): def ax2cu(ax):
@ -723,27 +906,38 @@ class Rotation:
@staticmethod @staticmethod
def ro2ax(ro): def ro2ax(ro):
"""Rodrigues-Frank vector to axis angle pair.""" """Rodrigues-Frank vector to axis angle pair."""
ta = ro[3] if len(ro.shape) == 1:
if np.abs(ro[3]) < 1.e-6:
if iszero(ta): ax = np.array([ 0.0, 0.0, 1.0, 0.0 ])
ax = [ 0.0, 0.0, 1.0, 0.0 ] elif not np.isfinite(ro[3]):
elif not np.isfinite(ta): ax = np.array([ ro[0], ro[1], ro[2], np.pi ])
ax = [ ro[0], ro[1], ro[2], np.pi ]
else: else:
angle = 2.0*np.arctan(ta) angle = 2.0*np.arctan(ro[3])
ta = 1.0/np.linalg.norm(ro[0:3]) ta = np.linalg.norm(ro[0:3])
ax = [ ro[0]/ta, ro[1]/ta, ro[2]/ta, angle ] ax = np.array([ ro[0]*ta, ro[1]*ta, ro[2]*ta, angle ])
return np.array(ax) else:
with np.errstate(invalid='ignore',divide='ignore'):
ax = np.where(np.isfinite(ro[...,3:4]),
np.block([ro[...,0:3]*np.linalg.norm(ro[...,0:3],axis=-1,keepdims=True),2.*np.arctan(ro[...,3:4])]),
np.block([ro[...,0:3],np.broadcast_to(np.pi,ro[...,3:4].shape)]))
ax[np.abs(ro[...,3]) < 1.e-6] = np.array([ 0.0, 0.0, 1.0, 0.0 ])
return ax
@staticmethod @staticmethod
def ro2ho(ro): def ro2ho(ro):
"""Rodrigues-Frank vector to homochoric vector.""" """Rodrigues-Frank vector to homochoric vector."""
if iszero(np.sum(ro[0:3]**2.0)): if len(ro.shape) == 1:
ho = [ 0.0, 0.0, 0.0 ] if np.sum(ro[0:3]**2.0) < 1.e-6:
ho = np.zeros(3)
else: else:
f = 2.0*np.arctan(ro[3]) -np.sin(2.0*np.arctan(ro[3])) if np.isfinite(ro[3]) else np.pi f = 2.0*np.arctan(ro[3]) -np.sin(2.0*np.arctan(ro[3])) if np.isfinite(ro[3]) else np.pi
ho = ro[0:3] * (0.75*f)**(1.0/3.0) ho = ro[0:3] * (0.75*f)**(1.0/3.0)
return np.array(ho) else:
f = np.where(np.isfinite(ro[...,3:4]),2.0*np.arctan(ro[...,3:4]) -np.sin(2.0*np.arctan(ro[...,3:4])),np.pi)
ho = np.where(np.broadcast_to(np.sum(ro[...,0:3]**2.0,axis=-1,keepdims=True) < 1.e-6,ro[...,0:3].shape),
np.zeros(3), ro[...,0:3]* (0.75*f)**(1.0/3.0))
return ho
@staticmethod @staticmethod
def ro2cu(ro): def ro2cu(ro):
@ -778,6 +972,7 @@ class Rotation:
+0.0001703481934140054, -0.00012062065004116828, +0.0001703481934140054, -0.00012062065004116828,
+0.000059719705868660826, -0.00001980756723965647, +0.000059719705868660826, -0.00001980756723965647,
+0.000003953714684212874, -0.00000036555001439719544]) +0.000003953714684212874, -0.00000036555001439719544])
if len(ho.shape) == 1:
# normalize h and store the magnitude # normalize h and store the magnitude
hmag_squared = np.sum(ho**2.) hmag_squared = np.sum(ho**2.)
if iszero(hmag_squared): if iszero(hmag_squared):
@ -791,6 +986,17 @@ class Rotation:
hm *= hmag_squared hm *= hmag_squared
s += tfit[i] * hm s += tfit[i] * hm
ax = np.append(ho/np.sqrt(hmag_squared),2.0*np.arccos(np.clip(s,-1.0,1.0))) ax = np.append(ho/np.sqrt(hmag_squared),2.0*np.arccos(np.clip(s,-1.0,1.0)))
else:
hmag_squared = np.sum(ho**2.,axis=-1,keepdims=True)
hm = hmag_squared.copy()
s = tfit[0] + tfit[1] * hmag_squared
for i in range(2,16):
hm *= hmag_squared
s += tfit[i] * hm
with np.errstate(invalid='ignore'):
ax = np.where(np.broadcast_to(np.abs(hmag_squared)<1.e-6,ho.shape[:-1]+(4,)),
[ 0.0, 0.0, 1.0, 0.0 ],
np.block([ho/np.sqrt(hmag_squared),2.0*np.arccos(np.clip(s,-1.0,1.0))]))
return ax return ax
@staticmethod @staticmethod
@ -801,7 +1007,10 @@ class Rotation:
@staticmethod @staticmethod
def ho2cu(ho): def ho2cu(ho):
"""Homochoric vector to cubochoric vector.""" """Homochoric vector to cubochoric vector."""
if len(ho.shape) == 1:
return ball_to_cube(ho) return ball_to_cube(ho)
else:
raise NotImplementedError
#---------- Cubochoric ---------- #---------- Cubochoric ----------
@ -833,4 +1042,7 @@ class Rotation:
@staticmethod @staticmethod
def cu2ho(cu): def cu2ho(cu):
"""Cubochoric vector to homochoric vector.""" """Cubochoric vector to homochoric vector."""
if len(cu.shape) == 1:
return cube_to_ball(cu) return cube_to_ball(cu)
else:
raise NotImplementedError

View File

@ -1,5 +1,5 @@
from scipy import spatial from scipy import spatial as _spatial
import numpy as np import numpy as _np
def _ks(size,grid,first_order=False): def _ks(size,grid,first_order=False):
""" """
@ -11,16 +11,16 @@ def _ks(size,grid,first_order=False):
physical size of the periodic field. physical size of the periodic field.
""" """
k_sk = np.where(np.arange(grid[0])>grid[0]//2,np.arange(grid[0])-grid[0],np.arange(grid[0]))/size[0] k_sk = _np.where(_np.arange(grid[0])>grid[0]//2,_np.arange(grid[0])-grid[0],_np.arange(grid[0]))/size[0]
if grid[0]%2 == 0 and first_order: k_sk[grid[0]//2] = 0 # Nyquist freq=0 for even grid (Johnson, MIT, 2011) if grid[0]%2 == 0 and first_order: k_sk[grid[0]//2] = 0 # Nyquist freq=0 for even grid (Johnson, MIT, 2011)
k_sj = np.where(np.arange(grid[1])>grid[1]//2,np.arange(grid[1])-grid[1],np.arange(grid[1]))/size[1] k_sj = _np.where(_np.arange(grid[1])>grid[1]//2,_np.arange(grid[1])-grid[1],_np.arange(grid[1]))/size[1]
if grid[1]%2 == 0 and first_order: k_sj[grid[1]//2] = 0 # Nyquist freq=0 for even grid (Johnson, MIT, 2011) if grid[1]%2 == 0 and first_order: k_sj[grid[1]//2] = 0 # Nyquist freq=0 for even grid (Johnson, MIT, 2011)
k_si = np.arange(grid[2]//2+1)/size[2] k_si = _np.arange(grid[2]//2+1)/size[2]
kk, kj, ki = np.meshgrid(k_sk,k_sj,k_si,indexing = 'ij') kk, kj, ki = _np.meshgrid(k_sk,k_sj,k_si,indexing = 'ij')
return np.concatenate((ki[:,:,:,None],kj[:,:,:,None],kk[:,:,:,None]),axis = 3) return _np.concatenate((ki[:,:,:,None],kj[:,:,:,None],kk[:,:,:,None]),axis = 3)
def curl(size,field): def curl(size,field):
@ -33,18 +33,18 @@ def curl(size,field):
physical size of the periodic field. physical size of the periodic field.
""" """
n = np.prod(field.shape[3:]) n = _np.prod(field.shape[3:])
k_s = _ks(size,field.shape[:3],True) k_s = _ks(size,field.shape[:3],True)
e = np.zeros((3, 3, 3)) e = _np.zeros((3, 3, 3))
e[0, 1, 2] = e[1, 2, 0] = e[2, 0, 1] = +1.0 # Levi-Civita symbol e[0, 1, 2] = e[1, 2, 0] = e[2, 0, 1] = +1.0 # Levi-Civita symbol
e[0, 2, 1] = e[2, 1, 0] = e[1, 0, 2] = -1.0 e[0, 2, 1] = e[2, 1, 0] = e[1, 0, 2] = -1.0
field_fourier = np.fft.rfftn(field,axes=(0,1,2)) field_fourier = _np.fft.rfftn(field,axes=(0,1,2))
curl_ = (np.einsum('slm,ijkl,ijkm ->ijks', e,k_s,field_fourier)*2.0j*np.pi if n == 3 else # vector, 3 -> 3 curl_ = (_np.einsum('slm,ijkl,ijkm ->ijks', e,k_s,field_fourier)*2.0j*_np.pi if n == 3 else # vector, 3 -> 3
np.einsum('slm,ijkl,ijknm->ijksn',e,k_s,field_fourier)*2.0j*np.pi) # tensor, 3x3 -> 3x3 _np.einsum('slm,ijkl,ijknm->ijksn',e,k_s,field_fourier)*2.0j*_np.pi) # tensor, 3x3 -> 3x3
return np.fft.irfftn(curl_,axes=(0,1,2),s=field.shape[:3]) return _np.fft.irfftn(curl_,axes=(0,1,2),s=field.shape[:3])
def divergence(size,field): def divergence(size,field):
@ -57,14 +57,14 @@ def divergence(size,field):
physical size of the periodic field. physical size of the periodic field.
""" """
n = np.prod(field.shape[3:]) n = _np.prod(field.shape[3:])
k_s = _ks(size,field.shape[:3],True) k_s = _ks(size,field.shape[:3],True)
field_fourier = np.fft.rfftn(field,axes=(0,1,2)) field_fourier = _np.fft.rfftn(field,axes=(0,1,2))
div_ = (np.einsum('ijkl,ijkl ->ijk', k_s,field_fourier)*2.0j*np.pi if n == 3 else # vector, 3 -> 1 div_ = (_np.einsum('ijkl,ijkl ->ijk', k_s,field_fourier)*2.0j*_np.pi if n == 3 else # vector, 3 -> 1
np.einsum('ijkm,ijklm->ijkl',k_s,field_fourier)*2.0j*np.pi) # tensor, 3x3 -> 3 _np.einsum('ijkm,ijklm->ijkl',k_s,field_fourier)*2.0j*_np.pi) # tensor, 3x3 -> 3
return np.fft.irfftn(div_,axes=(0,1,2),s=field.shape[:3]) return _np.fft.irfftn(div_,axes=(0,1,2),s=field.shape[:3])
def gradient(size,field): def gradient(size,field):
@ -77,17 +77,17 @@ def gradient(size,field):
physical size of the periodic field. physical size of the periodic field.
""" """
n = np.prod(field.shape[3:]) n = _np.prod(field.shape[3:])
k_s = _ks(size,field.shape[:3],True) k_s = _ks(size,field.shape[:3],True)
field_fourier = np.fft.rfftn(field,axes=(0,1,2)) field_fourier = _np.fft.rfftn(field,axes=(0,1,2))
grad_ = (np.einsum('ijkl,ijkm->ijkm', field_fourier,k_s)*2.0j*np.pi if n == 1 else # scalar, 1 -> 3 grad_ = (_np.einsum('ijkl,ijkm->ijkm', field_fourier,k_s)*2.0j*_np.pi if n == 1 else # scalar, 1 -> 3
np.einsum('ijkl,ijkm->ijklm',field_fourier,k_s)*2.0j*np.pi) # vector, 3 -> 3x3 _np.einsum('ijkl,ijkm->ijklm',field_fourier,k_s)*2.0j*_np.pi) # vector, 3 -> 3x3
return np.fft.irfftn(grad_,axes=(0,1,2),s=field.shape[:3]) return _np.fft.irfftn(grad_,axes=(0,1,2),s=field.shape[:3])
def cell_coord0(grid,size,origin=np.zeros(3)): def cell_coord0(grid,size,origin=_np.zeros(3)):
""" """
Cell center positions (undeformed). Cell center positions (undeformed).
@ -103,7 +103,7 @@ def cell_coord0(grid,size,origin=np.zeros(3)):
""" """
start = origin + size/grid*.5 start = origin + size/grid*.5
end = origin + size - size/grid*.5 end = origin + size - size/grid*.5
return np.mgrid[start[0]:end[0]:grid[0]*1j,start[1]:end[1]:grid[1]*1j,start[2]:end[2]:grid[2]*1j].T return _np.mgrid[start[0]:end[0]:grid[0]*1j,start[1]:end[1]:grid[1]*1j,start[2]:end[2]:grid[2]*1j].T
def cell_displacement_fluct(size,F): def cell_displacement_fluct(size,F):
@ -118,19 +118,19 @@ def cell_displacement_fluct(size,F):
deformation gradient field. deformation gradient field.
""" """
integrator = 0.5j*size/np.pi integrator = 0.5j*size/_np.pi
k_s = _ks(size,F.shape[:3],False) k_s = _ks(size,F.shape[:3],False)
k_s_squared = np.einsum('...l,...l',k_s,k_s) k_s_squared = _np.einsum('...l,...l',k_s,k_s)
k_s_squared[0,0,0] = 1.0 k_s_squared[0,0,0] = 1.0
displacement = -np.einsum('ijkml,ijkl,l->ijkm', displacement = -_np.einsum('ijkml,ijkl,l->ijkm',
np.fft.rfftn(F,axes=(0,1,2)), _np.fft.rfftn(F,axes=(0,1,2)),
k_s, k_s,
integrator, integrator,
) / k_s_squared[...,np.newaxis] ) / k_s_squared[...,_np.newaxis]
return np.fft.irfftn(displacement,axes=(0,1,2),s=F.shape[:3]) return _np.fft.irfftn(displacement,axes=(0,1,2),s=F.shape[:3])
def cell_displacement_avg(size,F): def cell_displacement_avg(size,F):
@ -145,8 +145,8 @@ def cell_displacement_avg(size,F):
deformation gradient field. deformation gradient field.
""" """
F_avg = np.average(F,axis=(0,1,2)) F_avg = _np.average(F,axis=(0,1,2))
return np.einsum('ml,ijkl->ijkm',F_avg-np.eye(3),cell_coord0(F.shape[:3][::-1],size)) return _np.einsum('ml,ijkl->ijkm',F_avg-_np.eye(3),cell_coord0(F.shape[:3][::-1],size))
def cell_displacement(size,F): def cell_displacement(size,F):
@ -164,7 +164,7 @@ def cell_displacement(size,F):
return cell_displacement_avg(size,F) + cell_displacement_fluct(size,F) return cell_displacement_avg(size,F) + cell_displacement_fluct(size,F)
def cell_coord(size,F,origin=np.zeros(3)): def cell_coord(size,F,origin=_np.zeros(3)):
""" """
Cell center positions. Cell center positions.
@ -193,17 +193,17 @@ def cell_coord0_gridSizeOrigin(coord0,ordered=True):
expect coord0 data to be ordered (x fast, z slow). expect coord0 data to be ordered (x fast, z slow).
""" """
coords = [np.unique(coord0[:,i]) for i in range(3)] coords = [_np.unique(coord0[:,i]) for i in range(3)]
mincorner = np.array(list(map(min,coords))) mincorner = _np.array(list(map(min,coords)))
maxcorner = np.array(list(map(max,coords))) maxcorner = _np.array(list(map(max,coords)))
grid = np.array(list(map(len,coords)),'i') grid = _np.array(list(map(len,coords)),'i')
size = grid/np.maximum(grid-1,1) * (maxcorner-mincorner) size = grid/_np.maximum(grid-1,1) * (maxcorner-mincorner)
delta = size/grid delta = size/grid
origin = mincorner - delta*.5 origin = mincorner - delta*.5
# 1D/2D: size/origin combination undefined, set origin to 0.0 # 1D/2D: size/origin combination undefined, set origin to 0.0
size [np.where(grid==1)] = origin[np.where(grid==1)]*2. size [_np.where(grid==1)] = origin[_np.where(grid==1)]*2.
origin[np.where(grid==1)] = 0.0 origin[_np.where(grid==1)] = 0.0
if grid.prod() != len(coord0): if grid.prod() != len(coord0):
raise ValueError('Data count {} does not match grid {}.'.format(len(coord0),grid)) raise ValueError('Data count {} does not match grid {}.'.format(len(coord0),grid))
@ -211,13 +211,13 @@ def cell_coord0_gridSizeOrigin(coord0,ordered=True):
start = origin + delta*.5 start = origin + delta*.5
end = origin - delta*.5 + size end = origin - delta*.5 + size
if not np.allclose(coords[0],np.linspace(start[0],end[0],grid[0])) and \ if not _np.allclose(coords[0],_np.linspace(start[0],end[0],grid[0])) and \
np.allclose(coords[1],np.linspace(start[1],end[1],grid[1])) and \ _np.allclose(coords[1],_np.linspace(start[1],end[1],grid[1])) and \
np.allclose(coords[2],np.linspace(start[2],end[2],grid[2])): _np.allclose(coords[2],_np.linspace(start[2],end[2],grid[2])):
raise ValueError('Regular grid spacing violated.') raise ValueError('Regular grid spacing violated.')
if ordered and not np.allclose(coord0.reshape(tuple(grid[::-1])+(3,)),cell_coord0(grid,size,origin)): if ordered and not _np.allclose(coord0.reshape(tuple(grid[::-1])+(3,)),cell_coord0(grid,size,origin)):
raise ValueError('Input data is not a regular grid.') raise ValueError('I_nput data is not a regular grid.')
return (grid,size,origin) return (grid,size,origin)
@ -235,7 +235,7 @@ def coord0_check(coord0):
cell_coord0_gridSizeOrigin(coord0,ordered=True) cell_coord0_gridSizeOrigin(coord0,ordered=True)
def node_coord0(grid,size,origin=np.zeros(3)): def node_coord0(grid,size,origin=_np.zeros(3)):
""" """
Nodal positions (undeformed). Nodal positions (undeformed).
@ -249,7 +249,7 @@ def node_coord0(grid,size,origin=np.zeros(3)):
physical origin of the periodic field. Defaults to [0.0,0.0,0.0]. physical origin of the periodic field. Defaults to [0.0,0.0,0.0].
""" """
return np.mgrid[origin[0]:size[0]+origin[0]:(grid[0]+1)*1j, return _np.mgrid[origin[0]:size[0]+origin[0]:(grid[0]+1)*1j,
origin[1]:size[1]+origin[1]:(grid[1]+1)*1j, origin[1]:size[1]+origin[1]:(grid[1]+1)*1j,
origin[2]:size[2]+origin[2]:(grid[2]+1)*1j].T origin[2]:size[2]+origin[2]:(grid[2]+1)*1j].T
@ -281,8 +281,8 @@ def node_displacement_avg(size,F):
deformation gradient field. deformation gradient field.
""" """
F_avg = np.average(F,axis=(0,1,2)) F_avg = _np.average(F,axis=(0,1,2))
return np.einsum('ml,ijkl->ijkm',F_avg-np.eye(3),node_coord0(F.shape[:3][::-1],size)) return _np.einsum('ml,ijkl->ijkm',F_avg-_np.eye(3),node_coord0(F.shape[:3][::-1],size))
def node_displacement(size,F): def node_displacement(size,F):
@ -300,7 +300,7 @@ def node_displacement(size,F):
return node_displacement_avg(size,F) + node_displacement_fluct(size,F) return node_displacement_avg(size,F) + node_displacement_fluct(size,F)
def node_coord(size,F,origin=np.zeros(3)): def node_coord(size,F,origin=_np.zeros(3)):
""" """
Nodal positions. Nodal positions.
@ -319,18 +319,18 @@ def node_coord(size,F,origin=np.zeros(3)):
def cell_2_node(cell_data): def cell_2_node(cell_data):
"""Interpolate periodic cell data to nodal data.""" """Interpolate periodic cell data to nodal data."""
n = ( cell_data + np.roll(cell_data,1,(0,1,2)) n = ( cell_data + _np.roll(cell_data,1,(0,1,2))
+ np.roll(cell_data,1,(0,)) + np.roll(cell_data,1,(1,)) + np.roll(cell_data,1,(2,)) + _np.roll(cell_data,1,(0,)) + _np.roll(cell_data,1,(1,)) + _np.roll(cell_data,1,(2,))
+ np.roll(cell_data,1,(0,1)) + np.roll(cell_data,1,(1,2)) + np.roll(cell_data,1,(2,0)))*0.125 + _np.roll(cell_data,1,(0,1)) + _np.roll(cell_data,1,(1,2)) + _np.roll(cell_data,1,(2,0)))*0.125
return np.pad(n,((0,1),(0,1),(0,1))+((0,0),)*len(cell_data.shape[3:]),mode='wrap') return _np.pad(n,((0,1),(0,1),(0,1))+((0,0),)*len(cell_data.shape[3:]),mode='wrap')
def node_2_cell(node_data): def node_2_cell(node_data):
"""Interpolate periodic nodal data to cell data.""" """Interpolate periodic nodal data to cell data."""
c = ( node_data + np.roll(node_data,1,(0,1,2)) c = ( node_data + _np.roll(node_data,1,(0,1,2))
+ np.roll(node_data,1,(0,)) + np.roll(node_data,1,(1,)) + np.roll(node_data,1,(2,)) + _np.roll(node_data,1,(0,)) + _np.roll(node_data,1,(1,)) + _np.roll(node_data,1,(2,))
+ np.roll(node_data,1,(0,1)) + np.roll(node_data,1,(1,2)) + np.roll(node_data,1,(2,0)))*0.125 + _np.roll(node_data,1,(0,1)) + _np.roll(node_data,1,(1,2)) + _np.roll(node_data,1,(2,0)))*0.125
return c[:-1,:-1,:-1] return c[:-1,:-1,:-1]
@ -347,23 +347,23 @@ def node_coord0_gridSizeOrigin(coord0,ordered=False):
expect coord0 data to be ordered (x fast, z slow). expect coord0 data to be ordered (x fast, z slow).
""" """
coords = [np.unique(coord0[:,i]) for i in range(3)] coords = [_np.unique(coord0[:,i]) for i in range(3)]
mincorner = np.array(list(map(min,coords))) mincorner = _np.array(list(map(min,coords)))
maxcorner = np.array(list(map(max,coords))) maxcorner = _np.array(list(map(max,coords)))
grid = np.array(list(map(len,coords)),'i') - 1 grid = _np.array(list(map(len,coords)),'i') - 1
size = maxcorner-mincorner size = maxcorner-mincorner
origin = mincorner origin = mincorner
if (grid+1).prod() != len(coord0): if (grid+1).prod() != len(coord0):
raise ValueError('Data count {} does not match grid {}.'.format(len(coord0),grid)) raise ValueError('Data count {} does not match grid {}.'.format(len(coord0),grid))
if not np.allclose(coords[0],np.linspace(mincorner[0],maxcorner[0],grid[0]+1)) and \ if not _np.allclose(coords[0],_np.linspace(mincorner[0],maxcorner[0],grid[0]+1)) and \
np.allclose(coords[1],np.linspace(mincorner[1],maxcorner[1],grid[1]+1)) and \ _np.allclose(coords[1],_np.linspace(mincorner[1],maxcorner[1],grid[1]+1)) and \
np.allclose(coords[2],np.linspace(mincorner[2],maxcorner[2],grid[2]+1)): _np.allclose(coords[2],_np.linspace(mincorner[2],maxcorner[2],grid[2]+1)):
raise ValueError('Regular grid spacing violated.') raise ValueError('Regular grid spacing violated.')
if ordered and not np.allclose(coord0.reshape(tuple((grid+1)[::-1])+(3,)),node_coord0(grid,size,origin)): if ordered and not _np.allclose(coord0.reshape(tuple((grid+1)[::-1])+(3,)),node_coord0(grid,size,origin)):
raise ValueError('Input data is not a regular grid.') raise ValueError('I_nput data is not a regular grid.')
return (grid,size,origin) return (grid,size,origin)
@ -386,10 +386,10 @@ def regrid(size,F,new_grid):
+ cell_displacement_avg(size,F) \ + cell_displacement_avg(size,F) \
+ cell_displacement_fluct(size,F) + cell_displacement_fluct(size,F)
outer = np.dot(np.average(F,axis=(0,1,2)),size) outer = _np.dot(_np.average(F,axis=(0,1,2)),size)
for d in range(3): for d in range(3):
c[np.where(c[:,:,:,d]<0)] += outer[d] c[_np.where(c[:,:,:,d]<0)] += outer[d]
c[np.where(c[:,:,:,d]>outer[d])] -= outer[d] c[_np.where(c[:,:,:,d]>outer[d])] -= outer[d]
tree = spatial.cKDTree(c.reshape(-1,3),boxsize=outer) tree = _spatial.cKDTree(c.reshape(-1,3),boxsize=outer)
return tree.query(cell_coord0(new_grid,outer))[1].flatten() return tree.query(cell_coord0(new_grid,outer))[1].flatten()

View File

@ -1,4 +1,4 @@
import numpy as np import numpy as _np
def Cauchy(P,F): def Cauchy(P,F):
""" """
@ -14,10 +14,10 @@ def Cauchy(P,F):
First Piola-Kirchhoff stress. First Piola-Kirchhoff stress.
""" """
if np.shape(F) == np.shape(P) == (3,3): if _np.shape(F) == _np.shape(P) == (3,3):
sigma = 1.0/np.linalg.det(F) * np.dot(P,F.T) sigma = 1.0/_np.linalg.det(F) * _np.dot(P,F.T)
else: else:
sigma = np.einsum('i,ijk,ilk->ijl',1.0/np.linalg.det(F),P,F) sigma = _np.einsum('i,ijk,ilk->ijl',1.0/_np.linalg.det(F),P,F)
return symmetric(sigma) return symmetric(sigma)
@ -31,8 +31,8 @@ def deviatoric_part(T):
Tensor of which the deviatoric part is computed. Tensor of which the deviatoric part is computed.
""" """
return T - np.eye(3)*spherical_part(T) if np.shape(T) == (3,3) else \ return T - _np.eye(3)*spherical_part(T) if _np.shape(T) == (3,3) else \
T - np.einsum('ijk,i->ijk',np.broadcast_to(np.eye(3),[T.shape[0],3,3]),spherical_part(T)) T - _np.einsum('ijk,i->ijk',_np.broadcast_to(_np.eye(3),[T.shape[0],3,3]),spherical_part(T))
def eigenvalues(T_sym): def eigenvalues(T_sym):
@ -48,7 +48,7 @@ def eigenvalues(T_sym):
Symmetric tensor of which the eigenvalues are computed. Symmetric tensor of which the eigenvalues are computed.
""" """
return np.linalg.eigvalsh(symmetric(T_sym)) return _np.linalg.eigvalsh(symmetric(T_sym))
def eigenvectors(T_sym,RHS=False): def eigenvectors(T_sym,RHS=False):
@ -65,13 +65,13 @@ def eigenvectors(T_sym,RHS=False):
Enforce right-handed coordinate system. Default is False. Enforce right-handed coordinate system. Default is False.
""" """
(u,v) = np.linalg.eigh(symmetric(T_sym)) (u,v) = _np.linalg.eigh(symmetric(T_sym))
if RHS: if RHS:
if np.shape(T_sym) == (3,3): if _np.shape(T_sym) == (3,3):
if np.linalg.det(v) < 0.0: v[:,2] *= -1.0 if _np.linalg.det(v) < 0.0: v[:,2] *= -1.0
else: else:
v[np.linalg.det(v) < 0.0,:,2] *= -1.0 v[_np.linalg.det(v) < 0.0,:,2] *= -1.0
return v return v
@ -99,7 +99,7 @@ def maximum_shear(T_sym):
""" """
w = eigenvalues(T_sym) w = eigenvalues(T_sym)
return (w[0] - w[2])*0.5 if np.shape(T_sym) == (3,3) else \ return (w[0] - w[2])*0.5 if _np.shape(T_sym) == (3,3) else \
(w[:,0] - w[:,2])*0.5 (w[:,0] - w[:,2])*0.5
@ -141,10 +141,10 @@ def PK2(P,F):
Deformation gradient. Deformation gradient.
""" """
if np.shape(F) == np.shape(P) == (3,3): if _np.shape(F) == _np.shape(P) == (3,3):
S = np.dot(np.linalg.inv(F),P) S = _np.dot(_np.linalg.inv(F),P)
else: else:
S = np.einsum('ijk,ikl->ijl',np.linalg.inv(F),P) S = _np.einsum('ijk,ikl->ijl',_np.linalg.inv(F),P)
return symmetric(S) return symmetric(S)
@ -187,14 +187,14 @@ def spherical_part(T,tensor=False):
""" """
if T.shape == (3,3): if T.shape == (3,3):
sph = np.trace(T)/3.0 sph = _np.trace(T)/3.0
return sph if not tensor else np.eye(3)*sph return sph if not tensor else _np.eye(3)*sph
else: else:
sph = np.trace(T,axis1=1,axis2=2)/3.0 sph = _np.trace(T,axis1=1,axis2=2)/3.0
if not tensor: if not tensor:
return sph return sph
else: else:
return np.einsum('ijk,i->ijk',np.broadcast_to(np.eye(3),(T.shape[0],3,3)),sph) return _np.einsum('ijk,i->ijk',_np.broadcast_to(_np.eye(3),(T.shape[0],3,3)),sph)
def strain_tensor(F,t,m): def strain_tensor(F,t,m):
@ -216,22 +216,22 @@ def strain_tensor(F,t,m):
""" """
F_ = F.reshape(1,3,3) if F.shape == (3,3) else F F_ = F.reshape(1,3,3) if F.shape == (3,3) else F
if t == 'V': if t == 'V':
B = np.matmul(F_,transpose(F_)) B = _np.matmul(F_,transpose(F_))
w,n = np.linalg.eigh(B) w,n = _np.linalg.eigh(B)
elif t == 'U': elif t == 'U':
C = np.matmul(transpose(F_),F_) C = _np.matmul(transpose(F_),F_)
w,n = np.linalg.eigh(C) w,n = _np.linalg.eigh(C)
if m > 0.0: if m > 0.0:
eps = 1.0/(2.0*abs(m)) * (+ np.matmul(n,np.einsum('ij,ikj->ijk',w**m,n)) eps = 1.0/(2.0*abs(m)) * (+ _np.matmul(n,_np.einsum('ij,ikj->ijk',w**m,n))
- np.broadcast_to(np.eye(3),[F_.shape[0],3,3])) - _np.broadcast_to(_np.eye(3),[F_.shape[0],3,3]))
elif m < 0.0: elif m < 0.0:
eps = 1.0/(2.0*abs(m)) * (- np.matmul(n,np.einsum('ij,ikj->ijk',w**m,n)) eps = 1.0/(2.0*abs(m)) * (- _np.matmul(n,_np.einsum('ij,ikj->ijk',w**m,n))
+ np.broadcast_to(np.eye(3),[F_.shape[0],3,3])) + _np.broadcast_to(_np.eye(3),[F_.shape[0],3,3]))
else: else:
eps = np.matmul(n,np.einsum('ij,ikj->ijk',0.5*np.log(w),n)) eps = _np.matmul(n,_np.einsum('ij,ikj->ijk',0.5*_np.log(w),n))
return eps.reshape(3,3) if np.shape(F) == (3,3) else \ return eps.reshape(3,3) if _np.shape(F) == (3,3) else \
eps eps
@ -258,8 +258,8 @@ def transpose(T):
Tensor of which the transpose is computed. Tensor of which the transpose is computed.
""" """
return T.T if np.shape(T) == (3,3) else \ return T.T if _np.shape(T) == (3,3) else \
np.transpose(T,(0,2,1)) _np.transpose(T,(0,2,1))
def _polar_decomposition(T,requested): def _polar_decomposition(T,requested):
@ -275,17 +275,17 @@ def _polar_decomposition(T,requested):
V for left stretch tensor and U for right stretch tensor. V for left stretch tensor and U for right stretch tensor.
""" """
u, s, vh = np.linalg.svd(T) u, s, vh = _np.linalg.svd(T)
R = np.dot(u,vh) if np.shape(T) == (3,3) else \ R = _np.dot(u,vh) if _np.shape(T) == (3,3) else \
np.einsum('ijk,ikl->ijl',u,vh) _np.einsum('ijk,ikl->ijl',u,vh)
output = [] output = []
if 'R' in requested: if 'R' in requested:
output.append(R) output.append(R)
if 'V' in requested: if 'V' in requested:
output.append(np.dot(T,R.T) if np.shape(T) == (3,3) else np.einsum('ijk,ilk->ijl',T,R)) output.append(_np.dot(T,R.T) if _np.shape(T) == (3,3) else _np.einsum('ijk,ilk->ijl',T,R))
if 'U' in requested: if 'U' in requested:
output.append(np.dot(R.T,T) if np.shape(T) == (3,3) else np.einsum('ikj,ikl->ijl',R,T)) output.append(_np.dot(R.T,T) if _np.shape(T) == (3,3) else _np.einsum('ikj,ikl->ijl',R,T))
return tuple(output) return tuple(output)
@ -303,5 +303,5 @@ def _Mises(T_sym,s):
""" """
d = deviatoric_part(T_sym) d = deviatoric_part(T_sym)
return np.sqrt(s*(np.sum(d**2.0))) if np.shape(T_sym) == (3,3) else \ return _np.sqrt(s*(_np.sum(d**2.0))) if _np.shape(T_sym) == (3,3) else \
np.sqrt(s*np.einsum('ijk->i',d**2.0)) _np.sqrt(s*_np.einsum('ijk->i',d**2.0))

View File

@ -9,37 +9,22 @@ from optparse import Option
import numpy as np import numpy as np
class bcolors: # limit visibility
""" __all__=[
ASCII Colors. 'srepr',
'croak',
https://svn.blender.org/svnroot/bf-blender/trunk/blender/build_files/scons/tools/bcolors.py 'report',
https://stackoverflow.com/questions/287871 'emph','deemph','delete','strikeout',
""" 'execute',
'show_progress',
HEADER = '\033[95m' 'scale_to_coprime',
OKBLUE = '\033[94m' 'return_message',
OKGREEN = '\033[92m' 'extendableOption',
WARNING = '\033[93m' ]
FAIL = '\033[91m'
ENDC = '\033[0m'
BOLD = '\033[1m'
DIM = '\033[2m'
UNDERLINE = '\033[4m'
CROSSOUT = '\033[9m'
def disable(self):
self.HEADER = ''
self.OKBLUE = ''
self.OKGREEN = ''
self.WARNING = ''
self.FAIL = ''
self.ENDC = ''
self.BOLD = ''
self.UNDERLINE = ''
self.CROSSOUT = ''
####################################################################################################
# Functions
####################################################################################################
def srepr(arg,glue = '\n'): def srepr(arg,glue = '\n'):
r""" r"""
Join arguments as individual lines. Join arguments as individual lines.
@ -144,6 +129,52 @@ def execute(cmd,
return out,error return out,error
def show_progress(iterable,N_iter=None,prefix='',bar_length=50):
"""
Decorate a loop with a status bar.
Use similar like enumerate.
Parameters
----------
iterable : iterable/function with yield statement
Iterable (or function with yield statement) to be decorated.
N_iter : int
Total # of iterations. Needed if number of iterations can not be obtained as len(iterable).
prefix : str, optional.
Prefix string.
bar_length : int, optional
Character length of bar. Defaults to 50.
"""
status = _ProgressBar(N_iter if N_iter else len(iterable),prefix,bar_length)
for i,item in enumerate(iterable):
yield item
status.update(i)
def scale_to_coprime(v):
"""Scale vector to co-prime (relatively prime) integers."""
MAX_DENOMINATOR = 1000
def get_square_denominator(x):
"""Denominator of the square of a number."""
return fractions.Fraction(x ** 2).limit_denominator(MAX_DENOMINATOR).denominator
def lcm(a, b):
"""Least common multiple."""
return a * b // np.gcd(a, b)
denominators = [int(get_square_denominator(i)) for i in v]
s = reduce(lcm, denominators) ** 0.5
m = (np.array(v)*s).astype(np.int)
return m//reduce(np.gcd,m)
####################################################################################################
# Classes
####################################################################################################
class extendableOption(Option): class extendableOption(Option):
""" """
Used for definition of new option parser action 'extend', which enables to take multiple option arguments. Used for definition of new option parser action 'extend', which enables to take multiple option arguments.
@ -215,47 +246,36 @@ class _ProgressBar:
sys.stderr.write('\n') sys.stderr.write('\n')
sys.stderr.flush() sys.stderr.flush()
def show_progress(iterable,N_iter=None,prefix='',bar_length=50):
class bcolors:
""" """
Decorate a loop with a status bar. ASCII Colors.
Use similar like enumerate.
Parameters
----------
iterable : iterable/function with yield statement
Iterable (or function with yield statement) to be decorated.
N_iter : int
Total # of iterations. Needed if number of iterations can not be obtained as len(iterable).
prefix : str, optional.
Prefix string.
bar_length : int, optional
Character length of bar. Defaults to 50.
https://svn.blender.org/svnroot/bf-blender/trunk/blender/build_files/scons/tools/bcolors.py
https://stackoverflow.com/questions/287871
""" """
status = _ProgressBar(N_iter if N_iter else len(iterable),prefix,bar_length)
for i,item in enumerate(iterable): HEADER = '\033[95m'
yield item OKBLUE = '\033[94m'
status.update(i) OKGREEN = '\033[92m'
WARNING = '\033[93m'
FAIL = '\033[91m'
ENDC = '\033[0m'
BOLD = '\033[1m'
DIM = '\033[2m'
UNDERLINE = '\033[4m'
CROSSOUT = '\033[9m'
def disable(self):
def scale_to_coprime(v): self.HEADER = ''
"""Scale vector to co-prime (relatively prime) integers.""" self.OKBLUE = ''
MAX_DENOMINATOR = 1000 self.OKGREEN = ''
self.WARNING = ''
def get_square_denominator(x): self.FAIL = ''
"""Denominator of the square of a number.""" self.ENDC = ''
return fractions.Fraction(x ** 2).limit_denominator(MAX_DENOMINATOR).denominator self.BOLD = ''
self.UNDERLINE = ''
def lcm(a, b): self.CROSSOUT = ''
"""Least common multiple."""
return a * b // np.gcd(a, b)
denominators = [int(get_square_denominator(i)) for i in v]
s = reduce(lcm, denominators) ** 0.5
m = (np.array(v)*s).astype(np.int)
return m//reduce(np.gcd,m)
class return_message: class return_message:
@ -276,4 +296,3 @@ class return_message:
def __repr__(self): def __repr__(self):
"""Return message suitable for interactive shells.""" """Return message suitable for interactive shells."""
return srepr(self.message) return srepr(self.message)

View File

@ -5,12 +5,82 @@ import numpy as np
from damask import Rotation from damask import Rotation
n = 1000 n = 1100
atol=1.e-4
scatter=1.e-2
@pytest.fixture @pytest.fixture
def default(): def default():
"""A set of n random rotations.""" """A set of n random rotations."""
return [Rotation.fromRandom() for r in range(n)] specials = np.array(
[np.array([ 1.0, 0.0, 0.0, 0.0]),
#-----------------------------------------------
np.array([0.0, 1.0, 0.0, 0.0]),
np.array([0.0, 0.0, 1.0, 0.0]),
np.array([0.0, 0.0, 0.0, 1.0]),
np.array([0.0,-1.0, 0.0, 0.0]),
np.array([0.0, 0.0,-1.0, 0.0]),
np.array([0.0, 0.0, 0.0,-1.0]),
#-----------------------------------------------
np.array([1.0, 1.0, 0.0, 0.0])/np.sqrt(2.),
np.array([1.0, 0.0, 1.0, 0.0])/np.sqrt(2.),
np.array([1.0, 0.0, 0.0, 1.0])/np.sqrt(2.),
np.array([0.0, 1.0, 1.0, 0.0])/np.sqrt(2.),
np.array([0.0, 1.0, 0.0, 1.0])/np.sqrt(2.),
np.array([0.0, 0.0, 1.0, 1.0])/np.sqrt(2.),
#-----------------------------------------------
np.array([1.0,-1.0, 0.0, 0.0])/np.sqrt(2.),
np.array([1.0, 0.0,-1.0, 0.0])/np.sqrt(2.),
np.array([1.0, 0.0, 0.0,-1.0])/np.sqrt(2.),
np.array([0.0, 1.0,-1.0, 0.0])/np.sqrt(2.),
np.array([0.0, 1.0, 0.0,-1.0])/np.sqrt(2.),
np.array([0.0, 0.0, 1.0,-1.0])/np.sqrt(2.),
#-----------------------------------------------
np.array([0.0, 1.0,-1.0, 0.0])/np.sqrt(2.),
np.array([0.0, 1.0, 0.0,-1.0])/np.sqrt(2.),
np.array([0.0, 0.0, 1.0,-1.0])/np.sqrt(2.),
#-----------------------------------------------
np.array([0.0,-1.0,-1.0, 0.0])/np.sqrt(2.),
np.array([0.0,-1.0, 0.0,-1.0])/np.sqrt(2.),
np.array([0.0, 0.0,-1.0,-1.0])/np.sqrt(2.),
#-----------------------------------------------
np.array([1.0, 1.0, 1.0, 0.0])/np.sqrt(3.),
np.array([1.0, 1.0, 0.0, 1.0])/np.sqrt(3.),
np.array([1.0, 0.0, 1.0, 1.0])/np.sqrt(3.),
np.array([1.0,-1.0, 1.0, 0.0])/np.sqrt(3.),
np.array([1.0,-1.0, 0.0, 1.0])/np.sqrt(3.),
np.array([1.0, 0.0,-1.0, 1.0])/np.sqrt(3.),
np.array([1.0, 1.0,-1.0, 0.0])/np.sqrt(3.),
np.array([1.0, 1.0, 0.0,-1.0])/np.sqrt(3.),
np.array([1.0, 0.0, 1.0,-1.0])/np.sqrt(3.),
np.array([1.0,-1.0,-1.0, 0.0])/np.sqrt(3.),
np.array([1.0,-1.0, 0.0,-1.0])/np.sqrt(3.),
np.array([1.0, 0.0,-1.0,-1.0])/np.sqrt(3.),
#-----------------------------------------------
np.array([0.0, 1.0, 1.0, 1.0])/np.sqrt(3.),
np.array([0.0, 1.0,-1.0, 1.0])/np.sqrt(3.),
np.array([0.0, 1.0, 1.0,-1.0])/np.sqrt(3.),
np.array([0.0,-1.0, 1.0, 1.0])/np.sqrt(3.),
np.array([0.0,-1.0,-1.0, 1.0])/np.sqrt(3.),
np.array([0.0,-1.0, 1.0,-1.0])/np.sqrt(3.),
np.array([0.0,-1.0,-1.0,-1.0])/np.sqrt(3.),
#-----------------------------------------------
np.array([1.0, 1.0, 1.0, 1.0])/2.,
np.array([1.0,-1.0, 1.0, 1.0])/2.,
np.array([1.0, 1.0,-1.0, 1.0])/2.,
np.array([1.0, 1.0, 1.0,-1.0])/2.,
np.array([1.0,-1.0,-1.0, 1.0])/2.,
np.array([1.0,-1.0, 1.0,-1.0])/2.,
np.array([1.0, 1.0,-1.0,-1.0])/2.,
np.array([1.0,-1.0,-1.0,-1.0])/2.,
])
specials_scatter = specials + np.broadcast_to(np.random.rand(4)*scatter,specials.shape)
specials_scatter /= np.linalg.norm(specials_scatter,axis=1).reshape(-1,1)
specials_scatter[specials_scatter[:,0]<0]*=-1
return [Rotation.fromQuaternion(s) for s in specials] + \
[Rotation.fromQuaternion(s) for s in specials_scatter] + \
[Rotation.fromRandom() for _ in range(n-len(specials)-len(specials_scatter))]
@pytest.fixture @pytest.fixture
def reference_dir(reference_dir_base): def reference_dir(reference_dir_base):
@ -22,35 +92,151 @@ class TestRotation:
def test_Eulers(self,default): def test_Eulers(self,default):
for rot in default: for rot in default:
assert np.allclose(rot.asQuaternion(), m = rot.asQuaternion()
Rotation.fromEulers(rot.asEulers()).asQuaternion()) o = Rotation.fromEulers(rot.asEulers()).asQuaternion()
ok = np.allclose(m,o,atol=atol)
if np.isclose(rot.asQuaternion()[0],0.0,atol=atol):
ok = ok or np.allclose(m*-1.,o,atol=atol)
print(m,o,rot.asQuaternion())
assert ok and np.isclose(np.linalg.norm(o),1.0)
def test_AxisAngle(self,default): def test_AxisAngle(self,default):
for rot in default: for rot in default:
assert np.allclose(rot.asEulers(), m = rot.asEulers()
Rotation.fromAxisAngle(rot.asAxisAngle()).asEulers()) o = Rotation.fromAxisAngle(rot.asAxisAngle()).asEulers()
u = np.array([np.pi*2,np.pi,np.pi*2])
ok = np.allclose(m,o,atol=atol)
ok = ok or np.allclose(np.where(np.isclose(m,u),m-u,m),np.where(np.isclose(o,u),o-u,o),atol=atol)
if np.isclose(m[1],0.0,atol=atol) or np.isclose(m[1],np.pi,atol=atol):
sum_phi = np.unwrap([m[0]+m[2],o[0]+o[2]])
ok = ok or np.isclose(sum_phi[0],sum_phi[1],atol=atol)
print(m,o,rot.asQuaternion())
assert ok and (np.zeros(3)-1.e-9 <= o).all() and (o <= np.array([np.pi*2.,np.pi,np.pi*2.])+1.e-9).all()
def test_Matrix(self,default): def test_Matrix(self,default):
for rot in default: for rot in default:
assert np.allclose(rot.asAxisAngle(), m = rot.asAxisAngle()
Rotation.fromMatrix(rot.asMatrix()).asAxisAngle()) o = Rotation.fromAxisAngle(rot.asAxisAngle()).asAxisAngle()
ok = np.allclose(m,o,atol=atol)
if np.isclose(m[3],np.pi,atol=atol):
ok = ok or np.allclose(m*np.array([-1.,-1.,-1.,1.]),o,atol=atol)
print(m,o,rot.asQuaternion())
assert ok and np.isclose(np.linalg.norm(o[:3]),1.0) and o[3]<=np.pi++1.e-9
def test_Rodriques(self,default): def test_Rodrigues(self,default):
for rot in default: for rot in default:
assert np.allclose(rot.asMatrix(), m = rot.asMatrix()
Rotation.fromRodrigues(rot.asRodrigues()).asMatrix()) o = Rotation.fromRodrigues(rot.asRodrigues()).asMatrix()
ok = np.allclose(m,o,atol=atol)
print(m,o)
assert ok and np.isclose(np.linalg.det(o),1.0)
def test_Homochoric(self,default): def test_Homochoric(self,default):
cutoff = np.tan(np.pi*.5*(1.-1e-4))
for rot in default: for rot in default:
assert np.allclose(rot.asRodrigues(), m = rot.asRodrigues()
Rotation.fromHomochoric(rot.asHomochoric()).asRodrigues(),rtol=1.e-4) o = Rotation.fromHomochoric(rot.asHomochoric()).asRodrigues()
ok = np.allclose(np.clip(m,None,cutoff),np.clip(o,None,cutoff),atol=atol)
ok = ok or np.isclose(m[3],0.0,atol=atol)
print(m,o,rot.asQuaternion())
assert ok and np.isclose(np.linalg.norm(o[:3]),1.0)
def test_Cubochoric(self,default): def test_Cubochoric(self,default):
for rot in default: for rot in default:
assert np.allclose(rot.asHomochoric(), m = rot.asHomochoric()
Rotation.fromCubochoric(rot.asCubochoric()).asHomochoric()) o = Rotation.fromCubochoric(rot.asCubochoric()).asHomochoric()
ok = np.allclose(m,o,atol=atol)
print(m,o,rot.asQuaternion())
assert ok and np.linalg.norm(o) < (3.*np.pi/4.)**(1./3.) + 1.e-9
def test_Quaternion(self,default): def test_Quaternion(self,default):
for rot in default: for rot in default:
assert np.allclose(rot.asCubochoric(), m = rot.asCubochoric()
Rotation.fromQuaternion(rot.asQuaternion()).asCubochoric()) o = Rotation.fromQuaternion(rot.asQuaternion()).asCubochoric()
ok = np.allclose(m,o,atol=atol)
print(m,o,rot.asQuaternion())
assert ok and o.max() < np.pi**(2./3.)*0.5+1.e-9
@pytest.mark.parametrize('conversion',[Rotation.qu2om,
Rotation.qu2eu,
Rotation.qu2ax,
Rotation.qu2ro,
Rotation.qu2ho])
def test_quaternion_vectorization(self,default,conversion):
qu = np.array([rot.asQuaternion() for rot in default])
conversion(qu.reshape(qu.shape[0]//2,-1,4))
co = conversion(qu)
for q,c in zip(qu,co):
print(q,c)
assert np.allclose(conversion(q),c)
@pytest.mark.parametrize('conversion',[Rotation.om2qu,
Rotation.om2eu,
Rotation.om2ax,
Rotation.om2ro,
Rotation.om2ho,
])
def test_matrix_vectorization(self,default,conversion):
om = np.array([rot.asMatrix() for rot in default])
conversion(om.reshape(om.shape[0]//2,-1,3,3))
co = conversion(om)
for o,c in zip(om,co):
print(o,c)
assert np.allclose(conversion(o),c)
@pytest.mark.parametrize('conversion',[Rotation.eu2qu,
Rotation.eu2om,
Rotation.eu2ax,
Rotation.eu2ro,
Rotation.eu2ho,
])
def test_Euler_vectorization(self,default,conversion):
eu = np.array([rot.asEulers() for rot in default])
conversion(eu.reshape(eu.shape[0]//2,-1,3))
co = conversion(eu)
for e,c in zip(eu,co):
print(e,c)
assert np.allclose(conversion(e),c)
@pytest.mark.parametrize('conversion',[Rotation.ax2qu,
Rotation.ax2om,
Rotation.ax2eu,
Rotation.ax2ro,
Rotation.ax2ho,
])
def test_axisAngle_vectorization(self,default,conversion):
ax = np.array([rot.asAxisAngle() for rot in default])
conversion(ax.reshape(ax.shape[0]//2,-1,4))
co = conversion(ax)
for a,c in zip(ax,co):
print(a,c)
assert np.allclose(conversion(a),c)
@pytest.mark.parametrize('conversion',[Rotation.ro2qu,
Rotation.ro2om,
Rotation.ro2eu,
Rotation.ro2ax,
Rotation.ro2ho,
])
def test_Rodrigues_vectorization(self,default,conversion):
ro = np.array([rot.asRodrigues() for rot in default])
conversion(ro.reshape(ro.shape[0]//2,-1,4))
co = conversion(ro)
for r,c in zip(ro,co):
print(r,c)
assert np.allclose(conversion(r),c)
@pytest.mark.parametrize('conversion',[Rotation.ho2qu,
Rotation.ho2om,
Rotation.ho2eu,
Rotation.ho2ax,
Rotation.ho2ro,
])
def test_homochoric_vectorization(self,default,conversion):
ho = np.array([rot.asHomochoric() for rot in default])
conversion(ho.reshape(ho.shape[0]//2,-1,3))
co = conversion(ho)
for h,c in zip(ho,co):
print(h,c)
assert np.allclose(conversion(h),c)

View File

@ -24,7 +24,7 @@ class TestGridFilters:
n = grid_filters.node_coord0(grid,size) + size/grid*.5 n = grid_filters.node_coord0(grid,size) + size/grid*.5
assert np.allclose(c,n) assert np.allclose(c,n)
@pytest.mark.parametrize('mode',[('cell'),('node')]) @pytest.mark.parametrize('mode',['cell','node'])
def test_grid_DNA(self,mode): def test_grid_DNA(self,mode):
"""Ensure that xx_coord0_gridSizeOrigin is the inverse of xx_coord0.""" """Ensure that xx_coord0_gridSizeOrigin is the inverse of xx_coord0."""
grid = np.random.randint(8,32,(3)) grid = np.random.randint(8,32,(3))
@ -49,7 +49,7 @@ class TestGridFilters:
assert np.allclose(grid_filters.node_coord(size,F) [1:-1,1:-1,1:-1],grid_filters.cell_2_node( assert np.allclose(grid_filters.node_coord(size,F) [1:-1,1:-1,1:-1],grid_filters.cell_2_node(
grid_filters.cell_coord(size,F))[1:-1,1:-1,1:-1]) grid_filters.cell_coord(size,F))[1:-1,1:-1,1:-1])
@pytest.mark.parametrize('mode',[('cell'),('node')]) @pytest.mark.parametrize('mode',['cell','node'])
def test_coord0_origin(self,mode): def test_coord0_origin(self,mode):
origin= np.random.random(3) origin= np.random.random(3)
size = np.random.random(3) # noqa size = np.random.random(3) # noqa
@ -61,22 +61,24 @@ class TestGridFilters:
elif mode == 'node': elif mode == 'node':
assert np.allclose(shifted,unshifted+np.broadcast_to(origin,tuple(grid[::-1]+1)+(3,))) assert np.allclose(shifted,unshifted+np.broadcast_to(origin,tuple(grid[::-1]+1)+(3,)))
@pytest.mark.parametrize('mode',[('cell'),('node')]) @pytest.mark.parametrize('function',[grid_filters.cell_displacement_avg,
def test_displacement_avg_vanishes(self,mode): grid_filters.node_displacement_avg])
def test_displacement_avg_vanishes(self,function):
"""Ensure that random fluctuations in F do not result in average displacement.""" """Ensure that random fluctuations in F do not result in average displacement."""
size = np.random.random(3) # noqa size = np.random.random(3)
grid = np.random.randint(8,32,(3)) grid = np.random.randint(8,32,(3))
F = np.random.random(tuple(grid)+(3,3)) F = np.random.random(tuple(grid)+(3,3))
F += np.eye(3) - np.average(F,axis=(0,1,2)) F += np.eye(3) - np.average(F,axis=(0,1,2))
assert np.allclose(eval('grid_filters.{}_displacement_avg(size,F)'.format(mode)),0.0) assert np.allclose(function(size,F),0.0)
@pytest.mark.parametrize('mode',[('cell'),('node')]) @pytest.mark.parametrize('function',[grid_filters.cell_displacement_fluct,
def test_displacement_fluct_vanishes(self,mode): grid_filters.node_displacement_fluct])
def test_displacement_fluct_vanishes(self,function):
"""Ensure that constant F does not result in fluctuating displacement.""" """Ensure that constant F does not result in fluctuating displacement."""
size = np.random.random(3) # noqa size = np.random.random(3)
grid = np.random.randint(8,32,(3)) grid = np.random.randint(8,32,(3))
F = np.broadcast_to(np.random.random((3,3)), tuple(grid)+(3,3)) # noqa F = np.broadcast_to(np.random.random((3,3)), tuple(grid)+(3,3))
assert np.allclose(eval('grid_filters.{}_displacement_fluct(size,F)'.format(mode)),0.0) assert np.allclose(function(size,F),0.0)
def test_regrid(self): def test_regrid(self):
size = np.random.random(3) size = np.random.random(3)

59
src/LAPACK_interface.f90 Normal file
View File

@ -0,0 +1,59 @@
!--------------------------------------------------------------------------------------------------
!> @author Martin Diehl, Max-Planck-Institut für Eisenforschung GmbH
!> @brief Fortran interfaces for LAPACK routines
!> @details https://www.netlib.org/lapack/
!--------------------------------------------------------------------------------------------------
module LAPACK_interface
interface
subroutine dgeev(jobvl,jobvr,n,a,lda,wr,wi,vl,ldvl,vr,ldvr,work,lwork,info)
use prec
character, intent(in) :: jobvl,jobvr
integer, intent(in) :: n,lda,ldvl,ldvr,lwork
real(pReal), intent(inout), dimension(lda,n) :: a
real(pReal), intent(out), dimension(n) :: wr,wi
real(pReal), intent(out), dimension(ldvl,n) :: vl
real(pReal), intent(out), dimension(ldvr,n) :: vr
real(pReal), intent(out), dimension(max(1,lwork)) :: work
integer, intent(out) :: info
end subroutine dgeev
subroutine dgesv(n,nrhs,a,lda,ipiv,b,ldb,info)
use prec
integer, intent(in) :: n,nrhs,lda,ldb
real(pReal), intent(inout), dimension(lda,n) :: a
integer, intent(out), dimension(n) :: ipiv
real(pReal), intent(out), dimension(ldb,nrhs) :: b
integer, intent(out) :: info
end subroutine dgesv
subroutine dgetrf(m,n,a,lda,ipiv,info)
use prec
integer, intent(in) :: m,n,lda
real(pReal), intent(inout), dimension(lda,n) :: a
integer, intent(out), dimension(min(m,n)) :: ipiv
integer, intent(out) :: info
end subroutine dgetrf
subroutine dgetri(n,a,lda,ipiv,work,lwork,info)
use prec
integer, intent(in) :: n,lda,lwork
real(pReal), intent(inout), dimension(lda,n) :: a
integer, intent(out), dimension(n) :: ipiv
real(pReal), intent(out), dimension(max(1,lwork)) :: work
integer, intent(out) :: info
end subroutine dgetri
subroutine dsyev(jobz,uplo,n,a,lda,w,work,lwork,info)
use prec
character, intent(in) :: jobz,uplo
integer, intent(in) :: n,lda,lwork
real(pReal), intent(inout), dimension(lda,n) :: a
real(pReal), intent(out), dimension(n) :: w
real(pReal), intent(out), dimension(max(1,lwork)) :: work
integer, intent(out) :: info
end subroutine dsyev
end interface
end module LAPACK_interface

View File

@ -75,7 +75,7 @@ pure function Lambert_CubeToBall(cube) result(ball)
real(pReal), dimension(2) :: T real(pReal), dimension(2) :: T
real(pReal) :: c, s, q real(pReal) :: c, s, q
real(pReal), parameter :: eps = 1.0e-8_pReal real(pReal), parameter :: eps = 1.0e-8_pReal
integer, dimension(3) :: p integer, dimension(3,2) :: p
integer, dimension(2) :: order integer, dimension(2) :: order
if (maxval(abs(cube)) > AP/2.0+eps) then if (maxval(abs(cube)) > AP/2.0+eps) then
@ -89,7 +89,7 @@ pure function Lambert_CubeToBall(cube) result(ball)
else center else center
! get pyramide and scale by grid parameter ratio ! get pyramide and scale by grid parameter ratio
p = GetPyramidOrder(cube) p = GetPyramidOrder(cube)
XYZ = cube(p) * sc XYZ = cube(p(:,1)) * sc
! intercept all the points along the z-axis ! intercept all the points along the z-axis
special: if (all(dEq0(XYZ(1:2)))) then special: if (all(dEq0(XYZ(1:2)))) then
@ -112,7 +112,7 @@ pure function Lambert_CubeToBall(cube) result(ball)
endif special endif special
! reverse the coordinates back to order according to the original pyramid number ! reverse the coordinates back to order according to the original pyramid number
ball = LamXYZ(p) ball = LamXYZ(p(:,2))
endif center endif center
@ -130,7 +130,7 @@ pure function Lambert_BallToCube(xyz) result(cube)
real(pReal), dimension(3) :: cube, xyz1, xyz3 real(pReal), dimension(3) :: cube, xyz1, xyz3
real(pReal), dimension(2) :: Tinv, xyz2 real(pReal), dimension(2) :: Tinv, xyz2
real(pReal) :: rs, qxy, q2, sq2, q, tt real(pReal) :: rs, qxy, q2, sq2, q, tt
integer, dimension(3) :: p integer, dimension(3,2) :: p
rs = norm2(xyz) rs = norm2(xyz)
if (rs > R1) then if (rs > R1) then
@ -142,7 +142,7 @@ pure function Lambert_BallToCube(xyz) result(cube)
cube = 0.0_pReal cube = 0.0_pReal
else center else center
p = GetPyramidOrder(xyz) p = GetPyramidOrder(xyz)
xyz3 = xyz(p) xyz3 = xyz(p(:,1))
! inverse M_3 ! inverse M_3
xyz2 = xyz3(1:2) * sqrt( 2.0*rs/(rs+abs(xyz3(3))) ) xyz2 = xyz3(1:2) * sqrt( 2.0*rs/(rs+abs(xyz3(3))) )
@ -166,7 +166,7 @@ pure function Lambert_BallToCube(xyz) result(cube)
xyz1 = [ Tinv(1), Tinv(2), sign(1.0_pReal,xyz3(3)) * rs / pref ] /sc xyz1 = [ Tinv(1), Tinv(2), sign(1.0_pReal,xyz3(3)) * rs / pref ] /sc
! reverse the coordinates back to order according to the original pyramid number ! reverse the coordinates back to order according to the original pyramid number
cube = xyz1(p) cube = xyz1(p(:,2))
endif center endif center
@ -181,17 +181,17 @@ end function Lambert_BallToCube
pure function GetPyramidOrder(xyz) pure function GetPyramidOrder(xyz)
real(pReal),intent(in),dimension(3) :: xyz real(pReal),intent(in),dimension(3) :: xyz
integer, dimension(3) :: GetPyramidOrder integer, dimension(3,2) :: GetPyramidOrder
if (((abs(xyz(1)) <= xyz(3)).and.(abs(xyz(2)) <= xyz(3))) .or. & if (((abs(xyz(1)) <= xyz(3)).and.(abs(xyz(2)) <= xyz(3))) .or. &
((abs(xyz(1)) <= -xyz(3)).and.(abs(xyz(2)) <= -xyz(3)))) then ((abs(xyz(1)) <= -xyz(3)).and.(abs(xyz(2)) <= -xyz(3)))) then
GetPyramidOrder = [1,2,3] GetPyramidOrder = reshape([[1,2,3],[1,2,3]],[3,2])
else if (((abs(xyz(3)) <= xyz(1)).and.(abs(xyz(2)) <= xyz(1))) .or. & else if (((abs(xyz(3)) <= xyz(1)).and.(abs(xyz(2)) <= xyz(1))) .or. &
((abs(xyz(3)) <= -xyz(1)).and.(abs(xyz(2)) <= -xyz(1)))) then ((abs(xyz(3)) <= -xyz(1)).and.(abs(xyz(2)) <= -xyz(1)))) then
GetPyramidOrder = [2,3,1] GetPyramidOrder = reshape([[2,3,1],[3,1,2]],[3,2])
else if (((abs(xyz(1)) <= xyz(2)).and.(abs(xyz(3)) <= xyz(2))) .or. & else if (((abs(xyz(1)) <= xyz(2)).and.(abs(xyz(3)) <= xyz(2))) .or. &
((abs(xyz(1)) <= -xyz(2)).and.(abs(xyz(3)) <= -xyz(2)))) then ((abs(xyz(1)) <= -xyz(2)).and.(abs(xyz(3)) <= -xyz(2)))) then
GetPyramidOrder = [3,1,2] GetPyramidOrder = reshape([[3,1,2],[2,3,1]],[3,2])
else else
GetPyramidOrder = -1 ! should be impossible, but might simplify debugging GetPyramidOrder = -1 ! should be impossible, but might simplify debugging
end if end if

View File

@ -9,6 +9,7 @@
#include "list.f90" #include "list.f90"
#include "future.f90" #include "future.f90"
#include "config.f90" #include "config.f90"
#include "LAPACK_interface.f90"
#include "math.f90" #include "math.f90"
#include "quaternions.f90" #include "quaternions.f90"
#include "Lambert.f90" #include "Lambert.f90"

View File

@ -838,8 +838,6 @@ function integrateStress(ipc,ip,el,timeFraction) result(broken)
jacoCounterLp, & jacoCounterLp, &
jacoCounterLi ! counters to check for Jacobian update jacoCounterLi ! counters to check for Jacobian update
logical :: error,broken logical :: error,broken
external :: &
dgesv
broken = .true. broken = .true.

View File

@ -27,30 +27,19 @@ module homogenization
implicit none implicit none
private private
!--------------------------------------------------------------------------------------------------
! General variables for the homogenization at a material point
logical, public :: & logical, public :: &
terminallyIll = .false. !< at least one material point is terminally ill terminallyIll = .false. !< at least one material point is terminally ill
!--------------------------------------------------------------------------------------------------
! General variables for the homogenization at a material point
real(pReal), dimension(:,:,:,:), allocatable, public :: & real(pReal), dimension(:,:,:,:), allocatable, public :: &
materialpoint_F0, & !< def grad of IP at start of FE increment materialpoint_F0, & !< def grad of IP at start of FE increment
materialpoint_F, & !< def grad of IP to be reached at end of FE increment materialpoint_F !< def grad of IP to be reached at end of FE increment
real(pReal), dimension(:,:,:,:), allocatable, public, protected :: &
materialpoint_P !< first P--K stress of IP materialpoint_P !< first P--K stress of IP
real(pReal), dimension(:,:,:,:,:,:), allocatable, public :: & real(pReal), dimension(:,:,:,:,:,:), allocatable, public, protected :: &
materialpoint_dPdF !< tangent of first P--K stress at IP materialpoint_dPdF !< tangent of first P--K stress at IP
real(pReal), dimension(:,:,:,:), allocatable :: &
materialpoint_subF0, & !< def grad of IP at beginning of homogenization increment
materialpoint_subF !< def grad of IP to be reached at end of homog inc
real(pReal), dimension(:,:), allocatable :: &
materialpoint_subFrac, &
materialpoint_subStep, &
materialpoint_subdt
logical, dimension(:,:), allocatable :: &
materialpoint_requested, &
materialpoint_converged
logical, dimension(:,:,:), allocatable :: &
materialpoint_doneAndHappy
type :: tNumerics type :: tNumerics
integer :: & integer :: &
nMPstate !< materialpoint state loop limit nMPstate !< materialpoint state loop limit
@ -161,15 +150,7 @@ subroutine homogenization_init
allocate(materialpoint_dPdF(3,3,3,3,discretization_nIP,discretization_nElem), source=0.0_pReal) allocate(materialpoint_dPdF(3,3,3,3,discretization_nIP,discretization_nElem), source=0.0_pReal)
materialpoint_F0 = spread(spread(math_I3,3,discretization_nIP),4,discretization_nElem) ! initialize to identity materialpoint_F0 = spread(spread(math_I3,3,discretization_nIP),4,discretization_nElem) ! initialize to identity
materialpoint_F = materialpoint_F0 ! initialize to identity materialpoint_F = materialpoint_F0 ! initialize to identity
allocate(materialpoint_subF0(3,3,discretization_nIP,discretization_nElem), source=0.0_pReal)
allocate(materialpoint_subF(3,3,discretization_nIP,discretization_nElem), source=0.0_pReal)
allocate(materialpoint_P(3,3,discretization_nIP,discretization_nElem), source=0.0_pReal) allocate(materialpoint_P(3,3,discretization_nIP,discretization_nElem), source=0.0_pReal)
allocate(materialpoint_subFrac(discretization_nIP,discretization_nElem), source=0.0_pReal)
allocate(materialpoint_subStep(discretization_nIP,discretization_nElem), source=0.0_pReal)
allocate(materialpoint_subdt(discretization_nIP,discretization_nElem), source=0.0_pReal)
allocate(materialpoint_requested(discretization_nIP,discretization_nElem), source=.false.)
allocate(materialpoint_converged(discretization_nIP,discretization_nElem), source=.true.)
allocate(materialpoint_doneAndHappy(2,discretization_nIP,discretization_nElem), source=.true.)
write(6,'(/,a)') ' <<<+- homogenization init -+>>>'; flush(6) write(6,'(/,a)') ' <<<+- homogenization init -+>>>'; flush(6)
@ -203,6 +184,16 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
e, & !< element number e, & !< element number
mySource, & mySource, &
myNgrains myNgrains
real(pReal), dimension(3,3) :: &
subF
real(pReal), dimension(discretization_nIP,discretization_nElem) :: &
subFrac, &
subStep
logical, dimension(discretization_nIP,discretization_nElem) :: &
requested, &
converged
logical, dimension(2,discretization_nIP,discretization_nElem) :: &
doneAndHappy
#ifdef DEBUG #ifdef DEBUG
if (iand(debug_level(debug_homogenization), debug_levelBasic) /= 0) then if (iand(debug_level(debug_homogenization), debug_levelBasic) /= 0) then
@ -216,7 +207,7 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
#endif #endif
!-------------------------------------------------------------------------------------------------- !--------------------------------------------------------------------------------------------------
! initialize restoration points of ... ! initialize restoration points
do e = FEsolving_execElem(1),FEsolving_execElem(2) do e = FEsolving_execElem(1),FEsolving_execElem(2)
myNgrains = homogenization_Ngrains(material_homogenizationAt(e)) myNgrains = homogenization_Ngrains(material_homogenizationAt(e))
do i = FEsolving_execIP(1),FEsolving_execIP(2); do i = FEsolving_execIP(1),FEsolving_execIP(2);
@ -238,74 +229,60 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
enddo enddo
subFrac(i,e) = 0.0_pReal
materialpoint_subF0(1:3,1:3,i,e) = materialpoint_F0(1:3,1:3,i,e) converged(i,e) = .false. ! pretend failed step ...
materialpoint_subFrac(i,e) = 0.0_pReal subStep(i,e) = 1.0_pReal/num%subStepSizeHomog ! ... larger then the requested calculation
materialpoint_subStep(i,e) = 1.0_pReal/num%subStepSizeHomog ! <<added to adopt flexibility in cutback size>> requested(i,e) = .true. ! everybody requires calculation
materialpoint_converged(i,e) = .false. ! pretend failed step of twice the required size
materialpoint_requested(i,e) = .true. ! everybody requires calculation
if (homogState(material_homogenizationAt(e))%sizeState > 0) & if (homogState(material_homogenizationAt(e))%sizeState > 0) &
homogState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = & homogState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = &
homogState(material_homogenizationAt(e))%State0( :,material_homogenizationMemberAt(i,e)) ! ...internal homogenization state homogState(material_homogenizationAt(e))%State0( :,material_homogenizationMemberAt(i,e))
if (thermalState(material_homogenizationAt(e))%sizeState > 0) & if (thermalState(material_homogenizationAt(e))%sizeState > 0) &
thermalState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = & thermalState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = &
thermalState(material_homogenizationAt(e))%State0( :,material_homogenizationMemberAt(i,e)) ! ...internal thermal state thermalState(material_homogenizationAt(e))%State0( :,material_homogenizationMemberAt(i,e))
if (damageState(material_homogenizationAt(e))%sizeState > 0) & if (damageState(material_homogenizationAt(e))%sizeState > 0) &
damageState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = & damageState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = &
damageState(material_homogenizationAt(e))%State0( :,material_homogenizationMemberAt(i,e)) ! ...internal damage state damageState(material_homogenizationAt(e))%State0( :,material_homogenizationMemberAt(i,e))
enddo enddo
enddo enddo
NiterationHomog = 0 NiterationHomog = 0
cutBackLooping: do while (.not. terminallyIll .and. & cutBackLooping: do while (.not. terminallyIll .and. &
any(materialpoint_subStep(:,FEsolving_execELem(1):FEsolving_execElem(2)) > num%subStepMinHomog)) any(subStep(:,FEsolving_execELem(1):FEsolving_execElem(2)) > num%subStepMinHomog))
!$OMP PARALLEL DO PRIVATE(myNgrains) !$OMP PARALLEL DO PRIVATE(myNgrains)
elementLooping1: do e = FEsolving_execElem(1),FEsolving_execElem(2) elementLooping1: do e = FEsolving_execElem(1),FEsolving_execElem(2)
myNgrains = homogenization_Ngrains(material_homogenizationAt(e)) myNgrains = homogenization_Ngrains(material_homogenizationAt(e))
IpLooping1: do i = FEsolving_execIP(1),FEsolving_execIP(2) IpLooping1: do i = FEsolving_execIP(1),FEsolving_execIP(2)
converged: if (materialpoint_converged(i,e)) then if (converged(i,e)) then
#ifdef DEBUG #ifdef DEBUG
if (iand(debug_level(debug_homogenization), debug_levelExtensive) /= 0 & if (iand(debug_level(debug_homogenization), debug_levelExtensive) /= 0 &
.and. ((e == debug_e .and. i == debug_i) & .and. ((e == debug_e .and. i == debug_i) &
.or. .not. iand(debug_level(debug_homogenization),debug_levelSelective) /= 0)) then .or. .not. iand(debug_level(debug_homogenization),debug_levelSelective) /= 0)) then
write(6,'(a,1x,f12.8,1x,a,1x,f12.8,1x,a,i8,1x,i2/)') '<< HOMOG >> winding forward from', & write(6,'(a,1x,f12.8,1x,a,1x,f12.8,1x,a,i8,1x,i2/)') '<< HOMOG >> winding forward from', &
materialpoint_subFrac(i,e), 'to current materialpoint_subFrac', & subFrac(i,e), 'to current subFrac', &
materialpoint_subFrac(i,e)+materialpoint_subStep(i,e),'in materialpoint_stressAndItsTangent at el ip',e,i subFrac(i,e)+subStep(i,e),'in materialpoint_stressAndItsTangent at el ip',e,i
endif endif
#endif #endif
!--------------------------------------------------------------------------------------------------- !---------------------------------------------------------------------------------------------------
! calculate new subStep and new subFrac ! calculate new subStep and new subFrac
materialpoint_subFrac(i,e) = materialpoint_subFrac(i,e) + materialpoint_subStep(i,e) subFrac(i,e) = subFrac(i,e) + subStep(i,e)
materialpoint_subStep(i,e) = min(1.0_pReal-materialpoint_subFrac(i,e), & subStep(i,e) = min(1.0_pReal-subFrac(i,e),num%stepIncreaseHomog*subStep(i,e)) ! introduce flexibility for step increase/acceleration
num%stepIncreaseHomog*materialpoint_subStep(i,e)) ! introduce flexibility for step increase/acceleration
steppingNeeded: if (materialpoint_subStep(i,e) > num%subStepMinHomog) then steppingNeeded: if (subStep(i,e) > num%subStepMinHomog) then
! wind forward grain starting point of... ! wind forward grain starting point
crystallite_partionedF0 (1:3,1:3,1:myNgrains,i,e) = & crystallite_partionedF0 (1:3,1:3,1:myNgrains,i,e) = crystallite_partionedF(1:3,1:3,1:myNgrains,i,e)
crystallite_partionedF(1:3,1:3,1:myNgrains,i,e) crystallite_partionedFp0(1:3,1:3,1:myNgrains,i,e) = crystallite_Fp (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedLp0(1:3,1:3,1:myNgrains,i,e) = crystallite_Lp (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedFp0 (1:3,1:3,1:myNgrains,i,e) = & crystallite_partionedFi0(1:3,1:3,1:myNgrains,i,e) = crystallite_Fi (1:3,1:3,1:myNgrains,i,e)
crystallite_Fp (1:3,1:3,1:myNgrains,i,e) crystallite_partionedLi0(1:3,1:3,1:myNgrains,i,e) = crystallite_Li (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedS0 (1:3,1:3,1:myNgrains,i,e) = crystallite_S (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedLp0 (1:3,1:3,1:myNgrains,i,e) = &
crystallite_Lp (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedFi0 (1:3,1:3,1:myNgrains,i,e) = &
crystallite_Fi (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedLi0 (1:3,1:3,1:myNgrains,i,e) = &
crystallite_Li (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedS0 (1:3,1:3,1:myNgrains,i,e) = &
crystallite_S (1:3,1:3,1:myNgrains,i,e)
do g = 1,myNgrains do g = 1,myNgrains
plasticState (material_phaseAt(g,e))%partionedState0(:,material_phasememberAt(g,i,e)) = & plasticState (material_phaseAt(g,e))%partionedState0(:,material_phasememberAt(g,i,e)) = &
@ -326,15 +303,12 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
damageState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = & damageState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) = &
damageState(material_homogenizationAt(e))%State (:,material_homogenizationMemberAt(i,e)) damageState(material_homogenizationAt(e))%State (:,material_homogenizationMemberAt(i,e))
materialpoint_subF0(1:3,1:3,i,e) = materialpoint_subF(1:3,1:3,i,e)
endif steppingNeeded endif steppingNeeded
else converged else
if ( (myNgrains == 1 .and. materialpoint_subStep(i,e) <= 1.0 ) .or. & ! single grain already tried internal subStepping in crystallite if ( (myNgrains == 1 .and. subStep(i,e) <= 1.0 ) .or. & ! single grain already tried internal subStepping in crystallite
num%subStepSizeHomog * materialpoint_subStep(i,e) <= num%subStepMinHomog ) then ! would require too small subStep num%subStepSizeHomog * subStep(i,e) <= num%subStepMinHomog ) then ! would require too small subStep
! cutback makes no sense ! cutback makes no sense
!$OMP FLUSH(terminallyIll)
if (.not. terminallyIll) then ! so first signals terminally ill... if (.not. terminallyIll) then ! so first signals terminally ill...
!$OMP CRITICAL (write2out) !$OMP CRITICAL (write2out)
write(6,*) 'Integration point ', i,' at element ', e, ' terminally ill' write(6,*) 'Integration point ', i,' at element ', e, ' terminally ill'
@ -342,32 +316,27 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
endif endif
terminallyIll = .true. ! ...and kills all others terminallyIll = .true. ! ...and kills all others
else ! cutback makes sense else ! cutback makes sense
materialpoint_subStep(i,e) = num%subStepSizeHomog * materialpoint_subStep(i,e) ! crystallite had severe trouble, so do a significant cutback subStep(i,e) = num%subStepSizeHomog * subStep(i,e) ! crystallite had severe trouble, so do a significant cutback
#ifdef DEBUG #ifdef DEBUG
if (iand(debug_level(debug_homogenization), debug_levelExtensive) /= 0 & if (iand(debug_level(debug_homogenization), debug_levelExtensive) /= 0 &
.and. ((e == debug_e .and. i == debug_i) & .and. ((e == debug_e .and. i == debug_i) &
.or. .not. iand(debug_level(debug_homogenization), debug_levelSelective) /= 0)) then .or. .not. iand(debug_level(debug_homogenization), debug_levelSelective) /= 0)) then
write(6,'(a,1x,f12.8,a,i8,1x,i2/)') & write(6,'(a,1x,f12.8,a,i8,1x,i2/)') &
'<< HOMOG >> cutback step in materialpoint_stressAndItsTangent with new materialpoint_subStep:',& '<< HOMOG >> cutback step in materialpoint_stressAndItsTangent with new subStep:',&
materialpoint_subStep(i,e),' at el ip',e,i subStep(i,e),' at el ip',e,i
endif endif
#endif #endif
!-------------------------------------------------------------------------------------------------- !--------------------------------------------------------------------------------------------------
! restore... ! restore
if (materialpoint_subStep(i,e) < 1.0_pReal) then ! protect against fake cutback from \Delta t = 2 to 1. Maybe that "trick" is not necessary anymore at all? I.e. start with \Delta t = 1 if (subStep(i,e) < 1.0_pReal) then ! protect against fake cutback from \Delta t = 2 to 1. Maybe that "trick" is not necessary anymore at all? I.e. start with \Delta t = 1
crystallite_Lp(1:3,1:3,1:myNgrains,i,e) = & crystallite_Lp(1:3,1:3,1:myNgrains,i,e) = crystallite_partionedLp0(1:3,1:3,1:myNgrains,i,e)
crystallite_partionedLp0(1:3,1:3,1:myNgrains,i,e) crystallite_Li(1:3,1:3,1:myNgrains,i,e) = crystallite_partionedLi0(1:3,1:3,1:myNgrains,i,e)
crystallite_Li(1:3,1:3,1:myNgrains,i,e) = &
crystallite_partionedLi0(1:3,1:3,1:myNgrains,i,e)
endif ! maybe protecting everything from overwriting (not only L) makes even more sense endif ! maybe protecting everything from overwriting (not only L) makes even more sense
crystallite_Fp(1:3,1:3,1:myNgrains,i,e) = & crystallite_Fp(1:3,1:3,1:myNgrains,i,e) = crystallite_partionedFp0(1:3,1:3,1:myNgrains,i,e)
crystallite_partionedFp0(1:3,1:3,1:myNgrains,i,e) crystallite_Fi(1:3,1:3,1:myNgrains,i,e) = crystallite_partionedFi0(1:3,1:3,1:myNgrains,i,e)
crystallite_Fi(1:3,1:3,1:myNgrains,i,e) = & crystallite_S (1:3,1:3,1:myNgrains,i,e) = crystallite_partionedS0 (1:3,1:3,1:myNgrains,i,e)
crystallite_partionedFi0(1:3,1:3,1:myNgrains,i,e)
crystallite_S(1:3,1:3,1:myNgrains,i,e) = &
crystallite_partionedS0(1:3,1:3,1:myNgrains,i,e)
do g = 1, myNgrains do g = 1, myNgrains
plasticState (material_phaseAt(g,e))%state( :,material_phasememberAt(g,i,e)) = & plasticState (material_phaseAt(g,e))%state( :,material_phasememberAt(g,i,e)) = &
plasticState (material_phaseAt(g,e))%partionedState0(:,material_phasememberAt(g,i,e)) plasticState (material_phaseAt(g,e))%partionedState0(:,material_phasememberAt(g,i,e))
@ -386,15 +355,11 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
damageState(material_homogenizationAt(e))%State( :,material_homogenizationMemberAt(i,e)) = & damageState(material_homogenizationAt(e))%State( :,material_homogenizationMemberAt(i,e)) = &
damageState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e)) damageState(material_homogenizationAt(e))%subState0(:,material_homogenizationMemberAt(i,e))
endif endif
endif converged endif
if (materialpoint_subStep(i,e) > num%subStepMinHomog) then if (subStep(i,e) > num%subStepMinHomog) then
materialpoint_requested(i,e) = .true. requested(i,e) = .true.
materialpoint_subF(1:3,1:3,i,e) = materialpoint_subF0(1:3,1:3,i,e) & doneAndHappy(1:2,i,e) = [.false.,.true.]
+ materialpoint_subStep(i,e) * (materialpoint_F(1:3,1:3,i,e) &
- materialpoint_F0(1:3,1:3,i,e))
materialpoint_subdt(i,e) = materialpoint_subStep(i,e) * dt
materialpoint_doneAndHappy(1:2,i,e) = [.false.,.true.]
endif endif
enddo IpLooping1 enddo IpLooping1
enddo elementLooping1 enddo elementLooping1
@ -403,8 +368,8 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
NiterationMPstate = 0 NiterationMPstate = 0
convergenceLooping: do while (.not. terminallyIll .and. & convergenceLooping: do while (.not. terminallyIll .and. &
any( materialpoint_requested(:,FEsolving_execELem(1):FEsolving_execElem(2)) & any( requested(:,FEsolving_execELem(1):FEsolving_execElem(2)) &
.and. .not. materialpoint_doneAndHappy(1,:,FEsolving_execELem(1):FEsolving_execElem(2)) & .and. .not. doneAndHappy(1,:,FEsolving_execELem(1):FEsolving_execElem(2)) &
) .and. & ) .and. &
NiterationMPstate < num%nMPstate) NiterationMPstate < num%nMPstate)
NiterationMPstate = NiterationMPstate + 1 NiterationMPstate = NiterationMPstate + 1
@ -413,14 +378,15 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
! deformation partitioning ! deformation partitioning
! based on materialpoint_subF0,.._subF,crystallite_partionedF0, and homogenization_state, ! based on materialpoint_subF0,.._subF,crystallite_partionedF0, and homogenization_state,
! results in crystallite_partionedF ! results in crystallite_partionedF
!$OMP PARALLEL DO PRIVATE(myNgrains) !$OMP PARALLEL DO PRIVATE(myNgrains,subF)
elementLooping2: do e = FEsolving_execElem(1),FEsolving_execElem(2) elementLooping2: do e = FEsolving_execElem(1),FEsolving_execElem(2)
myNgrains = homogenization_Ngrains(material_homogenizationAt(e)) myNgrains = homogenization_Ngrains(material_homogenizationAt(e))
IpLooping2: do i = FEsolving_execIP(1),FEsolving_execIP(2) IpLooping2: do i = FEsolving_execIP(1),FEsolving_execIP(2)
if ( materialpoint_requested(i,e) .and. & ! process requested but... if(requested(i,e) .and. .not. doneAndHappy(1,i,e)) then ! requested but not yet done
.not. materialpoint_doneAndHappy(1,i,e)) then ! ...not yet done material points subF = materialpoint_F0(1:3,1:3,i,e) &
call partitionDeformation(i,e) ! partition deformation onto constituents + (materialpoint_F(1:3,1:3,i,e)-materialpoint_F0(1:3,1:3,i,e))*(subStep(i,e)+subFrac(i,e))
crystallite_dt(1:myNgrains,i,e) = materialpoint_subdt(i,e) ! propagate materialpoint dt to grains call partitionDeformation(subF,i,e) ! partition deformation onto constituents
crystallite_dt(1:myNgrains,i,e) = dt*subStep(i,e) ! propagate materialpoint dt to grains
crystallite_requested(1:myNgrains,i,e) = .true. ! request calculation for constituents crystallite_requested(1:myNgrains,i,e) = .true. ! request calculation for constituents
else else
crystallite_requested(1:myNgrains,i,e) = .false. ! calculation for constituents not required anymore crystallite_requested(1:myNgrains,i,e) = .false. ! calculation for constituents not required anymore
@ -434,20 +400,21 @@ subroutine materialpoint_stressAndItsTangent(updateJaco,dt)
! based on crystallite_partionedF0,.._partionedF ! based on crystallite_partionedF0,.._partionedF
! incrementing by crystallite_dt ! incrementing by crystallite_dt
materialpoint_converged = crystallite_stress() !ToDo: MD not sure if that is the best logic converged = crystallite_stress() !ToDo: MD not sure if that is the best logic
!-------------------------------------------------------------------------------------------------- !--------------------------------------------------------------------------------------------------
! state update ! state update
!$OMP PARALLEL DO !$OMP PARALLEL DO PRIVATE(subF)
elementLooping3: do e = FEsolving_execElem(1),FEsolving_execElem(2) elementLooping3: do e = FEsolving_execElem(1),FEsolving_execElem(2)
IpLooping3: do i = FEsolving_execIP(1),FEsolving_execIP(2) IpLooping3: do i = FEsolving_execIP(1),FEsolving_execIP(2)
if ( materialpoint_requested(i,e) .and. & if (requested(i,e) .and. .not. doneAndHappy(1,i,e)) then
.not. materialpoint_doneAndHappy(1,i,e)) then if (.not. converged(i,e)) then
if (.not. materialpoint_converged(i,e)) then doneAndHappy(1:2,i,e) = [.true.,.false.]
materialpoint_doneAndHappy(1:2,i,e) = [.true.,.false.]
else else
materialpoint_doneAndHappy(1:2,i,e) = updateState(i,e) subF = materialpoint_F0(1:3,1:3,i,e) &
materialpoint_converged(i,e) = all(materialpoint_doneAndHappy(1:2,i,e)) ! converged if done and happy + (materialpoint_F(1:3,1:3,i,e)-materialpoint_F0(1:3,1:3,i,e))*(subStep(i,e)+subFrac(i,e))
doneAndHappy(1:2,i,e) = updateState(dt*subStep(i,e),subF,i,e)
converged(i,e) = all(doneAndHappy(1:2,i,e)) ! converged if done and happy
endif endif
endif endif
enddo IpLooping3 enddo IpLooping3
@ -481,8 +448,10 @@ end subroutine materialpoint_stressAndItsTangent
!-------------------------------------------------------------------------------------------------- !--------------------------------------------------------------------------------------------------
!> @brief partition material point def grad onto constituents !> @brief partition material point def grad onto constituents
!-------------------------------------------------------------------------------------------------- !--------------------------------------------------------------------------------------------------
subroutine partitionDeformation(ip,el) subroutine partitionDeformation(subF,ip,el)
real(pReal), intent(in), dimension(3,3) :: &
subF
integer, intent(in) :: & integer, intent(in) :: &
ip, & !< integration point ip, & !< integration point
el !< element number el !< element number
@ -490,17 +459,17 @@ subroutine partitionDeformation(ip,el)
chosenHomogenization: select case(homogenization_type(material_homogenizationAt(el))) chosenHomogenization: select case(homogenization_type(material_homogenizationAt(el)))
case (HOMOGENIZATION_NONE_ID) chosenHomogenization case (HOMOGENIZATION_NONE_ID) chosenHomogenization
crystallite_partionedF(1:3,1:3,1,ip,el) = materialpoint_subF(1:3,1:3,ip,el) crystallite_partionedF(1:3,1:3,1,ip,el) = subF
case (HOMOGENIZATION_ISOSTRAIN_ID) chosenHomogenization case (HOMOGENIZATION_ISOSTRAIN_ID) chosenHomogenization
call mech_isostrain_partitionDeformation(& call mech_isostrain_partitionDeformation(&
crystallite_partionedF(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), & crystallite_partionedF(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), &
materialpoint_subF(1:3,1:3,ip,el)) subF)
case (HOMOGENIZATION_RGC_ID) chosenHomogenization case (HOMOGENIZATION_RGC_ID) chosenHomogenization
call mech_RGC_partitionDeformation(& call mech_RGC_partitionDeformation(&
crystallite_partionedF(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), & crystallite_partionedF(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), &
materialpoint_subF(1:3,1:3,ip,el),& subF,&
ip, & ip, &
el) el)
end select chosenHomogenization end select chosenHomogenization
@ -512,8 +481,12 @@ end subroutine partitionDeformation
!> @brief update the internal state of the homogenization scheme and tell whether "done" and !> @brief update the internal state of the homogenization scheme and tell whether "done" and
!> "happy" with result !> "happy" with result
!-------------------------------------------------------------------------------------------------- !--------------------------------------------------------------------------------------------------
function updateState(ip,el) function updateState(subdt,subF,ip,el)
real(pReal), intent(in) :: &
subdt !< current time step
real(pReal), intent(in), dimension(3,3) :: &
subF
integer, intent(in) :: & integer, intent(in) :: &
ip, & !< integration point ip, & !< integration point
el !< element number el !< element number
@ -527,8 +500,8 @@ function updateState(ip,el)
mech_RGC_updateState(crystallite_P(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), & mech_RGC_updateState(crystallite_P(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), &
crystallite_partionedF(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), & crystallite_partionedF(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), &
crystallite_partionedF0(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el),& crystallite_partionedF0(1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el),&
materialpoint_subF(1:3,1:3,ip,el),& subF,&
materialpoint_subdt(ip,el), & subdt, &
crystallite_dPdF(1:3,1:3,1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), & crystallite_dPdF(1:3,1:3,1:3,1:3,1:homogenization_Ngrains(material_homogenizationAt(el)),ip,el), &
ip, & ip, &
el) el)
@ -538,7 +511,7 @@ function updateState(ip,el)
case (THERMAL_adiabatic_ID) chosenThermal case (THERMAL_adiabatic_ID) chosenThermal
updateState = & updateState = &
updateState .and. & updateState .and. &
thermal_adiabatic_updateState(materialpoint_subdt(ip,el), & thermal_adiabatic_updateState(subdt, &
ip, & ip, &
el) el)
end select chosenThermal end select chosenThermal
@ -547,7 +520,7 @@ function updateState(ip,el)
case (DAMAGE_local_ID) chosenDamage case (DAMAGE_local_ID) chosenDamage
updateState = & updateState = &
updateState .and. & updateState .and. &
damage_local_updateState(materialpoint_subdt(ip,el), & damage_local_updateState(subdt, &
ip, & ip, &
el) el)
end select chosenDamage end select chosenDamage

View File

@ -9,6 +9,7 @@ module math
use prec use prec
use IO use IO
use numerics use numerics
use LAPACK_interface
implicit none implicit none
public public
@ -487,16 +488,12 @@ function math_invSym3333(A)
integer, dimension(6) :: ipiv6 integer, dimension(6) :: ipiv6
real(pReal), dimension(6,6) :: temp66 real(pReal), dimension(6,6) :: temp66
real(pReal), dimension(6*(64+2)) :: work real(pReal), dimension(6*6) :: work
integer :: ierr_i, ierr_f integer :: ierr_i, ierr_f
external :: &
dgetrf, &
dgetri
temp66 = math_sym3333to66(A) temp66 = math_sym3333to66(A)
call dgetrf(6,6,temp66,6,ipiv6,ierr_i) call dgetrf(6,6,temp66,6,ipiv6,ierr_i)
call dgetri(6,temp66,6,ipiv6,work,size(work,1),ierr_f) call dgetri(6,temp66,6,ipiv6,work,size(work,1),ierr_f)
if (ierr_i /= 0 .or. ierr_f /= 0) then if (ierr_i /= 0 .or. ierr_f /= 0) then
call IO_error(400, ext_msg = 'math_invSym3333') call IO_error(400, ext_msg = 'math_invSym3333')
else else
@ -516,11 +513,8 @@ subroutine math_invert(InvA, error, A)
logical, intent(out) :: error logical, intent(out) :: error
integer, dimension(size(A,1)) :: ipiv integer, dimension(size(A,1)) :: ipiv
real(pReal), dimension(size(A,1)*(64+2)) :: work real(pReal), dimension(size(A,1)**2) :: work
integer :: ierr integer :: ierr
external :: &
dgetrf, &
dgetri
invA = A invA = A
call dgetrf(size(A,1),size(A,1),invA,size(A,1),ipiv,ierr) call dgetrf(size(A,1),size(A,1),invA,size(A,1),ipiv,ierr)
@ -884,9 +878,7 @@ subroutine math_eigh(m,w,v,error)
logical, intent(out) :: error logical, intent(out) :: error
integer :: ierr integer :: ierr
real(pReal), dimension((64+2)*size(m,1)) :: work ! block size of 64 taken from http://www.netlib.org/lapack/double/dsyev.f real(pReal), dimension(size(m,1)**2) :: work
external :: &
dsyev
v = m ! copy matrix to input (doubles as output) array v = m ! copy matrix to input (doubles as output) array
call dsyev('V','U',size(m,1),v,size(m,1),w,work,size(work,1),ierr) call dsyev('V','U',size(m,1),v,size(m,1),w,work,size(work,1),ierr)
@ -1041,9 +1033,7 @@ function math_eigvalsh(m)
real(pReal), dimension(size(m,1),size(m,1)) :: m_ real(pReal), dimension(size(m,1),size(m,1)) :: m_
integer :: ierr integer :: ierr
real(pReal), dimension((64+2)*size(m,1)) :: work ! block size of 64 taken from http://www.netlib.org/lapack/double/dsyev.f real(pReal), dimension(size(m,1)**2) :: work
external :: &
dsyev
m_= m ! copy matrix to input (will be destroyed) m_= m ! copy matrix to input (will be destroyed)
call dsyev('N','U',size(m,1),m_,size(m,1),math_eigvalsh,work,size(work,1),ierr) call dsyev('N','U',size(m,1),m_,size(m,1),math_eigvalsh,work,size(work,1),ierr)

View File

@ -432,18 +432,17 @@ pure function qu2eu(qu) result(eu)
real(pReal), intent(in), dimension(4) :: qu real(pReal), intent(in), dimension(4) :: qu
real(pReal), dimension(3) :: eu real(pReal), dimension(3) :: eu
real(pReal) :: q12, q03, chi, chiInv real(pReal) :: q12, q03, chi
q03 = qu(1)**2+qu(4)**2 q03 = qu(1)**2+qu(4)**2
q12 = qu(2)**2+qu(3)**2 q12 = qu(2)**2+qu(3)**2
chi = sqrt(q03*q12) chi = sqrt(q03*q12)
degenerated: if (dEq0(chi)) then degenerated: if (dEq0(q12)) then
eu = merge([atan2(-P*2.0_pReal*qu(1)*qu(4),qu(1)**2-qu(4)**2), 0.0_pReal, 0.0_pReal], & eu = [atan2(-P*2.0_pReal*qu(1)*qu(4),qu(1)**2-qu(4)**2), 0.0_pReal, 0.0_pReal]
[atan2( 2.0_pReal*qu(2)*qu(3),qu(2)**2-qu(3)**2), PI, 0.0_pReal], & elseif (dEq0(q03)) then
dEq0(q12)) eu = [atan2( 2.0_pReal*qu(2)*qu(3),qu(2)**2-qu(3)**2), PI, 0.0_pReal]
else degenerated else degenerated
chiInv = 1.0_pReal/chi
eu = [atan2((-P*qu(1)*qu(3)+qu(2)*qu(4))*chi, (-P*qu(1)*qu(2)-qu(3)*qu(4))*chi ), & eu = [atan2((-P*qu(1)*qu(3)+qu(2)*qu(4))*chi, (-P*qu(1)*qu(2)-qu(3)*qu(4))*chi ), &
atan2( 2.0_pReal*chi, q03-q12 ), & atan2( 2.0_pReal*chi, q03-q12 ), &
atan2(( P*qu(1)*qu(3)+qu(2)*qu(4))*chi, (-P*qu(1)*qu(2)+qu(3)*qu(4))*chi )] atan2(( P*qu(1)*qu(3)+qu(2)*qu(4))*chi, (-P*qu(1)*qu(2)+qu(3)*qu(4))*chi )]
@ -596,8 +595,6 @@ function om2ax(om) result(ax)
real(pReal), dimension(3,3) :: VR, devNull, om_ real(pReal), dimension(3,3) :: VR, devNull, om_
integer :: ierr, i integer :: ierr, i
external :: dgeev
om_ = om om_ = om
! first get the rotation angle ! first get the rotation angle