beltDriveReevingSystem.py

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

  1 #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  2# This is an EXUDYN example
  3#
  4# Details:  Model for belt drive; According to thread deliverable D2.2 Test case
  5#
  6# Author:   Johannes Gerstmayr
  7# Date:     2022-02-27
  8#
  9# 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.
 10#
 11#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 12
 13import exudyn as exu
 14from exudyn.itemInterface import *
 15from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
 16import exudyn.graphics as graphics #only import if it does not conflict
 17from exudyn.beams import *
 18
 19import numpy as np
 20from math import sin, cos, pi, sqrt , asin, acos, atan2, exp
 21import copy
 22
 23
 24SC = exu.SystemContainer()
 25mbs = SC.AddSystem()
 26
 27#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 28
 29improvedBelt = True #True: improved belt model (tEnd ~= 2.5 seconds simulation, more damping, better initial conditions, etc.)
 30
 31#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 32#Parameters for the belt
 33gVec = [0,-9.81*1,0]     # gravity
 34Emodulus=1e7*1           # Young's modulus of ANCF element in N/m^2
 35b=0.08 #0.002            # width of rectangular ANCF element in m
 36hc = 0.01                # height (geometric) of rectangular ANCF element in m
 37hcStiff = 0.01           # stiffness relevant height
 38rhoBeam=1036.            # density of ANCF element in kg/m^3
 39A=b*hcStiff              # cross sectional area of ANCF element in m^2
 40I=(b*hcStiff**3)/12      # second moment of area of ANCF element in m^4
 41EI = Emodulus*I
 42EA = Emodulus*A
 43rhoA = rhoBeam*A
 44dEI = 0*1e-3*Emodulus*I         #REMARK: bending proportional damping. Set zero in the 2013 paper there is not. We need the damping for changing the initial configuration.
 45#dEA = 0.1*1e-2*Emodulus*A          #axial strain proportional damping. Same as for the
 46dEA = 1 #dEA=1 in paper PechsteinGerstmayr 2013, according to HOTINT C++ files ...
 47# bending damping.
 48#%%
 49
 50
 51#%%
 52#settings:
 53useGraphics= True
 54useContact = True
 55doDynamic = True
 56makeAnimation = False
 57velocityControl = True
 58staticEqulibrium = False #False in 2013 paper; starts from pre-deformed reference configuration
 59useBristleModel = improvedBelt
 60
 61#in 2013 paper, reference curvature is set according to initial geometry and released until tAccStart
 62preCurved = False #uses preCurvature according to straight and curved initial segments
 63strainIsRelativeToReference = 1. #0: straight reference, 1.: curved reference
 64useContactCircleFriction = True
 65
 66movePulley = False #as in 2013 paper, move within first 0.05 seconds; but this does not work with Index 2 solver
 67
 68tEnd = 1#1*2.25#*0.1 #*5 #end time of dynamic simulation
 69stepSize = 0.25*1e-4  #accurate: 2.5e-5 # for frictionVelocityPenalty = 1e7*... it must be not larger than 2.5e-5
 70if improvedBelt:
 71    stepSize = 1e-4
 72discontinuousIterations = 3 #larger is more accurate, but smaller step size is equivalent
 73
 74#h = 1e-3 #step size
 75tAccStart = 0.05
 76tAccEnd = 0.6
 77omegaFinal = 12
 78
 79useFriction = True
 80dryFriction = 0.5#0.5#1.2
 81contactStiffness = 1e8#2e5
 82contactDamping = 0#1e-3*contactStiffness
 83
 84nSegments = 2 #4, for nANCFnodes=60, nSegments = 2 lead to less oscillations inside, but lot of stick-slip...
 85nANCFnodes = 8*30#2*60#120 works well, 60 leads to oscillatory tangent/normal forces for improvedBelt=True
 86
 87wheelMass = 50#1 the wheel mass is not given in the paper, only the inertia
 88# for the second pulley
 89wheelInertia = 0.25#0.01
 90rotationDampingWheels = 0 #zero in example in 2013 paper; torque proportional to rotation speed
 91
 92#torque = 1
 93
 94#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 95#create circles
 96#complicated shape:
 97initialDisplacement = -0.0025 #not used in improvedBelt!
 98initialDisplacement0 = initialDisplacement*int(1-movePulley) #this is set at t=0
 99
100#h = 0.25e-3
101radiusPulley = 0.09995
102positionPulley2x = 0.1*pi
103#preStretch = -1*(pi*0.4099+0.005)/ pi*0.4099
104initialDistance = positionPulley2x - 0
105initialLength = 2*initialDistance +2* pi*(radiusPulley + hcStiff/2)
106finalLength = initialLength - 2* initialDisplacement0
107preStretch = -(finalLength - initialLength)/ initialLength
108
109factorStriplen = (2*initialDistance+2*pi*radiusPulley)/(2*initialDistance+2*pi*(radiusPulley + hcStiff/2));
110print('factorStriplen =', factorStriplen )
111
112preStretch += (1-1./factorStriplen) #this is due to an error in the original paper 2013
113
114
115if improvedBelt:
116    rotationDampingWheels = 2 #to reduce vibrations of driven pulley
117    tEnd = 2.45 #at 2.45 node 1 is approximately at initial position!
118    preStretch = -0.05
119    initialDisplacement0 = 0
120    staticEqulibrium = True
121    strainIsRelativeToReference = False
122    #dryFriction = 0
123    hc *= 0.01
124    EI *= 0.02
125
126print('preStretch=', preStretch)
127circleList = [[[initialDisplacement0,0], radiusPulley,'L'],
128              [[positionPulley2x,0], radiusPulley,'L'],
129              # [[initialDisplacement0,0], radiusPulley,'L'],
130              # [[positionPulley2x,0], radiusPulley,'L'],
131              ]
132
133#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
134#create geometry:
135reevingDict = CreateReevingCurve(circleList, drawingLinesPerCircle = 64,
136                                radialOffset=0.5*hc, closedCurve=True, #allows closed curve
137                                numberOfANCFnodes=nANCFnodes, graphicsNodeSize= 0.01)
138
139
140
141# set precurvature at location of pulleys:
142elementCurvatures = [] #no pre-curvatures
143if preCurved:
144    elementCurvatures = reevingDict['elementCurvatures']
145
146gList=[]
147if False: #visualize reeving curve, without simulation
148    gList = reevingDict['graphicsDataLines'] + reevingDict['graphicsDataCircles']
149
150oGround=mbs.AddObject(ObjectGround(referencePosition= [0,0,0], visualization=VObjectGround(show=False)))#, visualization = {'show : False'}
151nGround = mbs.AddNode(NodePointGround())
152mCoordinateGround = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=nGround, coordinate=0))
153
154
155#mbs.SetObjectParameter(objectNumber = oGround, parameterName = 'Vshow', value=False)
156#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
157#create ANCF elements:
158dimZ = b #z.dimension
159
160cableTemplate = Cable2D(#physicsLength = L / nElements, #set in GenerateStraightLineANCFCable2D(...)
161                        physicsMassPerLength = rhoA,
162                        physicsBendingStiffness = EI,
163                        physicsAxialStiffness = EA,
164                        physicsBendingDamping = dEI,
165                        physicsAxialDamping = dEA,
166                        physicsReferenceAxialStrain = preStretch*int(improvedBelt), #prestretch
167                        physicsReferenceCurvature = 0.,#-1/(radiusPulley + hc/2),
168                        useReducedOrderIntegration = 2, #2=improved axial strain in postprocessing!
169                        strainIsRelativeToReference = strainIsRelativeToReference,
170                        visualization=VCable2D(drawHeight=hc),
171                        )
172
173ancf = PointsAndSlopes2ANCFCable2D(mbs, reevingDict['ancfPointsSlopes'],
174                                   reevingDict['elementLengths'],
175                                   cableTemplate, massProportionalLoad=gVec,
176                                   fixedConstraintsNode0=[1*staticEqulibrium,0,0,0], #fixedConstraintsNode1=[1,1,1,1],
177                                   elementCurvatures  = elementCurvatures,
178                                   firstNodeIsLastNode=True, graphicsSizeConstraints=0.01)
179
180if useContactCircleFriction:
181    lElem = reevingDict['totalLength'] / nANCFnodes
182    cFact=b*lElem/nSegments #stiffness shall be per area, but is applied at every segment
183    print('cFact=',cFact, ', lElem=', lElem)
184
185    contactStiffness*=cFact
186    contactDamping = 2000*cFact #according to Dufva 2008 paper ... seems also to be used in 2013 PEchstein Gerstmayr
187    if useBristleModel:
188        frictionStiffness = 1e8*cFact #1e7 converges good; 1e8 is already quite accurate
189        massSegment = rhoA*lElem/nSegments
190        frictionVelocityPenalty = 1*sqrt(frictionStiffness*massSegment) #bristle damping; should be adjusted to reduce vibrations induced by bristle model
191    else:
192        frictionVelocityPenalty = 0.1*1e7*cFact #1e7 is original in 2013 paper; requires smaller time step
193        #frictionVelocityPenalty = 0.25e7*cFact # 0.25e7*cFact  with  discontinuous.maxIterations = 4
194        frictionStiffness = 0 #as in 2013 paper
195
196if improvedBelt:
197    frictionStiffness *= 10*5
198    frictionVelocityPenalty *= 10
199    contactStiffness *= 10*4
200    contactDamping *=10*4
201#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
202#create sensors for all nodes
203sMidVel = []
204sAxialForce = []
205sCable0Pos = []
206# sObjectDisp =[]
207
208ancfNodes = ancf[0]
209ancfObjects = ancf[1]
210positionList2Node = [] #axial position at x=0 and x=0.5*lElem
211positionListMid = [] #axial position at midpoint of element
212positionListSegments = [] #axial position at midpoint of segments
213currentPosition = 0 #is increased at every iteration
214for i,obj in enumerate(ancfObjects):
215    lElem = reevingDict['elementLengths'][i]
216    positionList2Node += [currentPosition, currentPosition + 0.5*lElem]
217    positionListMid += [currentPosition + 0.5*lElem]
218
219    for j in range(nSegments):
220        segPos = (j+0.5)*lElem/nSegments + currentPosition
221        positionListSegments += [segPos]
222    currentPosition += lElem
223
224    sAxialForce += [mbs.AddSensor(SensorBody(bodyNumber = obj,
225                                              storeInternal=True,
226                                              localPosition=[0.*lElem,0,0],
227                                              outputVariableType=exu.OutputVariableType.ForceLocal))]
228    sAxialForce += [mbs.AddSensor(SensorBody(bodyNumber = obj,
229                                              storeInternal=True,
230                                              localPosition=[0.5*lElem,0,0],
231                                              outputVariableType=exu.OutputVariableType.ForceLocal))]
232    sMidVel += [mbs.AddSensor(SensorBody(bodyNumber = obj,
233                                          storeInternal=True,
234                                          localPosition=[0.5*lElem,0,0], #0=at left node
235                                          outputVariableType=exu.OutputVariableType.VelocityLocal))]
236    sCable0Pos += [mbs.AddSensor(SensorBody(bodyNumber = obj,
237                                            storeInternal=True,
238                                            localPosition=[0.*lElem,0,0],
239                                            outputVariableType=exu.OutputVariableType.Position))]
240    # sObjectDisp += [mbs.AddSensor(SensorBody(bodyNumber = obj,
241    #                                           storeInternal=True,
242    #                                           localPosition=[0.5*lElem,0,0],
243    #                                           outputVariableType=exu.OutputVariableType.Displacement))]
244
245
246#for testing, fix two nodes:
247if False:
248    ii0 = 1
249    ii1 = 14
250    for i in range(4):
251        mANCF0 = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=ancfNodes[ii0], coordinate=i))
252        mANCF1 = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=ancfNodes[ii1], coordinate=i))
253        mbs.AddObject(CoordinateConstraint(markerNumbers=[mCoordinateGround, mANCF0],
254                                           visualization=VCoordinateConstraint(show = False)))
255        mbs.AddObject(CoordinateConstraint(markerNumbers=[mCoordinateGround, mANCF1],
256                                           visualization=VCoordinateConstraint(show = False)))
257
258    #reference solution for clamped-clamped beam:
259    lElem = reevingDict['elementLengths'][0] #all same
260    L = lElem * 13 #span is 13 elements long
261    wMax = rhoA*9.81*L**4 /(384*EI)
262    print('wMax=',wMax)
263
264#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
265#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
266#add contact:
267if useContact:
268
269    contactObjects = [[],[]] #list of contact objects
270
271    gContact = mbs.AddGeneralContact()
272    gContact.verboseMode = 1
273
274    gContact.frictionProportionalZone = 0.005 #limit velocity. I didn't find
275    #gContact.frictionVelocityPenalty = 0*1e3   #limit velocity. I didn't find
276    #this in the paper
277    gContact.ancfCableUseExactMethod = False
278    gContact.ancfCableNumberOfContactSegments = nSegments
279    ssx = 16#32 #search tree size
280    ssy = 16#32 #search tree size
281    ssz = 1 #search tree size
282    gContact.SetSearchTreeCellSize(numberOfCells=[ssx,ssy,ssz])
283    #gContact.SetSearchTreeBox(pMin=np.array([-1,-1,-1]), pMax=np.array([4,1,1])) #automatically computed!
284
285    dimZ= 0.01 #for drawing
286    sWheelRot = [] #sensors for angular velocity
287
288    nMassList = []
289    wheelSprings = [] #for static computation
290    for i, wheel in enumerate(circleList):
291        p = [wheel[0][0], wheel[0][1], 0] #position of wheel center
292        r = wheel[1]
293
294        rot0 = 0 #initial rotation
295        pRef = [p[0], p[1], rot0]
296        gList = [graphics.Cylinder(pAxis=[0,0,-dimZ],vAxis=[0,0,-dimZ], radius=r,
297                                      color= graphics.color.dodgerblue, nTiles=64),
298                 graphics.Arrow(pAxis=[0,0,0], vAxis=[-0.9*r,0,0], radius=0.01*r, color=graphics.color.orange),
299                 graphics.Arrow(pAxis=[0,0,0], vAxis=[0.9*r,0,0], radius=0.01*r, color=graphics.color.orange)]
300
301        omega0 = 0 #initial angular velocity
302        v0 = np.array([0,0,omega0])
303
304        nMass = mbs.AddNode(NodeRigidBody2D(referenceCoordinates=pRef, initialVelocities=v0,
305                                            visualization=VNodeRigidBody2D(drawSize=dimZ*2)))
306        nMassList += [nMass]
307        oMass = mbs.AddObject(ObjectRigidBody2D(physicsMass=wheelMass, physicsInertia=wheelInertia,
308                                                nodeNumber=nMass, visualization=
309                                                VObjectRigidBody2D(graphicsData=gList)))
310        mNode = mbs.AddMarker(MarkerNodeRigid(nodeNumber=nMass))
311        mGroundWheel = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oGround, localPosition=p, visualization = VMarkerBodyRigid(show = False)))
312
313        #mbs.AddObject(RevoluteJoint2D(markerNumbers=[mGroundWheel, mNode], visualization=VRevoluteJoint2D(show=False)))
314
315        mCoordinateWheelX = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=nMass, coordinate=0))
316        mCoordinateWheelY = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=nMass, coordinate=1))
317        constraintX = mbs.AddObject(CoordinateConstraint(markerNumbers=[mCoordinateGround, mCoordinateWheelX],
318                                                 visualization=VCoordinateConstraint(show = False)))
319        constraintY = mbs.AddObject(CoordinateConstraint(markerNumbers=[mCoordinateGround, mCoordinateWheelY],
320                                                 visualization=VCoordinateConstraint(show = False)))
321        if i==0:
322            constraintPulleyLeftX = constraintX
323
324        if True:
325
326            sWheelRot += [mbs.AddSensor(SensorNode(nodeNumber=nMass,
327                                                   storeInternal=True,
328                                                   fileName='solutionDelete/wheel'+str(i)+'angVel.txt',
329                                                   outputVariableType=exu.OutputVariableType.AngularVelocity))]
330        tdisplacement = 0.05
331
332
333        def UFvelocityDrive(mbs, t, itemNumber, lOffset): #time derivative of UFoffset
334            if t < tAccStart:
335                v = 0
336            if t >= tAccStart and t < tAccEnd:
337                v = omegaFinal/(tAccEnd-tAccStart)*(t-tAccStart)
338            elif t >= tAccEnd:
339                v = omegaFinal
340            return v
341
342        if doDynamic:
343            if i == 0:
344                if velocityControl:
345                    mCoordinateWheel = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=nMass, coordinate=2))
346                    velControl = mbs.AddObject(CoordinateConstraint(markerNumbers=[mCoordinateGround, mCoordinateWheel],
347                                                        velocityLevel=True, offsetUserFunction_t= UFvelocityDrive,
348                                                        visualization=VCoordinateConstraint(show = False)))#UFvelocityDrive
349            if i == 1:
350                mCoordinateWheel = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=nMass, coordinate=2))
351                mbs.AddObject(CoordinateSpringDamper(markerNumbers=[mCoordinateGround, mCoordinateWheel],
352                                                     damping = rotationDampingWheels,
353                                                     visualization=VCoordinateSpringDamper(show = False)))
354
355                #this is used for times > 1 in order to see influence of torque step in Wheel1
356                def UFforce(mbs, t, load):
357                    tau = 0.
358                    tau +=  25.*(SmoothStep(t, 1., 1.5, 0., 1.) - SmoothStep(t, 3.5, 4., 0., 1.))
359                    #tau += 16.*(SmoothStep(t, 5, 5.5, 0., 1.) - SmoothStep(t, 7.5, 8., 0., 1.))
360                    return -tau
361
362                mbs.AddLoad(LoadCoordinate(markerNumber=mCoordinateWheel,
363                                           load = 0, loadUserFunction = UFforce))
364
365        if staticEqulibrium:
366            mCoordinateWheel = mbs.AddMarker(MarkerNodeCoordinate(nodeNumber=nMass, coordinate=2))
367            csd = mbs.AddObject(CoordinateConstraint(markerNumbers=[mCoordinateGround, mCoordinateWheel],
368                                                     visualization=VCoordinateConstraint(show = False)))
369            wheelSprings += [csd]
370
371
372        frictionMaterialIndex=0
373        gContact.AddSphereWithMarker(mNode, radius=r, contactStiffness=contactStiffness,
374                                     contactDamping=contactDamping, frictionMaterialIndex=frictionMaterialIndex)
375
376        if not useContactCircleFriction:
377            for oIndex in ancf[1]:
378                gContact.AddANCFCable(objectIndex=oIndex, halfHeight= hc/2, #halfHeight should be h/2, but then cylinders should be smaller
379                                      contactStiffness=contactStiffness, contactDamping=contactDamping,
380                                      frictionMaterialIndex=0)
381        else:
382            cableList = ancf[1]
383            mCircleBody = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oMass))
384            #mCircleBody = mbs.AddMarker(MarkerNodeRigid(nodeNumber=nMass))
385            for k in range(len(cableList)):
386                initialGapList = [0.1]*nSegments + [-2]*(nSegments) + [0]*(nSegments) #initial gap of 0., isStick (0=slip, +-1=stick, -2 undefined initial state), lastStickingPosition (0)
387
388                mCable = mbs.AddMarker(MarkerBodyCable2DShape(bodyNumber=cableList[k],
389                                                              numberOfSegments = nSegments, verticalOffset=-hc/2))
390                nodeDataContactCable = mbs.AddNode(NodeGenericData(initialCoordinates=initialGapList,
391                                                                   numberOfDataCoordinates=nSegments*(1+2) ))
392
393                co = mbs.AddObject(ObjectContactFrictionCircleCable2D(markerNumbers=[mCircleBody, mCable], nodeNumber = nodeDataContactCable,
394                                                         numberOfContactSegments=nSegments,
395                                                         contactStiffness = contactStiffness,
396                                                         contactDamping=contactDamping,
397                                                         frictionVelocityPenalty = frictionVelocityPenalty,
398                                                         frictionStiffness = frictionStiffness,
399                                                         frictionCoefficient=int(useFriction)*dryFriction,
400                                                         circleRadius = r,
401                                                         visualization=VObjectContactFrictionCircleCable2D(showContactCircle=False)))
402                contactObjects[i] += [co]
403
404    frictionMatrix = np.zeros((2,2))
405    frictionMatrix[0,0]=int(useFriction)*dryFriction
406    frictionMatrix[0,1]=0 #no friction between some rolls and cable
407    frictionMatrix[1,0]=0 #no friction between some rolls and cable
408    gContact.SetFrictionPairings(frictionMatrix)
409
410
411#+++++++++++++++++++++++++++++++++++++++++++
412#create list of sensors for contact
413sContactDisp = [[],[]]
414sContactForce = [[],[]]
415for i in range(len(contactObjects)):
416    for obj in contactObjects[i]:
417        sContactForce[i] += [mbs.AddSensor(SensorObject(objectNumber = obj,
418                                                        storeInternal=True,
419                                                        outputVariableType=exu.OutputVariableType.ForceLocal))]
420        sContactDisp[i] += [mbs.AddSensor(SensorObject(objectNumber = obj,
421                                                        storeInternal=True,
422                                                        outputVariableType=exu.OutputVariableType.Coordinates))]
423
424
425
426#user function to smoothly transform from curved to straight reference configuration as
427#in paper 2013, Pechstein, Gerstmayr
428def PreStepUserFunction(mbs, t):
429
430    if True and t <= tAccStart+1e-10:
431        cableList = ancf[1]
432        fact = (tAccStart-t)/tAccStart #from 1 to 0
433        if fact < 1e-12: fact = 0. #for very small values ...
434        #curvatures = reevingDict['elementCurvatures']
435        #print('fact=', fact)
436        for i in range(len(cableList)):
437            oANCF = cableList[i]
438            mbs.SetObjectParameter(oANCF, 'strainIsRelativeToReference',
439                                   fact)
440            mbs.SetObjectParameter(oANCF, 'physicsReferenceAxialStrain',
441                                    preStretch*(1.-fact))
442
443        # if movePulley:
444        #     #WARNING: this does not work for Index2 solver:
445        #     mbs.SetObjectParameter(constraintPulleyLeftX, 'offset', initialDisplacement*(1.-fact))
446        #     #print('offset=', initialDisplacement*(1.-fact))
447
448    return True
449
450
451mbs.Assemble()
452
453
454simulationSettings = exu.SimulationSettings() #takes currently set values or default values
455
456simulationSettings.linearSolverType = exu.LinearSolverType.EigenSparse
457simulationSettings.solutionSettings.coordinatesSolutionFileName = 'solution_nosync/testCoords.txt'
458
459simulationSettings.solutionSettings.writeSolutionToFile = True
460simulationSettings.solutionSettings.solutionWritePeriod = 0.002
461simulationSettings.solutionSettings.sensorsWritePeriod = 0.001
462simulationSettings.displayComputationTime = True
463simulationSettings.parallel.numberOfThreads = 1 #use 4 to speed up for > 100 ANCF elements
464simulationSettings.displayStatistics = True
465
466simulationSettings.timeIntegration.endTime = tEnd
467simulationSettings.timeIntegration.numberOfSteps = int(tEnd/stepSize)
468simulationSettings.timeIntegration.stepInformation= 255
469
470simulationSettings.timeIntegration.verboseMode = 1
471
472simulationSettings.timeIntegration.newton.useModifiedNewton = True
473#simulationSettings.timeIntegration.newton.numericalDifferentiation.minimumCoordinateSize = 1
474#simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.5
475
476simulationSettings.timeIntegration.discontinuous.iterationTolerance = 1e-3
477simulationSettings.timeIntegration.discontinuous.maxIterations = discontinuousIterations #3
478
479simulationSettings.displayStatistics = True
480
481
482SC.visualizationSettings.general.circleTiling = 24
483SC.visualizationSettings.loads.show=False
484SC.visualizationSettings.sensors.show=False
485SC.visualizationSettings.markers.show=False
486SC.visualizationSettings.nodes.defaultSize = 0.002
487SC.visualizationSettings.openGL.multiSampling = 4
488SC.visualizationSettings.openGL.lineWidth = 2
489SC.visualizationSettings.window.renderWindowSize = [1920,1080]
490
491SC.visualizationSettings.connectors.showContact = True
492SC.visualizationSettings.contact.contactPointsDefaultSize = 0.0002
493SC.visualizationSettings.contact.showContactForces = True
494SC.visualizationSettings.contact.contactForcesFactor = 0.005
495
496if makeAnimation == True:
497    simulationSettings.solutionSettings.recordImagesInterval = 0.02
498    SC.visualizationSettings.exportImages.saveImageFileName = "animationNew/frame"
499
500
501if True:
502    SC.visualizationSettings.bodies.beams.axialTiling = 1
503    SC.visualizationSettings.bodies.beams.drawVertical = True
504    SC.visualizationSettings.bodies.beams.drawVerticalLines = True
505
506    SC.visualizationSettings.contour.outputVariableComponent=0
507    SC.visualizationSettings.contour.outputVariable=exu.OutputVariableType.ForceLocal
508    SC.visualizationSettings.bodies.beams.drawVerticalFactor = 0.001
509    SC.visualizationSettings.bodies.beams.drawVerticalOffset = -120
510    if improvedBelt:
511        SC.visualizationSettings.bodies.beams.drawVerticalFactor = 0.0003
512        SC.visualizationSettings.bodies.beams.drawVerticalOffset = -220
513
514    SC.visualizationSettings.bodies.beams.reducedAxialInterploation = True
515
516    # SC.visualizationSettings.contour.outputVariable=exu.OutputVariableType.VelocityLocal
517    # SC.visualizationSettings.bodies.beams.drawVerticalFactor = -0.25
518    # SC.visualizationSettings.bodies.beams.drawVerticalOffset = 0.30
519    # SC.visualizationSettings.bodies.beams.reducedAxialInterploation = False
520
521#visualize contact:
522if False:
523    SC.visualizationSettings.contact.showSearchTree =True
524    SC.visualizationSettings.contact.showSearchTreeCells =True
525    SC.visualizationSettings.contact.showBoundingBoxes = True
526
527if useGraphics:
528    exu.StartRenderer()
529    mbs.WaitForUserToContinue()
530
531#simulationSettings.staticSolver.newton.absoluteTolerance = 1e-10
532simulationSettings.staticSolver.adaptiveStep = False
533simulationSettings.staticSolver.loadStepGeometric = True;
534simulationSettings.staticSolver.loadStepGeometricRange=1e4
535simulationSettings.staticSolver.numberOfLoadSteps = 10
536#simulationSettings.staticSolver.useLoadFactor = False
537simulationSettings.staticSolver.stabilizerODE2term = 1e5
538simulationSettings.staticSolver.newton.relativeTolerance = 1e-6
539simulationSettings.staticSolver.newton.absoluteTolerance = 1e-6
540
541if staticEqulibrium: #precompute static equilibrium
542    mbs.SetObjectParameter(velControl, 'activeConnector', False)
543
544    for i in range(len(contactObjects)):
545        for obj in contactObjects[i]:
546            mbs.SetObjectParameter(obj, 'frictionCoefficient', 0.)
547            mbs.SetObjectParameter(obj, 'frictionStiffness', 1e-8) #do not set to zero, as it needs to do some initialization...
548
549    # simulationSettings.solutionSettings.appendToFile=False
550    mbs.SolveStatic(simulationSettings, updateInitialValues=True)
551    # simulationSettings.solutionSettings.appendToFile=True
552
553    #check total force on support, expect: supportLeftX \approx 2*preStretch*EA
554    supportLeftX = mbs.GetObjectOutput(constraintPulleyLeftX,variableType=exu.OutputVariableType.Force)
555    print('Force x in support of left pulley = ', supportLeftX)
556    print('Belt pre-tension=', preStretch*EA)
557
558    for i in range(len(contactObjects)):
559        for obj in contactObjects[i]:
560            mbs.SetObjectParameter(obj, 'frictionCoefficient', dryFriction)
561            mbs.SetObjectParameter(obj, 'frictionStiffness', frictionStiffness)
562
563    for coordinateConstraint in ancf[4]:
564        mbs.SetObjectParameter(coordinateConstraint, 'activeConnector', False)
565
566    mbs.SetObjectParameter(velControl, 'activeConnector', True)
567    for csd in wheelSprings:
568        mbs.SetObjectParameter(csd, 'activeConnector', False)
569else:
570    mbs.SetPreStepUserFunction(PreStepUserFunction)
571
572if True:
573    mbs.SolveDynamic(simulationSettings, solverType=exu.DynamicSolverType.TrapezoidalIndex2) #183 Newton iterations, 0.114 seconds
574#mbs.SolveDynamic(simulationSettings)
575
576if useGraphics and False:
577    SC.visualizationSettings.general.autoFitScene = False
578    SC.visualizationSettings.general.graphicsUpdateInterval=0.02
579
580    sol = LoadSolutionFile('solution_nosync/testCoords.txt', safeMode=True)#, maxRows=100)
581    mbs.SolutionViewer(sol)
582
583
584if useGraphics:
585    SC.WaitForRenderEngineStopFlag()
586    exu.StopRenderer() #safely close rendering window!
587
588
589#%%++++++++++++++++++++++++++++++++++++++++
590if False:
591    #shift data depending on axial position by subtracting xOff; put negative x values+shiftValue to end of array
592    def ShiftXoff(data, xOff, shiftValue):
593        indOff = 0
594        n = data.shape[0]
595        data[:,0] -= xOff
596        for i in range(n):
597           if data[i,0] < 0:
598               indOff+=1
599               data[i,0] += shiftValue
600        print('indOff=', indOff)
601        data = np.vstack((data[indOff:,:], data[0:indOff,:]))
602        return data
603
604    import matplotlib.pyplot as plt
605    import matplotlib.ticker as ticker
606    from exudyn.plot import DataArrayFromSensorList
607
608    mbs.PlotSensor(closeAll=True)
609
610    #compute axial offset, to normalize results:
611    nodePos0 = mbs.GetSensorValues(sCable0Pos[0])
612    xOff = nodePos0[0]
613    maxXoff = 0.5*positionPulley2x
614    maxYoff = 0.1*r
615    # indOff = 0 #single data per element
616    # indOff2 = 0 #double data per element
617    correctXoffset = True
618    if abs(nodePos0[1]-r) > maxYoff or nodePos0[0] > maxXoff or nodePos0[0] < -0.1*maxXoff:
619        print('*****************')
620        print('warning: final position not at top of belt or too far away')
621        print('nodePos0=',nodePos0)
622        print('*****************')
623        xOff = 0
624        correctXoffset = False
625    else:
626        #compute offset index:
627        # for (i,s) in enumerate(sCable0Pos):
628        #     p = mbs.GetSensorValues(s)
629        #     print('p'+str(i)+'=', p)
630        #     if p[0] > 0  and i > int(0.8*nANCFnodes):
631        #         indOff+=1
632        #         indOff2+=2
633        # indOff -= 1
634        # indOff2 -= 2
635        print('******************\nxOff=', xOff)
636
637
638    dataVel = DataArrayFromSensorList(mbs, sensorNumbers=sMidVel, positionList=positionListMid)
639    if correctXoffset:
640        dataVel=ShiftXoff(dataVel,xOff, reevingDict['totalLength'])
641
642    mbs.PlotSensor(sensorNumbers=[dataVel], components=0, labels=['axial velocity'],
643               xLabel='axial position (m)', yLabel='velocity (m/s)')
644
645    #axial force over beam length:
646    dataForce = DataArrayFromSensorList(mbs, sensorNumbers=sAxialForce, positionList=positionList2Node)
647    if correctXoffset:
648        dataForce = ShiftXoff(dataForce,xOff, reevingDict['totalLength'])
649    mbs.PlotSensor(sensorNumbers=[dataForce], components=0, labels=['axial force'], colorCodeOffset=2,
650               xLabel='axial position (m)', yLabel='axial force (N)')
651
652
653    if improvedBelt and dryFriction==0.5 and nANCFnodes==120:
654        #analytical exponential curve, Euler's/Eytelwein's solution:
655        na = 12 #number of data points
656        dataExp = np.zeros((na*2, 2))
657        #f0 = 278.733 #this is at low level, but exp starts later
658        f0 = 191.0#287.0
659        x0 = 0.5860 #1.1513 #starting coordinate, drawn in -x direction
660        d = 0.28     #amount along x drawn
661        for i in range(na):
662            x = i/na*d
663            beta = x/(radiusPulley + hc/2)
664            val = f0*exp(beta*dryFriction)
665            #print('x=',x,',exp=',val)
666            dataExp[i,0] = x0-x
667            dataExp[i,1] = val
668
669        f0 = 193.4#287.0
670        x0 = 0.984 #1.1513 #starting coordinate, drawn in -x direction
671        for i in range(na):
672            x = i/na*d
673            beta = x/(radiusPulley + hc/2)
674            val = f0*exp(beta*dryFriction)
675            dataExp[i+na,0] = x0+x
676            dataExp[i+na,1] = val
677
678        mbs.PlotSensor(sensorNumbers=[dataExp], components=0, labels=['analytical Eytelwein'], colorCodeOffset=3, newFigure=False,
679                   lineStyles=[''], markerStyles=['x '], markerDensity=2*na)
680
681    #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
682    #contact forces are stored (x/y) for every segment ==> put into consecutive array
683    contactForces =[[],[]] #these are the contact forces of the whole belt, but from both pulleys!
684    for i in range(len(sContactForce)):
685        contactForces[i] = np.zeros((len(sContactForce[i])*nSegments, 3)) #per row: [position, Fx, Fy]
686        for j, sensor in enumerate(sContactForce[i]):
687            values = mbs.GetSensorValues(sensor)
688            for k in range(nSegments):
689                row = j*nSegments + k
690                contactForces[i][row,0] = positionListSegments[row]
691                contactForces[i][row, 1:] = values[k*2:k*2+2]
692
693    contactForcesTotal = contactForces[0]
694    contactForcesTotal[:,1:] += contactForces[1][:,1:]
695
696    #plot contact forces over beam length:
697    mbs.PlotSensor(sensorNumbers=[contactForcesTotal,contactForcesTotal], components=[0,1], labels=['tangential force','normal force'],
698               xLabel='axial position (m)', yLabel='contact forces (N)', newFigure=True)
699    # mbs.PlotSensor(sensorNumbers=[contactForces[1],contactForces[1]], components=[0,1], labels=['tangential force','normal force'],
700    #            xLabel='axial position (m)', yLabel='contact forces (N)', newFigure=False)
701
702    contactDisp =[[],[]] #slip and gap
703    for i in range(len(sContactDisp)):
704        contactDisp[i] = np.zeros((len(sContactDisp[i])*nSegments, 3)) #per row: [position, Fx, Fy]
705        for j, sensor in enumerate(sContactDisp[i]):
706            values = mbs.GetSensorValues(sensor)
707            for k in range(nSegments):
708                row = j*nSegments + k
709                contactDisp[i][row,0] = positionListSegments[row]
710                contactDisp[i][row, 1:] = values[k*2:k*2+2]
711
712    mbs.PlotSensor(sensorNumbers=[contactDisp[0],contactDisp[0]], components=[0,1], labels=['slip','gap'],
713               xLabel='axial position (m)', yLabel='slip, gap (m)', newFigure=True)
714    mbs.PlotSensor(sensorNumbers=[contactDisp[1],contactDisp[1]], components=[0,1], labels=['slip','gap'],
715               xLabel='axial position (m)', yLabel='slip, gap (m)', newFigure=False)
716
717
718    header  = ''
719    header += 'endTime='+str(tEnd)+'\n'
720    header += 'stepSize='+str(stepSize)+'\n'
721    header += 'nSegments='+str(nSegments)+'\n'
722    header += 'nANCFnodes='+str(nANCFnodes)+'\n'
723    header += 'contactStiffness='+str(contactStiffness)+'\n'
724    header += 'contactDamping='+str(contactDamping)+'\n'
725    header += 'frictionStiffness='+str(frictionStiffness)+'\n'
726    header += 'frictionVelocityPenalty='+str(frictionVelocityPenalty)+'\n'
727    header += 'dryFriction='+str(dryFriction)+'\n'
728    fstr  = 'h'+str(stepSize)+'n'+str(int(nANCFnodes/60))+'s'+str(nSegments)+'cs'+str(int((contactStiffness/41800)))
729    fstr += 'fs'+str(int((frictionStiffness/52300)))
730
731    #export solution:
732    if improvedBelt:
733        np.savetxt('solutionDelete/contactForces'+fstr+'.txt', contactForces[0]+contactForces[1], delimiter=',',
734                   header='Exudyn: solution of belt drive, contact forces over belt length\n'+header, encoding=None)
735        np.savetxt('solutionDelete/contactDisp'+fstr+'.txt', contactDisp[0]+contactDisp[1], delimiter=',',
736                   header='Exudyn: solution of belt drive, slip and gap over belt length\n'+header, encoding=None)
737
738
739    #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
740
741    mbs.PlotSensor(sensorNumbers=[sWheelRot[0], sWheelRot[1]], components=[2,2])#,sWheelRot[1]
742    #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++