objectFFRFTest.py

You can view and download this file on Github: objectFFRFTest.py

  1#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  2# This is an EXUDYN example
  3#
  4# Details:  Test for ObjectFFRF with C++ implementation user function for reduced order equations of motion
  5# NOTE: this is a development file, with lots of unstructured code; just kept for consistency!
  6#
  7# Author:   Johannes Gerstmayr
  8# Date:     2020-05-13
  9#
 10# Copyright:This file is part of Exudyn. Exudyn is free software. You can redistribute it and/or modify it under the terms of the Exudyn license. See 'LICENSE.txt' for more details.
 11#
 12#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 13
 14import exudyn as exu
 15from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
 16import exudyn.graphics as graphics #only import if it does not conflict
 17from exudyn.FEM import *
 18
 19useGraphics = True #without test
 20#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 21#you can erase the following lines and all exudynTestGlobals related operations if this is not intended to be used as TestModel:
 22try: #only if called from test suite
 23    from modelUnitTests import exudynTestGlobals #for globally storing test results
 24    useGraphics = exudynTestGlobals.useGraphics
 25except:
 26    class ExudynTestGlobals:
 27        pass
 28    exudynTestGlobals = ExudynTestGlobals()
 29#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 30
 31SC = exu.SystemContainer()
 32mbs = SC.AddSystem()
 33
 34import numpy as np
 35
 36#==> DO NOT USE THE APPROACH of this test, but use the FEMinterface; also use the more efficient ObjectFFRFreducedOrder !!!!
 37
 38nodeDrawSize = 0.0025
 39
 40testMode = 1 #0=MarkerGeneric, 1=MarkerSuperElement
 41modeNames = ['FFRF_MG','FFRF']
 42
 43#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 44#Use FEMinterface to import FEM model and create FFRFreducedOrder object
 45fem = FEMinterface()
 46inputFileName = 'testData/rotorDiscTest' #runTestSuite.py is at another directory
 47
 48nodes=fem.ImportFromAbaqusInputFile(inputFileName+'.inp', typeName='Instance', name='rotor-1')
 49elements = np.array(fem.elements[0]['Hex8'])
 50
 51fem.ReadMassMatrixFromAbaqus(inputFileName+'MASS1.mtx')
 52fem.ReadStiffnessMatrixFromAbaqus(inputFileName+'STIF1.mtx')
 53fem.ScaleStiffnessMatrix(1e-2) #for larger deformations, stiffness is reduced to 1%
 54
 55massMatrix = fem.GetMassMatrix(sparse=False)
 56stiffnessMatrix = fem.GetStiffnessMatrix(sparse=False)
 57
 58#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 59
 60exu.Print("nodes size=", nodes.shape)
 61exu.Print("elements size=", elements.shape)
 62
 63minZ = min(nodes[:,2])
 64maxZ = max(nodes[:,2])
 65midZ = 0.5*(minZ+maxZ)
 66
 67#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 68
 69#nLeft = (78-1)
 70#nRight = (77-1)
 71#nMid = (43-1)
 72nLeft = -1
 73nRight = -1
 74nMid = -1
 75nForce = -1 #40; node where fore is attached
 76forceZ = 0.1
 77
 78#nTopRight = 12 #JG, excitation
 79nForce = 12 #JG, excitation
 80nTopMid = 9  #alternative: 103; JG, fixed node "rotation"
 81
 82unbalance = 0.1
 83massMatrix[nTopMid*3+0,nTopMid*3+0] += unbalance
 84massMatrix[nTopMid*3+1,nTopMid*3+1] += unbalance
 85massMatrix[nTopMid*3+2,nTopMid*3+2] += unbalance
 86
 87#find output nodes:
 88for i in range(len(nodes)):
 89    n = nodes[i]
 90    if abs(n[2] - minZ) < 1e-6 and abs(n[1]) < 1e-6 and abs(n[0]) < 1e-6:
 91        nLeft = i
 92    if abs(n[2] - maxZ) < 1e-6 and abs(n[1]) < 1e-6 and abs(n[0]) < 1e-6:
 93        nRight = i
 94    if abs(n[2] - midZ) < 1e-6 and abs(n[1]) < 1e-6 and abs(n[0]) < 1e-6:
 95        nMid = i
 96    #if abs(n[2] - forceZ) < 1e-6 and abs(n[1]) < 1e-6 and abs(n[0]) < 1e-6:
 97    #    nForce = i
 98
 99
100#exu.Print("nLeft=", nLeft, ", nRight=", nRight, ", nMid=", nMid, ", nForce=", nForce)
101
102#posX=0.15 #+/- x coordinate of nodes
103posLeft = nodes[nLeft]
104posRight = nodes[nRight]
105
106nNodes = len(nodes)
107nODE2 = nNodes*3
108exu.Print("nNodes=", nNodes, ", nODE2=", nODE2)
109
110#+++++++++++++++++++++++++++++++++++++++++++++++++++++++
111calcEig = True
112if calcEig:
113    from scipy.linalg import solve, eigh, eig #eigh for symmetric matrices, positive definite
114
115    [eigvals, eigvecs] = eigh(stiffnessMatrix, massMatrix) #this gives omega^2 ... squared eigen frequencies (rad/s)
116    ev = np.sort(a=abs(eigvals))
117
118    listEig = []
119    for i in range(18):
120        listEig += [np.sqrt(ev[i])/(2*np.pi)]
121    exu.Print("eigenvalues =", listEig)
122#+++++++++++++++++++++++++++++++++++++++++++++++++++++++
123
124#eigenvalues of constrained system:
125#+++++++++++++++++++++++++++++++++++++++++++++++++++++++
126calcEigConstrained = False
127if calcEigConstrained:
128
129    constrainedCoordinates = [0]*nODE2
130    constrainedCoordinates[nLeft*3+0] = 1  #X
131    constrainedCoordinates[nLeft*3+1] = 1  #Y
132    constrainedCoordinates[nLeft*3+2] = 1  #Z
133    constrainedCoordinates[nRight*3+1] = 1 #Y
134    constrainedCoordinates[nRight*3+2] = 1 #Z
135
136    nConstrained = sum(constrainedCoordinates)
137    indexList = []
138    cnt = 0
139    for i in range(nODE2):
140        if constrainedCoordinates[i] == 0:
141            indexList+=[i]
142
143    nODE2C = nODE2-nConstrained
144    massMatrixC = np.zeros((nODE2C,nODE2C))
145    stiffnessMatrixC = np.zeros((nODE2C,nODE2C))
146
147    for i in range(nODE2C):
148        for j in range(nODE2C):
149            massMatrixC[i,j] = massMatrix[indexList[i],indexList[j]]
150            stiffnessMatrixC[i,j] = stiffnessMatrix[indexList[i],indexList[j]]
151
152    from scipy.linalg import solve, eigh, eig #eigh for symmetric matrices, positive definite
153
154    [eigvals, eigvecs] = eigh(stiffnessMatrixC, massMatrixC) #this gives omega^2 ... squared eigen frequencies (rad/s)
155    ev = np.sort(a=abs(eigvals))
156
157    listEig = []
158    for i in range(18):
159        listEig += [np.sqrt(ev[i])/(2*np.pi)]
160    exu.Print("eigenvalues of constrained system (Hz)=", listEig)
161
162
163#compute (3 x 3*n) skew matrix from (3*n) vector
164def ComputeSkewMatrix(v):
165    n = int(len(v)/3) #number of nodes
166    sm = np.zeros((3*n,3))
167
168    for i in range(n):
169        off = 3*i
170        x=v[off+0]
171        y=v[off+1]
172        z=v[off+2]
173        mLoc = np.array([[0,-z,y],[z,0,-x],[-y,x,0]])
174        sm[off:off+3,:] = mLoc[:,:]
175
176    return sm
177    #Y0=np.array([[0,0,0],[0,0,1],[0,-1,0]])
178    #Y1=np.array([[0,0,-1],[0,0,0],[1,0,0]])
179    #Y2=np.array([[0,1,0],[-1,0,0],[0,0,0]])
180
181
182#+++++++++++++++++++++++++++++++++++++++++++++++++++++++
183
184nNodesFFRF = nNodes
185nODE2FFRF = nNodes*3
186
187#the following is only working for useFFRFobject = True; with False, it represents an old mode, deactivated with newer ObjectGenericODE2!
188useFFRFobject = True #uses ObjectFFRF instead of ObjectGenericODE2 ==> mesh nodes are indexed from 0 .. n_meshNodes-1
189decFFRFobject = 0    #adapt node numbers if useFFRFobject=True
190if useFFRFobject: decFFRFobject = 1
191
192useFFRF = True
193if useFFRF:
194    p0 = [0,0,midZ*0] #reference position
195    v0 = [0,0,0] #initial translational velocity
196    omega0 = [0,0,50*2*pi] #arbitrary initial angular velocity
197    ep0 = np.array(eulerParameters0) #no rotation
198    ep_t0 = AngularVelocity2EulerParameters_t(omega0, ep0)
199    #adjust mass and stiffness matrices
200    nODE2rigid = len(p0)+len(ep0)
201    nODE2rot = len(ep0) #dimension of rotation parameters
202    dim3D = len(p0)     #dimension of position
203    nODE2FFRF = nODE2rigid + nODE2
204    nNodesFFRF = nNodes+1
205
206    Knew = np.zeros((nODE2FFRF,nODE2FFRF))
207    Mnew = np.zeros((nODE2FFRF,nODE2FFRF))
208
209    FillInSubMatrix(stiffnessMatrix, Knew, nODE2rigid, nODE2rigid)
210    FillInSubMatrix(massMatrix, Mnew, nODE2rigid, nODE2rigid)
211
212    Dnew = 2e-4*Knew #add little bit of damping
213    fNew = np.zeros(nODE2FFRF)
214
215    #+++++++++++++++++++++++++++++++++++++++++++++++++++++++
216    #FFRF constant matrices:
217    unit3D = np.eye(3)
218    Phit = np.kron(np.ones(nNodes),unit3D).T
219    PhitTM = Phit.T @ massMatrix
220
221    Mtt = Phit.T @ massMatrix @ Phit
222    Mnew[0:3,0:3] = Mtt
223    totalMass = Mtt[0,0] #must be diagonal matrix with mass in diagonal
224
225    xRef = nodes.flatten() #node reference values in single vector (can be added then to q[7:])
226    xRefTilde = ComputeSkewMatrix(xRef) #rfTilde without q
227
228    inertiaLocal = xRefTilde.T @ massMatrix @ xRefTilde
229    if False:
230        exu.Print("Phit=", Phit[0:6,:])
231        exu.Print("PhitTM=", PhitTM[0:3,0:6])
232        exu.Print("xRef=", xRef[0:6])
233        exu.Print("xRefTilde=", xRefTilde[0:6,:])
234
235        exu.Print("python inertiaLocal=", inertiaLocal)
236        exu.Print("python totalMass=", totalMass)
237        exu.Print("python Mtt=", Mtt)
238
239    #+++++++++++++++++++++++++++++++++++++++++++++++++++++++
240    #compute gravity term
241    g=np.array([0,-9.81,0]) #gravity vector
242    fGravRigid = list(totalMass*g)+[0,0,0,0]
243    #fGrav = np.array(fGravRigid + list((massMatrix @ Phit) @ g) ) #only local vector, without rotation
244    #exu.Print("fGrav=",fGrav)
245    #+++++++++++++++++++++++++++++++++++++++++++++++++++++++
246
247
248
249#    mbs.Reset()
250#background
251rect = [-0.3,-0.1,0.3,0.1] #xmin,ymin,xmax,ymax
252background = {'type':'Line', 'color':[0.1,0.1,0.8,1], 'data':[rect[0],rect[1],0, rect[2],rect[1],0, rect[2],rect[3],0, rect[0],rect[3],0, rect[0],rect[1],0]} #background
253oGround = mbs.AddObject(ObjectGround(referencePosition= [0,0,0]))
254mGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oGround, localPosition=p0))
255#exu.Print("goundMarker=", mGround)
256
257nodeList = []
258nRB = -1
259
260if useFFRF:
261    nRB = mbs.AddNode(NodeRigidBodyEP(referenceCoordinates=p0+list(ep0),
262                                      initialVelocities=v0+list(ep_t0)))
263    nodeList += [nRB]
264
265
266    #adjust node numbers:
267    #in all cases, triglist is same; elements = elements  + 1 - decFFRFobject #increase node numbers, because of FFRFnode
268
269    #boundary nodes not adjusted for old constraints in
270    nLeft += 1
271    nRight += 1
272    nMid += 1
273    nForce += 1
274    nTopMid += 1
275
276for node in nodes:
277    n3 = mbs.AddNode(Point(referenceCoordinates = list(node), visualization=VNodePoint(show = not useFFRF))) #not useFFRF)))
278    nodeList += [n3]
279#+++++++++++++++++++++++++++++++++++++++++++++++++++++++
280
281
282
283
284#exu.Print("nForce=", nForce)
285
286#conventional user function:
287def UFforce(mbs, t, itemIndex, q, q_t):
288    force = np.zeros(nODE2FFRF)
289    Avec = mbs.GetNodeOutput(nRB,  exu.OutputVariableType.RotationMatrix)
290    A = Avec.reshape((3,3))
291
292    #implementation for Euler Parameters (Glocal_t*theta_t=0)
293    ep = np.array(q[dim3D:nODE2rigid]) + ep0 #add reference values, q are only the change w.r.t. reference values!
294    G = EulerParameters2GLocal(ep)
295
296    cF_t = np.array(q_t[nODE2rigid:])         #velocities of flexible coordinates
297
298    rF = xRef + np.array(q[nODE2rigid:]) #nodal position
299
300    omega3D = G @ np.array(q_t[dim3D:nODE2rigid])
301    omega3Dtilde = Skew(omega3D)
302    omega = np.array(list(omega3D)*nNodes)
303    omegaTilde = np.kron(np.eye(nNodes),omega3Dtilde)
304
305    #squared angul. vel. matrix:
306    omega3Dtilde2 = Skew(omega3D) @ Skew(omega3D)
307    omegaTilde2 = np.kron(np.eye(nNodes),omega3Dtilde2)
308
309    if True: #for rotordynamics, we assume rigid body motion with constant ang. vel.
310        #these 2 terms are computationally costly:
311        rfTilde = ComputeSkewMatrix(rF) #rfTilde
312        cF_tTilde = ComputeSkewMatrix(cF_t)
313
314        fTrans = A @ (omega3Dtilde @ PhitTM @ rfTilde @ omega3D + 2*PhitTM @ cF_tTilde @ omega3D)
315        force[0:dim3D] = fTrans
316
317        fRot = -G.T@(omega3Dtilde @ rfTilde.T @ massMatrix @ rfTilde @ omega3D +
318                        2*rfTilde.T @ massMatrix @ cF_tTilde @ omega3D)
319        force[dim3D:nODE2rigid] = fRot
320
321    fFlex = -massMatrix @ (omegaTilde2 @ rF + 2*(omegaTilde @ cF_t))
322    force[nODE2rigid:] = fFlex
323
324    #add gravity:
325    if False:
326        fGrav = np.array(fGravRigid + list(PhitTM.T @ (A.T @ g)) ) #only local vector, without rotation
327        force += fGrav
328
329
330    return force
331
332#ffrf mass matrix:
333def UFmassGenericODE2(mbs, t, itemIndex, q, q_t):
334    Avec = mbs.GetNodeOutput(nRB,  exu.OutputVariableType.RotationMatrix)
335    A = Avec.reshape((3,3))
336    ep = q[dim3D:nODE2rigid] + ep0 #add reference values, q are only the change w.r.t. reference values!
337    G = EulerParameters2GLocal(ep)
338
339    rF = xRef + q[nODE2rigid:] #nodal position
340    rfTilde = ComputeSkewMatrix(rF) #rfTilde
341
342    #Mtr:
343    Mtr = -A @ PhitTM @ rfTilde @ G
344    Mnew[0:dim3D, dim3D:dim3D+nODE2rot] = Mtr
345    Mnew[dim3D:dim3D+nODE2rot, 0:dim3D] = Mtr.T
346    #Mtf:
347    Mtf = A @ PhitTM
348    Mnew[0:dim3D, nODE2rigid:] = Mtf
349    Mnew[nODE2rigid:, 0:dim3D] = Mtf.T
350    #Mrf:
351    Mrf = -G.T @ rfTilde.T @ massMatrix
352    Mnew[dim3D:dim3D+nODE2rot, nODE2rigid:] = Mrf
353    Mnew[nODE2rigid:, dim3D:dim3D+nODE2rot] = Mrf.T
354    #Mrr:
355    Mnew[dim3D:dim3D+nODE2rot, dim3D:dim3D+nODE2rot] = -Mrf @ rfTilde @ G   #G.T @ rfTilde.T @ massMatrix @ rfTilde @ G
356
357    #exu.Print(np.linalg.norm(rF))
358    #omega3D = G @ q_t[dim3D:nODE2rigid]
359    #exu.Print(omega3D)
360
361    #exu.Print("Mtt Mtr Mtf=",Mnew[0:3,0:10].round(5))
362    #exu.Print("Mrr=",Mnew[3:7,3:7].round(5))
363    #exu.Print("Mff=",Mnew[7:10,7:13].round(5))
364    #Mnew[:,:] = 0 #for testing
365    return Mnew
366
367
368#convert elements to triangles for drawing:
369trigList = []
370for element in elements:
371    trigList += ConvertHexToTrigs(element)
372trigList = np.array(trigList)
373#exu.Print("trig list=", trigList)
374#exu.Print("trig list size=", trigList.shape)
375
376stiffnessMatrixFF = exu.MatrixContainer()
377stiffnessMatrixFF.SetWithDenseMatrix(stiffnessMatrix,useDenseMatrix=False)
378massMatrixFF = exu.MatrixContainer()
379massMatrixFF.SetWithDenseMatrix(massMatrix,useDenseMatrix=False)
380emptyMC = exu.MatrixContainer()
381
382#add generic body for FFRF-Object:
383if useFFRFobject:
384    oGenericODE2 = mbs.AddObject(ObjectFFRF(nodeNumbers = nodeList,
385                                                    #massMatrixFF=Mnew,
386                                                    stiffnessMatrixFF=stiffnessMatrixFF,
387                                                    #dampingMatrixFF=Dnew,
388                                                    massMatrixFF=massMatrixFF,
389                                                    #dampingMatrixFF=emptyMC,
390                                                    #forceVector=fNew, #now is a global vector!
391                                                    #forceUserFunction=UFforce,
392                                                    #computeFFRFterms=True,
393                                                    #massMatrixUserFunction=UFmassGenericODE2,
394                                                    visualization=VObjectFFRF(triangleMesh = trigList,
395                                                                              color=graphics.color.lightred,
396                                                                              showNodes = True)))
397else:
398    oGenericODE2 = mbs.AddObject(ObjectGenericODE2(nodeNumbers = nodeList,
399                                                    massMatrix=Mnew,
400                                                    stiffnessMatrix=Knew,
401                                                    dampingMatrix=Dnew,
402                                                    forceVector=fNew, forceUserFunction=UFforce,
403                                                    useFirstNodeAsReferenceFrame=True, #does not exist anymore
404                                                    massMatrixUserFunction=UFmassGenericODE2,
405                                                    visualization=VObjectGenericODE2(triangleMesh = trigList,
406                                                                                     color=graphics.color.lightred,
407                                                                                     showNodes = True)))
408
409if nODE2rot == 4: #for euler parameters --> add body to constrain EP
410    epsMass = 1e-3#needed, if not all ffrf terms are included
411    #add rigid body to node for Euler Parameter constraint:
412    nReferenceFrame = mbs.AddObject(ObjectRigidBody(nodeNumber=nRB, physicsMass=epsMass, physicsInertia=[epsMass,epsMass,epsMass,0,0,0]))
413
414mRB = mbs.AddMarker(MarkerNodeRigid(nodeNumber=nRB))
415#exu.Print("rigidNodeMarker=", mRB)
416
417
418#mbs.AddLoad(Torque(markerNumber=mRB, loadVector=[0,0,100*2*pi])) #add drive for reference frame
419
420if False: #OPTIONAL: lock rigid body motion of reference frame (for tests):
421    mbs.AddObject(GenericJoint(markerNumbers=[mGround, mRB], constrainedAxes=[1,1,1, 1,1,0]))
422
423
424
425#ground point:
426nGroundLeft = mbs.AddNode(NodePointGround(referenceCoordinates=[0,0,minZ], visualization = VNodePointGround(show=False))) #ground node for coordinate constraint
427nGroundRight = mbs.AddNode(NodePointGround(referenceCoordinates=[0,0,maxZ], visualization = VNodePointGround(show=False))) #ground node for coordinate constraint
428
429mGroundLeft = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber = nGroundLeft, coordinate=0)) #Ground node ==> no action
430mGroundRight = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber = nGroundRight, coordinate=0)) #Ground node ==> no action
431
432mGroundPosLeft = mbs.AddMarker(MarkerNodePosition(nodeNumber = nGroundLeft)) #Ground node ==> no action
433mGroundPosRight = mbs.AddMarker(MarkerNodePosition(nodeNumber = nGroundRight)) #Ground node ==> no action
434
435#exu.Print("ground Node/Coordinate Markers =", mGroundLeft, "...", mGroundPosRight)
436
437#++++++++++++++++++++++++++++++++++++++++++
438#find nodes at left and right surface:
439nodeListLeft = []
440nodeListRight = []
441
442for i in range(len(nodes)):
443    n = nodes[i]
444    if abs(n[2] - minZ) < 1e-6:
445        nodeListLeft += [i+useFFRF] #add 1 for rigid body node, which is first node in GenericODE2 object
446    elif abs(n[2] - maxZ) < 1e-6:
447        nodeListRight += [i+useFFRF]
448
449#exu.Print("nodeListLeft =",nodeListLeft)
450#exu.Print("nodeListRight =",nodeListRight)
451
452lenLeft = len(nodeListLeft)
453lenRight = len(nodeListRight)
454weightsLeft = np.array((1./lenLeft)*np.ones(lenLeft))
455weightsRight = np.array((1./lenRight)*np.ones(lenRight))
456
457#exu.Print("nodeLeft =",nLeft)
458#exu.Print("nodeRight =",nRight)
459
460#lock FFRF reference frame:
461for i in range(3):
462    mLeft = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber = nLeft, coordinate=i))
463#    exu.Print("mLeftCoord=", mLeft)
464
465    mbs.AddObject(CoordinateConstraint(markerNumbers=[mGroundLeft,mLeft]))
466    if i != 2: #exclude double constraint in z-direction (axis)
467        mRight = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber = nRight, coordinate=i))
468#        exu.Print("mRightCoord=", mRight)
469        mbs.AddObject(CoordinateConstraint(markerNumbers=[mGroundRight,mRight]))
470
471#lock rotation (also needed in FFRF):
472mTopRight = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber = nTopMid, coordinate=0)) #x-coordinate of node with y-max
473#exu.Print("mTopRight=", mTopRight)
474mbs.AddObject(CoordinateConstraint(markerNumbers=[mGroundRight,mTopRight]))
475
476addSupports = True
477if addSupports:
478    k = 2e8
479    d = k*0.01
480
481    useSpringDamper = True
482
483    if testMode == 0:
484        raise ValueError('does not exist any more')
485        # mLeft = mbs.AddMarker(MarkerGenericBodyPosition(bodyNumber=oGenericODE2,
486        #                                                 nodeNumbers=nodeListLeft,
487        #                                                 weightingFactors=weightsLeft,
488        #                                                 useFirstNodeAsReferenceFrame=useFFRF))
489        # mRight = mbs.AddMarker(MarkerGenericBodyPosition(bodyNumber=oGenericODE2,
490        #                                                 nodeNumbers=nodeListRight,
491        #                                                 weightingFactors=weightsRight,
492        #                                                 useFirstNodeAsReferenceFrame=useFFRF))
493    else:
494        mLeft = mbs.AddMarker(MarkerSuperElementPosition(bodyNumber=oGenericODE2,
495                                                        meshNodeNumbers=np.array(nodeListLeft)-1, #these are the meshNodeNumbers
496                                                        weightingFactors=weightsLeft))
497        mRight = mbs.AddMarker(MarkerSuperElementPosition(bodyNumber=oGenericODE2,
498                                                        meshNodeNumbers=np.array(nodeListRight)-1, #these are the meshNodeNumbers
499                                                        weightingFactors=weightsRight))
500
501    if useSpringDamper:
502        oSJleft = mbs.AddObject(CartesianSpringDamper(markerNumbers=[mLeft, mGroundPosLeft],
503                                            stiffness=[k,k,k], damping=[d,d,d]))
504        oSJright = mbs.AddObject(CartesianSpringDamper(markerNumbers=[mRight,mGroundPosRight],
505                                            stiffness=[k,k,0], damping=[d,d,d]))
506    else:
507        oSJleft = mbs.AddObject(SphericalJoint(markerNumbers=[mGroundPosLeft,mLeft], visualization=VObjectJointSpherical(jointRadius=nodeDrawSize)))
508        oSJright= mbs.AddObject(SphericalJoint(markerNumbers=[mGroundPosRight,mRight], visualization=VObjectJointSpherical(jointRadius=nodeDrawSize)))
509
510
511fileDir = 'solution/'
512sDisp=mbs.AddSensor(SensorSuperElement(bodyNumber=oGenericODE2, meshNodeNumber=nMid-1, #meshnode is -1
513                         storeInternal=True,#fileName=fileDir+'nMidDisplacement'+modeNames[testMode]+'test.txt',
514                         outputVariableType = exu.OutputVariableType.Displacement))
515
516
517#exu.Print(mbs)
518mbs.Assemble()
519
520#exu.Print("ltg GenericODE2 left =", mbs.systemData.GetObjectLTGODE2(oSJleft))
521#exu.Print("ltg GenericODE2 right=", mbs.systemData.GetObjectLTGODE2(oSJright))
522
523simulationSettings = exu.SimulationSettings()
524
525SC.visualizationSettings.nodes.defaultSize = nodeDrawSize
526SC.visualizationSettings.nodes.drawNodesAsPoint = False
527SC.visualizationSettings.connectors.defaultSize = 2*nodeDrawSize
528
529SC.visualizationSettings.nodes.show = True
530SC.visualizationSettings.nodes.showBasis = True #of rigid body node of reference frame
531SC.visualizationSettings.nodes.basisSize = 0.12
532SC.visualizationSettings.bodies.deformationScaleFactor = 10
533
534SC.visualizationSettings.openGL.showFaceEdges = True
535SC.visualizationSettings.openGL.showFaces = True
536
537SC.visualizationSettings.sensors.show = True
538SC.visualizationSettings.sensors.drawSimplified = False
539SC.visualizationSettings.sensors.defaultSize = 0.01
540SC.visualizationSettings.markers.drawSimplified = False
541SC.visualizationSettings.markers.show = True
542SC.visualizationSettings.markers.defaultSize = 0.01
543
544SC.visualizationSettings.loads.drawSimplified = False
545
546SC.visualizationSettings.contour.outputVariable = exu.OutputVariableType.Displacement
547SC.visualizationSettings.contour.outputVariableComponent = 2 #z-component
548
549simulationSettings.solutionSettings.solutionInformation = modeNames[testMode]
550simulationSettings.solutionSettings.writeSolutionToFile=False
551
552h=1e-4
553tEnd = 0.001
554simulationSettings.timeIntegration.numberOfSteps = int(tEnd/h)
555simulationSettings.timeIntegration.endTime = tEnd
556simulationSettings.solutionSettings.solutionWritePeriod = h
557simulationSettings.timeIntegration.verboseMode = 1
558simulationSettings.timeIntegration.newton.useModifiedNewton = True
559#simulationSettings.timeIntegration.newton.maxModifiedNewtonIterations = 10
560#simulationSettings.timeIntegration.newton.modifiedNewtonJacUpdatePerStep = True #this improves the FFRF simulation slightly
561
562simulationSettings.solutionSettings.sensorsWritePeriod = h
563
564simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.5 #SHOULD work with 0.9 as well
565#simulationSettings.displayStatistics = True
566#simulationSettings.displayComputationTime = True
567
568#create animation:
569#simulationSettings.solutionSettings.recordImagesInterval = 0.0002
570#SC.visualizationSettings.exportImages.saveImageFileName = "animation/frame"
571
572if useGraphics:
573    exu.StartRenderer()
574    if 'lastRenderState' in vars():
575        SC.SetRenderState(lastRenderState) #load last model view
576
577    mbs.WaitForUserToContinue() #press space to continue
578
579mbs.SolveDynamic(simulationSettings)
580
581data = mbs.GetSensorStoredData(sDisp)
582#data = np.loadtxt(fileDir+'nMidDisplacement'+modeNames[testMode]+'test.txt', comments='#', delimiter=',')
583result = abs(data).sum()
584#pos = mbs.GetObjectOutputBody(objFFRF['oFFRFreducedOrder'],exu.OutputVariableType.Position, localPosition=[0,0,0])
585exu.Print('solution of ObjectFFRF=',result)
586
587exudynTestGlobals.testError = result - (0.0064600108120842666) #2022-02-20 (changed to internal sensor data); 2020-05-17 (tEnd=0.001, h=1e-4): 0.006445369560936511
588exudynTestGlobals.testResult = result#0.006460010812070858
589
590
591if useGraphics:
592    SC.WaitForRenderEngineStopFlag()
593    exu.StopRenderer() #safely close rendering window!
594    lastRenderState = SC.GetRenderState() #store model view for next simulation
595
596##++++++++++++++++++++++++++++++++++++++++++++++q+++++++
597#plot results
598cList=['r-','g-','b-','k-','c-','r:','g:','b:','k:','c:']
599if useGraphics:
600
601
602    mbs.PlotSensor(sDisp, components=0, closeAll=True)