beltDriveALE.py

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

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