00001 00009 #ifndef _diesel_dg_H 00010 #define _diesel_dg_H 00011 00012 #include <stdarg.h> 00013 #include "generators.h" 00014 00015 EXPORT SIMULATIONMODE interupdate_diesel_dg(OBJECT *obj, unsigned int64 delta_time, unsigned long dt, unsigned int iteration_count_val); 00016 EXPORT STATUS postupdate_diesel_dg(OBJECT *obj, complex *useful_value, unsigned int mode_pass); 00017 00018 //AVR state variable structure 00019 typedef struct { 00020 double bias; //Bias term of avr 00021 double xe; //State variable 00022 double xb; //State variable for transient gain reduction 00023 00024 double xfd; // State variable for PI control of the Q constant mode 00025 00026 // double x_cvr; // State variable for PI controller for CVR control 00027 // double xerr_cvr; // State variable for PID controller for CVR control 00028 double x_cvr1; // State variable for PI controller for CVR control 00029 double x_cvr2; // State variable for PI controller for CVR control 00030 double diff_f; // Difference between measured and reference frequency 00031 } AVR_VARS; 00032 00033 //GOV_DEGOV1 state variable structure 00034 typedef struct { 00035 double x1; //Electric box state variable 00036 double x2; //Electric box state variable 00037 double x4; //Actuator state variable 00038 double x5; //Actuator state variable 00039 double x6; //Actuator state variable 00040 double throttle; //governor actuator output 00041 } GOV_DEGOV1_VARS; 00042 00043 // gastflag 00044 //GOV_GAST state variable structure 00045 typedef struct { 00046 double x1; //Electric box state variable 00047 double x2; //Electric box state variable 00048 double x3; //Temp limiter state variable 00049 double throttle; //governor actuator output 00050 } GOV_GAST_VARS; 00051 00052 //GGOV1 state variable structure 00053 typedef struct { 00054 double werror; 00055 double x1; 00056 double x2; 00057 double x2a; 00058 double x3; 00059 double x3a; 00060 double x4; 00061 double x4a; 00062 double x4b; 00063 double x5; 00064 double x5a; 00065 double x5b; 00066 double x6; 00067 double x7; 00068 double x7a; 00069 double x8; 00070 double x8a; 00071 double x9; 00072 double x9a; 00073 double x10; 00074 double x10a; 00075 double x10b; 00076 double ValveStroke; 00077 double FuelFlow; 00078 double GovOutPut; 00079 double RselectValue; 00080 double fsrn; 00081 double fsrtNoLim; 00082 double fsrt; 00083 double fsra; 00084 double err2; 00085 double err2a; 00086 double err3; 00087 double err4; 00088 double err7; 00089 double LowValSelect1; 00090 double LowValSelect; 00091 } GOV_GGOV1_VARS; 00092 00093 // P_CONSTANT mode state variable structure 00094 typedef struct { 00095 double x1; 00096 double x4; 00097 double x4a; 00098 double x4b; 00099 double x5; 00100 double x5a; 00101 double x5b; 00102 double err4; 00103 double ValveStroke; 00104 double FuelFlow; 00105 double GovOutPut; 00106 double x_Pconstant; 00107 } GOV_P_CONSTANT_VARS; 00108 00109 //Machine state variable structure 00110 typedef struct { 00111 double rotor_angle; //Rotor angle of machine 00112 double omega; //Current speed of machine 00113 double Vfd; //Field voltage of machine 00114 double Flux1d; //Transient flux on d-axis 00115 double Flux2q; //Sub-transient flux on q-axis 00116 complex EpRotated; //d-q rotated E' internal voltage 00117 complex VintRotated; //d-q rotated Vint voltage 00118 complex EintVal[3]; //Unrotated, un-sequenced internal voltage 00119 complex Irotated; //d-q rotated current value 00120 complex pwr_electric; //Total electric power output of generator 00121 double pwr_mech; //Mechanical power output of generator 00122 double torque_mech; //Mechanical torque of generator 00123 double torque_elec; //electrical torque of generator 00124 GOV_DEGOV1_VARS gov_degov1; //DEGOV1 Governor state variables 00125 GOV_GAST_VARS gov_gast; //GAST Governor state variables 00126 GOV_GGOV1_VARS gov_ggov1; //GGOV1 governor state variables 00127 GOV_P_CONSTANT_VARS gov_pconstant; //P_CONSTANT mode state variables 00128 AVR_VARS avr; //Automatic Voltage Regulator state variables 00129 } MAC_STATES; 00130 00131 //Set-point/adjustable variables 00132 typedef struct { 00133 double wref; //Reference frequency/bias for generator object (governor) 00134 double vset; //Reference per-unit voltage/bias for generator object (AVR) 00135 double vseta; //Reference per-unit voltage/bias for generator object (AVR) before going into bound check 00136 double vsetb; //Reference per-unit voltage/bias for generator object (AVR) after going into bound check 00137 double vadd; //Additioal value added to the field voltage before going into the bound 00138 double vadd_a; //Additioal value added to the field voltage before going into the bound before going into bound check 00139 double Pref; //Reference real power output/bias (per-unit) for generator object (governor) 00140 double Qref; //Reference reactive power output/bias (per-unit) for generator object (AVR) 00141 } MAC_INPUTS; 00142 00143 class diesel_dg : public gld_object 00144 { 00145 private: 00146 double Rated_V_LN; //Rated voltage - LN value 00147 00148 gld_property *pCircuit_V[3]; 00149 gld_property *pLine_I[3]; 00150 gld_property *pPower[3]; 00151 00152 complex value_Circuit_V[3]; 00153 complex value_Line_I[3]; 00154 complex value_Power[3]; 00155 complex value_prev_Power[3]; 00156 00157 bool parent_is_powerflow; 00158 00159 bool first_run; 00160 bool is_isochronous_gen; 00161 00162 //Internal synchronous machine variables 00163 gld_property *pbus_full_Y_mat; //Link to the full_Y bus variable -- used for Norton equivalents 00164 gld_property *pbus_full_Y_all_mat; //Link to the full_Y_all bus variable -- used for Norton equivalents 00165 gld_property *pPGenerated; //Link to bus PGenerated field - mainly used for SWING generator 00166 gld_property *pIGenerated[3]; //Link to direct current injections to powerflow at bus-level (prerot current) 00167 complex value_IGenerated[3]; //Accumulator/holding variable for direct current injections at bus-level (pre-rotated current) 00168 complex generator_admittance[3][3]; //Generator admittance matrix converted from sequence values 00169 complex full_bus_admittance_mat[3][3]; //Full self-admittance of Ybus form - pulled from node connection 00170 double power_base; //Per-phase basis (divide by 3) 00171 double voltage_base; //Voltage p.u. base for analysis (converted from delta) 00172 double current_base; //Current p.u. base for analysis 00173 double impedance_base; //Impedance p.u. base for analysis 00174 complex YS0; //Zero sequence admittance - scaled (not p.u.) 00175 complex YS1; //Positive sequence admittance - scaled (not p.u.) 00176 complex YS2; //Negative sequence admittance - scaled (not p.u.) 00177 complex YS1_Full; //Positive sequence admittance - full Ybus value 00178 double Rr; //Rotor resistance term - derived 00179 double *torque_delay; //Buffer of delayed governor torques 00180 double *x5a_delayed; //Buffer of delayed x5a variables (ggov1) 00181 unsigned int torque_delay_len; //Length of the torque delay buffer 00182 unsigned int torque_delay_write_pos;//Indexing variable for writing the torque_delay_buffer 00183 unsigned int torque_delay_read_pos; //Indexing variable for reading torque_delay_buffer 00184 unsigned int x5a_delayed_len; //Length of the torque delay buffer 00185 unsigned int x5a_delayed_write_pos;//Indexing variable for writing the torque_delay_buffer 00186 unsigned int x5a_delayed_read_pos; //Indexing variable for reading torque_delay_buffer 00187 double prev_rotor_speed_val; //Previous value of rotor speed - used for delta-exiting convergence check 00188 double prev_voltage_val[3]; //Previous value of voltage magnitude - used for delta-exiting convergence check 00189 complex last_power_output[3]; //Tracking variable for previous power output - used to do super-second frequency adjustments 00190 TIMESTAMP prev_time; //Tracking variable for previous "new time" run 00191 double prev_time_dbl; //Tracking variable for previous "new time" run -- deltamode capable 00192 00193 MAC_STATES curr_state; //Current state of all vari 00194 MAC_STATES next_state; 00195 MAC_STATES predictor_vals; //Predictor pass values of variables 00196 MAC_STATES corrector_vals; //Corrector pass values of variables 00197 00198 bool deltamode_inclusive; //Boolean for deltamode calls - pulled from object flags 00199 gld_property *mapped_freq_variable; //Mapping to frequency variable in powerflow module - deltamode updates 00200 00201 double Overload_Limit_Value; //The computed maximum output power, based on the Rated_VA and the Overload_Limit_Value 00202 00203 protected: 00204 /* TODO: put unpublished but inherited variables */ 00205 public: 00206 /* TODO: put published variables here */ 00207 enum {DYNAMIC=1, NON_DYN_CONSTANT_PQ}; 00208 enumeration Gen_type; 00209 00210 //Dynamics synchronous generator capabilities 00211 enum {NO_EXC=1, SEXS}; 00212 enumeration Exciter_type; 00213 //gastflag 00214 enum {NO_GOV=1, DEGOV1=2, GAST=3, GGOV1_OLD=4, GGOV1=5, P_CONSTANT=6}; 00215 enumeration Governor_type; 00216 00217 //Enable/Disable low-value select blocks 00218 bool gov_ggv1_fsrt_enable; //Enables/disables top fsrt of low-value-select (load limiter) 00219 bool gov_ggv1_fsra_enable; //Enables/disables middle fsra of low-value select (acceleration limiter) 00220 bool gov_ggv1_fsrn_enable; //Enables/disables lower fsrn of low-value select (normal PID controller) 00221 00222 //General properties 00223 double Rated_V_LL; //Rated voltage - LL value 00224 double Rated_VA; 00225 double Overload_Limit_Pub; //Maximum rating for the generator, in per-unit 00226 double power_factor; 00227 00228 //Synchronous gen inputs 00229 00230 double Max_Ef;//< maximum induced voltage in p.u., e.g. 1.2 00231 double Min_Ef;//< minimus induced voltage in p.u., e.g. 0.8 00232 complex current_val[3]; //Present current output of the generator 00233 complex power_val[3]; //Present power output of the generator 00234 00235 //Convergence criteria (ion right now) 00236 double rotor_speed_convergence_criterion; 00237 double voltage_convergence_criterion; 00238 00239 //Which convergence to apply 00240 bool apply_rotor_speed_convergence; 00241 bool apply_voltage_mag_convergence; 00242 00243 //Dynamics-capable synchronous generator inputs 00244 double omega_ref; //Nominal frequency 00245 double inertia; //Inertial constant (H) of generator 00246 double damping; //Damping constant (D) of generator 00247 double number_poles; //Number of poles in the generator 00248 double Ra; //Stator resistance (p.u.) 00249 double Xd; //d-axis reactance (p.u.) 00250 double Xq; //q-axis reactance (p.u.) 00251 double Xdp; //d-axis transient reactance (p.u.) 00252 double Xqp; //q-axis transient reactance (p.u.) 00253 double Xdpp; //d-axis subtransient reactance (p.u.) 00254 double Xqpp; //q-axis subtransient reactance (p.u.) 00255 double Xl; //Leakage reactance (p.u.) 00256 double Tdp; //d-axis short circuit time constant (s) 00257 double Tdop; //d-axis open circuit time constant (s) 00258 double Tqop; //q-axis open circuit time constant (s) 00259 double Tdopp; //d-axis open circuit subtransient time constant (s) 00260 double Tqopp; //q-axis open circuit subtransient time constant (s) 00261 double Ta; //Armature short-circuit time constant (s) 00262 complex X0; //Zero sequence impedance (p.u.) 00263 complex X2; //Negative sequence impedance (p.u.) 00264 00265 MAC_INPUTS gen_base_set_vals; //Base set points for the various control objects 00266 bool Vset_defined; // Flag indicating whether Vset has been defined in glm file or not 00267 00268 //AVR properties (Simplified Exciter System (SEXS) - Industry acronym, I swear) 00269 double exc_KA; //Exciter gain (p.u.) 00270 double exc_TA; //Exciter time constant (seconds) 00271 double exc_TB; //Exciter transient gain reduction time constant (seconds) 00272 double exc_TC; //Exciter transient gain reduction time constant (seconds) 00273 double exc_EMAX; //Exciter upper limit (p.u.) 00274 double exc_EMIN; //Exciter lower limit (p.u.) 00275 00276 double ki_Pconstant; // ki for the PI controller implemented in P constant delta mode 00277 double kp_Pconstant; // kp for the PI controller implemented in P constant delta mode 00278 00279 bool P_constant_mode; // Flag indicating whether P constant mode is imployed 00280 bool Q_constant_mode; // Flag indicating whether Q constant mode is imployed 00281 double ki_Qconstant; // ki for the PI controller implemented in Q constant delta mode 00282 double kp_Qconstant; // kp for the PI controller implemented in Q constant delta mode 00283 00284 // parameters related to CVR control in AVR 00285 bool CVRenabled; // Flag indicating whether CVR control is enabled or not inside the exciter 00286 double ki_cvr; // Integral gain for PI/PID controller of the CVR control 00287 double kp_cvr; // Proportional gain for PI/PID controller of the CVR control 00288 double kd_cvr; // Deviation gain for PID controller of the CVR control 00289 double kt_cvr; // Gain for feedback loop in CVR control 00290 double kw_cvr; // Gain for feedback loop in CVR control 00291 bool CVR_PI; // Flag indicating CVR implementation is using PI controller 00292 bool CVR_PID; // Flag indicating CVR implementation is using PID controller 00293 double vset_EMAX; // Vset uppper limit 00294 double vset_EMIN; // Vset lower limit 00295 double Vref; // vset initial value before entering transient 00296 double Kd1; // Parameter of second order transfer function 00297 double Kd2; // Parameter of second order transfer function 00298 double Kd3; // Parameter of second order transfer function 00299 double Kn1; // Parameter of second order transfer function 00300 double Kn2; // Parameter of second order transfer function 00301 double vset_delta_MAX; // Delta Vset uppper limit 00302 double vset_delta_MIN; // Delta Vset lower limit 00303 00304 //CVR mode choices 00305 enum {HighOrder=1, Feedback}; 00306 enumeration CVRmode; 00307 00308 //Governor properties (DEGOV1) 00309 double gov_degov1_R; //Governor droop constant (p.u.) 00310 double gov_degov1_T1; //Governor electric control box time constant (s) 00311 double gov_degov1_T2; //Governor electric control box time constant (s) 00312 double gov_degov1_T3; //Governor electric control box time constant (s) 00313 double gov_degov1_T4; //Governor actuator time constant (s) 00314 double gov_degov1_T5; //Governor actuator time constant (s) 00315 double gov_degov1_T6; //Governor actuator time constant (s) 00316 double gov_degov1_K; //Governor actuator gain 00317 double gov_degov1_TMAX; //Governor actuator upper limit (p.u.) 00318 double gov_degov1_TMIN; //Governor actuator lower limit (p.u.) 00319 double gov_degov1_TD; //Governor combustion delay (s) 00320 00321 //Governor properties (GAST) 00322 double gov_gast_R; //Governor droop constant (p.u.) 00323 double gov_gast_T1; //Governor electric control box time constant (s) 00324 double gov_gast_T2; //Governor electric control box time constant (s) 00325 double gov_gast_T3; //Governor temp limiter time constant (s) 00326 double gov_gast_AT; //Governor Ambient Temperature load limit (units) 00327 double gov_gast_KT; //Governor temperature control loop gain 00328 double gov_gast_VMAX; //Governor actuator upper limit (p.u.) 00329 double gov_gast_VMIN; //Governor actuator lower limit (p.u.) 00330 // double gov_gast_TD; //Governor combustion delay (s) 00331 00332 //Governor properties (GGOV1) 00333 double gov_ggv1_r; //Permanent droop, p.u. 00334 unsigned int gov_ggv1_rselect; //Feedback signal for droop, = 1 selected electrical power, = 0 none (isochronous governor), = -1 fuel valve stroke ( true stroke),= -2 governor output ( requested stroke) 00335 double gov_ggv1_Tpelec; //Electrical power transducer time constant, sec. (>0.) 00336 double gov_ggv1_maxerr; //Maximum value for speed error signal 00337 double gov_ggv1_minerr; //Minimum value for speed error signal 00338 double gov_ggv1_Kpgov; //Governor proportional gain 00339 double gov_ggv1_Kigov; //Governor integral gain 00340 double gov_ggv1_Kdgov; //Governor derivative gain 00341 double gov_ggv1_Tdgov; //Governor derivative controller time constant, sec. 00342 double gov_ggv1_vmax; //Maximum valve position limit 00343 double gov_ggv1_vmin; //Minimum valve position limit 00344 double gov_ggv1_Tact; //Actuator time constant 00345 double gov_ggv1_Kturb; //Turbine gain (>0.) 00346 double gov_ggv1_wfnl; //No load fuel flow, p.u 00347 double gov_ggv1_Tb; //Turbine lag time constant, sec. (>0.) 00348 double gov_ggv1_Tc; //Turbine lead time constant, sec. 00349 unsigned int gov_ggv1_Flag; //Switch for fuel source characteristic, = 0 for fuel flow independent of speed, = 1 fuel flow proportional to speed 00350 double gov_ggv1_Teng; //Transport lag time constant for diesel engine 00351 double gov_ggv1_Tfload; //Load Limiter time constant, sec. (>0.) 00352 double gov_ggv1_Kpload; //Load limiter proportional gain for PI controller 00353 double gov_ggv1_Kiload; //Load limiter integral gain for PI controller 00354 double gov_ggv1_Ldref; //Load limiter reference value p.u. 00355 double gov_ggv1_Dm; //Speed sensitivity coefficient, p.u. 00356 double gov_ggv1_ropen; //Maximum valve opening rate, p.u./sec. 00357 double gov_ggv1_rclose; //Minimum valve closing rate, p.u./sec. 00358 double gov_ggv1_Kimw; //Power controller (reset) gain 00359 double gov_ggv1_Pmwset; //Power controller setpoint, MW 00360 double gov_ggv1_aset; //Acceleration limiter setpoint, p.u. / sec. 00361 double gov_ggv1_Ka; //Acceleration limiter Gain 00362 double gov_ggv1_Ta; //Acceleration limiter time constant, sec. (>0.) 00363 double gov_ggv1_db; //Speed governor dead band 00364 double gov_ggv1_Tsa; //Temperature detection lead time constant, sec. 00365 double gov_ggv1_Tsb; //Temperature detection lag time constant, sec. 00366 //double gov_ggv1_rup; //Maximum rate of load limit increase 00367 //double gov_ggv1_rdown; //Maximum rate of load limit decrease 00368 00369 set phases; 00371 // P_CONSTANT mode properties 00372 double pconstant_Tpelec; //Electrical power transducer time constant, sec. (>0.) 00373 double pconstant_Tact; //Actuator time constant 00374 double pconstant_Kturb; //Turbine gain (>0.) 00375 double pconstant_wfnl; //No load fuel flow, p.u 00376 double pconstant_Tb; //Turbine lag time constant, sec. (>0.) 00377 double pconstant_Tc; //Turbine lead time constant, sec. 00378 double pconstant_Teng; //Transport lag time constant for diesel engine 00379 double pconstant_ropen; //Maximum valve opening rate, p.u./sec. 00380 double pconstant_rclose; //Minimum valve closing rate, p.u./sec. 00381 double pconstant_Kimw; //Power controller (reset) gain 00382 unsigned int pconstant_Flag; //Switch for fuel source characteristic, = 0 for fuel flow independent of speed, = 1 fuel flow proportional to speed 00383 00384 // Fuel useage and emmisions 00385 bool fuelEmissionCal; // Boolean value indicating whether calculation of fuel and emissions are enabled 00386 double outputEnergy; // Total energy(kWh) output from the generator 00387 double FuelUse; // Total fuel usage (gal) based on kW power output 00388 double efficiency; // Total energy output per fuel usage (kWh/gal) 00389 double CO2_emission; // Total CO2 emissions (lbs) based on fule usage 00390 double SOx_emission; // Total SOx emissions (lbs) based on fule usage 00391 double NOx_emission; // Total NOx emissions (lbs) based on fule usage 00392 double PM10_emission; // Total PM-10 emissions (lbs) based on fule usage 00393 TIMESTAMP last_time; 00394 double dg_1000_a; // Parameter to calculate fuel usage (gal)based on VA power output (for 1000 kVA rating dg) 00395 double dg_1000_b; // Parameter to calculate fuel usage (gal)based on VA power output (for 1000 kVA rating dg) 00396 00397 // Relationship between frequency deviation and real power changes 00398 double frequency_deviation; 00399 double frequency_deviation_energy; 00400 double frequency_deviation_max; 00401 double realPowerChange; 00402 double ratio_f_p; 00403 double pwr_electric_init; 00404 00405 public: 00406 /* required implementations */ 00407 diesel_dg(MODULE *module); 00408 int create(void); 00409 int init(OBJECT *parent); 00410 TIMESTAMP presync(TIMESTAMP t0, TIMESTAMP t1); 00411 TIMESTAMP sync(TIMESTAMP t0, TIMESTAMP t1); 00412 TIMESTAMP postsync(TIMESTAMP t0, TIMESTAMP t1); 00413 //STATUS deltaupdate(unsigned int64 dt, unsigned int iteration_count_val); 00414 SIMULATIONMODE inter_deltaupdate(unsigned int64 delta_time, unsigned long dt, unsigned int iteration_count_val); 00415 STATUS post_deltaupdate(complex *useful_value, unsigned int mode_pass); 00416 public: 00417 static CLASS *oclass; 00418 static diesel_dg *defaults; 00419 void convert_Ypn0_to_Yabc(complex Y0, complex Y1, complex Y2, complex *Yabcmat); 00420 void convert_pn0_to_abc(complex *Xpn0, complex *Xabc); 00421 void convert_abc_to_pn0(complex *Xabc, complex *Xpn0); 00422 STATUS apply_dynamics(MAC_STATES *curr_time, MAC_STATES *curr_delta, double deltaT); 00423 STATUS init_dynamics(MAC_STATES *curr_time); 00424 complex complex_exp(double angle); 00425 double abs_complex(complex val); 00426 00427 friend class controller_dg; 00428 00429 gld_property *map_complex_value(OBJECT *obj, char *name); 00430 gld_property *map_double_value(OBJECT *obj, char *name); 00431 void pull_powerflow_values(void); 00432 void push_powerflow_values(bool update_voltage); 00433 void reset_powerflow_accumulators(void); 00434 00435 #ifdef OPTIONAL 00436 static CLASS *pclass; 00437 TIMESTAMPP plc(TIMESTAMP t0, TIMESTAMP t1); 00438 #endif 00439 }; 00440 00441 #endif 00442