pistonEngine.py

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

  1#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  2# This is an EXUDYN example
  3#
  4# Details:  Create piston engine with variable number of pistons, crank and piston angles;
  5#           Showing unbalance and harmonics of unbalance
  6#
  7# Model:    Generic piston engine
  8#
  9# Author:   Johannes Gerstmayr
 10# Date:     2020-12-20
 11#
 12# 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.
 13#
 14# *clean example*
 15#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 16
 17## import basic libaries
 18import exudyn as exu
 19from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
 20import exudyn.graphics as graphics #only import if it does not conflict
 21from math import sin, cos, asin, acos, pi, exp, log, tan, atan, radians
 22
 23
 24## some simulation parameters for
 25createFigures = False
 26useLogY = False
 27showSolutionViewer = True
 28omegaDrive = 2*pi #angular velocity
 29tEnd = 2.5+40 #simulation time
 30nodeType = exu.NodeType.RotationEulerParameters
 31fixedSpeed = True #if false, the speed is given only for first 1 second
 32
 33
 34## a class to store engine parameters and with geometric functions for piston engine
 35class EngineParameters:
 36    def __init__(self, crankAnglesDegrees=[], pistonAnglesDegrees=[]):
 37        #parameters in m, s, kg, rad, ...
 38        self.crankAnglesDegrees = crankAnglesDegrees
 39        if pistonAnglesDegrees == []:
 40            self.pistonAnglesDegrees = list(0*np.array(crankAnglesDegrees))
 41        else:
 42            self.pistonAnglesDegrees = pistonAnglesDegrees
 43
 44        crankAngles = pi/180*np.array(crankAnglesDegrees)
 45        self.crankAngles = list(crankAngles)
 46
 47        pistonAngles = pi/180*np.array(self.pistonAnglesDegrees)
 48        self.pistonAngles = list(pistonAngles)
 49
 50        densitySteel = 7850
 51        #kinematics & inertia & drawing
 52        fZ = 1#0.2
 53        self.pistonDistance = 0.08
 54        self.pistonMass = 0.5
 55        self.pistonLength = 0.05
 56        self.pistonRadius = 0.02
 57
 58        self.conrodLength = 0.1 #X
 59        self.conrodHeight = 0.02*fZ#Y
 60        self.conrodWidth = 0.02*fZ #Z
 61        self.conrodRadius = 0.012*fZ #Z
 62
 63        self.crankArmLength = 0.04      #X
 64        self.crankArmHeight = 0.016     #Y
 65        self.crankArmWidth = 0.01*fZ       #Z width of arm
 66        self.crankBearingWidth = 0.012*fZ   #Z
 67        self.crankBearingRadius = 0.01
 68
 69        self.conrodCrankCylLength = 0.024*fZ  #Z; length of cylinder (bearing conrod-crank)
 70        self.conrodCrankCylRadius = 0.008 #radius of cylinder (bearing conrod-crank)
 71
 72        self.pistonDistance = self.crankBearingWidth + 2*self.crankArmWidth + self.conrodCrankCylLength #Z distance
 73
 74        self.inertiaConrod = InertiaCuboid(densitySteel, sideLengths=[self.conrodLength, self.conrodHeight, self.conrodWidth])
 75
 76        eL = self.Length()
 77        #last bearing:
 78        densitySteel2 = densitySteel
 79        self.inertiaCrank = InertiaCylinder(densitySteel2, self.crankBearingWidth, self.crankBearingRadius, axis=2).Translated([0,0,0.5*eL-0.5*self.crankBearingWidth])
 80
 81
 82
 83        for cnt, angle in enumerate(self.crankAngles):
 84            A = RotationMatrixZ(angle)
 85            zOff = -0.5*eL + cnt*self.pistonDistance
 86            arm = InertiaCuboid(densitySteel2, sideLengths=[self.crankArmLength, self.crankArmHeight, self.crankArmWidth])
 87            cylCrank = InertiaCylinder(densitySteel2, self.crankBearingWidth, self.crankBearingRadius, axis=2)
 88            cylConrod = InertiaCylinder(densitySteel2, self.conrodCrankCylLength, self.conrodCrankCylRadius, axis=2)
 89            #add inertias:
 90            self.inertiaCrank += cylCrank.Translated([0,0,zOff+self.crankBearingWidth*0.5])
 91            self.inertiaCrank += arm.Rotated(A).Translated(A@[self.crankArmLength*0.5,0,zOff+self.crankBearingWidth+self.crankArmWidth*0.5])
 92            self.inertiaCrank += cylConrod.Translated(A@[self.crankArmLength,0,zOff+self.crankBearingWidth+self.crankArmWidth+self.conrodCrankCylLength*0.5])
 93            self.inertiaCrank += arm.Rotated(A).Translated(A@[self.crankArmLength*0.5,0,zOff+self.crankBearingWidth+self.crankArmWidth*1.5+self.conrodCrankCylLength])
 94
 95        # self.inertiaCrank = InertiaCylinder(1e-8*densitySteel, length=self.pistonLength,
 96        #                                      outerRadius=self.pistonRadius, innerRadius=0.5*self.pistonRadius, axis=2)
 97
 98        self.inertiaPiston = InertiaCylinder(densitySteel, length=self.pistonLength,
 99                                             outerRadius=self.pistonRadius, innerRadius=0.5*self.pistonRadius, axis=0)
100
101    def Length(self):
102        return self.pistonDistance*len(self.crankAngles) + self.crankBearingWidth
103
104    def MaxDimX(self):
105        return self.crankArmLength + self.conrodLength + self.pistonLength
106
107## compute essential geometrical parameters for slider-crank with crank angle, piston angle, crank length l1 and conrod length l2
108def ComputeSliderCrank(angleCrank, anglePiston, l1, l2):
109    phi1 = angleCrank-anglePiston
110    h = l1*sin(phi1) #height of crank-conrod bearing
111    phi2 = asin(h/l2) #angle of conrod in 2D slider-crank, corotated with piston rotation
112    angleConrod = anglePiston-phi2
113    Acr = RotationMatrixZ(angleConrod)
114    dp = l1*cos(phi1) + l2*cos(phi2) #distance of piston from crank rotation axis
115    return [phi1,phi2, angleConrod, Acr, dp]
116
117
118## function to create multibody system for certain crank and piston configuration
119def CreateEngine(P):
120
121    colorCrank = graphics.color.grey
122    colorConrod = graphics.color.dodgerblue
123    colorPiston = graphics.color.brown[0:3]+[0.5]
124    showJoints = True
125
126    ## set up ground object
127    gravity = [0,-9.81*0,0]
128    eL = P.Length()
129    oGround=mbs.AddObject(ObjectGround(referencePosition= [0,0,0], visualization=VObjectGround(graphicsData= [])))
130    nGround=mbs.AddNode(NodePointGround(referenceCoordinates = [0,0,0]))
131
132    gEngine = [graphics.Brick(centerPoint=[0,0,0], size=[P.MaxDimX()*2, P.MaxDimX(), eL*1.2],
133                                          color=[0.6,0.6,0.6,0.1], addEdges=True,
134                                          edgeColor = [0.8,0.8,0.8,0.3], addFaces=False)]
135
136    ## create rigid body for housing; this body allows to measure support forces and torques
137    oEngine = mbs.CreateRigidBody(referencePosition=[0,0,0],
138                                             inertia=InertiaCuboid(1000, sideLengths=[1,1,1]), #dummy engine inertia
139                                             nodeType = nodeType,
140                                             graphicsDataList = gEngine
141                                             )
142    nEngine = mbs.GetObjectParameter(oEngine, 'nodeNumber')
143
144    ## create joint between engine and ground to measure forces
145    oEngineJoint = mbs.CreateGenericJoint(bodyNumbers=[oEngine, oGround],
146                                          position=[0,0,0],
147                                          constrainedAxes=[1,1,1, 1,1,1],
148                                          show=False)[0]
149
150    ## add sensors for
151    sEngineForce = mbs.AddSensor(SensorObject(objectNumber=oEngineJoint, storeInternal=True,
152                                              outputVariableType=exu.OutputVariableType.ForceLocal))
153    sEngineTorque = mbs.AddSensor(SensorObject(objectNumber=oEngineJoint, storeInternal=True,
154                                              outputVariableType=exu.OutputVariableType.TorqueLocal))
155
156    ## loop over all slider-cranks in n-piston engine
157    bConrodList = []
158    bPistonList = []
159    gCrank = []
160    for cnt, angleCrank in enumerate(P.crankAngles):
161        anglePiston = P.pistonAngles[cnt]
162        Ac = RotationMatrixZ(angleCrank)
163        Ap = RotationMatrixZ(anglePiston)
164        [phi1,phi2, angleConrod, Acr, dp] = ComputeSliderCrank(angleCrank, anglePiston, P.crankArmLength, P.conrodLength)
165
166        zOff = -0.5*eL + cnt*P.pistonDistance
167        zAdd = 0
168        if cnt>0: zAdd = P.crankArmWidth
169
170        ### create graphics for crank part
171        gCrank += [graphics.Cylinder(pAxis=[0,0,zOff-zAdd], vAxis=[0,0,P.crankBearingWidth+P.crankArmWidth+zAdd],
172                                        radius=P.crankBearingRadius, color=graphics.color.red)]
173        ### create graphics for crank arm1
174        arm1 = graphics.Brick([P.crankArmLength*0.5,0,zOff+P.crankArmWidth*0.5+P.crankBearingWidth],
175                                              size=[P.crankArmLength,P.crankArmHeight,P.crankArmWidth], color=colorCrank)
176        gCrank += [graphics.Move(arm1, [0,0,0], Ac)]
177
178        ### create graphics for conrod bearing
179        gCrank += [graphics.Cylinder(pAxis=Ac@[P.crankArmLength,0,zOff+P.crankBearingWidth+P.crankArmWidth*0],
180                                       vAxis=[0,0,P.conrodCrankCylLength+2*P.crankArmWidth], radius=P.conrodCrankCylRadius, color=colorCrank)]
181
182        ### create graphics for crank arm2
183        arm2 = graphics.Brick([P.crankArmLength*0.5,0,zOff+P.crankArmWidth*1.5+P.crankBearingWidth+P.conrodCrankCylLength],
184                                              size=[P.crankArmLength,P.crankArmHeight,P.crankArmWidth],
185                                              color=colorCrank)
186        gCrank += [graphics.Move(arm2, [0,0,0], Ac)]
187
188        if cnt == len(P.crankAngles)-1:
189            gCrank += [graphics.Cylinder(pAxis=[0,0,zOff+P.crankArmWidth+P.crankBearingWidth+P.conrodCrankCylLength], vAxis=[0,0,P.crankBearingWidth+P.crankArmWidth],
190                                            radius=P.crankBearingRadius, color=graphics.color.red)]
191
192        #++++++++++++++++++++++++++++++++++++++
193        ### create graphics for conrod
194        gConrod = [ graphics.RigidLink(p0=[-0.5*P.conrodLength, 0, 0], p1=[0.5*P.conrodLength,0,0], axis0= [0,0,1], axis1= [0,0,1],
195                                           radius= [P.conrodRadius]*2,
196                                           thickness= P.conrodHeight, width=[P.conrodWidth]*2, color= colorConrod, nTiles= 16)]
197
198        ### create rigid body for conrod
199        bConrod = mbs.CreateRigidBody(inertia = P.inertiaConrod,
200                                      nodeType = nodeType,
201                                      referencePosition=Ac@[P.crankArmLength,0,0] + Acr@[0.5*P.conrodLength,0,
202                                                            zOff+P.crankArmWidth+P.crankBearingWidth+0.5*P.conrodCrankCylLength],
203                                      referenceRotationMatrix=Acr,
204                                      gravity = gravity,
205                                      graphicsDataList = gConrod
206                                      )
207        bConrodList += [bConrod]
208        #++++++++++++++++++++++++++++++++++++++
209        ### create graphics for piston
210        gPiston = [graphics.Cylinder(pAxis=[-P.conrodRadius*0.5,0,0],
211                                         vAxis=[P.pistonLength,0,0], radius=P.pistonRadius, color=colorPiston)]
212        ### create rigid body for piston
213        bPiston = mbs.CreateRigidBody(inertia = P.inertiaPiston,
214                                      nodeType = nodeType,
215                                      referencePosition=Ap@[dp,0,
216                                                  zOff+P.crankArmWidth+P.crankBearingWidth+0.5*P.conrodCrankCylLength],
217                                      referenceRotationMatrix=Ap,
218                                      gravity = gravity,
219                                      graphicsDataList = gPiston
220                                      )
221        bPistonList += [bPiston]
222
223    ## create rigid body for crankshaft
224    bCrank = mbs.CreateRigidBody(inertia = P.inertiaCrank,
225                                 nodeType = nodeType,
226                                 referencePosition=[0,0,0],
227                                 gravity = gravity,
228                                 graphicsDataList = gCrank
229                                 )
230    nCrank = mbs.GetObjectParameter(bCrank, 'nodeNumber')
231
232    ## add sensor for crank angular velocity
233    sCrankAngVel = mbs.AddSensor(SensorNode(nodeNumber=nCrank, storeInternal=True,
234                                              outputVariableType=exu.OutputVariableType.AngularVelocity))
235
236    #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
237    ## create revulute joint between engine and crankshaft
238    [oJointCrank, mBody0Crank, mBody1Crank] = mbs.CreateRevoluteJoint(bodyNumbers=[oEngine, bCrank],
239                                                                      position=[0,0,-0.5*eL],
240                                                                      axis=[0,0,1],
241                                                                      show=showJoints,
242                                                                      axisRadius=P.crankBearingRadius*1.2,
243                                                                      axisLength=P.crankBearingWidth*0.8)
244
245    ## loop over all slider cranks to create joints
246    for cnt, angleCrank in enumerate(P.crankAngles):
247        anglePiston = P.pistonAngles[cnt]
248        Ac = RotationMatrixZ(angleCrank)
249        Ap = RotationMatrixZ(anglePiston)
250        [phi1,phi2, angleConrod, Acr, dp] = ComputeSliderCrank(angleCrank, anglePiston, P.crankArmLength, P.conrodLength)
251
252        zOff = -0.5*eL + cnt*P.pistonDistance
253        #zOff = 0
254
255        ### create revolute joint between crankshaft and conrod
256        [oJointCC, mBody0CC, mBody1CC] = mbs.CreateRevoluteJoint(bodyNumbers=[bCrank, bConrodList[cnt]],
257                                                          position=Ac@[P.crankArmLength,0,zOff + P.crankBearingWidth+P.crankArmWidth+0.5*P.conrodCrankCylLength],
258                                                          axis=[0,0,1],
259                                                          show = showJoints,
260                                                          axisRadius=P.crankBearingRadius*1.3,
261                                                          axisLength=P.crankBearingWidth*0.8)
262
263        ### create revolute joint between conrod and piston
264        pPiston = Ap@[dp,0,zOff + P.crankBearingWidth+P.crankArmWidth+0.5*P.conrodCrankCylLength]
265        [oJointCP, mBody0CP, mBody1CP] = mbs.CreateRevoluteJoint(bodyNumbers=[bConrodList[cnt], bPistonList[cnt]],
266                                                          position=pPiston,
267                                                          axis=[0,0,1],
268                                                          show=showJoints,
269                                                          axisRadius=P.crankBearingRadius*1.3,
270                                                          axisLength=P.crankBearingWidth*0.8)
271
272        ### create prismatic joint between piston and engine, using a generic joint
273        mbs.CreateGenericJoint(bodyNumbers=[bPistonList[cnt], oEngine],
274                               position=[0,0,0],
275                               constrainedAxes=[0,1,0, 0,0,1],
276                               useGlobalFrame=False,
277                               show=True,
278                               axesRadius=P.conrodRadius*1.4,
279                               axesLength=0.05)
280
281    #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
282    ## define user function for crankshaft angle (not used, because velocity level is used):
283    def UFoffset(mbs, t, itemNumber, lOffset):
284        return 0
285
286    ## define user function for crankshaft angular velocity:
287    def UFoffset_t(mbs, t, itemNumber, lOffset): #time derivative of UFoffset
288        return SmoothStep(t, 0, 0.5, 0, omegaDrive)
289
290    ## create coordinate constraint for crankshaft velocity
291    mCrankRotation = mbs.AddMarker(MarkerNodeRotationCoordinate(nodeNumber=nCrank, rotationCoordinate=2))
292    mNodeEngine = mbs.AddMarker(MarkerNodeRotationCoordinate(nodeNumber=nEngine, rotationCoordinate=2))
293    oRotationConstraint = mbs.AddObject(CoordinateConstraint(markerNumbers=[mNodeEngine, mCrankRotation],
294                                                             velocityLevel=True,
295                                        offsetUserFunction=UFoffset,
296                                        offsetUserFunction_t=UFoffset_t,
297                                        visualization=VCoordinateConstraint(show=False)))
298
299    return [oEngine, oEngineJoint, sEngineForce, sEngineTorque, sCrankAngVel, oRotationConstraint, nCrank, bCrank]
300
301## define engine parameters for certain case
302# engine = EngineParameters([0])                                           #R1
303# engine = EngineParameters([0,180])                                       #R2
304# engine = EngineParameters([0,180,180,0])                                 #R4 straight-four engine, Reihen-4-Zylinder
305# engine = EngineParameters([0,90,270,180])                                #R4 in different configuration
306engine = EngineParameters([0,180,180,0],[0,180,180,0])                   #Boxer 4-piston perfect mass balancing
307
308# engine = EngineParameters([0,120,240])                                   #R3
309# engine = EngineParameters(list(np.arange(0,5)*144))]                      #R5
310# engine = EngineParameters([0,120,240,240,120,0])                         #R6
311# engine = EngineParameters([0,0,120,120,240,240],[-30,30,-30,30,-30,30])  #V6
312# engine = EngineParameters([0,0,120,120,240,240,240,240,120,120,0,0],[-30,30,-30,30,-30,30,30,-30,30,-30,30,-30]) #V12
313
314# engine = EngineParameters([0,90,180,270,270,180,90,360])                  #R8
315# engine = EngineParameters([0,0,90,90,270,270,180,180], [-45,45,-45,45, 45,-45,45,-45]) #V8
316
317SC = exu.SystemContainer()
318mbs = SC.AddSystem()
319
320[oEngine, oEngineJoint, sEngineForce, sEngineTorque, sCrankAngVel, oRotationConstraint,
321 nCrank, bCrank] = CreateEngine(engine)
322
323## add prestep user function to turn off drive in case fixedSpeed=False
324def PreStepUF(mbs, t):
325    u = mbs.systemData.GetODE2Coordinates()
326
327    if not fixedSpeed and t >= 1: #at this point, the mechanism runs freely
328        mbs.SetObjectParameter(oRotationConstraint, 'activeConnector', False)
329
330    return True
331
332## add prestep user function
333mbs.SetPreStepUserFunction(PreStepUF)
334
335## assemble system
336mbs.Assemble()
337
338## setup simulation parameters
339stepSize = 0.002
340simulationSettings = exu.SimulationSettings() #takes currently set values or default values
341
342simulationSettings.timeIntegration.numberOfSteps = int(tEnd/stepSize)
343simulationSettings.timeIntegration.endTime = tEnd
344simulationSettings.timeIntegration.verboseMode = 1
345
346simulationSettings.timeIntegration.simulateInRealtime = True
347
348simulationSettings.solutionSettings.solutionWritePeriod=0.01
349simulationSettings.solutionSettings.writeSolutionToFile = True
350simulationSettings.solutionSettings.sensorsWritePeriod = stepSize
351simulationSettings.solutionSettings.writeInitialValues = False #otherwise values are duplicated
352simulationSettings.solutionSettings.coordinatesSolutionFileName = 'solution/coordinatesSolution.txt'
353
354simulationSettings.timeIntegration.newton.useModifiedNewton = True
355simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.5
356simulationSettings.timeIntegration.generalizedAlpha.computeInitialAccelerations = False
357
358simulationSettings.timeIntegration.generalizedAlpha.lieGroupAddTangentOperator = False
359simulationSettings.linearSolverType=exu.LinearSolverType.EigenSparse
360
361simulationSettings.solutionSettings.solutionInformation = "Piston engine"
362
363SC.visualizationSettings.general.graphicsUpdateInterval = 0.01
364SC.visualizationSettings.general.drawWorldBasis = True
365SC.visualizationSettings.general.worldBasisSize = 0.1
366
367SC.visualizationSettings.loads.show = False
368SC.visualizationSettings.nodes.show = False
369SC.visualizationSettings.connectors.show = False
370
371SC.visualizationSettings.openGL.multiSampling = 4
372SC.visualizationSettings.openGL.lineWidth = 3
373SC.visualizationSettings.openGL.perspective = 0.5
374SC.visualizationSettings.openGL.light0position = [0.25,1,3,0]
375SC.visualizationSettings.window.renderWindowSize = [1600,1200]
376
377#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
378
379## start visualization and solve
380SC.visualizationSettings.general.autoFitScene = False #use loaded render state
381exu.StartRenderer()
382if 'renderState' in exu.sys:
383    SC.SetRenderState(exu.sys[ 'renderState' ])
384
385mbs.WaitForUserToContinue()
386
387exu.SolveDynamic(mbs, simulationSettings)
388
389exu.StopRenderer() #safely close rendering window!
390
391
392## import plot tools and plot some sensors
393from exudyn.plot import PlotSensor,PlotSensorDefaults
394
395PlotSensor(mbs, closeAll=True)
396PlotSensor(mbs, [sCrankAngVel], components=[2], title='crank speed', sizeInches=[2*6.4,2*4.8])
397PlotSensor(mbs, sEngineForce, components=[0,1,2], title='joint forces')
398PlotSensor(mbs, sEngineTorque, components=[0,1,2], title='joint torques')