<<

Modeling & Identication for Pressure Estimation - condential -

Aart-Jan van der Hoeven CST 2012.111

Internship Report

Advisors: dr.ir. M.C.F. Donkers (TNO)

dr.ir. F.P.T. Willems (TU/e)

Eindhoven University of Technology Department of Mechanical Engineering Control Systems Technology

Eindhoven, December, 2012 Summary

The control problem of (heavy-duty diesel) engines consists of meeting the driver's torque request, while minimizing fuel consumption and staying within emission legislation constraints. With the introduction of cylinder pressure sensors, it becomes possible to control the combustion process using closed-loop control, which enables advanced combustion concepts, improves transient performance and is more robust to uncertainties. The cylinder pressure sensors necessary for this approach are relatively expensive and not yet in mass-production for heavy-duty diesel applications. At TNO, a virtual cylinder pressure sensor concept has been developed in which only one cylinder pressure sensor is used and the other cylinder pressures are estimated by using the crankshaft position signal. A dynamic model of the crankshaft and system, that provides the relation between cylinder pressures and angular velocity, plays a crucial role in this algorithm and is developed within this internship project. Several dynamic crankshaft models can be found in literature. They are either used for structural design [6], combustion phasing estimation [9] or indication of cylinder health [4]. The work presented in this report is aimed for application in an on-line estimation of heavy-duty diesel cylinder pressure.

The presented model does use six cylinder pressure signals as input and provides the angular velocity at the location of the position encoder as output. The crankshaft model consists of nine bodies; six of them represent the cylinders, including a -slider mechanism and static friction model. The rear of the crankshaft is supplemented with a ywheel body, which also contains an amount of lumped mass due to components connected to it. The front of the crankshaft is supplemented with a torsional damper and front pulley body. All bodies are interconnected by springs and dampers, which represent the stiness and damping of the material.

A parameter identication is performed using the least squares error tting algorithm lsqnonlin of the MATLAB Optimization Toolbox. High-accuracy measurement data of cylinder pressures and angular velocity were measured at TNO and used for identication. After identifying appropriate values for the parameters of the model, the model is analyzed in terms of accuracy, complexity and sensitivity. For nine operating points throughout the operating region of the engine, the average RMS velocity output error is about 0.5 rad/s (0.3%) and the model performs well in predicting the velocity waveform. After evaluating multiple model extensions and their performance, the presented model is considered as a good compromise between complexity, performance and robustness.

Two candidates for model simplication are proposed. The rst proposal is using a constant mass matrix in the equations of motions, and is shown to be feasible in terms of model output. The second proposal is a simplied friction modeling in which the instantaneous friction torque is replaced by a constant average friction torque. This reduces the amount of parameters to be identied at each operating point. The proposal might be feasible, but should be evaluated using a dedicated parameter identication. Reducing the crankshaft model to a single rigid-body, which is commonly the approach for light-duty engines, is shown to be an invalid approach for heavy-duty engines.

A model describing the dynamic behavior of a heavy-duty has become available as a result of this work. Since this control oriented model was required for the next step in the development and validation of the virtual cylinder pressure sensor concept, this algorithm might now actually prove itself on real engine data. The virtual sensor will make implementation of closed-loop combustion control much more attractive and will contribute to cleaner and more fuel ecient vehicles.

2 Contents

1. Introduction 4

2. Engine Description 6 2.1. Engine Overview ...... 6 2.2. Crankshaft ...... 7 2.3. Torsional Damper ...... 7 2.4. Measurements ...... 8

3. Crankshaft Modeling 9 3.1. Crankshaft Model ...... 9 3.2. Crank-Slider Kinematics ...... 10 3.3. Friction ...... 12 3.4. Equations of motion ...... 12 3.5. Implementation ...... 15

4. Parameter Identication 16 4.1. Identication Method ...... 16 4.2. Parameters ...... 16 4.3. Initial Conditions ...... 18 4.4. Results ...... 19

5. Analysis 21 5.1. Accuracy ...... 21 5.2. Model Simplications ...... 26 5.3. Parameter Sensitivity ...... 33

6. Conclusions, Recommendations and Implications 39 6.1. Conclusions ...... 39 6.2. Recommendations for Future Research ...... 40 6.3. Implications ...... 40

Bibliography 40

A. DAF MX Engine Data 42

B. Inertial Properties 45

C. Testbench Dynamics 47

D. MATLAB Implementation 49

3 1. Introduction

The control problem of (heavy-duty diesel) engines consists of meeting the driver's torque request while minimizing fuel consumption and staying within emission legislation constraints. In traditional diesel engine control systems this problem is solved by a separate air path and fuel path controller. The air path is regulated in closed-loop with indirect measurement of performance quantities, but the fuel path is mainly relying on feed-forward with compensations for transients. A more robust approach became available with the introduction of cylinder pressure sensors. Performance quantities like indicated mean eective pressure (IMEP), 50% heat release crank-angle (CA50), cylinder pressure rise (dp/dα) and peak cylinder pressure (pmax) can be determined and can be used in closed-loop combustion control [11]. The benets of this type of control are enhanced combustion stability, which is needed to enable advanced combustion concepts, improved dynamic operating performance in terms of emissions, fuel consumption and torque response, robustness for variations in the combustion process due to production tolerances and aging [12] and for monitoring and diagnostics. The cylinder pressure sensors needed for closed-loop combustion control are relatively expensive and not yet in mass-production for heavy-duty diesel applications. Research can be found in which the number of necessary sensors is reduced or in which virtual sensing concepts are applied [9, 13, 4]. By virtual sensing, we mean that the cylinder pressure is not directly measured, but estimated from other outputs using an algorithm that includes a mathematical model. At TNO, a virtual cylinder pressure sensor concept has been developed whereby only one cylinder pressure sensor is used and the other cylinder pressures are estimated by using the crankshaft position signal. The problem of estimating multiple unknown cylinder pressures from one measured pressure and crankshaft position is, roughly speaking, solved in three steps, as schematically shown in Figure 1.1. First, the measured cylinder pressure is used to derive initial estimates of the induced torques on the crankshaft. Then, the initial estimates are improved, using crankshaft position information, by solving a LQ tracking problem. Finally, the cylinder pressures are reconstructed from the estimated induced torques. A dynamic model of the crankshaft and piston system, that provides the relation between cylinder pressures and angular velocity, plays a crucial role in this procedure and is developed within this internship project.

Figure 1.1.: Overview of the virtual cylinder pressure sensor algorithm.

Using numerical simulations, the idea of the virtual sensor concept is shown to have potential. Yet, it has to be validated using measurements and a dynamic crankshaft model of a real heavy-duty diesel

4 engine. For this validation, six high-frequency cylinder pressures and a crankshaft position signal are recorded on a DAF MX 6-cylinder engine. The crankshaft model, that is developed within this internship project, enables validation of the virtual sensor concept on the DAF engine. Also, the developed crankshaft model structure can be easily applied to other (heavy-duty diesel) engines.

Several dynamic crankshaft models can be found in literature. They are either used for structural design [6], combustion phasing estimation [9] or indication of cylinder health [4]. The work presented in this report is aimed for application in an on-line estimation of heavy-duty diesel cylinder pressure and should predict the angular velocity with a small error margin (5%).

This report is organized as follows. First a description of the engine being used for the measurements is given in Chapter 2. A derivation of the crankshaft model structure and its implementation is given in Chapter 3. In Chapter 4, the identication of the model parameters is outlined and the simulation results are given. In Chapter 5, the results and parameter sensitivity are analyzed and three simplied models are proposed. Finally, Chapter 6 provides the conclusions and recommendations for this work.

5 2. Engine Description

In this chapter, the heavy-duty diesel engine being used for this work is described. This engine has been used to measure the cylinder pressures and crankshaft position with high accuracy. The structural information of the crankshaft is provided by the manufacturer. This enables the development and validation of a crankshaft model, which will be done in next chapter.

2.1. Engine Overview

A DAF MX 6-cylinder diesel engine is used to represent a heavy-duty diesel engine with exhaust gas recirculation (EGR), variable turbine geometry (VTG) and . At TNO, a demonstrator engine of this type has been used to do experiments on new combustion control concepts. These experiments required this engine to be equipped with six cylinder pressure sensors and a high-resolution crankshaft position encoder. A schematic overview of the engine and some important parameters are shown in Figure 2.1. The crankshaft drives the oil-pump and by means of a gear transmission at the rear (ywheel-side). The camshaft, in turn, actuates both the cylinder and fuel unit-pumps. The front of the crankshaft is equipped with a torsional damper of which the housing also serves as a pulley for the accessory . Some of the accessories are the water pump, air-conditioner compressor and .

Number of cylinders 6 Cylinder volume 12.9 L 17.45 130 mm 162 mm Connecting rod length 262 mm Piston o-set 0.8 mm 1-5-3-6-2-4 Max. torque 2500 Nm Max. power 375 kW

Figure 2.1.: Overview of a DAF MX 6-cylinder diesel engine and some characteristic parameters.

6 2.2. Crankshaft

A schematic of the crankshaft is shown in Figure 2.2. The front of the crankshaft (left) is supplemented with a torsional damper. The rear of the crankshaft (right) is supplemented with a gear-wheel and ywheel (not shown). The cylinder numbering is 1 to 6 from front to rear.

Figure 2.2.: Overview of the DAF MX 6-cylinder crankshaft.

The crankshaft is partitioned into six cylinder segments that all have the same structure, as shown in Figure 2.3. Each cylinder segments consists of half of the crankshaft mains, two crankshaft webs and a crankshaft pin to which the connecting rod is mounted. The length, inertia and torsional stiness of each segment is provided by DAF, resulting from a FEM analysis of a CAD model, and can be found in Appendix A.

Figure 2.3.: A schematic of the crankshaft segments per cylinder (left) and a schematic of the torsional damper (right).

2.3. Torsional Damper

Crankshafts are often equipped with a torsional damper, in order to remove energy from torsional vibration of the system. The engine being used for the measurements is equipped with a damper of the viscous uid type and it is attached to the front side of the crankshaft. A hollow housing is rigidly connected to the crankshaft and an inertia ring is close-tted inside it, while being suspended in a small layer of viscous silicon uid. The housing rotates along with the crankshaft and due to shear forces generated by a relative velocity between ring and housing, energy is dissipated in the form of heat [7]. This allows the damper to be modeled as a damping between two bodies. A schematic overview of the damper is shown in the right-hand gure of Figure 2.3. The outer circumference of the housing also serves as a pulley for the accessories belt.

7 2.4. Measurements

High-frequency measurements are conducted on a testbench at TNO. The measurements are sampled with a resolution of 0.1 crankshaft angle degree (CAD). The measured signals include the six individual cylinder pressures, which are measured using Kistler piezoelectric pressure transducers, and crankshaft position, which is measured using an optical position encoder. The position encoder was mounted to the torsional damper housing at the front of the crankshaft, while the load was applied to the ywheel at the rear of the crankshaft. The load was generated with an electric drive connected to the ywheel by means of a shaft and rubber coupling. A schematic overview of the measurement set-up can be seen in Figure 2.4. All cylinder pressure signals are sampled with reference to the encoder position and pegged, using the polytropic coecient method, to obtain absolute pressure levels.

Figure 2.4.: Measurement set-up with engine, shaft, coupling and electric drive.

Measurements are conducted at several combinations of engine speed and load. At each operating point, 200 cycles are measured. This allows to analyze, identify and validate the crankshaft model at multiple operating points. The model should be robust enough to match the measurement data with a comparable accuracy at all operating points. One set of intermediate points will be only used for model validation, to prevent an over-t to the measurement data and to prove robustness of the identied model. The operating points being used are shown in the engine operating map in Figure 2.5. The {A, B, C} operating points are at {1213, 1525, 1838} rpm.

3500 max. valid. identify 3000 A100 2500 B100

2000 C100 A60 1500 B50

Engine torque [Nm] 1000 C40 A20 500 B10 C0 0 1000 1200 1400 1600 1800 2000 Engine speed [rpm]

Figure 2.5.: Engine operating points for identication and validation.

8 3. Crankshaft Modeling

In this chapter, we will develop the dynamic crankshaft model of the engine discussed in previous chapter. First, an overview of the developed crankshaft model is given. Subsequently, the crank-slider kinematics are studied, to obtain expressions for the piston acceleration and combustion torque as a function of crankshaft angle and angular velocity. Then, an instantaneous representation of the piston friction is dened. Finally, the dynamic behavior of the multi-body model of a crankshaft is presented, its equations of motion are derived and a few notes on the numerical implementation are given.

3.1. Crankshaft Model

For modeling the dynamic behavior of the crankshaft, it is split into nine bodies as can be seen in

Figure 3.1. Body J1 at the front represents the torsional damper ring. Body J2 represents the front of the crankshaft including the torsional damper housing and lumped accessories. For each cylinder i ∈ {1, ..., 6}, a body Ji+2 is added, which have a position dependent kinetic energy due to the oscillating mass. At the rear of the crankshaft, body J9 represents the ywheel and lumped masses of gear-wheel, camshaft, testbench coupling, etc. All bodies are interconnected with springs and dampers, which represent the material stiness and damping. The external load Tload provided by the testbench is applied at the ywheel. At the front of the crankshaft, a load Tf represents the load of the accessories. Furthermore, each cylinder body is actuated by a torque resulting from combustion and friction. The states of the model are the angular position and velocity of each body, i ∈ {1, ..., 9}. The dynamics of the testbench are not included in the model, for reasons discussed in Appendix C.

Figure 3.1.: Schematic representation of the crankshaft model.

9 3.2. Crank-Slider Kinematics

Based on the geometry of the crank-slider mechanism, the equations for the piston velocity and combustion torque are derived in this section. Both equations can be expressed using a so-called eective radius of the crankshaft, which is a function of crankshaft angular position. The piston velocity and cylinder pressure torque are used in Section 3.4 for describing the dynamics of the crankshaft-piston system.

3.2.1. Piston Velocity

The piston velocity is derived from the geometry of the crank-slider mechanism, which is shown in Figure 3.2. First, the relation between the connecting rod angle and crankshaft angle is derived. Second, the eective height of the connecting rod is approximated, which is used in an expression for the angular velocity of the connecting rod. The position of the piston is dened as a function of crankshaft angle. Next, using the previously derived expressions, the piston velocity can also be dened as a function of crankshaft position.

Figure 3.2.: Schematic overview of a crank-slider mechanism.

The angle of the connecting rod ψ is a function of the crankshaft angle θ, and satises

L sin ψ = R sin θ (3.1) in which L is the connecting rod length and R is the crankshaft radius. The eective height of the connecting rod, as seen from the cylinder axis, is given by

p L cos ψ = L2 − R2 sin2 θ ≈ L (3.2) in which the Pythagoras Theorem is used to derive the unknown quantity. For the small connecting rod angles ψ, that typically occur in internal combustion engines, the eective height can be approximated by the length of the connecting rod itself. The angular velocity of the connecting rod, obtained by taking the time derivative of (3.1) and rearranging terms and substituting (3.2), is a function of crankshaft position and crankshaft velocity and is given by

R cos θ R ψ˙ = θ˙ ≈ θ˙ cos θ (3.3) L cos ψ L

10 The position of the piston Xp is derived from the geometry of the crank-slider mechanism as

Xp = R cos θ + L cos ψ (3.4)

The velocity of the piston is obtained by taking the time derivative of the piston position, as given by

 R2  X˙ = −Rθ˙ sin θ − Lψ˙ sin ψ = − R sin θ + sin 2θ θ˙ = −reθ˙ (3.5) p 2L in which (3.3) is substituted and the identity 1 is used. Hence, the angular and sin θ cos θ = 2 sin 2θ linear velocity are related through the eective radius re of the crank-slider mechanism.

3.2.2. Cylinder Pressure Torque

The induced torque due to pressure in the cylinder Tcomb is also derived from the geometry of the crank-slider mechanism, which is shown in Figure 3.3 with the relevant forces for this derivation.

Figure 3.3.: Schematic overview of a crank-slider mechanism with relevant forces.

The cylinder pressure pcyl multiplied with the piston area A results in a combustion force Fcomb in line with the cylinder axis towards the rotation axis of the crankshaft. The combustion force can be decomposed into a normal force and force in the direction of the connecting rod and is given by

F p A F = comb = cyl (3.6) cr cos ψ cos ψ

0 The length R perpendicular to Fcr towards the rotation axis of the crankshaft, is given by

R0 = R sin (θ + ψ) = R (sin θ cos ψ + cos θ sin ψ) (3.7)

The cylinder pressure torque can thus be expressed by the product of the force in the direction of the 0 connecting rod Fcomb (3.6) and the length R (3.7), i.e.,

 2  0 R T (θ) = R F = R sin θ + cos 2θ F = reF (3.8) comb cr 2L comb comb in which again the eective radius is used, as in (3.5).

11 3.3. Friction

The engine is subjected to several sources of friction at its components. In general, detailed models are necessary to calculate the friction amplitudes. The main source of friction is the piston and liner interaction per cylinder [1, 3, 8]. As an approximation of the friction characteristics that have been experimentally observed and reported in literature, the total friction torque can be modeled by three terms that are applied at each cylinder, being a constant, an absolute piston velocity dependent term and an absolute combustion torque dependent term [3]. The magnitude of these three terms are characterized by the friction coecients c1, c2 and c3, resulting in the friction torque equation used in this report, which is

˙ (3.9) Tfric,i = c1 + c2 Xp + c3 · |Tcomb|

120 instantaneous 100 average 80

60

40

Friction torque [Nm] 20

0 0 120 240 360 480 600 720 Crankshaft position [deg]

Figure 3.4.: Typical friction torque waveform per cylinder.

A typical waveform of the total friction torque per cylinder as shown in Figure 3.4, is calculated using (3.9) and some typical cylinder pressure and velocity proles. The two large peaks are mainly related to the load dependent term which is dominant around top-dead-center at 360 deg, while the others are mainly speed dependent.

The friction coecients may vary among the operating points of the engine. Using cylinder pressure and velocity measurements of an engine, it might be possible to identify them as a function of engine speed and load and derive the describing relation of these maps. More details about this approach are given in Section 5.2.2.

3.4. Equations of motion

In this report, we will derive the equations of motion of the system by using the Lagrangian mechanics method [2, 6]. The equations of motions can be obtained by solving

d ∂E  ∂E ∂E kin − kin + pot = Q (3.10) dt ∂θ˙i ∂θi ∂θi

12 where Ekin is the kinetic energy, Epot is the potential energy and Q the vector of all nonconservative torques. The total kinetic energy is given by

9 8 8 X 1 ˙2 X 1 ˙2 X 1 ˙ 2 (3.11) Ekin = 2 Jcs,iθi + 2 Jcr,rotθi + 2 moscXp,i (ϕi) i=1 i=3 i=3 which is a summation of the kinetic energy of the rotating crankshaft segments and the connecting rod bodies, and the oscillating mass. The inertia of each cylinder segment consists of two times half the crankshaft mains that surround the cylinder, two crankshaft webs and one crankshaft pin, as was explained in Section 2.2, and is denoted by Jcs,i. The rotating part of the connecting rod is represented by Jcr,rot. The oscillating mass mosc consists of all piston related components, but also includes the oscillating part of the connecting rod. A correction for obtaining the correct equivalent connecting rod inertia is neglected here, as explained in Appendix B. The kinetic energy of the oscillating mass is expressed in terms of its linear velocity (3.5), which is a function of its corresponding absolute crankshaft position as dened by

X˙ p,i (ϕi) = −re (ϕi) θ˙i (3.12) in which the absolute position, because of the ring order 1-5-3-6-2-4, is given by

h i 2π ϕi = θi − 0 4 2 5 1 3 (3.13) 3

The total potential energy Epot is given by

8 X 1 2 (3.14) Epot = 2 ki (θi+1 − θi) i=1 in which ki is the stiness between the bodies. Qi contains all nonconservative torques

h iT ∂D (3.15) Q = 0 Tf T1 T2 T3 T4 T5 T6 Tload − ∂θ˙i in which D contains the material damping of the crankshaft model

8  2 X 1 ˙ ˙ (3.16) D = 2 di θi+1 − θi i=1 and the torques Ti applied at the cylinder bodies Ji, i ∈ {3, ..., 8} consist of the cylinder pressure torque (3.8) minus the friction torque (3.9)

Ti = Tcomb,i − Tfric,i (3.17)

13 With the provided information, (3.10) can be solved to obtain nine equations of motion, which can be written in the form

M(θ)θ¨ + Kθ = F (θ,˙ θ) (3.18) in which the nonconstant mass matrix M(θ) = {Mi,j} consists of elements

 J for i = j ∈ {1, 2, 9}  cs,i 2 Mi,j = Jcs,i + Jcr,rot + moscre (ϕi) for i = j ∈ {3, ..., 8} (3.19) 0 elsewhere with ϕi as in (3.13). The stiness matrix K = {Ki,j} has elements

 −ki − ki+1 for i = j, i ∈ {1, ..., 9}  k for i = j − 1, i ∈ {2, ..., 9} K = i−1 (3.20) i,j for , ki i = j + 1 i ∈ {1, ..., 8}  0 elsewhere with k0 = k9 := 0, and the input torque vector F (θ,˙ θ) = {Fi} consists of elements

( Qi for i ∈ {1, 2, 9} Fi = (3.21) Qi − moscre (ϕi)r ˙e (ϕi) θ˙i for i ∈ {3, ..., 8} with ϕi as in (3.13). The last term of the input torque for the cylinder bodies comes from the variation in kinetic energy as a function crankshaft position and results in a static nonlinear input function. The numerical values of the entries of the nonconstant mass matrix M are given in Appendix A, but can also be seen in Figure 3.5 in which the terms of matrix entry M3,3 of cylinder segment #1 are given as a function of crankshaft position. The variation is dependent on one of the system states and therefore results in nonlinear system dynamics. The analysis of the approximation of the mass matrix by a constant matrix will be given in Section 5.2.1.

0.07

0.06 crankshaft connecting rod oscillating mass 0.05

0.04 [kgm²]

3,3 0.03 M 0.02

0.01

0 0 120 240 360 480 600 720 Crankshaft position [deg]

Figure 3.5.: Matrix entry M3,3 terms of cylinder segment #1.

14 3.5. Implementation

In general, the crankshaft model can be represented by the block diagram shown in Figure 3.6. The input to the model consists of the cylinder pressures per cylinder i ∈ {1, ..., 6} and the loads applied by the testbench (Tload) and accessories (Tf ). Since the cylinder pressures were measured with the position encoder at the front pulley as a reference, the cylinder pressures have to be applied based on the same reference. The output of the model consists of the velocity of the crankshaft, as determined at the front pulley, which is at the same location as the position encoder during the measurements.

Figure 3.6.: Block diagram of the crankshaft model.

The model can be represented by a state-space description with nonconstant A matrix and a static nonlinear input function, as given by

x˙ = A(x) x + B f(x, p ) cyl,i (3.22) y = C x in which the system states consist of the body angular velocities and positions dened by

h iT (3.23) x = θ˙1 θ1 ... θ˙9 θ9 and the static nonlinear input function consists of the input torque vector (3.21), as dened by

f(x, pcyl,i) = F (3.24)

The dierential equations are implemented in MATLAB and numerically solved by an ordinary dif- ferential equation (ODE) solver. Using the default ode45 solver results in relatively long simulation times, since small time steps are necessary to obtain a stable solution using the explicit method, thereby indicating that the problem is sti. Therefore the implicit ode15s solver was chosen to per- form the simulations. For the variable time steps, a relative tolerance of 2 · 105 was chosen as a compromise between accuracy and simulation time. The front pulley velocity θ˙2 is selected as output of the model. After simulation, the output can be used to calculate the error with the measured output for identication purposes or other analysis. The MATLAB code of the implementation is given in Appendix D.

15 4. Parameter Identication

The model structure presented in the previous chapter contains a set of parameters, which still need to be determined. For most of the parameters, an initial estimate is available from data that has been provided by the engine manufacturer. However, this data was generated by simulation software and might contain some uncertainty. Furthermore, there are also unknown parameters that initially can only be estimated by rules of thumb. This makes it necessary to do parameter identication in order to nd appropriate values for the parameters, such that the model reproduces the output of the real engine as closely as possible. This chapter will give a description of the identication procedure that has been applied, an overview of the parameters to be identied and some observations on the inuence of the initial conditions of the simulations. Finally, the identication results are discussed and simulation results are given for the crankshaft model with identied parameters. The simulation results will be analyzed in next chapter.

4.1. Identication Method

As already mentioned, the inputs u of the model consist of the measured cylinder pressure signals and the constant load applied by the testbench, which is obtained by averaging a low frequency torque measurement over the 200 measured cycles. The load due to the accessories is neglected, in order to reduce the amount of unknowns. By choosing a certain set of parameters in the model, its front pulley velocity output yˆ can be compared to the measured velocity output y, as shown in Figure 4.1. The error e between those two signals is used in a least-squares error tting algorithm to search for the set of parameters that minimizes the output error. The lsqnonlin function provided by the MATLAB Optimization Toolbox is used to do this. This function uses a trust-region-reective method for determining the direction at which the parameters should be modied in order to obtain the minimal model error. The measured output velocity is zero-phase ltered, using the MATLAB filtfilt function with a low-pass Butterworth lter, in order to contain only frequencies up to the 36th harmonic. The ltered signal is then used in the parameter identication process.

Figure 4.1.: Overview of the parameter identication process.

4.2. Parameters

The parameters of the model can be grouped into inertia, mass, stiness, damping, friction, geometry, velocity and load related parameters. A full list of parameters and how they are identied is shown

16 in Table 4.1. The data provided by the engine manufacturer, given in Appendix A, was used here as initial estimates of the parameters.

Model parameter Unit Initial est. Ident. parameter Ident. model parameter

J1 kgm² -

J2 kgm² scale factor p1

J3,rot kgm² -

J4,rot kgm² - Inertia J5,rot kgm² -

J6,rot kgm² -

J7,rot kgm² -

J8,rot kgm² -

J9 kgm² scale factor p2

Mass mosc kg -

k1 MNm/rad - k MNm/rad scale factor p Stiness 2 3 k3,...,k7 MNm/rad scale factor p4

k8 MNm/rad scale factor p5 d Ns/m scale factor p Damping 1 6 cd s²/m² cd = p7/100

c1 Nm c1 = p8+3(k−1) see Table 5.3 Friction c2 Ns c2 = p9+3(k−1)/100 see Table 5.3

c3 - c3 = p10+3(k−1)/100 see Table 5.3 R m - Geometry L m - A m² - ˙ ˙ Velocity θ0,k rad/s N0/30 · π θ0,k = p8+3n+(k−1) see Appendix D

Load Tload Nm - - From measurements

Table 4.1.: Overview of the parameters in the crankshaft model.

The uncertainty for the inertia model parameters is mainly present at the inertia of the front J2 and rear J9 body of the crankshaft, since the amount of lumped mass is not directly known. The identication parameters p1 and p2 are used to multiply the initial estimates during identication. The initial estimates of the torsional damper ring inertia J1, the constant terms of the cylinder body inertias Ji,rot with i ∈ {3, ..., 8} , and the oscillating mass mosc are considered to be accurate enough to be used directly in simulation. The uncertainty in their values, for instance due to production

17 tolerances, is assumed to be too small to add additional identication parameters. The oscillating mass is assumed to be equal for each cylinder.

The stiness coecient k1 is neglected, since the viscous silicon uid of the torsional damper is not expected to have any torsional stiness. If the model is used to simulate the behavior of an engine with tuned-mass torsional damper, consisting of a spring-supported oating mass, then k1 can be given a nonzero value. All cylinder bodies do have a similar structural layout. The stiness between those bodies is expected to have the same amount of uncertainty and are therefore scaled with the same identication parameter p4. The stiness coecients that connect the front and rear body to the cylinders are scaled with identication parameters p3 and p5. They are expected to have each their own uncertainty, since the eective length of these bodies may in practice deviate from the lengths that were used to obtain the initial estimates in FEM simulation.

For the internal material damping that is modeled by the relative damping coecients di, with i ∈ {2, ..., 8}, the values are determined by the relation provided in [6] and is given by di = cd ki/ω in which the parameter cd is used to t the model to the data. The factor ki is of the corresponding stiness coecient and ω is the crankshaft velocity. As can be seen, the material damping decreases when the velocity increases and increases when the stiness increases. Using the given relation, only one parameter is needed to t the internal damping at multiple operating speeds. The damping of the torsional damper is scaled by identication parameter p6.

The friction coecients c1, c2 and c3 are identied for each individual operating point. The number of identication parameters therefore varies with the number n of provided operating points. The same ˙ holds for the initial velocities θ0,k of the bodies. The operating points are indexed by k ∈ {1, ..., n}. Additional pre-scaling was applied to some identication parameters in order to obtain similar mag- nitudes of range in which the parameters are allowed to be varied by the parameter identication process. The implementation of the actual parameter identication process in MATLAB, using the lsqnonlin function, is given in Appendix D.

4.3. Initial Conditions

At all the measured operating points, the system is at the same angular velocity after each cycle of two revolutions. Still, the simulations have to be started with non-zero initial conditions. The velocities

θ˙i, i ∈ {1, ..., 9} may be approximated by the average crankshaft velocity, but the angular positions θi, i ∈ {1, ..., 9} are more dicult. However, it is observed that the angular positions converge to a stable set of positions, when evaluating them in subsequent cycles at the same crankshaft position. By starting a simulation with the approximated velocities and zero-valued positions as initial conditions, the states at the end of a cycle can be used as initial conditions for the next simulation. As long as the system is kept at the steady-state operating point, the nal condition of one cycle can be used as initial condition for the next cycle. This approach can be used in simulation both for parameter identication and analysis of the results as done in the next chapter.

The two-step identication procedure is shown in Figure 4.2. At the rst step, the simulation is run for one cycle of 720 degrees. The state determined at the end of this cycle is used to start the simulation of the second step, which is a series of three subsequent cycles. In this step, the error between measured and simulated output of the second cycle and half of the rst and third cycle is used to identify the parameters. The identication data therefore consists of two cycles that cover the combustion events in the cylinder order 1-5-3-6-2-4 and the range of data is long enough to ensure a parameter t that keeps the system at its operating point.

18 Figure 4.2.: Two-step identication procedure.

The identication data consists of multiple operating points. The outlined two-step procedure is performed for every individual operating point. The error output of each operating point is combined into one set of error data, which is used within the nonlinear least-squares error tting algorithm. By sampling the error output at a crankshaft position interval of one degree, all operating points are equally weighted by having the same number of error values.

4.4. Results

The parameter values resulting from the identication process are given in Table 4.1. The identied amount of inertia for the front body J2 is approximately equal to the initial estimate. The accessories, which are connected to the front body by means of a belt, therefore seem to be dynamically decoupled from the crankshaft. The identied amount of inertia for the rear body J9 is substantially larger than the initial estimate, since the the camshaft is connected to the crankshaft by a gear transmission and inertia is added by the shaft and coupling of the testbench. The stiness parameters have been underestimated in FEM analysis, with increasing underestimation towards the front of the crankshaft.

Using the identied set of model parameters, it is possible to perform simulations in MATLAB. The simulation results given here are the angular velocity θ˙2 at the front body, as a function of the angular position θ2 of the front body. Results are shown for nine operating points, discussed in Section 2.4:

ˆ Operating points for identication (A100, B100, C100, A20, B10, C0) Simulations are performed using the identied set of model parameters.

ˆ Operating points for validation (A60, B50, C40) The same model parameters are used. The friction coecients are interpolated between the ones that have been identied. Using the cylinder pressure signals of the validation operating points and correct estimates of the initial velocity, it is possible to perform simulations.

All graphs do have a 120 degree grid interval, to indicate the 6 cylinder events. Measurements were performed with the combustion event of cylinder 1 located at 360 CAD. The same event location is used in simulations, such that the combustion event order is 6-2-4-1-5-3 for 0,120,240,360,480,600 degrees crankshaft position. The determination of these event locations is described in Section 5.2.3.

With the same set of model parameters, the model is able to capture most dynamics at the selected operating points. As expected, the amount of variation in speed is mostly related to the load condi- tions. The waveform is mostly related to the engine speed. While the variation in speed is about 60 rpm at A100, the variation increases up to 160 rpm at C100. The results will be analyzed in the next chapter.

19 A20 A60 A100 1250 1250 1250

1240 1240 1240

1230 1230 1230

1220 1220 1220

1210 1210 1210

Speed [rpm] 1200 Speed [rpm] 1200 Speed [rpm] 1200

1190 1190 1190 measurement 1180 filtered 1180 1180 simulation 1170 1170 1170 0 120 240 360 480 600 720 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg] Crankshaft position [deg]

B10 B50 B100 1580 1580 1580

1570 1570 1570

1560 1560 1560

1550 1550 1550

1540 1540 1540

1530 1530 1530

1520 1520 1520 Speed [rpm] Speed [rpm] Speed [rpm]

1510 1510 1510

1500 1500 1500

1490 1490 1490

1480 1480 1480 0 120 240 360 480 600 720 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg] Crankshaft position [deg]

C0 C40 C100

1920 1920 1920

1900 1900 1900

1880 1880 1880

1860 1860 1860

1840 1840 1840

1820 1820 1820 Speed [rpm] Speed [rpm] Speed [rpm]

1800 1800 1800

1780 1780 1780

1760 1760 1760

0 120 240 360 480 600 720 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg] Crankshaft position [deg]

Figure 4.3.: Front body angular velocity θ˙2 for the studied operating points. 20 5. Analysis

After identifying appropriate values for the parameters of the model, the model can be analyzed in terms of accuracy, complexity and sensitivity. In the rst section of this chapter, the accuracy of the model is determined in both time and frequency domain. In the second section, the complexity of the model is reduced by proposing three simplications and analyzing the consequences for modeling accuracy. These simplications include using a constant mass matrix, a simplied friction model and a reduction to a single rigid-body crankshaft model. In the third section, the sensitivity of the crankshaft model to variation of parameters is studied in order to obtain insight in the importance of the individual parameters for identication and robustness.

5.1. Accuracy

The accuracy of the identied crankshaft model is determined by analyzing the error between the measured and simulated angular velocity in both time and frequency domain, for all studied operating points. In the frequency domain, the error is expressed as a function of engine harmonics. To do so, rst a denition of the engine harmonics is given and the frequency content of the input and output data is determined for two operating points. Second, the resonance frequencies of the crankshaft system are determined and related to the observed output behavior. Based on the knowledge gained in the rst two sections, the model error is nally analyzed to determine the accuracy of the identied crankshaft model.

5.1.1. Engine Harmonics

The cyclic nature of internal combustion engines can be described in terms of engine harmonics. For a four-stroke engine with two revolutions per cycle, the harmonic frequencies occur at multiples of the cycle duration, and have frequencies

N f = k , k ∈ (5.1) i 60 · 2 h h N

Since the studied engine has six combustion events per cycle, every 6th harmonic is of special interest. The frequency components of the induced torque due to combustion are shown in Figure 5.1 for an A100 and C100 operating point. These torques were determined from the unltered cylinder pressure measurements. For each harmonic frequency, the frequency content is determined using the MATLAB function goertzel. This function implements a discrete Fourier transform using the Goertzel algorithm and returns the Fourier transform for a selected set of frequencies. The frequency axis is normalized to engine harmonics. It is clearly visible that every 6th, 12th, 18th and 24th harmonic is dominant in the system input. Frequency components above the 36th harmonic are not signicant anymore, when compared to the most dominant harmonics.

21 4 A100 4 C100 10 10

2 2 10 10

0 0 10 10 Combustion torque |T(f)| [Nm] Combustion torque |T(f)| [Nm] 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 Harmonic: f/ f [−] Harmonic: f/ f [−] i 1 i 1

Figure 5.1.: Frequency components of the combustion torque.

The frequency components of the output angular velocity, measured at the pulley at the front of the engine, are shown in Figure 5.2. Although the frequency components of the combustion torque look quite the same for the two given operating points, the output speed of the C100 operating point shows excessive response at the 12th harmonic. This suggests a resonance frequency of the crankshaft system in the neighborhood of 184 Hz.

1 A100 1 C100 10 10

0 0 10 10 /dt(f)| [rad/s] /dt(f)| [rad/s] θ −1 θ −1 10 10

−2 −2 10 10

Output speed |d −3 Output speed |d −3 10 10 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 Harmonic: f/ f [−] Harmonic: f/ f [−] i 1 i 1

Figure 5.2.: Frequency components of the output speed.

5.1.2. Resonance Frequencies

With the identied model parameters, it is possible to determine the system resonance frequencies. Due to the nonlinear nature of the system, the model does not have resonance frequencies at isolated frequencies. To still have an idea of the resonances of the system, it is linearized at dierent crankshaft positions, namely at θ2 = {0, 45, 90, 135, 180, 225, 270, 315} degrees. For each crankshaft position, the state-space representation of the system has constant matrices and is therefore regarded as locally linearized. The Bode diagram of the transfer functions between torque inputs at the cylinder bodies and front body position output is shown in Figure 5.3.

The location of the resonance varies between 196.5 and 203.6 Hz and is the same for every input location. The location of the resonance agrees with the earlier rough estimation, in previous section,

22 based upon the measurement data. The anti-resonance however is also dependent on the input location and for cylinder 1 to 6, it is located around 61, 67, 76, 89, 113 and 168 Hz respectively. As can be seen, the nonlinear eects do not cause a very large range of (linearized) dynamic behavior. A linearization of the system is not expected to have dramatic eects on the performance of the model. A partial linearization, by averaging the mass matrix, will be therefore studied in Section 5.2.1.

From: T 1 From: T 2 From: T 3 From: T 4 From: T 5 From: T 6 −40

−60

−80

−100

−120

2 −140

To: θ To: −160 Magnitude (dB) Magnitude −180

−200

−220

−240 0 2 0 2 0 2 0 2 0 2 0 2 10 10 10 10 10 10 10 10 10 10 10 10 Frequency (Hz)

Figure 5.3.: Bode diagram of the locally linearized system, from torque inputs at the cylinder bodies to angular position at the front body.

The excitation frequencies, of the combustion torque, can be shown as a function of engine speed. By also showing the system resonance frequency band, a so-called Campbell diagram is obtained, see Figure 5.4. The A, B and C operating speeds, with their corresponding speed variations, are indicated by the red areas. The resonance frequency band is highlighted in blue. The harmonics are shown by the dashed lines, whereby every 6th harmonic is solid. As can be seen, for operating speed A the 20th harmonic does coincide with the resonance and one of the main harmonics (18th) is nearby, while at operating speed C the 13th harmonic does coincide with the resonance and one of its main harmonics (12th) is nearby. This explains why at operating speed C a large uctuation in output speed is observed.

250

200

150

100 Frequency [Hz] 50

0 0 500 1000 1500 2000 2500 Engine speed [rpm]

Figure 5.4.: Campbell diagram with excitation and resonance frequencies.

23 5.1.3. Model Error

The accuracy of the model is determined by evaluating a number of properties in time and frequency domain, at the operating points for validation. In the time-domain, the properties to evaluate model accuracy are the minimum, maximum and root mean square (RMS) error between measured and simulated crankshaft velocity over one cycle. The relative RMS error is obtained by relating the RMS error to the average crankshaft velocity θ˙2 at the front body. The time-domain properties are shown in Table 5.1.

Model error θ˙ [rad/s] 2 Min [rad/s] Max [rad/s] RMS [rad/s] RMS [%]

A100 127.0 -0.9477 1.4441 0.4331 0.34 B100 159.7 -1.2659 1.9229 0.4993 0.31 C100 192.5 -2.0587 2.7798 0.7279 0.38 A60 127.0 -1.2627 1.3517 0.4129 0.33 B50 159.7 -1.5294 1.7083 0.4873 0.31 C40 192.5 -2.1657 2.1888 0.5619 0.29 A20 127.0 -0.9469 1.4293 0.3617 0.28 B10 159.7 -1.4739 1.8382 0.4725 0.30 C0 192.5 -2.0860 1.8624 0.6053 0.31 average -1.5263 1.8362 0.5069 0.32

Table 5.1.: Model accuracy at various operating points.

In general, the RMS error increases with increasing engine speed and slightly with increasing load. The crankshaft speed variation amplitude itself shows the same behavior for the given operating points, making the observed error characteristic feasible. Relating the RMS error to the average crankshaft velocity does result in an average model error of 0.32%. Even when considering that peak values of the error might be three times larger than the RMS value, the relative error is very acceptable.

In order to obtain more information on the source of the model error, its frequency components are determined in terms of the engine harmonics. These frequency components are shown in Figure 5.5. At all operating points, the model error shows harmonic frequency components around 0.05 rad/s. At the A (1213 rpm) operating speed, the most dominant model error harmonics are around the 18th and 36th harmonic. At the B (1525 rpm) and C (1838 rpm) operating speeds, the most dominant model error harmonics are mostly around the 12th harmonic. These are quite the same frequencies as those that are dominant in the measured output because of the resonance frequency that is excited, thus making it hard to determine a possible error source. The dynamics around the 6th main harmonic are generally captured well. As shown by the relative RMS error, the performance of the identied model is good. In order to improve the result, more attention should be given to identifying the system behavior around the resonance frequency. This can be accomplished by increasing the importance of the C operating speeds during identication and should result in more equally distributed frequency content of the velocity error.

24 A20 A60 A100

0.5 0.5 0.5

0.4 0.4 0.4

0.3 0.3 0.3

0.2 0.2 0.2 Velocity error: |e(f)| [rad/s] Velocity error: |e(f)| [rad/s] Velocity error: |e(f)| [rad/s] 0.1 0.1 0.1

0 0 0 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 Harmonic: f / f [−] Harmonic: f / f [−] Harmonic: f / f [−] i 1 i 1 i 1

B10 B50 B100

0.5 0.5 0.5

0.4 0.4 0.4

0.3 0.3 0.3

0.2 0.2 0.2 Velocity error: |e(f)| [rad/s] Velocity error: |e(f)| [rad/s] Velocity error: |e(f)| [rad/s] 0.1 0.1 0.1

0 0 0 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 Harmonic: f / f [−] Harmonic: f / f [−] Harmonic: f / f [−] i 1 i 1 i 1

C0 C40 C100

0.5 0.5 0.5

0.4 0.4 0.4

0.3 0.3 0.3

0.2 0.2 0.2 Velocity error: |e(f)| [rad/s] Velocity error: |e(f)| [rad/s] Velocity error: |e(f)| [rad/s] 0.1 0.1 0.1

0 0 0 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 0 6 12 18 24 30 36 42 48 Harmonic: f / f [−] Harmonic: f / f [−] Harmonic: f / f [−] i 1 i 1 i 1

Figure 5.5.: Frequency components of the model error.

25 5.2. Model Simplications

In previous section, the accuracy of the proposed model with its identied parameters has been shown. The proposed model structure is nonlinear and contains a signicant number of parameters. To study whether this amount of model complexity is really necessary, some simplications of the model are investigated in this section. Three simplications are proposed, which are based on using a constant mass matrix, a simplied friction model and by representing the crankshaft as a single rigid-body. Reducing the model complexity is benecial for reducing the computational eort during identication and in the implementation of the virtual sensor algorithm on the ECU.

5.2.1. Constant mass matrix

The crankshaft model contains a crank-slider mechanism for every cylinder body. The kinetic energy of these bodies therefore varies as a function of its angular position and is one of the two reasons why the system is nonlinear. Namely, it causes the mass matrix (3.19) to become a function of angular position. The second reason why the system is nonlinear is because the input torque (3.21) is a static nonlinear function of angular position. In this section, the consequences of averaging the mass matrix is evaluated. The reason for investigating this simplication is that it would allow the system to be decomposed into an interconnection of a linear time-invariant system and a static nonlinear function. The current version of the virtual cylinder pressure sensor algorithm is developed for this type of system structure, where the constant mass matrix was originally obtained by neglecting the variation due to the oscillating mass.

In Figure 3.5, the variation of the mass matrix element M3,3 is shown. The nonconstant contribution 2 of the oscillating mass can be averaged by taking the average value of moscre. As a result, the averaged mass matrix is given by

 J for i = j ∈ {1, 2, 9}  cs,i   2 4  R R for (5.2) Mi,j = Jcs,i + Jcr,rot + mosc 2 + 8L2 i = j ∈ {3, ..., 8}  0 elsewhere

which is independent of the crankshaft position. The input torque remains the same static nonlinear function. As can be seen in Figure 5.6, the proposed constant mass matrix shows very little dierence in output at the A100 and C100 operating points.

26 A100 C100 1250 1950 1240 1900 1230 1220 1850 1210

1200 1800 1190

Speed [rpm] 1180 Speed [rpm] 1750 1170 measurement measurement 1700 1160 filtered filtered nonconstant nonconstant 1150 constant 1650 constant 1140 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg]

Figure 5.6.: Simulation output for the system with nonconstant and constant mass matrix.

The dierence in output is hardly visible. The model error of both the simulation output with nonconstant and constant mass matrix is therefore shown in Figure 5.7.

A100 C100 10 20

8 15

6 10

4 5 2 0 0 −5

Speed error [rpm] −2 Speed error [rpm] −10 −4 −15 −6 nonconstant constant −20 nonconstant constant −8 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg]

Figure 5.7.: Model error for the system with nonconstant and constant mass matrix.

The RMS model error for the operating points used for identication is given in Table 5.2 for both the model with nonconstant and constant mass matrix. In general, the dierence in performance is small and both positive and negative. At high loads the error increases slightly, but not excessively. The crankshaft model with the proposed constant mass matrix is therefore a good candidate for implementation in the virtual cylinder pressure sensor algorithm. This removes the necessity to increase the complexity and computational eort of the algorithm to deal with a non-LTI crankshaft model.

27 However, the actual performance should be evaluated in the intended application and a parameter identication dedicated to the simplied model may improve the results.

Model error (RMS) [rad/s] Nonconstant Constant Dierence

A100 0.4331 0.4443 0.0112 (2.6%) B100 0.4993 0.5165 0.0172 (3.4%) C100 0.7279 0.7375 0.0096 (1.3%) A20 0.3617 0.3598 -0.0019 (-0.5%) B10 0.4725 0.4775 0.0050 (1.1%) C0 0.6053 0.6149 0.0096 (1.6%)

Table 5.2.: Comparison in model error for the system with nonconstant and constant mass matrix

5.2.2. Simplied Friction Modeling

The friction coecients, as dened in Section 3.3, are identied for every single operating point. For the given set of operating points for identication, this results in a set of six values for every coecient. This amount of values is not enough to determine a detailed trend or engine characteristic throughout the map of operating points. The identied values are listed in Table 5.3.

Constant Velocity Load

c1 c2 · 100 c3 · 100 A100 B100 C100 A20 B10 C0

Table 5.3.: Identied friction coecients.

A visualization of the friction coecients within the engine map is shown in Figure 5.8. The identied coecients are shown in blue, while the interpolated coecients for the validation operating points are shown in red. The friction coecient c1 for the constant term is in general a correction for the applied load by the testbench, and does not show a clear trend. Moreover, the constant term does not directly contribute to the dynamic behavior of the crankshaft. The friction coecient c2 for the dependency on absolute piston velocity and c3 for the dependency on absolute combustion torque both show a little bit more consistent trend.

28 4 0.03 0.05

2 0.02

1 2 3 0 c 0 c 0.01 c

−2 0 −0.05 4000 4000 4000

2000 2000 2000 2000 2000 2000 T [Nm] 1500 T [Nm] 1500 T [Nm] 1500 0 1000 N [rpm] 0 1000 N [rpm] 0 1000 N [rpm]

Figure 5.8.: Identied friction coecients in the engine map.

For the friction coecients at the validation operating points, the approach is to use the interpolated values for c2 and c3, while c1 is tuned for correct steady-state operation. As can be seen in Section 4.4, this approach performs well.

Due to the lack of detail in the friction coecient characterization, caused by not having a large set of operating points for identication, it could be questioned whether it is realistic to include the proposed amount of detail in friction modeling. The instantaneous nature of the friction torque adds to the dynamics of the system, but will a constant friction deviate much in performance? To further investigate this question, additional simulations have been performed, whereby the average value of the instantaneous friction torque is used to replace the friction torque at the cylinder bodies. For the A100 operating point, where piston velocities are relatively low and combustion torques are large, a comparison of simulation results is shown in Figure 5.9. A slightly dierent response can be seen, but in general the improvements and degradations cancel each other and a similar change in response is also possible by parameter tuning, as will be shown in Section 5.3.

1250 1240

1230

1220

1210

Speed [rpm] 1200

1190

1180 measured filtered instantaneous constant 1170 0 120 240 360 480 600 720 Crankshaft position [deg]

Figure 5.9.: Simulation comparison for instantaneous and constant friction torque at A100.

For the other operating points, the comparison is made by evaluating the dierence in model error, as shown in Table 5.4. Overall, the dierence in performance is small and both positive and negative. The C100 operating point is the only one that shows a large dierence in model error, but the relative

29 RMS error is still only (0.794/192.5=) 0.41%, which is acceptable. It should be noted however that the model parameters were identied using the instantaneous friction model and it would be better to compare the two models after performing individual identications. Furthermore, actual performance should also be evaluated in the intended application, namely the virtual cylinder pressure sensor.

Model error (RMS) [rad/s] Instantaneous Constant Dierence

A100 0.4331 0.4536 0.0205 (4.7%) B100 0.4993 0.4855 -0.0138 (-2.8%) C100 0.7279 0.7940 0.0661 (9.1%) A20 0.3617 0.3541 -0.0076 (-2.1%) B10 0.4725 0.4619 -0.0106 (-2.2%) C0 0.6053 0.6298 0.0245 (4.0%)

Table 5.4.: Comparison in model error for instantaneous and constant friction torque.

5.2.3. Rigid-Body Approximation

The proposed model structure consists of nine separate bodies. The question arises whether this amount of bodies is necessary for describing the dynamic torsional behavior of the crankshaft. A common approach for light-duty gasoline engines is to use a rigid-body model in which no deection between the cylinder bodies is present [13]. This approach is used here to determine whether the reduction to a lower order model can also be used for this particular heavy-duty diesel application. All bodies are lumped into one body with a nonconstant mass, due to a summation of the individual contributions of (3.19). The applied torque is a summation of all torques (3.21) that were originally applied per body. The equations of motion are given by M(θ)θ¨ = F (θ,˙ θ) in which the nonconstant mass is given by P9 P8 2 and the input torque ˙ M(θ) M = i=1 Jcs,i + 6Jcr,rot + i=3 moscre (ϕi) F (θ, θ) is given by P9 P8 ˙ . F = i=1 Qi − i=3 moscre (ϕi)r ˙e (ϕi) θi

The MATLAB implementation of the rigid-body model is given in Appendix D. Rigid-body simulations have been performed for the A20, A100, C0 and C100 operating point, of which the results are shown in Figure 5.10. As can be seen, the simulation output is dominated by the 6th harmonic frequency, where the measured output especially at the C operating speed does mainly contains the 12th harmonic frequency. For the A operating points, the amplitude and waveform of the simulation output roughly ts the measurement. At the C operating points, there is a large dierence in amplitude and less comparable waveform. It is clear that the rigid-body crankshaft model does not contain enough dynamics to describe the measured velocity output.

30 A20 A100 1250 1250

1240 1240

1230 1230

1220 1220

1210 1210

Speed [rpm] 1200 Speed [rpm] 1200

1190 1190 measurement 1180 filtered 1180 simulation 1170 1170 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg]

C0 C100

1920 1920

1900 1900

1880 1880

1860 1860

1840 1840

1820 1820 Speed [rpm] Speed [rpm]

1800 1800

1780 1780

1760 1760

0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg]

Figure 5.10.: Rigid-body simulation results for the A20, A100, C0 and C100 operating points.

Another way of looking at the reduction to a rigid-body model is by observing the deection of each body with relation to the front body, dened as θi −θ2 . Fairly large deections are present at full load, as shown in Figure 5.11 on next page. It should also be noted that the crankshaft passes through an almost non-deformed state every 120 degrees, which is mainly the result of the zero eective radius at cylinder top-dead-center. For cylinder 6, which is at largest distance from the front pulley at which the position is measured, the deection reaches up to 0.8 degree. Neglecting these deections by reducing the system to a rigid-body is therefore not realistic, as was already shown by the rigid-body simulations.

31 A20 A60 A100 0.6 0.6 0.6

0.4 0.4 0.4

0.2 0.2 0.2

0 0 0

−0.2 −0.2 −0.2

−0.4 −0.4 −0.4

Deflection w.r.t. front [deg] −0.6 Deflection w.r.t. front [deg] −0.6 Deflection w.r.t. front [deg] −0.6

−0.8 −0.8 −0.8

−1 −1 −1 0 120 240 360 480 600 720 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg] Crankshaft position [deg]

B10 B50 B100 0.6 0.6 0.6

0.4 0.4 0.4

0.2 0.2 0.2

0 0 0

−0.2 −0.2 −0.2

−0.4 −0.4 −0.4

Deflection w.r.t. front [deg] −0.6 Deflection w.r.t. front [deg] −0.6 Deflection w.r.t. front [deg] −0.6

−0.8 −0.8 −0.8

−1 −1 −1 0 120 240 360 480 600 720 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg] Crankshaft position [deg]

C0 C40 C100 0.6 0.6 0.6

0.4 0.4 0.4

0.2 0.2 0.2

0 0 0

−0.2 −0.2 −0.2 1 2 −0.4 −0.4 −0.4 3

Deflection w.r.t. front [deg] −0.6 4 Deflection w.r.t. front [deg] −0.6 Deflection w.r.t. front [deg] −0.6 5 −0.8 6 −0.8 −0.8 rear −1 −1 −1 0 120 240 360 480 600 720 0 120 240 360 480 600 720 0 120 240 360 480 600 720 Crankshaft position [deg] Crankshaft position [deg] Crankshaft position [deg]

Figure 5.11.: Deection angles with respect to the front body θi − θ2 for all operating points. 32 5.3. Parameter Sensitivity

In order to determine the relative importance of the model parameters, a parameter sensitivity study has been performed. This study gives an insight in which model parameters are important during identication and for robustness. It also gives an indication of which parameters are important for improving the performance at a particular operating point. The sensitivity is determined by varying each individual parameter at all operating points for identication and observing the change in RMS speed error. The parameter variation is done by scaling its identied value in a range of 90% to 110%. The change in RMS speed error is then expressed as the relative change to the RMS speed error of the initial parameter value.

The parameters being studied are the parameters that were identied, see Table 4.1. Also J1, Ji,rot and mosc are varied to observe their sensitivity. The parameter sensitivity results are given in the graphs below.

Front body inertia

The parameter sensitivity of the front body inertia J2 is shown in Figure 5.12. All operating points show a decrease in speed error RMS when the inertia of the front body is increased, except for the C100 operating point which shows a very sensitive response in the opposite direction. The C100 operating point, with one of its main excitation harmonics close to the system resonance frequency, is sensitive for the exact location of this resonance frequency. This location is dependent on the front body inertia. The optimal value of the inertia is not directly visible as a minimum for all operating points, but is a compromise between the performance at the various operating points.

1 1.2 A100 0.9 1.15 B100 0.8 C100 A20 1.1 0.7 B10 C0 0.6 1.05

0.5

Speed error RMS [rad/s] 1

0.4 Speed error RMS increase [−]

0.95 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 J / J [−] J / J [−] 2 2,identified 2 2,identified

Figure 5.12.: Model error for variation of the front body inertia.

Rear body inertia

The parameter sensitivity of the rear body inertia J9 is shown in Figure 5.13. The variation in rear body inertia results in optimal values for each operating point, where the value resulting from the identication process is the overall optimum. The A100 operating point is most sensitive to variation

33 of the rear body inertia, as would be expected since this operating point has the largest low frequency excitation. The large rear body inertia is relatively important for the low frequency system behavior.

1 1.25 A100 0.9 1.2 B100 0.8 C100 1.15 A20 0.7 B10 1.1 C0 0.6 1.05 0.5 Speed error RMS [rad/s] 1 0.4 Speed error RMS increase [−]

0.95 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 J / J [−] J / J [−] 9 9,identified 9 9,identified

Figure 5.13.: Model error for variation of the rear body inertia.

Front stiness

The parameter sensitivity of the front stiness k2 is shown in Figure 5.14. All operating points tend to be quite insensitive for variation in front stiness and there is no clear overall trend. The front stiness is quite large when compared to the stiness between the cylinders, thus making the system behavior relatively insensitive to variation of this parameter. From the identication process, the identied value is very close to the initial estimate from the available data.

0.75 1.1 A100 0.7 1.08 B100 0.65 C100 1.06 0.6 A20 1.04 B10 0.55 C0 0.5 1.02

0.45 1 Speed error RMS [rad/s]

0.4 Speed error RMS increase [−] 0.98 0.35 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 k / k [−] k / k [−] 2 2,identified 2 2,identified

Figure 5.14.: Model error for variation of the front stiness.

Stiness between cylinder bodies

The parameter sensitivity of the stiness ki,i ∈ {3, ..., 7} between the cylinder bodies is shown in Figure 5.15. The C100 operating point is strongly sensitive to variation of the stiness, due to

34 variation in the location of the system resonance frequency. All other operating points show a less sensitive response and do have an optimum just below the identied value. The identied value is again a compromise between all operating points.

2 3 A100 B100 2.5 1.5 C100 A20 B10 2 C0 1 1.5

0.5 Speed error RMS [rad/s] 1 Speed error RMS increase [−]

0 0.5 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 k / k [−] k / k [−] i i,identified i i,identified

Figure 5.15.: Model error for variation of the stiness between the cylinder bodies.

Rear stiness

The parameter sensitivity of the rear stiness k8 is shown in Figure 5.16. The variation of the rear stiness shows the same sensitivity behavior as the front body inertia, but in opposite direction, as p would be expected from the resonance frequency ωn ≈ k/m. That is, lowering the rear stiness improves the performance at all operating points, except the C100 operating point which shows excessive sensitivity in the other direction.

1 1.25 A100 0.9 1.2 B100 C100 0.8 A20 1.15 B10 0.7 C0 1.1 0.6 1.05 0.5 Speed error RMS [rad/s] 1 0.4 Speed error RMS increase [−]

0.95 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 k / k [−] k / k [−] 8 8,identified 8 8,identified

Figure 5.16.: Model error for variation of the rear stiness.

Torsional damper, damping coecient

The parameter sensitivity of the damping coecient d1 of the torsional damper is shown in Figure 5.17. Within the applied range of variation, the performance of the model is not very sensitive for

35 the damping coecient of the torsional damper. This observation holds for all operating points.

0.75 1.12 A100 0.7 1.1 B100 C100 0.65 1.08 A20 B10 0.6 1.06 C0 0.55 1.04 0.5 1.02 0.45 Speed error RMS [rad/s] 1

0.4 Speed error RMS increase [−] 0.98 0.35 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 d / d [−] d / d [−] 1 1,identified 1 1,identified

Figure 5.17.: Model error for variation of the damping coecient of the torsional damper.

Torsional damper, inertia

The parameter sensitivity of the inertia J1 of the torsional damper is shown in Figure 5.18. In general, an increase of the inertia of the torsional damper causes better performance of the model. The C100 operating point shows again an opposite and more sensitive behavior, comparable with the front body inertia. The optimal value for the inertia is a compromise between the performance of all operating points.

1 1.12 A100 1.1 0.9 B100 1.08 C100 0.8 A20 1.06 B10 0.7 C0 1.04 0.6 1.02 0.5 1 Speed error RMS [rad/s]

0.4 Speed error RMS increase [−] 0.98

0.96 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 J / J [−] J / J [−] 1 1,identified 1 1,identified

Figure 5.18.: Model error for variation of the inertia of the torsional damper.

Damping coecient

The parameter sensitivity of the damping coecient cd is shown in Figure 5.19. For most operating points, a somewhat increased damping coecient increases the performance of the model. For the

36 C100 operating point a decrease in damping coecient is benecial, again in contrast to the other operating points.

1 1.2 A100 0.9 B100 1.15 C100 0.8 A20 B10 1.1 0.7 C0

0.6 1.05

0.5

Speed error RMS [rad/s] 1

0.4 Speed error RMS increase [−]

0.95 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 c / c [−] c / c [−] d d,identified d d,identified

Figure 5.19.: Model error for variation of the damping coecient.

Cylinder body inertia

The parameter sensitivity of the cylinder body inertia Jcs,i is shown in Figure 5.20. The C100 operating point shows an optimum at 94% of the identied amount of cylinder body inertia. All other operating points show an improvement with increased cylinder body inertia.

1.1 1.4 A100 1 B100 1.3 0.9 C100 A20 B10 0.8 1.2 C0 0.7

0.6 1.1

0.5 Speed error RMS [rad/s] 1

0.4 Speed error RMS increase [−]

0.9 0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 J / J [−] J / J [−] i i,identified i i,identified

Figure 5.20.: Model error for variation of the cylinder body inertia.

Oscillating mass

The parameter sensitivity of the oscillating mass mosc is shown in Figure 5.21. In general, the model performance is increased with a decrease in oscillating mass. The C0 operating point shows a dierent behavior with an optimum at the original amount of oscillating mass.

37 0.8 1.15 A100 B100 0.7 C100 1.1 A20 B10 0.6 C0 1.05 0.5

Speed error RMS [rad/s] 0.4 1 Speed error RMS increase [−]

0.9 0.95 1 1.05 1.1 0.9 0.95 1 1.05 1.1 m / m [−] m / m [−] osc osc,identified osc osc,identified

Figure 5.21.: Model error for variation of the oscillating mass.

Observations on the sensitivity study

For all studied parameters, although not shown here, the summation of the speed error RMS values of each operating point does show a minimum at or nearby the identied value. This indicates that the identication process has successfully determined an optimal set of parameters. However, combinations of parameter variation are also possible and the identied set of parameters might therefore also be a local minimum and dependent on the initial estimates of the parameter values. The initial estimates are based on data that was determined already quite accurately and these initial estimates are considered to be a good starting point. For most parameters, the C100 operating point shows quite dierent and more sensitive behavior under inuence of parameter variation, due to its excitation at the system resonance frequency. This often leads to a compromise between the model performance of individual operating points. Since the C0 and C100 operating points are nearby the system resonance frequency with one of their main excitation harmonics and do show opposite behavior in their sensitivity to parameter variation, it is worth trying to identify the model parameters at only these two operating points. This would decrease the computational eort of the identication process, because the other operating points are only necessary for identifying their friction coecients.

The parameters k2 for the front stiness and d1 for the damping coecient of the torsional damper are relatively insensitive to variation. They may need a larger range of parameter values during the identication process in order to determine their optimal values. Within the range of variation of 90% to 110%, the parameters of the rear body inertia J9 and stiness between the cylinders ki,i ∈ {3, ..., 7} do show the largest sensitivity and may be considered as most important parameters during identication and for robustness. Both parameters do show a large dierence between their initial estimate and identied value. Since they are important for the model performance, it is recommended to provide a better initial estimate for the parameter identication.

38 6. Conclusions, Recommendations and Implications

In this report, a dynamic crankshaft model is presented, which is a crucial part in the virtual cylinder pressure sensor concept of TNO. In this chapter, conclusions are drawn from the work discussed in this report, some observations for future research are made and the implications of this work are discussed.

6.1. Conclusions

A new exible crankshaft model has been successfully developed and experimentally validated. The control oriented model does use six cylinder pressure signals as input and provides the angular velocity at the location of the position encoder as output. In contrast to crankshaft models found in literature, which are mainly used for structural design and diagnosis, the new model is developed for on-line estimation of individual cylinder pressure traces to be used in closed-loop combustion control. The presented work is dedicated to a DAF MX 6-cylinder diesel engine, which represents a typical heavy- duty diesel engine application. Compared to previous work at TNO, an improved approximation of the system is proposed, to obtain a LTI system with static nonlinear function which ts the current virtual sensor algorithm.

A parameter identication is performed using the least squares error tting algorithm lsqnonlin of the MATLAB Optimization Toolbox. The initial model parameter values are based on FEM data provided by the engine manufacturer and are proven to be close to the values identied from measurement data. A parameter sensitivity analysis does show that the cylinder body inertia Jcs,i,i ∈ {3, ..., 8}, rear body inertia J9 and cylinder stiness ki,i ∈ {3, ..., 7} are the most sensitive parameters and therefore most important during identication and for robustness.

For nine operating points throughout the operating region of the engine, the average RMS error between simulated and measured velocity is about 0.5 rad/s. Expressed as a relative error this is about 0.3% of the crankshaft velocity, which is a good result. At the C operating points (angular velocity equal to 1838 rpm), the rst natural frequency of the system is strongly excited. This results in a fairly simple velocity waveform, since it is dominated mainly by a single frequency. At lower engine speeds, the velocity waveform is dominated by more frequencies. Especially at the B operating points and at low loads, in which case the resonance frequencies are hardly excited, there is a larger dierence in simulated and measured velocity waveform, although not noticeable in the RMS error. Overall, the crankshaft model and single set of identied parameters performs well at all operating points in predicting the angular velocity with a small error, at the position encoder location.

Two candidates for model simplication are proposed. The rst proposal is an averaging of the mass matrix of the equations of motion. Using a constant mass matrix does not signicantly increase the output error and is therefore a good candidate for implementation in the virtual cylinder pressure sensor algorithm. The second proposal is to use a simple friction model in which the instantaneous friction

39 torque is replaced by a constant average friction torque. This reduces the amount of parameters to be identied at each operating point. For the considered set of operating points, the output error is both increased and decreased, but only with small amounts.

A reduction to a single rigid-body, which is commonly the approach for light-duty engines, is not a candidate for model simplication. It was shown that this is not a valid approach for the heavy-duty engine being considered here, since the amount of angular deection between the bodies cannot be neglected and will result in a large output error.

6.2. Recommendations for Future Research

The crankshaft model presented predicts the angular velocity with small error. As such, it is rec- ommended to implement the crankshaft model in the virtual cylinder pressure sensor algorithm to determine the actual performance of the model and identied set of parameters. In the virtual sensor algorithm, the required accuracy of the crankshaft model may be dened as crankshaft position de- pendent. The required accuracy around top-dead-center of each piston is larger, as a consequence of the method used by the virtual sensor algorithm to determine the six cylinder pressure traces from one angular velocity signal. This may be exploited by using a crankshaft position dependent weighting function during identication, in order to improve the performance of the virtual cylinder pressure sensor algorithm.

The intended application is in a heavy-duty vehicle drivetrain. It is expected that the vehicle drivetrain system may be regarded as dynamically decoupled from the crankshaft system, but additional research has to be done to prove this statement. A similar analysis as for the testbench dynamics can be used. If the drivetrain is not decoupled from the crankshaft system, this will introduce a transmission-gear dependent rear body inertia. Another problem to solve is knowledge about the applied load at the rear of the crankshaft system. The load can be estimated by the ECU of the engine, or has to be measured at the driveshaft. The load applied by the accessories also has to be estimated by the ECU or has to be measured at the front pulley system. For the real-time implementation of the algorithm, it is necessary to evaluate whether the calculations can be performed within the available time-span. Since production engines are equipped with low-resolution position sensors, it has to be determined whether interpolation of this signal is accurate enough for the virtual sensor algorithm. Future research may also focus on online estimation of the model parameters and on model accuracy during transients where the applied loads are not constant.

6.3. Implications

A model describing the dynamic behavior of a heavy-duty diesel engine has become available as a result of this work. Since this control oriented model was required for the next step in the development and validation of the virtual cylinder pressure sensor concept, the algorithm might actually prove itself on real engine data. The virtual sensor will make implementation of closed-loop combustion control much more attractive, because the amount of required cylinder pressure sensors is reduced to a single one. Closed-loop combustion control will, in turn, contribute to cleaner and more fuel ecient vehicles.

40 Bibliography

[1] E. Ciulli. A review of internal combustion engine losses part 2: studies for global evaluations. Institution of Mechanical Engineers: Journal of Automobile Engineering, D:13, 1993.

[2] B. de Kraker. Mechanical Vibrations, chapter 2: Lagrangian Mechanics, pages 7982. Shaker Publishing, 2009.

[3] C.D. Rakopoulos E.G. Giakoumis A.M. Dimaratos. Evaluation of various dynamic issues during transient operation of turbocharged diesel engine with special reference to friction development. SAE International, page 20, 2007.

[4] M. Geveci A.W. Osburn M.A. Franchek. An investigation of crankshaft oscillations for cylinder health diagnostics. Mechanical Systems and Signal Processing, 19, 2005.

[5] G. Genta. Vibration Dynamics and Control, chapter 29: Torsional Vibration of . Springer, 2009.

[6] H. Ying Y. Shouping Z. Fujun Z. Changlu L. Qiang W. Haiyan. Non-linear torsional vibra- tion characteristics of an internal combustion engine crankshaft assembly. Chinese Journal of Mechanical Engineering, 25:12, 2012.

[7] M. Harrison. Controlling Noise and Vibrations, chapter 6: Sources of vibration and their control, page 326. SAE International, 2004.

[8] J.B. Heywood. Internal Combustion Engine Fundamentals, chapter 13: Engine Friction and Lubrication, pages 712747. McGraw-Hill, 1988.

[9] I. Andersson T. McKelvey. A system inversion approach on a crankshaft of an internal combustion engine. IEEE Conference on Decision and Control, 2004.

[10] A.J. Martyr M.A. Plint. Engine Testing, Theory and Practice, chapter 9: Coupling the engine to the dynamometer, pages 170196. Elsevier, 2007.

[11] F.P.T. Willems E. Doosje F. Engels X. Seykens. Cylinder pressure-based control in heavy-duty egr diesel engines using a virtual heat release and emission sensor. SAE International, 2010.

[12] F.P.T. Willems. Cylinder pressure-based control for heavy-duty diesel engines: potential and control system specication. Technical report, TNO-060-HM-2011-00247, 2011.

[13] A. Al-Durra L. Fiorentini M. Canova S. Yurkovich. A model-based estimator of engine cylinder pressure imbalance for combustion feedback control applications. Proceedings of the American Control Conference, 2011.

41 B. Connecting Rod Inertial Properties

The inertial properties of the connecting rod are given by its mass mcr, inertia Jcr and location of the center of gravity (COG), as depicted in Figure B.1. The length of the connecting rod is dened by L. The COG is positioned by length a and b.

Figure B.1.: Representation of the connecting rod.

It is common practice to divide the connecting rod into a rotating mass mrot at the crankshaft pin and an oscillating mass mosc at the piston pin. This division is performed based on the length ratio of the COG position as shown by

b m = m ≈ 3.35 [kg] (B.1) rot L cr a m = m ≈ 1.44 [kg] (B.2) osc L cr

However, for a correct equivalent of the connecting rod in terms of its kinetic energy, a correction

Jcr,ψ has to be made to the resulting inertia of the two masses, as shown in [5] and here repeated by

2 2 Jcr,ψ = Jcr − mrota + moscb ≈ −0.0047 [kgm²] (B.3)

The correction Jcr,ψ is dened around the COG of the connecting rod. For calculations, it is more convenient to express the correction around the rotation axis of the crankshaft as Jcr,θ, such that it can be added to the inertia of the cylinder segment body. The conversion is based upon conservation of kinetic energy between the two considered points, as shown in

˙ !2 1 ˙2 1 ˙2 ψ Jcr,θθ = Jcr,ψψ → Jcr,θ = Jcr,ψ (B.4) 2 2 θ˙

By substituting (3.3) into (B.4), the correction is expressed as

45 R2 J = J cos2 θ (B.5) cr,θ cr,ψ L2

However, by evaluating the maximum absolute value of the correction at θ = 0

R2 max |J | = −J ≈ 4.51 · 10−4 [kgm2] (B.6) cr,θ cr,ψ L2 and comparing it to the constant part of the cylinder body inertia

max |J | cr,θ ≈ 0.5% (B.7) Jcyl the conclusion is drawn that it is not necessary to include the correction.

46 C. Testbench Dynamics

The measurements on the DAF MX engine are performed at a testbench, where the engine was connected to an electric motor using a shaft and rubber coupling. It is common practice to design the stiness of this coupling for obtaining a resonance frequency outside the normal operating range of engine speeds, as outlined in [10]. The testbench inertia can therefore be assumed to be decoupled from the crankshaft system and may be neglected in the dynamic analysis of the crankshaft. Since the stiness of the coupling is known for this particular set of measurements, a verication can be made whether this assumption is valid.

A comparison is made between a rigid-body crankshaft (system A) and a rigid-body crankshaft with a testbench inertia connected to it by means of a stiness (system B). A schematic diagram of both systems is shown in Figure C.1.

Figure C.1.: Testbench dynamic model comparison.

For system A, the equation of motion and its Laplace transform is given by

¨ 2 Jcsθcs = Tcs + Tload,1 → Jcss Θcs = Tcs + Tload,1 (C.1)

The angular position output can be written as

1 1 (C.2) Θout = Θcs = 2 Tcs + 2 Tload,1 Jcss Jcss

For system B, the equations of motion and their Laplace transform are given by

¨ 2  Jcsθcs = Tcs − k (θcs − θtb) → Jcss + k Θcs = Tcs + kΘtb (C.3) and ¨ 2  Jtbθtb = Tload,2 + k (θcs − θtb) → Jtbs + k Θtb = Tload,2 + kΘcs (C.4)

47 By substituting (C.3) in (C.4), the angular position output can be written as

 2    Jcss + k k (C.5) Θout = Θtb = 2 2 2 Tload,2 + 2 2 2 Tcs (Jcss + k)(Jtbs + k) − k (Jcss + k)(Jtbs + k) − k

The amplication between input torque Tcs and output position Θout is used to determine the similarity of both models in the frequency domain. By multiplying the amplication derived from (C.2) with the amplication and its inverse derived from (C.5), the model comparison is expressed as

k 1 (C.6) 2 2 2 = 2 Hcompare (Jcss + k)(Jtbs + k) − k Jcss in which Hcompare is given by

2 Jcss k (C.7) Hcompare = 2 2 2 (Jcss + k)(Jtbs + k) − k

The amplitude of Hcompare is a measure for frequencies where the crankshaft and testbench may be regarded as decoupled. Around the resonance frequency of this transfer function, the behavior is dominated by the multi-body dynamics of system B. At other frequencies, the eect of the testbench inertia may be neglected when analyzing the crankshaft dynamics. The location of the resonance can be determined by solving for the poles of Hcompare, which are given by

r 1 Jcs + Jtb fn = k (C.8) 2π JcsJtb

When the testbench inertia increases, the resonance frequency decreases. There is an asymptotic minimum of the resonance frequency that can be achieved, which is dened by

1 r k fn,min = (C.9) 2π Jcs

For the engine being used in this report, the asymptotic boundary is at about 11Hz. Since only the amount of inertia of the crankshaft system and coupling components are known, and information about the electric motor is not available, it is not possible to dene an exact resonance frequency. Using the minimal amount of known inertia, an upper boundary at 32Hz can be determined using (C.8). The actual resonance frequency will be somewhere between these two limits. Whether this makes it necessary to include the testbench dynamics depends on the harmonic excitation frequencies of the engine. At a low engine speed of 1000rpm, the rst harmonic is located at 81/3Hz. For a 6-cylinder engine, mainly the 6th harmonic (50Hz) and its multiples are of importance, as was shown in Section 5.1.1. It is therefore not necessary to include the testbench dynamics into the model of the crankshaft.

48