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