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