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