├── .gitignore ├── ACMAnimate.py ├── ACMAnimate_extend_RT.py ├── ACMConfig.h ├── ACMGUI.py ├── ACMPlot.py ├── ACMSim.h ├── LICENSE.md ├── README.md ├── _femm ├── codes3 │ ├── CrossSectStator.py │ ├── FEMM_Solver.py │ ├── M-19-Steel-BH-Curve-afterJMAGsmooth.BH │ ├── VanGogh.py │ ├── acm_designer.py │ ├── acm_femm_script.py │ ├── default_setting.py │ ├── material.py │ ├── method_parallel_solve_4jmag.py │ ├── method_parasolve_greedy_search.py │ ├── parasolve.py │ ├── parasolve_greedy_search.py │ ├── parasolve_greedy_search_manager.py │ ├── population.py │ ├── pyfemm_script.py │ ├── pyrhonen_procedure_as_function.py │ ├── spec_Prototype2poleOD150mm500Hz_SpecifyTipSpeed.py │ ├── utility.py │ ├── utility_moo.py │ └── winding_layout.py └── release │ └── OneReport │ └── OneReport_TEX │ ├── OneReport.tex │ ├── epsfig.sty │ ├── interact.cls │ ├── subfig.sty │ ├── z.bat │ └── z_nul.bat ├── commissioning.c ├── commissioning.h ├── controller.c ├── controller.h ├── inverter.c ├── inverter.h ├── libsatlut.a ├── main.c ├── noloadtest.py ├── observer.c ├── observer.h ├── satlut-makefile-staticLIB.bat ├── satlut.c └── satlut.h /.gitignore: -------------------------------------------------------------------------------- 1 | # 2 | *.zip 3 | *.rar 4 | *.7z 5 | 6 | # sublime 7 | *.sublime-* 8 | 9 | # codes under development 10 | /_* 11 | 12 | # acm_simc related 13 | *.exe 14 | *.dat 15 | *.pyc 16 | /__pycache__ 17 | 18 | # acm_femm related 19 | /_femm/codes3/log 20 | /_femm/pop 21 | /_femm/run#* 22 | pyrhonen_procedure_s*.tex 23 | *.txt 24 | 25 | # subllime text 26 | *.sublime-project 27 | *.sublime-workspace 28 | 29 | # ----------------------------------------------------- for LaTeX related temporary files 30 | 31 | ## Core latex/pdflatex auxiliary files: 32 | *.aux 33 | *.lof 34 | *.log 35 | *.lot 36 | *.fls 37 | *.out 38 | *.toc 39 | *.fmt 40 | *.fot 41 | *.cb 42 | *.cb2 43 | .*.lb 44 | 45 | ## Intermediate documents: 46 | *.dvi 47 | *.xdv 48 | *-converted-to.* 49 | # these rules might exclude image files for figures etc. 50 | *.ps 51 | *.eps 52 | *.pdf 53 | 54 | ## Generated if empty string is given at "Please type another file name for output:" 55 | .pdf 56 | 57 | ## Bibliography auxiliary files (bibtex/biblatex/biber): 58 | *.bbl 59 | *.bcf 60 | *.blg 61 | *-blx.aux 62 | *-blx.bib 63 | *.run.xml 64 | 65 | ## Build tool auxiliary files: 66 | *.fdb_latexmk 67 | *.synctex 68 | *.synctex(busy) 69 | *.synctex.gz 70 | *.synctex.gz(busy) 71 | *.pdfsync 72 | 73 | ## Build tool directories for auxiliary files 74 | # latexrun 75 | latex.out/ 76 | 77 | ## Auxiliary and intermediate files from other packages: 78 | # algorithms 79 | *.alg 80 | *.loa 81 | 82 | # achemso 83 | acs-*.bib 84 | 85 | # amsthm 86 | *.thm 87 | 88 | # beamer 89 | *.nav 90 | *.pre 91 | *.snm 92 | *.vrb 93 | 94 | # changes 95 | *.soc 96 | 97 | # comment 98 | *.cut 99 | 100 | # cprotect 101 | *.cpt 102 | 103 | # elsarticle (documentclass of Elsevier journals) 104 | *.spl 105 | 106 | # endnotes 107 | *.ent 108 | 109 | # fixme 110 | *.lox 111 | 112 | # feynmf/feynmp 113 | *.mf 114 | *.mp 115 | *.t[1-9] 116 | *.t[1-9][0-9] 117 | *.tfm 118 | 119 | #(r)(e)ledmac/(r)(e)ledpar 120 | *.end 121 | *.?end 122 | *.[1-9] 123 | *.[1-9][0-9] 124 | *.[1-9][0-9][0-9] 125 | *.[1-9]R 126 | *.[1-9][0-9]R 127 | *.[1-9][0-9][0-9]R 128 | *.eledsec[1-9] 129 | *.eledsec[1-9]R 130 | *.eledsec[1-9][0-9] 131 | *.eledsec[1-9][0-9]R 132 | *.eledsec[1-9][0-9][0-9] 133 | *.eledsec[1-9][0-9][0-9]R 134 | 135 | # glossaries 136 | *.acn 137 | *.acr 138 | *.glg 139 | *.glo 140 | *.gls 141 | *.glsdefs 142 | *.lzo 143 | *.lzs 144 | 145 | # uncomment this for glossaries-extra (will ignore makeindex's style files!) 146 | # *.ist 147 | 148 | # gnuplottex 149 | *-gnuplottex-* 150 | 151 | # gregoriotex 152 | *.gaux 153 | *.gtex 154 | 155 | # htlatex 156 | *.4ct 157 | *.4tc 158 | *.idv 159 | *.lg 160 | *.trc 161 | *.xref 162 | 163 | # hyperref 164 | *.brf 165 | 166 | # knitr 167 | *-concordance.tex 168 | # TODO Comment the next line if you want to keep your tikz graphics files 169 | *.tikz 170 | *-tikzDictionary 171 | 172 | # listings 173 | *.lol 174 | 175 | # luatexja-ruby 176 | *.ltjruby 177 | 178 | # makeidx 179 | *.idx 180 | *.ilg 181 | *.ind 182 | 183 | # minitoc 184 | *.maf 185 | *.mlf 186 | *.mlt 187 | *.mtc[0-9]* 188 | *.slf[0-9]* 189 | *.slt[0-9]* 190 | *.stc[0-9]* 191 | 192 | # minted 193 | _minted* 194 | *.pyg 195 | 196 | # morewrites 197 | *.mw 198 | 199 | # nomencl 200 | *.nlg 201 | *.nlo 202 | *.nls 203 | 204 | # pax 205 | *.pax 206 | 207 | # pdfpcnotes 208 | *.pdfpc 209 | 210 | # sagetex 211 | *.sagetex.sage 212 | *.sagetex.py 213 | *.sagetex.scmd 214 | 215 | # scrwfile 216 | *.wrt 217 | 218 | # sympy 219 | *.sout 220 | *.sympy 221 | sympy-plots-for-*.tex/ 222 | 223 | # pdfcomment 224 | *.upa 225 | *.upb 226 | 227 | # pythontex 228 | *.pytxcode 229 | pythontex-files-*/ 230 | 231 | # tcolorbox 232 | *.listing 233 | 234 | # thmtools 235 | *.loe 236 | 237 | # TikZ & PGF 238 | *.dpth 239 | *.md5 240 | *.auxlock 241 | 242 | # todonotes 243 | *.tdo 244 | 245 | # vhistory 246 | *.hst 247 | *.ver 248 | 249 | # easy-todo 250 | *.lod 251 | 252 | # xcolor 253 | *.xcp 254 | 255 | # xmpincl 256 | *.xmpi 257 | 258 | # xindy 259 | *.xdy 260 | 261 | # xypic precompiled matrices and outlines 262 | *.xyc 263 | *.xyd 264 | 265 | # endfloat 266 | *.ttt 267 | *.fff 268 | 269 | # Latexian 270 | TSWLatexianTemp* 271 | 272 | ## Editors: 273 | # WinEdt 274 | *.bak 275 | *.sav 276 | 277 | # Texpad 278 | .texpadtmp 279 | 280 | # LyX 281 | *.lyx~ 282 | 283 | # Kile 284 | *.backup 285 | 286 | # KBibTeX 287 | *~[0-9]* 288 | 289 | # auto folder when using emacs and auctex 290 | ./auto/* 291 | *.el 292 | 293 | # expex forward references with \gathertags 294 | *-tags.tex 295 | 296 | # standalone packages 297 | *.sta 298 | 299 | # Makeindex log files 300 | *.lpz -------------------------------------------------------------------------------- /ACMAnimate.py: -------------------------------------------------------------------------------- 1 | import ACMGUI 2 | def restart(): 3 | print('Restart?') 4 | 5 | # import ACMGUI 6 | # gui = ACMGUI.ACMGUI() 7 | # gui.app 8 | 9 | global ani, _index 10 | # root = Tkinter.Tk() 11 | # root.withdraw() 12 | # result = tkMessageBox.askyesno("Restart", "Do you want to restart animation?") 13 | gui = ACMGUI.ACMGUI() 14 | 15 | # print(int(gui.mb.buttonReply)) 16 | if gui.mb.buttonReply == ACMGUI.QMessageBox.Yes: 17 | print('Yes clicked.') 18 | # ani.frame_seq = ani.new_frame_seq() 19 | # ani.event_source.start() 20 | _index = 0 21 | if gui.mb.buttonReply == ACMGUI.QMessageBox.No: 22 | print('No clicked.') 23 | plt.close() 24 | if gui.mb.buttonReply == ACMGUI.QMessageBox.Cancel: 25 | print('Cancelled') 26 | raise KeyboardInterrupt 27 | # gui.app.exec_() 28 | 29 | from pylab import subplots, mpl, plt, np 30 | import pandas as pd 31 | import time as time_package 32 | 33 | def get_data(fname): 34 | try: 35 | data = pd.read_csv(fname) #, skiprows=2, nrows=7) # na_values = ['no info', '.', ''] 36 | except pd.errors.EmptyDataError as error: 37 | # print(str(error)) 38 | # time_package.sleep(1) 39 | raise error 40 | keys = data.keys() 41 | return data, keys 42 | fname = './algorithm.dat' 43 | data, keys = get_data(fname) 44 | # print(keys) 45 | # print(data) 46 | # quit() 47 | 48 | fig, ax_list = plt.subplots(len(keys), sharex=True, figsize=(16*0.8, 9*0.8), dpi=80, facecolor='w', edgecolor='k', constrained_layout=False) 49 | 50 | SAMP_TS = 10/4000.000000 # TS=1/8000, down_exe=2, down-sampling 10: SAMP_TS=1/400 51 | n = number_points_draw_at_once = 100 # plot n points at a time 52 | POST_TS = SAMP_TS * n 53 | 54 | _index = 0 55 | def animate(_): 56 | global data, keys, _index 57 | if not bool_animate_pause: 58 | if _index > 0: 59 | time = np.arange(1, n*_index+1) * SAMP_TS 60 | for idx, ax in enumerate(ax_list): 61 | ax.cla() 62 | try: 63 | ax.plot(time, data[keys[idx]][:n*_index]) 64 | 65 | except ValueError as error: 66 | # print(str(error)) 67 | data_backup = data 68 | data, keys = get_data(fname) 69 | print('Read data.') 70 | if len(data[keys[0]]) == len(data_backup[keys[0]]): 71 | print('Plotting data are exausted. Quit now.') 72 | _index = -1 73 | break 74 | else: 75 | ax.set_ylabel(keys[idx]) 76 | ax_list[-1].set_xlabel('Time [s]') 77 | # ax.set_title("Frame {}".format(i)) 78 | # ax.relim() 79 | # ax.autoscale_view() 80 | 81 | if _index == -1: 82 | restart() 83 | # raise KeyboardInterrupt 84 | _index += 1 85 | 86 | def onClick(event): 87 | global bool_animate_pause 88 | bool_animate_pause ^= True 89 | 90 | import matplotlib.animation as animation 91 | bool_animate_pause = False 92 | ani = animation.FuncAnimation(fig, animate, blit=False, interval=10, repeat=False) 93 | fig.canvas.mpl_connect('button_press_event', onClick) 94 | time_package.sleep(0.1) 95 | 96 | print('Animate starts...') 97 | plt.show() 98 | 99 | -------------------------------------------------------------------------------- /ACMAnimate_extend_RT.py: -------------------------------------------------------------------------------- 1 | from pylab import subplots, mpl, plt, np 2 | import pandas as pd 3 | import time as time_package 4 | def get_data(fname): 5 | try: 6 | data = pd.read_csv(fname) #, skiprows=2, nrows=7) # na_values = ['no info', '.', ''] 7 | except pd.errors.EmptyDataError as error: 8 | # print(str(error)) 9 | # time_package.sleep(1) 10 | raise error 11 | keys = data.keys() 12 | return data, keys 13 | fname = './algorithm.dat' 14 | data, keys = get_data(fname) 15 | 16 | 17 | fig, ax_list = plt.subplots(5, sharex=True, figsize=(16*0.8, 9*0.8), dpi=80, facecolor='w', edgecolor='k', constrained_layout=False) 18 | 19 | SAMP_TS = 10/4000.000000 # TS=1/8000, down_exe=2, down-sampling 10: SAMP_TS=1/400 20 | n = number_points_draw_at_once = 100 # plot n points at a time 21 | POST_TS = SAMP_TS * n 22 | 23 | time = [0.0] 24 | for key in keys: 25 | exec(f'{key} = [0.0]') 26 | _index = 0 27 | def animate(_): 28 | global data, keys, _index 29 | if not bool_animate_pause: 30 | if _index > 0: 31 | time.extend(time[-1] + _index*np.arange(1/n, 1+0.5/n, 1/n) * SAMP_TS) 32 | for idx, ax in enumerate(ax_list): 33 | ax.cla() 34 | exec(f'{keys[idx]}.extend(data[keys[idx]][(_index-1)*n:_index*n])') 35 | try: 36 | ax.plot(time, eval(f'{keys[idx]}')) 37 | except ValueError as error: 38 | # print(str(error)) 39 | data_backup = data 40 | data, keys = get_data(fname) 41 | print('Read data.') 42 | if len(data[keys[0]]) == len(data_backup[keys[0]]): 43 | print('Plotting data are exausted. Quit now.') 44 | _index = -1 45 | break 46 | else: 47 | ax.set_ylabel(keys[idx]) 48 | ax_list[-1].set_xlabel('Time [s]') 49 | if _index == -1: 50 | raise KeyboardInterrupt 51 | _index += 1 52 | 53 | def onClick(event): 54 | global bool_animate_pause 55 | bool_animate_pause ^= True 56 | 57 | import matplotlib.animation as animation 58 | bool_animate_pause = False 59 | ani = animation.FuncAnimation(fig, animate, blit=False, interval=10, repeat=True) 60 | fig.canvas.mpl_connect('button_press_event', onClick) 61 | time_package.sleep(0.5) 62 | print('Animate starts...') 63 | plt.show() 64 | 65 | -------------------------------------------------------------------------------- /ACMConfig.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef ACMCONFIG_H 3 | #define ACMCONFIG_H 4 | 5 | #define NULL_D_AXIS_CURRENT_CONTROL -1 6 | #define MTPA -2 // not supported 7 | 8 | #define NUMBER_OF_STEPS (250000) 9 | #define DOWN_SAMPLE 1 10 | #define CONTROL_STRATEGY NULL_D_AXIS_CURRENT_CONTROL 11 | #define SENSORLESS_CONTROL false 12 | #define SENSORLESS_CONTROL_HFSI false 13 | #define VOLTAGE_CURRENT_DECOUPLING_CIRCUIT False 14 | #define SATURATED_MAGNETIC_CIRCUIT False 15 | #define INVERTER_NONLINEARITY false 16 | #define TS 0.00025 17 | #define TS_INVERSE 4000 18 | #define TS_UPSAMPLING_FREQ_EXE 0.5 19 | #define TS_UPSAMPLING_FREQ_EXE_INVERSE 2 20 | #define PMSM_NUMBER_OF_POLE_PAIRS 2 21 | #define PMSM_RESISTANCE 0.45 22 | #define PMSM_D_AXIS_INDUCTANCE 0.00415 23 | #define PMSM_Q_AXIS_INDUCTANCE 0.00415 // 0.01674 24 | #define PMSM_PERMANENT_MAGNET_FLUX_LINKAGE 0.504 25 | #define PMSM_SHAFT_INERTIA 0.06 // delta =3, 4, 10 26 | #define SPEED_LOOP_PID_PROPORTIONAL_GAIN 1.88 // 2.64 // 2.356 // 0.5 27 | #define SPEED_LOOP_PID_INTEGRAL_TIME_CONSTANT (1/20.9) // (1/8.8) // (1/19.635) // 1.05 28 | #define SPEED_LOOP_PID_DIREVATIVE_TIME_CONSTANT 0 29 | #define SPEED_LOOP_LIMIT_NEWTON_METER 8 // 8 30 | #define SPEED_LOOP_CEILING 4 31 | #define CURRENT_LOOP_PID_PROPORTIONAL_GAIN 0.78 // (3.65) //0.78 // 15 32 | #define CURRENT_LOOP_PID_INTEGRAL_TIME_CONSTANT (1/108.434) //0.08 33 | #define CURRENT_LOOP_PID_DIREVATIVE_TIME_CONSTANT 0 34 | #define CURRENT_LOOP_LIMIT_VOLTS 400 // 400 35 | #define DATA_FILE_NAME "pmsm_sc.dat" 36 | #define PC_SIMULATION True 37 | 38 | #define MACHINE_TS (TS*TS_UPSAMPLING_FREQ_EXE) //1.25e-4 39 | #define MACHINE_TS_INVERSE (TS_INVERSE*TS_UPSAMPLING_FREQ_EXE_INVERSE) // 8000 40 | 41 | #endif 42 | 43 | 44 | // delta = 3 45 | // 20 ms -> 5 ms 46 | // 电流环带宽 转速环带宽 47 | // 30 120 48 | // 22.5 66 49 | 50 | // 可以调节的量: 51 | // SPEED_LOOP_CEILING 52 | // LIMIT 53 | // ACM.Tload 54 | // ACM.rpm_cmd 55 | // CJH_TUNING_A 56 | 57 | // 无传感调试规律 58 | // delta = 3, Tuning_A =25 59 | // delta = 4, Tuning_A = 15 60 | // delta = 10, Tuning_A = 1 61 | 62 | -------------------------------------------------------------------------------- /ACMGUI.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | """ 3 | Spyder Editor 4 | This is a temporary script file. 5 | https://stackoverflow.com/questions/52380572/handling-folds-in-spyder 6 | """ 7 | 8 | import sys 9 | import qdarkstyle 10 | from PyQt5 import QtWidgets 11 | from PyQt5.QtWidgets import ( QApplication, QComboBox, QDialog, 12 | QDialogButtonBox, QFormLayout, QGridLayout, QGroupBox, QHBoxLayout, 13 | QLabel, QLineEdit, QMenu, QMenuBar, QPushButton, QSpinBox, QTextEdit, 14 | QVBoxLayout,QWidget ) 15 | 16 | from PyQt5.QtWidgets import QApplication, QWidget, QPushButton, QMessageBox 17 | from PyQt5.QtGui import QIcon 18 | from PyQt5.QtCore import pyqtSlot 19 | 20 | class Dialog(QDialog): 21 | NumGridRows = 3 22 | NumButtons = 4 23 | 24 | def __init__(self): 25 | super(Dialog, self).__init__() 26 | self.createFormGroupBox() 27 | 28 | buttonBox = QDialogButtonBox(QDialogButtonBox.Ok | QDialogButtonBox.Cancel) 29 | buttonBox.accepted.connect(self.accept) 30 | buttonBox.rejected.connect(self.reject) 31 | 32 | mainLayout = QVBoxLayout() 33 | mainLayout.addWidget(self.formGroupBox) 34 | mainLayout.addWidget(buttonBox) 35 | self.setLayout(mainLayout) 36 | 37 | self.setWindowTitle("Form Layout - pythonspot.com") 38 | 39 | def createFormGroupBox(self): 40 | self.formGroupBox = QGroupBox("Form layout") 41 | layout = QFormLayout() 42 | layout.addRow(QLabel("Name:"), QLineEdit()) 43 | layout.addRow(QLabel("Country:"), QComboBox()) 44 | layout.addRow(QLabel("Age:"), QSpinBox()) 45 | self.formGroupBox.setLayout(layout) 46 | 47 | class MessageBox(QWidget): 48 | 49 | def __init__(self): 50 | super().__init__() 51 | self.title = 'PyQt5 messagebox - pythonspot.com' 52 | self.left = 10 53 | self.top = 10 54 | self.width = 320 55 | self.height = 200 56 | self.initUI() 57 | 58 | def initUI(self): 59 | self.setWindowTitle(self.title) 60 | self.setGeometry(self.left, self.top, self.width, self.height) 61 | 62 | # self.buttonReply = QMessageBox.question(self, 'PyQt5 message', "Do you like PyQt5?", QMessageBox.Yes | QMessageBox.No, QMessageBox.No) 63 | self.buttonReply = QMessageBox.question(self, 'PyQt5 message', "Do you want to restart?", QMessageBox.Yes | QMessageBox.No | QMessageBox.Cancel, QMessageBox.Cancel) 64 | # self.show() 65 | 66 | if __name__ == '__main__': 67 | app = QApplication(sys.argv) 68 | mb = MessageBox() 69 | sys.exit(app.exec_()) 70 | 71 | 72 | class ACMGUI(object): 73 | def __init__(self): 74 | 75 | self.app = QApplication(sys.argv) 76 | self.mb = MessageBox() 77 | 78 | # # create the application and the main window 79 | # app = QApplication(sys.argv) 80 | # dialog = Dialog() 81 | # # app = QtWidgets.QApplication(sys.argv) 82 | # # window = QtWidgets.QMainWindow() 83 | 84 | # # setup stylesheet 85 | # app.setStyleSheet(qdarkstyle.load_stylesheet_pyqt5()) 86 | # self.app = app 87 | 88 | # # run 89 | # # sys.exit(dialog.exec_()) 90 | # # window.show() 91 | # # app.exec_() 92 | 93 | 94 | if __name__ == '__main__': 95 | # create the application and the main window 96 | app = QApplication(sys.argv) 97 | dialog = Dialog() 98 | # app = QtWidgets.QApplication(sys.argv) 99 | # window = QtWidgets.QMainWindow() 100 | 101 | # setup stylesheet 102 | app.setStyleSheet(qdarkstyle.load_stylesheet_pyqt5()) 103 | 104 | # run 105 | sys.exit(dialog.exec_()) 106 | # window.show() 107 | # app.exec_() 108 | 109 | -------------------------------------------------------------------------------- /ACMPlot.py: -------------------------------------------------------------------------------- 1 | #coding:u8 2 | from pylab import plt, mpl, np 3 | from mpl_toolkits.axes_grid1.inset_locator import zoomed_inset_axes 4 | from mpl_toolkits.axes_grid1.inset_locator import mark_inset 5 | # from pprint import pprint 6 | from collections import OrderedDict as O 7 | import pandas as pd 8 | # plot style 9 | style = np.random.choice(plt.style.available); print(style); 10 | plt.style.use('grayscale') # ['grayscale', u'dark_background', u'bmh', u'grayscale', u'ggplot', u'fivethirtyeight'] 11 | # plot setting 12 | mpl.rcParams['mathtext.fontset'] = 'stix' 13 | mpl.rcParams['font.family'] = 'STIXGeneral' 14 | mpl.rcParams['legend.fontsize'] = 12.5 15 | # mpl.rcParams['legend.family'] = 'Times New Roman' 16 | mpl.rcParams['font.family'] = ['Times New Roman'] 17 | mpl.rcParams['font.size'] = 14.0 18 | # mpl.style.use('classic') 19 | font = {'family' : 'Times New Roman', #'serif', 20 | 'color' : 'darkblue', 21 | 'weight' : 'normal', 22 | 'size' : 14,} 23 | textfont = {'family' : 'Times New Roman', #'serif', 24 | 'color' : 'darkblue', 25 | 'weight' : 'normal', 26 | 'size' : 11.5,} 27 | 28 | ###################### 29 | # Plotting 30 | def get_axis(cNr): 31 | # fig, axes = plt.subplots(ncols=cNr[0], nrows=cNr[1], dpi=150, sharex=True); 32 | fig, axes = plt.subplots(ncols=cNr[0], nrows=cNr[1], sharex=True, figsize=(16*0.8, 9*0.8), dpi=80, facecolor='w', edgecolor='k'); 33 | fig.subplots_adjust(right=0.95, bottom=0.1, top=0.95, hspace=0.2, wspace=0.02) 34 | # fig.subplots_adjust(right=0.85, bottom=0.1, top=0.95, hspace=0.25) 35 | if sum(cNr)<=2: 36 | return axes 37 | else: 38 | return axes.ravel() 39 | 40 | def plot_key(ax, key, df): 41 | ax.plot(time, df[key].values, '-', lw=1) 42 | ax.set_ylabel(key, fontdict=font) 43 | 44 | def plot_it(ax, ylabel, d, time=None): 45 | count = 0 46 | for k, v in d.items(): 47 | if count == 0: 48 | count += 1 49 | # ax.plot(time, v, '--', lw=2, label=k) 50 | ax.plot(time, v, '-', lw=1) 51 | else: 52 | # ax.plot(time, v, '-', lw=2, label=k) 53 | ax.plot(time, v, '-', lw=1) 54 | 55 | # ax.legend(loc='lower right', shadow=True) 56 | # ax.legend(bbox_to_anchor=(1.08,0.5), borderaxespad=0., loc='center', shadow=True) 57 | ax.set_ylabel(ylabel, fontdict=font) 58 | # ax.set_xlim(0,35) # shared x 59 | # ax.set_ylim(0.85,1.45) 60 | 61 | if __name__ == '__main__': 62 | 63 | df_info = pd.read_csv(r"./info.dat", na_values = ['1.#QNAN', '-1#INF00', '-1#IND00']) 64 | data_file_name = df_info['DATA_FILE_NAME'].values[0].strip() 65 | print(data_file_name) 66 | df_profiles = pd.read_csv(data_file_name, na_values = ['1.#QNAN', '-1#INF00', '-1#IND00']) 67 | 68 | no_samples = df_profiles.shape[0] 69 | no_traces = df_profiles.shape[1] 70 | print(df_info, 'Simulated time: %g s.'%(no_samples * df_info['TS'].values[0] * df_info['DOWN_SAMPLE'].values[0]), 'Key list:', sep='\n') 71 | for key in df_profiles.keys(): 72 | print('\t', key) 73 | 74 | time = np.arange(1, no_samples+1) * df_info['DOWN_SAMPLE'].values[0] * df_info['TS'].values[0] 75 | 76 | ax_list = [] 77 | for i in range(0, no_traces, 6): 78 | ax_list += list(get_axis((1,6))) 79 | 80 | for idx, key in enumerate(df_profiles.keys()): 81 | plot_it(ax_list[idx], key, O([ 82 | (str(idx), df_profiles[key]), 83 | # (str(idx), df_profiles[key]), 84 | ]), time) 85 | plt.show() 86 | quit() 87 | 88 | 89 | -------------------------------------------------------------------------------- /ACMSim.h: -------------------------------------------------------------------------------- 1 | #ifndef ACMSIM_H 2 | #define ACMSIM_H 3 | 4 | /* standard lib */ 5 | // #include // bool for _Bool and true for 1 6 | #include // printf #include // bool for _Bool and true for 1 7 | #include //reqd. for system function prototype 8 | #include // for clrscr, and getch() 9 | #include "stdlib.h" // for rand() 10 | #include "math.h" 11 | #include "time.h" 12 | 13 | /* Macro for Part transformation*/ 14 | #define AB2M(A, B, COS, SIN) ( (A)*COS + (B)*SIN ) 15 | #define AB2T(A, B, COS, SIN) ( (A)*-SIN + (B)*COS ) 16 | #define MT2A(M, T, COS, SIN) ( (M)*COS - (T)*SIN ) 17 | #define MT2B(M, T, COS, SIN) ( (M)*SIN + (T)*COS ) 18 | 19 | // Macro for Power-invariant inverse Clarke transformation 20 | #define AB2U(A, B) ( 0.816496580927726 * ( A ) ) 21 | #define AB2V(A, B) ( 0.816496580927726 * ( A*-0.5 + B*0.8660254037844387 ) ) 22 | #define AB2W(A, B) ( 0.816496580927726 * ( A*-0.5 + B*-0.8660254037844385 ) ) 23 | 24 | /* General Constants */ 25 | #define TRUE True 26 | #define FALSE False 27 | #define True true 28 | #define False false 29 | #define true (1) 30 | #define false (0) 31 | #define ONE_OVER_2PI 0.15915494309189535 // 1/(2*pi) 32 | #define TWO_PI_OVER_3 2.0943951023931953 33 | #define SIN_2PI_SLASH_3 0.86602540378443871 // sin(2*pi/3) 34 | #define SIN_DASH_2PI_SLASH_3 -0.86602540378443871 // sin(-2*pi/3) 35 | #define SQRT_2_SLASH_3 0.81649658092772603 // sqrt(2.0/3.0) 36 | #define abs use_fabs_instead_or_you_will_regret 37 | // #define RPM_2_RAD_PER_SEC 0.20943951023931953 // (2/60*Tpi) 38 | // #define RAD_PER_SEC_2_RPM 4.7746482927568605 // 1/(im.npp/60*Tpi) 39 | #define RAD_PER_SEC_2_RPM ( 60.0/(2*M_PI*ACM.npp) ) 40 | #define RPM_2_RAD_PER_SEC ( (2*M_PI*ACM.npp)/60.0 ) 41 | #define M_PI_OVER_180 0.017453292519943295 42 | // #define PI_D 3.1415926535897932384626433832795 /* double */ 43 | 44 | // 补充的宏,为了实现实验/仿真代码大一统 45 | #define Uint32 unsigned long int 46 | #define Uint16 unsigned int 47 | 48 | #define NUMBER_OF_STATES 4 // valid for PMSM 49 | #define PHASE_NUMBER 3 // 3 phase machine 50 | 51 | 52 | 53 | // Everthing else is in here 54 | #include "ACMConfig.h" 55 | 56 | 57 | 58 | #define UAL_C_DIST ACM.ual_c_dist // alpha-component of the distorted phase voltage = sine voltage + distored component 59 | #define UBE_C_DIST ACM.ube_c_dist 60 | #define DIST_AL ACM.dist_al // alpha-component of the distorted component of the voltage 61 | #define DIST_BE ACM.dist_be 62 | 63 | struct SynchronousMachineSimulated{ 64 | 65 | double Ts; 66 | 67 | double x[NUMBER_OF_STATES]; 68 | double x_dot[NUMBER_OF_STATES]; 69 | 70 | double omg_elec; 71 | double rpm; 72 | double rpm_cmd; 73 | double rpm_deriv_cmd; 74 | double Tload; 75 | double Tem; 76 | 77 | double npp; 78 | 79 | double R; 80 | double Ld; 81 | double Lq; 82 | double KE; // psi_PM 83 | double Js; 84 | 85 | double mu_m; 86 | double L0; 87 | double L1; 88 | 89 | double ual; 90 | double ube; 91 | double ial; 92 | double ibe; 93 | 94 | double ual_c_dist; 95 | double ube_c_dist; 96 | double dist_al; 97 | double dist_be; 98 | 99 | double theta_d; 100 | double ud; 101 | double uq; 102 | double id; 103 | double iq; 104 | 105 | double eemf_q; 106 | double eemf_al; 107 | double eemf_be; 108 | double theta_d__eemf; 109 | }; 110 | extern struct SynchronousMachineSimulated ACM; 111 | 112 | #include "controller.h" 113 | #include "observer.h" 114 | // #include "Add_TAAO.h" 115 | // #include "utility.h" 116 | #include "inverter.h" 117 | #include "commissioning.h" 118 | 119 | // Saturation 120 | // #include "satlut.h" 121 | // #define ACMSIMC_DEBUG false 122 | 123 | 124 | /* Declaration of Utility Function */ 125 | void write_header_to_file(FILE *fw); 126 | void write_data_to_file(FILE *fw); 127 | int isNumber(double x); 128 | double sign(double x); 129 | double fabs(double x); 130 | #endif -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ACMSIMC_TUT 2 | > AC Machine Simulation in C (Tutorial Version) 3 | 4 | ## Introduction 5 | I have used C to simulate motor control and adptive observers for over 4 years now. 6 | This is a tutorial for those who hate using Simulink to simulate ac motor control. 7 | The benefit is that you can directly reuse the codes in DSP based motor drive. 8 | 9 | ## Numerial Methods 10 | The numerical integration method is currently RK4, which is quite enough. 11 | DoPri54 will be included in future version (including stiffness detection and variable step numerical integration). 12 | 13 | ## Introduction to Current Branches (in time order): 14 | - [IM] vvvf: the skeleton with induction motor simulation and VVVF control. 15 | - [IM] foc: field oriented control (direct/indirect) with basic sensorless control. 16 | - [IM] animate: test the feature of waveform animation like an oscilloscope. 17 | - [PMSM] pmsm: id=0 control for interior permanent magnet synchronous motor. 18 | - [IM] vi_decouple: add voltage-current decoupling circuit for improved control performance during high speed reversal. 19 | - [IM] mras: model reference adaptive system based sensorless control (my 2017-Chen.Huang-Online paper). 20 | - [IM] \_femm: (This branch does not really belong here but I don't want to create a new repository for it...) It is about the design of the induction motor using free softwares as well as fitting the design to the equivalent circuit parameters for further control simulation. 21 | - [IM] saturation: include iron core saturation effect into the induction motor model simulation. 22 | - [Both] inverter_model: simple inverter modeling based on the paper 1996-Choi.Sul-Inverter. 23 | - [Both] **master: contain all the features of the branches mentioned above. The master branch is not updated anymore from this point, because I realized that having both IM and PMSM codes in one place is a silly idea.** 24 | - [PMSM] commissioning_pmsm: (under developing) self-commissioning procedure for permanent magnet motor. 25 | - [PMSM] eemf: sensorless control based on extended emf method proposed by Zhiqian Chen et al. (2003). Sensorless open loop works but closed-loop has problems. 26 | - [PMSM] hfsi-yoon: pulsating type square wave high frequency signal injection method based sensorless control for motor with saliency. 27 | - [PMSM] commissioning_spmsm: self-commissioning procedure for surface mounted permanent magnet synchronous motor. 28 | - [PMSM] spmsm_scvm_harnerfors06: statically compensated voltage model based sensorless control for SPMSM. This branch also includes new dynamic anti-windup and incremental PID regulator. 29 | 30 | (I recommend to use GitKraken to view this repository, so you know clearly which branch is the newest one. Note that master is obsolete. Sorry about my poor code management skills T-T.) 31 | 32 | ## Visualization 33 | - The plots are made using package matplotlib. 34 | - In branch animate, I tested the feature of waveform animation with matplotlib. 35 | - You can also try browser based libraries, e.g., plotly_express. 36 | 37 | ## Dependency under Windows 38 | - Anaconda 3 (you should be able to call python from cmd.exe) 39 | - MinGW (you should be able to call gcc from cmd.exe) 40 | - FEMM ([femm.info](http://www.femm.info/wiki/HomePage), you do not need this if you are not interested in Finite Element Analysis and motor design) 41 | - PyFEMM (a wrapper for FEMM API; use pip to install this) 42 | - Editor (optional): Sublime Text (preferred) or Visual Studio Code. 43 | 44 | ## Dependency under Linux 45 | - FEMM is a Windows-only FEA software. 46 | - Alternative is ElmerFEM for Linux, but it is poorly documented. Please DO NOT try it out unless you are a ドM. 47 | - Others are not tested yet. (Linux users should be able to figure it out...) 48 | 49 | ## Compile 50 | 51 | ### Compile in Sublime Text 52 | Create a file named "**!C_GCC.sublime-build**" in this folder "C:\Users\yourUserName\AppData\Roaming\Sublime Text 3\Packages\User" with the following content: 53 | ```json 54 | { 55 | "working_dir": "$file_path", 56 | "cmd": "gcc -Wall $file_name -o $file_base_name", 57 | "file_regex": "^(..[^:]*):([0-9]+):?([0-9]+)?:? (.*)$", 58 | "selector": "source.c", 59 | "variants": 60 | [ 61 | { 62 | "name": "ACMSIMC_TUT", 63 | // "shell_cmd": "gcc $file controller.c observer.c -L. -o $file_base_name && start cmd /c \"${file_path}/${file_base_name}\"" 64 | "shell_cmd": "gcc $file commissioning.c inverter.c controller.c observer.c -L. -o $file_base_name && start cmd /c \"${file_path}/${file_base_name}\"" 65 | } 66 | ] 67 | } 68 | ``` 69 | Press down Ctrl + Shift + B to select "ACMSIMC_TUT" and next time you only need to press down Ctrl + B to build. 70 | 71 | ### Compile in cmd.exe 72 | Change directory to where main.c is and open the cmd.exe there and type: 73 | ```batch 74 | gcc main.c commissioning.c inverter.c controller.c observer.c -I. -L. -o main 75 | ``` 76 | Then, double click main.exe to run. 77 | If you have python added to system path, plots will also pop up. 78 | 79 | 80 | ## Video Tutorials 81 | For unfamiliar users, I have been creating video tutorials. However, they are currently in Chinese. 82 | > *See [my Bilibili space](https://space.bilibili.com/7132537) (ACTIVELY UPDATED).* 83 | > 84 | > Also take a look at this link to [知乎](https://zhuanlan.zhihu.com/p/64445558) (not acvtively updated). 85 | > 86 | > Also check out [my personal page](https://horychen.github.io) for a list of tutorial videos (not acvtively updated). 87 | 88 | In near future, the English version will be brought about. But I would like to do it in high quality so I procrastinate. 89 | 90 | 94 | -------------------------------------------------------------------------------- /_femm/codes3/CrossSectStator.py: -------------------------------------------------------------------------------- 1 | from pylab import np, cos, sin, arctan 2 | class CrossSectInnerRotorStator: 3 | # CrossSectInnerRotorPMStator Describes the inner rotor PM stator. 4 | # Properties are set upon class creation and cannot be modified. 5 | # The anchor point for this is the center of the stator, 6 | # with the x-axis directed down the center of one of the stator teeth. 7 | def __init__(self, 8 | name = 'StatorCore', 9 | color = '#BAFD01', 10 | deg_alpha_st = 40, # span angle of tooth: class type DimAngular 11 | deg_alpha_so = 20, # angle of tooth edge: class type DimAngular 12 | mm_r_si = 40,# inner radius of stator teeth: class type DimLinear 13 | mm_d_so = 5,# tooth edge length: class type DimLinear 14 | mm_d_sp = 10,# tooth tip length: class type DimLinear 15 | mm_d_st = 15,# tooth base length: class type DimLinear 16 | mm_d_sy = 15,# back iron thickness: class type DimLinear 17 | mm_w_st = 13,# tooth base width: class type DimLinear 18 | mm_r_st = 0,# fillet on outter tooth: class type DimLinear 19 | mm_r_sf = 0,# fillet between tooth tip and base: class type DimLinear 20 | mm_r_sb = 0,# fillet at tooth base: class type DimLinear 21 | Q = 6, # number of stator slots (integer) 22 | location = None 23 | ): 24 | 25 | self.name = name 26 | self.color = color 27 | self.deg_alpha_st = deg_alpha_st 28 | self.deg_alpha_so = deg_alpha_so 29 | self.mm_r_si = mm_r_si 30 | self.mm_d_so = mm_d_so 31 | self.mm_d_sp = mm_d_sp 32 | self.mm_d_st = mm_d_st 33 | self.mm_d_sy = mm_d_sy 34 | self.mm_w_st = mm_w_st 35 | self.mm_r_st = mm_r_st 36 | self.mm_r_sf = mm_r_sf 37 | self.mm_r_sb = mm_r_sb 38 | self.Q = Q 39 | self.location = location 40 | 41 | def draw(self, drawer): 42 | 43 | drawer.getSketch(self.name, self.color) 44 | 45 | alpha_st = self.deg_alpha_st * np.pi/180 46 | alpha_so = -self.deg_alpha_so * np.pi/180 47 | r_si = self.mm_r_si 48 | d_so = self.mm_d_so 49 | d_sp = self.mm_d_sp 50 | d_st = self.mm_d_st 51 | d_sy = self.mm_d_sy 52 | w_st = self.mm_w_st 53 | r_st = self.mm_r_st 54 | r_sf = self.mm_r_sf 55 | r_sb = self.mm_r_sb 56 | Q = self.Q 57 | 58 | alpha_slot_span = 360/Q * np.pi/180 59 | 60 | P1 = [r_si, 0] 61 | P2 = [r_si*cos(alpha_st*0.5), r_si*-sin(alpha_st*0.5)] 62 | P3_temp = [ d_so*cos(alpha_st*0.5), 63 | d_so*-sin(alpha_st*0.5)] 64 | P3_local_rotate = [ cos(alpha_so)*P3_temp[0] + sin(alpha_so)*P3_temp[1], 65 | -sin(alpha_so)*P3_temp[0] + cos(alpha_so)*P3_temp[1] ] 66 | P3 = [ P3_local_rotate[0] + P2[0], 67 | P3_local_rotate[1] + P2[1] ] 68 | 69 | 三角形的底 = r_si + d_sp 70 | 三角形的高 = w_st*0.5 71 | 三角形的角度 = arctan(三角形的高 / 三角形的底) 72 | P4 = [ 三角形的底*cos(三角形的角度), 73 | 三角形的底*-sin(三角形的角度)] 74 | 75 | P5 = [ P4[0] + d_st, 76 | P4[1]] 77 | 78 | P6 = [ (r_si+d_sp+d_st)*cos(alpha_slot_span*0.5), 79 | (r_si+d_sp+d_st)*-sin(alpha_slot_span*0.5) ] 80 | 81 | P7 = [ (r_si+d_sp+d_st+d_sy)*cos(alpha_slot_span*0.5), 82 | (r_si+d_sp+d_st+d_sy)*-sin(alpha_slot_span*0.5) ] 83 | P8 = [ r_si+d_sp+d_st+d_sy, 0] 84 | 85 | list_segments = [] 86 | list_segments += drawer.drawArc([0,0], P2, P1) 87 | list_segments += drawer.drawLine(P2, P3) 88 | list_segments += drawer.drawLine(P3, P4) 89 | list_segments += drawer.drawLine(P4, P5) 90 | list_segments += drawer.drawArc([0,0], P6, P5) 91 | list_segments += drawer.drawLine(P6, P7) 92 | # l, vA = drawer.drawArc([0,0], P6, P5, returnVertexName=True) 93 | # list_segments += l 94 | # l, vB = drawer.drawLine(P6, P7, returnVertexName=True) 95 | # list_segments += l 96 | # drawer.addConstraintCocentricity(vA[0], vB[0]) 97 | # raise 98 | 99 | list_segments += drawer.drawArc([0,0], P7, P8) 100 | list_segments += drawer.drawLine(P8, P1) 101 | 102 | return [list_segments] 103 | 104 | def get_area_polygon(a,b,c,d): 105 | x1, x2, x3, x4 = a[0], b[0], c[0], d[0] 106 | y1, y2, y3, y4 = a[1], b[1], c[1], d[1] 107 | 108 | return 0.5*abs( x1*y2-y1*x2 + x2*y3-y2*x3 + x3*y4-y3*x4 + x4*y1-y4*x1 ) 109 | 110 | class CrossSectInnerRotorStatorWinding(object): 111 | def __init__(self, 112 | name = 'Coils', 113 | color = '#3D9970', 114 | stator_core = None 115 | ): 116 | self.name = name 117 | self.color = color 118 | self.stator_core = stator_core 119 | 120 | def draw(self, drawer, bool_re_evaluate=False): 121 | 122 | if False == bool_re_evaluate: 123 | drawer.getSketch(self.name, self.color) 124 | 125 | alpha_st = self.stator_core.deg_alpha_st * np.pi/180 126 | alpha_so = self.stator_core.deg_alpha_so * np.pi/180 127 | r_si = self.stator_core.mm_r_si 128 | d_so = self.stator_core.mm_d_so 129 | d_sp = self.stator_core.mm_d_sp 130 | d_st = self.stator_core.mm_d_st 131 | d_sy = self.stator_core.mm_d_sy 132 | w_st = self.stator_core.mm_w_st 133 | r_st = self.stator_core.mm_r_st 134 | r_sf = self.stator_core.mm_r_sf 135 | r_sb = self.stator_core.mm_r_sb 136 | Q = self.stator_core.Q 137 | 138 | alpha_slot_span = 360/Q * np.pi/180 139 | 140 | P1 = [r_si, 0] 141 | 142 | # 乘以0.99或0.95避免上层导体和下层导体重合导致导入Designer时产生多余的Parts。 143 | POpen = [(r_si+d_sp)*cos(alpha_slot_span*0.5*1.00), (r_si+d_sp)*-sin(alpha_slot_span*0.5*1.00)] 144 | 145 | # P2 = [r_si*cos(alpha_st*0.5), r_si*-sin(alpha_st*0.5)] 146 | 147 | # P3_temp = [ d_so*cos(alpha_st*0.5), 148 | # d_so*-sin(alpha_st*0.5)] 149 | # P3_local_rotate = [ cos(alpha_so)*P3_temp[0] + sin(alpha_so)*P3_temp[1], 150 | # -sin(alpha_so)*P3_temp[0] + cos(alpha_so)*P3_temp[1] ] 151 | # P3 = [ P3_local_rotate[0] + P2[0], 152 | # P3_local_rotate[1] + P2[1] ] 153 | 154 | 三角形的底 = r_si + d_sp 155 | 三角形的高 = w_st*0.5 156 | 三角形的角度 = arctan(三角形的高 / 三角形的底) 157 | P4 = [ 三角形的底*cos(三角形的角度), 158 | 三角形的底*-sin(三角形的角度) ] 159 | 160 | P5 = [ P4[0] + d_st, 161 | P4[1]] 162 | 163 | PMiddle45 = [0.5*(P4[0] + P5[0]), P4[1]] 164 | TheRadius = (P5[0] - P4[0])*0.45 165 | 166 | # 为了使得槽和导体之间不要接触,试着添加5%的clearance? 167 | P6 = [ (r_si+d_sp+d_st)*cos(alpha_slot_span*0.5) *1.00, 168 | (r_si+d_sp+d_st)*-sin(alpha_slot_span*0.5) *1.00 ] 169 | 170 | self.mm2_slot_area = 2 * get_area_polygon(P4, P5, P6, POpen) 171 | print('Slot area is %g mm^2'%(self.mm2_slot_area)) 172 | if bool_re_evaluate: 173 | return self.mm2_slot_area 174 | 175 | PMiddle6Open = [ 0.5*(P6[0]+POpen[0]), 0.5*(P6[1]+POpen[1])] 176 | self.PCoil = PCoil = [ 0.5*(PMiddle45[0]+PMiddle6Open[0]), 0.5*(PMiddle45[1]+PMiddle6Open[1])] 177 | 178 | # P7 = [ (r_si+d_sp+d_st+d_sy)*cos(alpha_slot_span*0.5), 179 | # (r_si+d_sp+d_st+d_sy)*-sin(alpha_slot_span*0.5) ] 180 | # P8 = [ r_si+d_sp+d_st+d_sy, 0] 181 | 182 | # Compute the vector starting from PCoil to one of the corner of the polygon. 183 | def shrink(PC, P): 184 | vector = [ P[0] - PC[0], P[1] - PC[1]] 185 | return [ PC[0]+0.95*vector[0], PC[1]+0.95*vector[1] ] 186 | P6_Shrink = shrink(PCoil, P6) 187 | P5_Shrink = shrink(PCoil, P5) 188 | P4_Shrink = shrink(PCoil, P4) 189 | POpen_Shrink = shrink(PCoil, POpen) 190 | 191 | list_regions = [] 192 | 193 | list_segments = [] 194 | # list_segments += drawer.drawCircle(PCoil, TheRadius) 195 | list_segments += drawer.drawArc([0,0], P6_Shrink, P5_Shrink) 196 | list_segments += drawer.drawLine(P5_Shrink, P4_Shrink) 197 | list_segments += drawer.drawLine(P4_Shrink, POpen_Shrink) 198 | list_segments += drawer.drawLine(POpen_Shrink, P6_Shrink) 199 | list_regions.append(list_segments) 200 | 201 | PCoil[1] *= -1 202 | P6_Shrink[1] *= -1 203 | P5_Shrink[1] *= -1 204 | P4_Shrink[1] *= -1 205 | POpen_Shrink[1] *= -1 206 | list_segments = [] 207 | # list_segments += drawer.drawCircle(PCoil, TheRadius) 208 | list_segments += drawer.drawArc([0,0], P5_Shrink, P6_Shrink) 209 | list_segments += drawer.drawLine(P5_Shrink, P4_Shrink) 210 | list_segments += drawer.drawLine(P4_Shrink, POpen_Shrink) 211 | list_segments += drawer.drawLine(POpen_Shrink, P6_Shrink) 212 | list_regions.append(list_segments) 213 | list_segments = [] 214 | 215 | return list_regions 216 | 217 | if __name__ == '__main__': 218 | import JMAG 219 | import Location2D 220 | if True: 221 | from utility import my_execfile 222 | my_execfile('./default_setting.py', g=globals(), l=locals()) 223 | fea_config_dict 224 | 225 | toolJd = JMAG.JMAG(fea_config_dict) 226 | 227 | project_name = 'proj%d'%(0) 228 | expected_project_file_path = './' + "%s.jproj"%(project_name) 229 | toolJd.open(expected_project_file_path) 230 | 231 | stator_core = CrossSectInnerRotorStator( name = 'StatorCore', 232 | deg_alpha_st = 40, 233 | deg_alpha_so = 20, 234 | mm_r_si = 40, 235 | mm_d_so = 5, 236 | mm_d_sp = 10, 237 | mm_d_st = 15, 238 | mm_d_sy = 15, 239 | mm_w_st = 13, 240 | mm_r_st = 0, 241 | mm_r_sf = 0, 242 | mm_r_sb = 0, 243 | Q = 6, 244 | location = Location2D.Location2D(anchor_xy=[0,0], deg_theta=0) 245 | ) 246 | 247 | list_regions = stator_core.draw(toolJd) 248 | toolJd.bMirror = True 249 | toolJd.iRotateCopy = stator_core.Q 250 | region1 = toolJd.prepareSection(list_regions) 251 | 252 | coils = CrossSectInnerRotorStatorWinding(name = 'Coils', 253 | stator_core = stator_core) 254 | 255 | list_regions = coils.draw(toolJd) 256 | toolJd.bMirror = False 257 | toolJd.iRotateCopy = coils.stator_core.Q 258 | region2 = toolJd.prepareSection(list_regions) 259 | 260 | # Import Model into Designer 261 | toolJd.doc.SaveModel(False) # True: Project is also saved. 262 | model = toolJd.app.GetCurrentModel() 263 | model.SetName('BPMSM Modeling') 264 | model.SetDescription('BPMSM Test') 265 | 266 | 267 | 268 | -------------------------------------------------------------------------------- /_femm/codes3/M-19-Steel-BH-Curve-afterJMAGsmooth.BH: -------------------------------------------------------------------------------- 1 | 0 0 2 | 3.7801785 0.0403935025191 3 | 7.560357 0.0807694208799 4 | 11.3405355 0.121110170924 5 | 15.120714 0.161398168493 6 | 17.0201085 0.181615891011 7 | 18.919503 0.20181362516 8 | 20.8188975 0.221989140297 9 | 22.718292 0.242140205779 10 | 23.99940225 0.255716837114 11 | 25.2805125 0.269280646379 12 | 26.56162275 0.282830949122 13 | 27.842733 0.296367060889 14 | 28.84990825 0.306998386537 15 | 29.8570835 0.317620185558 16 | 30.86425875 0.328232125368 17 | 31.871434 0.338833873385 18 | 32.7448365 0.34801899152 19 | 33.618239 0.357195978422 20 | 34.4916415 0.366364617208 21 | 35.365044 0.375524690994 22 | 36.17393 0.384000300376 23 | 36.982816 0.392468205071 24 | 37.791702 0.400928232795 25 | 38.600588 0.409380211262 26 | 39.3844915 0.417563306905 27 | 40.168395 0.425738524201 28 | 40.9522985 0.43390570634 29 | 41.736202 0.442064696513 30 | 42.52064625 0.450220957444 31 | 43.3050905 0.458368700943 32 | 44.08953475 0.466507769876 33 | 44.873979 0.474638007107 34 | 45.677436 0.482955979122 35 | 46.480893 0.491264352453 36 | 47.28435 0.499562958262 37 | 48.087807 0.50785162771 38 | 48.92516425 0.516479264598 39 | 49.7625215 0.525095734434 40 | 50.59987875 0.533700846094 41 | 51.437236 0.542294408453 42 | 52.32173225 0.551358990819 43 | 53.2062285 0.560410248444 44 | 54.09072475 0.569447956075 45 | 54.975221 0.578471888456 46 | 55.919664 0.588091956422 47 | 56.864107 0.597695787578 48 | 57.80855 0.607283107695 49 | 58.752993 0.616853642546 50 | 59.77065575 0.627147048867 51 | 60.7883185 0.637420304939 52 | 61.80598125 0.64767306768 53 | 62.823644 0.657904994009 54 | 63.92905425 0.668995154771 55 | 65.0344645 0.680059886495 56 | 66.13987475 0.691098749484 57 | 67.245285 0.702111304038 58 | 68.45506525 0.714132964288 59 | 69.6648455 0.726122010601 60 | 70.87462575 0.738077866604 61 | 72.084406 0.749999955922 62 | 73.4183295 0.762973007853 63 | 74.752253 0.775634769861 64 | 76.0861765 0.787979140509 65 | 77.4201 0.800000018361 66 | 78.90258025 0.813011673453 67 | 80.3850605 0.825686835123 68 | 81.86754075 0.838018604184 69 | 83.350021 0.850000081445 70 | 85.01241875 0.863056696856 71 | 86.6748165 0.875747796628 72 | 88.33721425 0.888065056114 73 | 89.999612 0.900000150662 74 | 91.88404725 0.913112578473 75 | 93.7684825 0.925823846834 76 | 95.65291775 0.938123285882 77 | 97.537353 0.950000225755 78 | 99.70336625 0.963185968031 79 | 101.8693795 0.975924152897 80 | 104.03539275 0.98820039198 81 | 106.201406 1.00000029691 82 | 108.7381705 1.01328669729 83 | 111.274935 1.02606225208 84 | 113.8116995 1.03830683818 85 | 116.348464 1.05000033252 86 | 119.39818025 1.06342863335 87 | 122.4478965 1.07625712192 88 | 125.49761275 1.08845720079 89 | 128.547329 1.10000027255 90 | 132.3518545 1.11362907216 91 | 136.15638 1.12653208745 92 | 139.9609055 1.13866913865 93 | 143.765431 1.15000004599 94 | 148.7626155 1.16390387023 95 | 153.7598 1.17690759696 96 | 158.7569845 1.18895745226 97 | 163.754169 1.19999966227 98 | 170.78266625 1.21425500668 99 | 177.8111635 1.22738361095 100 | 184.83966075 1.23932015416 101 | 191.868158 1.24999931536 102 | 202.60949525 1.26465305769 103 | 213.3508325 1.27791621586 104 | 224.09216975 1.28972090861 105 | 234.833507 1.29999925474 106 | 252.7525725 1.31502872468 107 | 270.671638 1.32840873681 108 | 288.5907035 1.34008406116 109 | 306.509769 1.34999946779 110 | 338.69612725 1.36528423221 111 | 370.8824855 1.37872905807 112 | 403.06884375 1.3903091545 113 | 435.255202 1.39999973061 114 | 495.1693935 1.41531132904 115 | 555.083585 1.42873258195 116 | 614.9977765 1.440287455 117 | 674.911968 1.44999991385 118 | 783.26536825 1.46501788944 119 | 891.6187685 1.47830130583 120 | 999.97216875 1.48993405237 121 | 1108.325569 1.50000001839 122 | 1284.51554375 1.51441852975 123 | 1460.7055185 1.52747648709 124 | 1636.89549325 1.53929622758 125 | 1813.085468 1.55000008838 126 | 2060.11845625 1.56379869711 127 | 2307.1514445 1.5766804428 128 | 2554.18443275 1.58872200496 129 | 2801.217421 1.60000006307 130 | 3114.326345 1.61350177798 131 | 3427.435269 1.62632807053 132 | 3740.544193 1.6384903429 133 | 4053.653117 1.64999999728 134 | 4438.01656025 1.66341549459 135 | 4822.3800035 1.6762083087 136 | 5206.74344675 1.68839697222 137 | 5591.10689 1.70000001776 138 | 6055.40977075 1.71338422413 139 | 6519.7126515 1.72618791144 140 | 6984.01553225 1.738397646 141 | 7448.318413 1.74999999411 142 | 8013.44272725 1.76343593089 143 | 8578.5670415 1.77624916625 144 | 9143.69135575 1.78843781892 145 | 9708.81567 1.8000000076 146 | 10403.3446562 1.8135056489 147 | 11097.8736425 1.82635769645 148 | 11792.4026288 1.83853090176 149 | 12486.931615 1.85000001637 150 | 13375.5696222 1.86383276338 151 | 14264.2076295 1.87684067649 152 | 15152.8456368 1.888928261 153 | 16041.483644 1.90000002223 154 | 17343.467889 1.91483103513 155 | 18645.452134 1.92828510969 156 | 19947.436379 1.94009662557 157 | 21249.420624 1.94999996248 158 | 23765.4394375 1.96601872789 159 | 26281.458251 1.97976046866 160 | 28797.4770645 1.99112196008 161 | 31313.495878 1.99999997742 162 | 36882.4836277 2.01558566376 163 | 42451.4713775 2.02890239705 164 | 48020.4591273 2.04026792697 165 | 53589.446877 2.05000000321 166 | 62311.456308 2.06353368916 167 | 71033.465739 2.07612761842 168 | 79755.47517 2.08815774193 169 | 88477.484601 2.10000001067 170 | 97440.4660857 2.11229089439 171 | 106403.44757 2.12474066225 172 | 115366.429055 2.13732010216 173 | 124329.41054 2.15000000203 174 | 133239.20023 2.16266256541 175 | 142148.98992 2.17528860171 176 | 151058.77961 2.187770336 177 | 159968.5693 2.19999999332 178 | 169414.328043 2.21264032416 179 | 178860.086786 2.22508058305 180 | 188305.845529 2.23748055016 181 | 197751.604272 2.25000000567 182 | 206819.891041 2.26225564436 183 | 215888.17781 2.27472073438 184 | 224956.464578 2.28732545864 185 | 234024.751347 2.3 -------------------------------------------------------------------------------- /_femm/codes3/acm_femm_script.py: -------------------------------------------------------------------------------- 1 | import shutil 2 | from utility import my_execfile 3 | from utility_moo import * 4 | from win32com.client import pywintypes 5 | bool_re_evaluate = False # re-evaluate the designs using csv (without calling FEA softwares) 6 | 7 | #~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~ 8 | # 0. FEA Setting / General Information & Packages Loading 9 | #~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~ 10 | my_execfile('./default_setting.py', g=globals(), l=locals()) 11 | fea_config_dict 12 | fea_config_dict['local_sensitivity_analysis'] = False 13 | fea_config_dict['bool_refined_bounds'] = False 14 | fea_config_dict['use_weights'] = 'O2' # this is not working 15 | if 'Y730' in fea_config_dict['pc_name']: 16 | ################################################################ 17 | # Y730 18 | ################################################################ 19 | # Combined winding IM 20 | fea_config_dict['TORQUE_CURRENT_RATIO'] = 0.975 21 | fea_config_dict['SUSPENSION_CURRENT_RATIO'] = 0.025 22 | fea_config_dict['which_filter'] = 'FixedStatorSlotDepth' # 'VariableStatorSlotDepth' 23 | run_folder = r'run#1000/' 24 | 25 | fea_config_dict['run_folder'] = run_folder 26 | 27 | # spec's 28 | my_execfile('./spec_Prototype2poleOD150mm500Hz_SpecifyTipSpeed.py', g=globals(), l=locals()) 29 | spec 30 | fea_config_dict['Active_Qr'] = spec.Qr 31 | fea_config_dict['use_drop_shape_rotor_bar'] = spec.use_drop_shape_rotor_bar 32 | build_model_name_prefix(fea_config_dict) # rebuild the model name for fea_config_dict 33 | spec.build_im_template(fea_config_dict) 34 | 35 | # select motor type ehere 36 | print('Build ACM template...') 37 | spec.acm_template = spec.im_template 38 | 39 | 40 | import acm_designer 41 | global ad 42 | ad = acm_designer.acm_designer(fea_config_dict, spec) 43 | if 'Y730' in fea_config_dict['pc_name']: 44 | ad.build_oneReport() # require LaTeX 45 | # ad.talk_to_mysql_database() # require MySQL 46 | # quit() 47 | ad.init_logger() 48 | ad.bool_re_evaluate = bool_re_evaluate 49 | 50 | ad.bounds_denorm = spec.get_im_classic_bounds(which_filter=fea_config_dict['which_filter']) 51 | ad.bound_filter = spec.bound_filter 52 | print('---------------------\nBounds:') 53 | idx_ad = 0 54 | for idx, f in enumerate(ad.bound_filter): 55 | if f == True: 56 | print(idx, f, '[%g,%g]'%tuple(spec.original_template_neighbor_bounds[idx]), '[%g,%g]'%tuple(ad.bounds_denorm[idx_ad])) 57 | idx_ad += 1 58 | else: 59 | print(idx, f, '[%g,%g]'%tuple(spec.original_template_neighbor_bounds[idx])) 60 | print('-'*20) 61 | # quit() 62 | counter_fitness_called, counter_loop = 0, 0 63 | 64 | cost_function, f1, f2, f3, FRW, \ 65 | normalized_torque_ripple, \ 66 | normalized_force_error_magnitude, \ 67 | force_error_angle = ad.evaluate_design(ad.spec.im_template, ad.spec.im_template.spec.x_denorm, counter_fitness_called, counter_loop=counter_loop) 68 | 69 | print(cost_function, f1, f2, f3, FRW, \ 70 | normalized_torque_ripple, \ 71 | normalized_force_error_magnitude, \ 72 | force_error_angle) 73 | -------------------------------------------------------------------------------- /_femm/codes3/default_setting.py: -------------------------------------------------------------------------------- 1 | import os 2 | fea_config_dict = { 3 | ########################## 4 | # Sysetm Control 5 | ########################## 6 | 'designer.Show': True, 7 | 'OnlyTableResults':False, # modified later according to pc_name # the only reason we want save mesh results are to obtain voltage profile for power factor evaluation 8 | 'local_sensitivity_analysis':False, 9 | 'local_sensitivity_analysis_number_of_variants': 20, 10 | 'flag_optimization':True, # also use true for sensitivity analysis 11 | 'Restart':False, # restart from frequency analysis is not needed, because SSATA is checked and JMAG 17103l version is used. 12 | 'MultipleCPUs':True, 13 | # True for: 14 | # multiple cpu (SMP=2) 15 | # use directSolver over ICCG Solver 16 | 17 | ########################## 18 | # FEA Setting 19 | ########################## 20 | 'TranRef-StepPerCycle':40, # FEMM: 5 deg # 360 to be precise as FEMM: 0.5 deg 21 | # 'FrequencyRange':range(1,6), # the first generation for PSO 22 | 'number_of_steps_1stTTS':32, # TSS actually... 23 | 'number_of_steps_2ndTTS':32, # use a multiples of 4! # 8*32 # steps for half period (0.5). That is, we implement two time sections, the 1st section lasts half slip period and the 2nd section lasts half fandamental period. 24 | 'number_cycles_prolonged':1, # 150 25 | 'FEMM_Coarse_Mesh':True, 26 | 27 | ########################## 28 | # Optimization 29 | ########################## 30 | 'JMAG_Scheduler':False, # multi-cores run 31 | 'delete_results_after_calculation': False, # check if True can we still export Terminal Voltage? 如果是True,那么就得不到Terminal Voltage和功率因数了! 32 | 'use_weights':None, 33 | 34 | ########################## 35 | # Design Specifications 36 | ########################## 37 | 'Active_Qr':None, #16, #32, 38 | 'PoleSpecific': True, 39 | 'use_drop_shape_rotor_bar': True, 40 | 'DPNV': True, 41 | # 'DPNV_separate_winding_implementation': None, # this is obsolete feature (it is not good because the copper loss is different from the reality and only works for Qs=24, p=2 case) 42 | 'mimic_separate_winding_with_DPNV_winding':False, 43 | 'End_Ring_Resistance':0, # 0 for consistency with FEMM with pre-determined currents # 9.69e-6, # this is still too small for Chiba's winding 44 | 'Steel': 'M19Gauge29', #'M15','Arnon5', 45 | # 75 deg Celsus: If you modify the temperature here, you should update the initial design (the im.DriveW_Rs should be updated and it used in JMAG FEM Coil) 46 | # This is actually the resistivity! 47 | # This is actually the resistivity! 48 | # This is actually the resistivity! 49 | 'Bar_Conductivity':1/((3.76*75+873)*1e-9/55.), # @75 Degree Celsius # 1/((3.76*100+873)*1e-9/55.) for Copper, where temperature is 25 or 100 deg Celsius. 50 | # 'Bar_Conductivity':40e6, # 40e6 for Aluminium; 51 | } 52 | def where_am_i(fea_config_dict): 53 | def get_pc_name(): 54 | import platform 55 | import socket 56 | n1 = platform.node() 57 | n2 = socket.gethostname() 58 | n3 = os.environ["COMPUTERNAME"] 59 | if n1 == n2 == n3: 60 | return n1 61 | elif n1 == n2: 62 | return n1 63 | elif n1 == n3: 64 | return n1 65 | elif n2 == n3: 66 | return n2 67 | else: 68 | raise Exception("Computer names are not equal to each other.") 69 | 70 | dir_interpreter = os.path.abspath('') 71 | print(dir_interpreter) 72 | if 'codes3' in dir_interpreter: 73 | dir_parent = dir_interpreter + '/../' # '../' <- relative path is not always a good option 74 | else: 75 | if '_femm' in dir_interpreter: 76 | dir_parent = dir_interpreter + '/' 77 | else: 78 | raise Exception('Do not run the script from this directory: %s'%(dir_interpreter)) 79 | dir_codes = dir_parent + 'codes3/' 80 | dir_femm_files = dir_parent + 'femm_files/' 81 | pc_name = get_pc_name() 82 | os.chdir(dir_codes) 83 | # print(dir_parent, dir_codes, pc_name, sep='\n'); quit() 84 | fea_config_dict['dir_interpreter'] = dir_interpreter 85 | fea_config_dict['dir_parent'] = dir_parent 86 | fea_config_dict['dir_codes'] = dir_codes 87 | fea_config_dict['dir_femm_files'] = dir_femm_files 88 | fea_config_dict['pc_name'] = pc_name 89 | 90 | fea_config_dict['delete_results_after_calculation'] = False # True for saving disk space (but you lose voltage profile and element data) 91 | if fea_config_dict['Restart'] == False: 92 | fea_config_dict['OnlyTableResults'] = True # save disk space for my PC 93 | # However, we need field data for iron loss calculation 94 | fea_config_dict['OnlyTableResults'] = False 95 | 96 | where_am_i(fea_config_dict) # add path to fea_config_dict 97 | 98 | from sys import path as sys_path 99 | # for importing your package 100 | sys_path.append(fea_config_dict['dir_codes']) 101 | 102 | import utility 103 | import pyrhonen_procedure_as_function 104 | from pylab import np, plt 105 | import logging 106 | 107 | # run_list = [1,1,0,0,0] # use JMAG only 108 | run_list = [0,1,0,0,0] # use FEMM to search for breakdown slip 109 | fea_config_dict['jmag_run_list'] = run_list 110 | def build_model_name_prefix(fea_config_dict, UID=None): 111 | if fea_config_dict['flag_optimization'] == True: 112 | fea_config_dict['model_name_prefix'] = 'OP' 113 | else: 114 | fea_config_dict['model_name_prefix'] = '' 115 | 116 | if fea_config_dict['PoleSpecific'] == True: 117 | fea_config_dict['model_name_prefix'] += '_PS' 118 | else: 119 | fea_config_dict['model_name_prefix'] += '_SC' 120 | 121 | fea_config_dict['model_name_prefix'] += '_Qr%d'%(fea_config_dict['Active_Qr']) 122 | 123 | if fea_config_dict['End_Ring_Resistance'] == 0: 124 | fea_config_dict['model_name_prefix'] += '_NoEndRing' 125 | 126 | if UID is not None: 127 | fea_config_dict['model_name_prefix'] += 'UID_%4d'%(UID) 128 | 129 | return fea_config_dict['model_name_prefix'] 130 | # print(build_model_name_prefix(fea_config_dict)) 131 | 132 | # FEMM Static FEA 133 | fea_config_dict['femm_deg_per_step'] = None # 0.25 * (360/4) / utility.lcm(24/4., fea_config_dict['Active_Qr']/4.) # at least half period 134 | # fea_config_dict['femm_deg_per_step'] = 1 * (360/4) / utility.lcm(24/4., fea_config_dict['Active_Qr']/4.) # at least half period 135 | # fea_config_dict['femm_deg_per_step'] = 0.1 #0.5 # deg 136 | # print 'femm_deg_per_step is', fea_config_dict['femm_deg_per_step'], 'deg (Qs=24, p=2)' 137 | 138 | 139 | -------------------------------------------------------------------------------- /_femm/codes3/material.py: -------------------------------------------------------------------------------- 1 | #coding:u8 2 | from pylab import * 3 | mu0 = (4*pi*1e-7) 4 | 5 | # fname = "../Arnon5/Arnon-5-NGOES-Magnetization-Curve_Redo.csv" 6 | # data = loadtxt(fname, delimiter=',', skiprows=1) # https://docs.scipy.org/doc/numpy-1.13.0/reference/generated/numpy.loadtxt.html 7 | # x = data[:,0] * 1000/(4*np.pi) # Oesteds to A/m 8 | # y = data[:,1] * 1e-4 # Gauss to Tesla 9 | 10 | # fname = "../Arnon5/M-19-Steel-BH-Curve.txt" 11 | # y, x = loadtxt(fname, unpack=True, usecols=(0,1)) 12 | 13 | fname = "../Arnon5/M-19-Steel-BH-Curve-afterJMAGsmooth.txt" 14 | y, x = loadtxt(fname, unpack=True, usecols=(1,0)) 15 | y = y[1:] # skip the (0,0) point will be essential for pade approximate to work 16 | x = x[1:] 17 | print(fname) 18 | 19 | def rational(x, p, q): # pade appximate 20 | """ https://stackoverflow.com/questions/29815094/rational-function-curve-fitting-in-python 21 | The general rational function description. 22 | p is a list with the polynomial coefficients in the numerator 23 | q is a list with the polynomial coefficients (except the first one) 24 | in the denominator 25 | The zeroth order coefficient of the denominator polynomial is fixed at 1. 26 | Numpy stores coefficients in [x**2 + x + 1] order, so the fixed 27 | zeroth order denominator coefficent must comes last. (Edited.) 28 | """ 29 | return np.polyval(p, x) / np.polyval(q + [1.0], x) 30 | 31 | def rational8_8(x, p0, p1, p2, p3, p4, p5, p6, p7, q1, q2, q3, q4, q5, q6, q7): 32 | '''88''' 33 | return rational(x, [p0, p1, p2, p3, p4, p5, p6, p7], [q1, q2, q3, q4, q5, q6, q7]) 34 | def rational8_7(x, p0, p1, p2, p3, p4, p5, p6, p7, q1, q2, q3, q4, q5, q6): 35 | '''87''' 36 | return rational(x, [p0, p1, p2, p3, p4, p5, p6, p7], [q1, q2, q3, q4, q5, q6]) 37 | def rational7_7(x, p0, p1, p2, p3, p4, p5, p6, q1, q2, q3, q4, q5, q6): 38 | '''77''' 39 | return rational(x, [p0, p1, p2, p3, p4, p5, p6], [q1, q2, q3, q4, q5, q6]) 40 | def rational7_6(x, p0, p1, p2, p3, p4, p5, p6, q1, q2, q3, q4, q5): 41 | '''76''' 42 | return rational(x, [p0, p1, p2, p3, p4, p5, p6], [q1, q2, q3, q4, q5]) 43 | def rational7_5(x, p0, p1, p2, p3, p4, p5, p6, q1, q2, q3, q4): 44 | '''75''' 45 | return rational(x, [p0, p1, p2, p3, p4, p5, p6], [q1, q2, q3, q4]) 46 | def rational6_6(x, p0, p1, p2, p3, p4, p5, q1, q2, q3, q4, q5): 47 | '''66''' 48 | return rational(x, [p0, p1, p2, p3, p4, p5], [q1, q2, q3, q4, q5]) 49 | def rational6_5(x, p0, p1, p2, p3, p4, p5, q1, q2, q3, q4): 50 | '''65''' 51 | return rational(x, [p0, p1, p2, p3, p4, p5], [q1, q2, q3, q4]) 52 | def rational6_4(x, p0, p1, p2, p3, p4, p5, q1, q2, q3): 53 | '''64''' 54 | return rational(x, [p0, p1, p2, p3, p4, p5], [q1, q2, q3]) 55 | def rational5_5(x, p0, p1, p2, p3, p4, q1, q2, q3, q4): 56 | '''55''' 57 | return rational(x, [p0, p1, p2, p3, p4], [q1, q2, q3, q4]) 58 | def rational5_3(x, p0, p1, p2, p3, p4, q1, q2): 59 | '''53''' 60 | return rational(x, [p0, p1, p2, p3, p4], [q1, q2]) 61 | def rational4_4(x, p0, p1, p2, p3, q1, q2, q3): 62 | '''44''' 63 | return rational(x, [p0, p1, p2, p3], [q1, q2, q3]) 64 | def rational4_3(x, p0, p1, p2, p3, q1, q2): 65 | '''43''' 66 | return rational(x, [p0, p1, p2, p3], [q1, q2]) 67 | def rational3_3(x, p0, p1, p2, q1, q2): 68 | '''33''' 69 | return rational(x, [p0, p1, p2], [q1, q2]) 70 | # x = np.linspace(0, 10, 100) 71 | # y = rational(x, [-0.2, 0.3, 0.5], [-1.0, 2.0]) 72 | # ynoise = y * (1.0 + np.random.normal(scale=0.1, size=x.shape)) 73 | 74 | ax1 = figure().gca() 75 | ax2 = figure().gca() 76 | 77 | from scipy.optimize import curve_fit 78 | global y_fit 79 | def fitting_test(ax1, ax2, x, y, rational_func, label): 80 | global y_fit 81 | 82 | popt, pcov = curve_fit(rational_func, x, y) #p0=(0.2, 0.3, 0.5, 1, -1.0, 2.0, 1), diag=(1./x.mean(),1./y.mean())) 83 | print('\n\n\n~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~') 84 | print(label) 85 | print(popt) 86 | y_fit = rational_func(x, *popt) 87 | 88 | ax1.plot(x, y_fit, label='fit'+label, alpha=0.33) 89 | ax2.plot(x, (y_fit - y) / y, label=label+'normalized fit error', alpha=0.33) 90 | 91 | print('accumulated error', sum((y_fit - y)/y)) 92 | 93 | return y_fit 94 | 95 | ''' BH curve and its pade apprximate [no (0,0) allowed] 96 | ''' 97 | # fitting_test(ax1, ax2, x, y, rational8_7, rational8_7.__doc__) 98 | # fitting_test(ax1, ax2, x, y, rational7_7, rational7_7.__doc__) 99 | fitting_test(ax1, ax2, x, y, rational7_6, rational7_6.__doc__) # after visual inspection, this is the best 100 | # fitting_test(ax1, ax2, x, y, rational6_6, rational6_6.__doc__) 101 | # fitting_test(ax1, ax2, x, y, rational6_5, rational6_5.__doc__) 102 | # fitting_test(ax1, ax2, x, y, rational6_4, rational6_4.__doc__) 103 | # fitting_test(ax1, ax2, x, y, rational5_5, rational5_5.__doc__) 104 | # fitting_test(ax1, ax2, x, y, rational5_3, rational5_3.__doc__) 105 | # fitting_test(ax1, ax2, x, y, rational4_4, rational4_4.__doc__) 106 | # fitting_test(ax1, ax2, x, y, rational4_3, rational4_3.__doc__) 107 | # fitting_test(ax1, ax2, x, y, rational3_3, rational3_3.__doc__) 108 | # fitting_test(ax1, ax2, x, y, rational8_8, rational8_8.__doc__) 109 | 110 | ax1.plot(x, y, '*', label='ori', alpha=0.33) 111 | ax1.grid() 112 | ax1.legend() 113 | ax2.grid() 114 | ax2.legend() 115 | 116 | ''' Dynamic Gradient/mu0 to H 117 | ''' 118 | ax3 = figure().gca() 119 | plot(x, gradient(y) / gradient(x) / mu0, '*', label='ori', alpha=0.33) 120 | plot(x, gradient(y_fit) / gradient(x) / mu0, 'o-', label='fit', alpha=0.33) 121 | ax3.grid() 122 | ax3.legend() 123 | 124 | ''' mu-H curve 125 | ''' 126 | ax4 = figure().gca() 127 | plot(x, y/x, '*', label='ori') 128 | plot(x, y_fit/x, '^', label='fit') 129 | 130 | ax4.grid() 131 | ax4.legend() 132 | 133 | ''' B-mu_r curve 134 | ''' 135 | ax5 = figure().gca() 136 | plot(y, y/x / mu0, '*', label='ori') 137 | plot(y_fit, y_fit/x / mu0, '^', label='fit') 138 | 139 | ax5.grid() 140 | ax5.legend() 141 | 142 | ''' Staiti Gradient (What you see in JMAG) 143 | ''' 144 | ax6 = figure().gca() 145 | plot(x, gradient(y) / gradient(x), '*', label='ori', alpha=0.33) 146 | plot(x, gradient(y_fit) / gradient(x), 'o-', label='fit', alpha=0.33) 147 | ax6.grid() 148 | ax6.legend() 149 | 150 | ''' Dynamic Gradient/mu0 to B 151 | ''' 152 | ax7 = figure().gca() 153 | plot( y, gradient(y) / gradient(x) / mu0, '*', label='ori', alpha=0.33) 154 | plot(y_fit, gradient(y_fit) / gradient(x) / mu0, 'o-', label='fit', alpha=0.33) 155 | ax7.grid() 156 | ax7.legend() 157 | 158 | 159 | 160 | show() 161 | 162 | # from scipy.integrate import cumtrapz, simps 163 | # def get_end_H(xM19, x): # xM19的数据足够长,而x的不够, 164 | # for ind, el in enumerate(xM19): 165 | # if el > x[-1]: 166 | # print el, x[-1], 'A/m' 167 | # print 'index is', ind 168 | # return ind 169 | # M19_gradient = gradient(yM19) / gradient(xM19) 170 | # # M19 appended to original 171 | # end_index = get_end_H(xM19, x) 172 | # y_fit_gradient_integrate = cumtrapz(M19_gradient[end_index:], xM19[end_index:], initial=0) + y[-1] 173 | # ax1.plot(xM19[end_index:], y_fit_gradient_integrate, 'v-', label='M19-ori', alpha=0.33) 174 | 175 | 176 | 177 | # from scipy import misc 178 | # e_exp = [1.0, 1.0, 1.0/2.0, 1.0/6.0, 1.0/24.0, 1.0/120.0] 179 | # p, q = misc.pade(e_exp, 2) 180 | # '这里的misc.pade需要已知近似对象的泰勒级数,呵呵' 181 | 182 | -------------------------------------------------------------------------------- /_femm/codes3/method_parallel_solve_4jmag.py: -------------------------------------------------------------------------------- 1 | import sys 2 | import subprocess 3 | 4 | dir_run = sys.argv[1] 5 | number_of_instantces = int(sys.argv[2]) 6 | 7 | procs = [] 8 | for i in range(number_of_instantces): 9 | proc = subprocess.Popen([sys.executable, 'parasolve.py', 10 | str(i), str(number_of_instantces), dir_run], bufsize=-1) 11 | procs.append(proc) 12 | 13 | for proc in procs: 14 | proc.wait() 15 | 16 | -------------------------------------------------------------------------------- /_femm/codes3/method_parasolve_greedy_search.py: -------------------------------------------------------------------------------- 1 | # coding:u8 2 | # method_parasolve_greedy_search 3 | 4 | import sys 5 | import subprocess 6 | 7 | dir_femm_temp = sys.argv[1] 8 | number_of_instantces = int(sys.argv[2]) 9 | str_stack_length = sys.argv[3] 10 | 11 | # debug 12 | # print sys.argv 13 | # import os 14 | # os.system("pause") 15 | # quit() 16 | 17 | # manager 18 | proc = subprocess.Popen([sys.executable, 'parasolve_greedy_search_manager.py', 19 | str(number_of_instantces), dir_femm_temp, str_stack_length], bufsize=-1) 20 | 21 | # 等了也是白等,直接就运行返回了 22 | proc.wait() 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /_femm/codes3/parasolve.py: -------------------------------------------------------------------------------- 1 | # coding:u8 2 | # https://stackoverflow.com/questions/19156467/run-multiple-instances-of-python-script-simultaneously 3 | # https://docs.python.org/2/library/subprocess.html#subprocess.Popen 4 | 5 | # wait 6 | # https://stackoverflow.com/questions/100624/python-on-windows-how-to-wait-for-multiple-child-processes 7 | 8 | import os 9 | import sys 10 | import femm 11 | from time import time 12 | 13 | from numpy import exp, pi # sqrt 14 | # from numpy import savetxt, c_ 15 | 16 | def write_Torque_and_B_data_to_file(str_rotor_position, rotation_operator): 17 | # call this after mi_analyze 18 | femm.mi_loadsolution() 19 | 20 | # Physical Amount on the Rotor 21 | femm.mo_groupselectblock(100) # rotor iron 22 | femm.mo_groupselectblock(101) # rotor bars 23 | Fx = femm.mo_blockintegral(18) #-- 18 x (or r) part of steady-state weighted stress tensor force 24 | Fy = femm.mo_blockintegral(19) #--19 y (or z) part of steady-state weighted stress tensor force 25 | torque = femm.mo_blockintegral(22) #-- 22 = Steady-state weighted stress tensor torque 26 | femm.mo_clearblock() 27 | # write results to a data file (write to partial files to avoid compete between parallel instances) 28 | handle_torque.write("%s %g %g %g\n" % ( str_rotor_position, torque, Fx, Fy )) 29 | 30 | # Field Amount of 1/4 model (this is valid if we presume the suspension two pole field is weak) 31 | number_of_elements = femm.mo_numelements() 32 | stator_Bx_data = [] 33 | stator_By_data = [] 34 | stator_Area_data = [] 35 | rotor_Bx_data = [] 36 | rotor_By_data = [] 37 | rotor_Area_data = [] 38 | # one_list = [] 39 | for id_element in range(1, number_of_elements+1): 40 | _, _, _, x, y, area, group = femm.mo_getelement(id_element) 41 | if y>0 and x>0: 42 | if group==10: # stator iron 43 | # 1. What we need for iron loss evaluation is the B waveform at a fixed point (x,y). 44 | # For example, (x,y) is the centeroid of element in stator tooth. 45 | Bx, By = femm.mo_getb(x, y) 46 | stator_Bx_data.append(Bx) 47 | stator_By_data.append(By) 48 | stator_Area_data.append(area) 49 | 50 | if group==100: # rotor iron 51 | # 2. The element at (x,y) is no longer the same element from last rotor position. 52 | # To find the exact element from last rotor position, 53 | # we rotate the (x,y) forward as we rotate the model (rotor), get the B value there: (x,y)*rotation_operator, and correct the (Bx,By)/rotation_operator 54 | complex_new_xy = (x + 1j*y) * rotation_operator 55 | Bx, By = femm.mo_getb( complex_new_xy.real, 56 | complex_new_xy.imag ) 57 | complex_new_BxBy = (Bx + 1j*By) * rotation_operator 58 | rotor_Bx_data.append(complex_new_BxBy.real) 59 | rotor_By_data.append(complex_new_BxBy.imag) 60 | rotor_Area_data.append(area) 61 | 62 | # one_list.append(sqrt(Bx**2 + By**2)) 63 | # one_list.append(area) 64 | # option 1 65 | handle_stator_B_data.write(str_rotor_position + ',' + ','.join(['%g,%g,%g'%(Bx,By,A) for Bx,By,A in zip(stator_Bx_data, stator_By_data, stator_Area_data) ]) + '\n') 66 | handle_rotor_B_data.write(str_rotor_position + ',' + ','.join(['%g,%g,%g'%(Bx,By,A) for Bx,By,A in zip(rotor_Bx_data, rotor_By_data, rotor_Area_data) ]) + '\n') 67 | 68 | # option 2: one_list 69 | # handle_B_data.write(str_rotor_position + ',' + ','.join(['%g'%(B) for B in B_data ]) + ','.join(['%g'%(A) for A in Area_data ]) + '\n') 70 | 71 | # numpy is slower than open().write!!! 72 | # tic = time() 73 | # # savetxt(handle_B_data, c_[one_list]) 74 | # savetxt(handle_B_data, one_list) 75 | # toc = time() 76 | # print toc - tic, 's\n\n' 77 | 78 | femm.mo_close() 79 | 80 | # test 81 | # print '-----------------Testing!!!' 82 | # id_solver = 0 83 | # number_of_instances = 5 84 | # # dir_run = r'D:\femm42\PS_Qr36_NoEndRing_M15_17303l_DPNV\static-femm/' 85 | # dir_run = r'D:\femm42\PS_Qr32_NoEndRing_M19Gauge29_DPNV_1e3Hz\static-femm\sweeping/' 86 | 87 | id_solver = int(sys.argv[1]) 88 | number_of_instances = int(sys.argv[2]) 89 | dir_run = sys.argv[3] 90 | print('ParaSolve', id_solver) 91 | 92 | handle_torque = open(dir_run + "static_results_%d.txt"%(id_solver), 'a') 93 | # handle_stator_B_data = open(dir_run + "static_results_stator_B_data_%d.txt"%(id_solver), 'a') # use 'ab' for np.savetxt https://stackoverflow.com/questions/27786868/python3-numpy-appending-to-a-file-using-numpy-savetxt 94 | # handle_rotor_B_data = open(dir_run + "static_results_rotor_B_data_%d.txt"%(id_solver), 'a') 95 | 96 | fem_file_list = os.listdir(dir_run) 97 | fem_file_list = [f for f in fem_file_list if '.fem' in f] 98 | 99 | femm.openfemm(True) # bHide 100 | femm.callfemm_noeval('smartmesh(0)') 101 | 102 | # this is essential to reduce elements counts from >50000 to ~20000. 103 | print('mi_smartmesh is off') 104 | 105 | for i in range(id_solver, len(fem_file_list), number_of_instances): 106 | 107 | output_file_name = dir_run + fem_file_list[i][:-4] 108 | 109 | if not os.path.exists(output_file_name + '.ans'): 110 | tic = time() 111 | femm.opendocument(output_file_name + '.fem') 112 | # femm.callfemm_noeval('mi_smartmesh(0)') 113 | try: 114 | # femm.mi_createmesh() # [useless] 115 | femm.mi_analyze(1) # None for inherited. 1 for a minimized window, 116 | # print '[debug]', deg_per_step*i*number_of_instances, 'deg' 117 | # rotor_position = deg_per_step*i*number_of_instances / 180. * pi 118 | # write_Torque_and_B_data_to_file(output_file_name[-4:], exp(1j*rotor_position)) # this function is moved to FEMM_Solver.py as keep... 119 | if True: 120 | # call this after mi_analyze 121 | femm.mi_loadsolution() 122 | # Physical Amount on the Rotor 123 | femm.mo_groupselectblock(100) # rotor iron 124 | femm.mo_groupselectblock(101) # rotor bars 125 | Fx = femm.mo_blockintegral(18) #-- 18 x (or r) part of steady-state weighted stress tensor force 126 | Fy = femm.mo_blockintegral(19) #--19 y (or z) part of steady-state weighted stress tensor force 127 | torque = femm.mo_blockintegral(22) #-- 22 = Steady-state weighted stress tensor torque 128 | femm.mo_clearblock() 129 | # write results to a data file (write to partial files to avoid compete between parallel instances) 130 | handle_torque.write("%s %g %g %g\n" % ( output_file_name[-4:], torque, Fx, Fy )) # output_file_name[-4:] = str_rotor_position 131 | # close post-process 132 | femm.mo_close() 133 | except Exception as error: 134 | error.args 135 | raise 136 | # print 'Is it: Material properties have not been defined for all regions? Check the following file:' 137 | # print i, fem_file_list[i] 138 | femm.mi_close() 139 | toc = time() 140 | print(i, fem_file_list[i], toc - tic, 's') 141 | femm.closefemm() 142 | 143 | handle_torque.close() 144 | # handle_B_data.close() 145 | 146 | 147 | # True 148 | # slip_freq_breakdown_torque: 3.0 Hz 149 | # ParaSolve! 150 | # 2 36-0Hz 30.ans 151 | # 6 36-0Hz 90.ans 152 | # 10 36-0Hz 180.fem 153 | # Traceback (most recent call last): 154 | # File "parasolve.py", line 29, in 155 | # Fx = femm.mo_blockintegral(18) #-- 18 x (or r) part of steady-state weighted stress tensor force 156 | # File "D:\Users\horyc\Anaconda2\lib\site-packages\femm\__init__.py", line 1722, in mo_blockintegral 157 | # return callfemm('mo_blockintegral(' + num(ptype) + ')' ); 158 | # File "D:\Users\horyc\Anaconda2\lib\site-packages\femm\__init__.py", line 25, in callfemm 159 | # x = HandleToFEMM.mlab2femm(myString).replace("[ ","[").replace(" ]","]").replace(" ",",").replace("I","1j"); 160 | # File "", line 3, in mlab2femm 161 | # pywintypes.com_error: (-2147023170, 'The remote procedure call failed.', None, None) 162 | -------------------------------------------------------------------------------- /_femm/codes3/parasolve_greedy_search.py: -------------------------------------------------------------------------------- 1 | # coding:u8 2 | 3 | import os 4 | import sys 5 | import femm 6 | from time import time 7 | # from itertools import izip 8 | # from numpy import exp, pi # sqrt 9 | # from numpy import savetxt, c_ 10 | 11 | def get_slipfreq_torque(): 12 | # call this after mi_analyze 13 | femm.mi_loadsolution() 14 | 15 | # Physical Amount on the Rotor 16 | femm.mo_groupselectblock(100) # rotor iron 17 | femm.mo_groupselectblock(101) # rotor bars 18 | # Fx = femm.mo_blockintegral(18) #-- 18 x (or r) part of steady-state weighted stress tensor force 19 | # Fy = femm.mo_blockintegral(19) #--19 y (or z) part of steady-state weighted stress tensor force 20 | torque = femm.mo_blockintegral(22) #-- 22 = Steady-state weighted stress tensor torque 21 | freq = femm.mo_getprobleminfo()[1] 22 | femm.mo_clearblock() 23 | femm.mo_close() 24 | 25 | return freq, torque 26 | 27 | id_solver = int(sys.argv[1]) 28 | dir_femm_temp = sys.argv[2][1:-1] 29 | print('ParaSolve', id_solver, end=' ') 30 | 31 | 32 | femm.openfemm(True) # bHide 33 | # this is essential to reduce elements counts from >50000 to ~20000. 34 | femm.callfemm_noeval('smartmesh(0)') 35 | print('smartmesh is off') 36 | 37 | tic = time() 38 | fem_file_path = dir_femm_temp + 'femm_temp_%d.fem'%(id_solver) 39 | 40 | # # debug 41 | # print fem_file_path 42 | # # print dir_femm_temp 43 | # os.system('pause') 44 | # quit() 45 | 46 | 47 | femm.opendocument(fem_file_path) 48 | counter_loop = 0 49 | while True: 50 | counter_loop += 1 51 | try: 52 | femm.mi_analyze(1) # None for inherited. 1 for a minimized window, 53 | freq, torque = get_slipfreq_torque() 54 | except Exception as error: 55 | print('Error occurs when analyzing the femm file.') 56 | print(error.args) 57 | if counter_loop > 3: 58 | raise error 59 | else: 60 | break 61 | femm.mi_close() 62 | toc = time() 63 | print('id_solver=%d:'% (id_solver), toc - tic, 's') 64 | femm.closefemm() 65 | 66 | # removing files is left for manager to decide 67 | # os.remove(fem_file_path) 68 | # os.remove(fem_file_path[:-4]+'.ans') 69 | 70 | with open(dir_femm_temp + "femm_temp_%d.txt"%(id_solver), 'w') as handle_torque: 71 | # write results to a data file (write to partial files to avoid compete between parallel instances) 72 | handle_torque.write("%g\n%g\n" % ( freq, torque)) 73 | -------------------------------------------------------------------------------- /_femm/codes3/parasolve_greedy_search_manager.py: -------------------------------------------------------------------------------- 1 | # coding:u8 2 | # parasolve_greedy_search_manager 3 | 4 | import os 5 | import sys 6 | import femm 7 | from time import time, sleep 8 | import operator 9 | import subprocess 10 | 11 | bool_remove_files = False 12 | 13 | def savetofile(id_solver, freq, stack_length): 14 | femm.mi_probdef(freq, 'millimeters', 'planar', 1e-8, # must < 1e-8 15 | stack_length, 18, 1) # The acsolver parameter (default: 0) specifies which solver is to be used for AC problems: 0 for successive approximation, 1 for Newton. 16 | femm.mi_saveas(dir_femm_temp+'femm_temp_%d.fem'%(id_solver)) 17 | 18 | def remove_files(list_solver_id, dir_femm_temp, suffix, id_solver_femm_found=None): 19 | print('Rename femm file for index', id_solver_femm_found, 'with suffix of', suffix, 'Others will be deleted.') 20 | for id_solver in list_solver_id: 21 | fname = dir_femm_temp + "femm_temp_%d"%(id_solver) + suffix 22 | 23 | if id_solver == id_solver_femm_found: 24 | found_file_name = dir_femm_temp + "femm_found" + suffix 25 | 26 | if os.path.exists(found_file_name): 27 | os.remove(found_file_name) # remove already existing file (due to interrupted run) 28 | 29 | if not os.path.exists(fname): 30 | raise Exception('FEMM file %s does not exist for id_solver=%d'%(fname, id_solver)) 31 | 32 | os.rename(fname, found_file_name) 33 | if bool_remove_files: 34 | continue 35 | else: 36 | break 37 | 38 | # what if we don't remove temp file??? 2019/7/8 39 | if bool_remove_files: 40 | os.remove(fname) 41 | 42 | DEBUG_MODE = False 43 | # if __name__ == '__main__': 44 | # DEBUG_MODE = True 45 | 46 | if DEBUG_MODE == False: 47 | number_of_instantces = int(sys.argv[1]) 48 | dir_femm_temp = sys.argv[2] 49 | stack_length = float(sys.argv[3]) 50 | VAREPSILON = 0.255 # difference between 1st and 2nd max torque slip frequencies 51 | else: 52 | #debug 53 | number_of_instantces = 5 54 | dir_femm_temp = "D:/OneDrive - UW-Madison/c/csv_opti/run#114/femm_temp/" # modify as expected 55 | stack_length = 186.4005899999999940 56 | VAREPSILON = 0.02 57 | 58 | 59 | femm.openfemm(True) 60 | femm.opendocument(dir_femm_temp + 'femm_temp.fem') 61 | 62 | # here, the only variable for an individual is frequency, so pop = list of frequencies 63 | freq_begin = 1. # hz 64 | freq_end = freq_begin + number_of_instantces - 1. # 5 Hz 65 | 66 | list_torque = [] 67 | list_slipfreq = [] 68 | list_solver_id = [] 69 | list_done_id = [] 70 | count_loop = 0 71 | while True: 72 | # freq_step can be negative! 73 | freq_step = (freq_end - freq_begin) / (number_of_instantces-1) 74 | 75 | count_done = len(list_done_id) 76 | if count_done % 5 == 0: 77 | list_solver_id = list(range(0, count_done+number_of_instantces, 1)) 78 | 79 | # parasolve 80 | procs = [] 81 | print('list_solver_id=', list_solver_id) 82 | print('list_solver_id[-number_of_instantces:]=', list_solver_id[-number_of_instantces:]) 83 | for i, id_solver in enumerate(list_solver_id[-number_of_instantces:]): 84 | savetofile(id_solver, freq_begin + i*freq_step, stack_length) 85 | 86 | proc = subprocess.Popen([sys.executable, 'parasolve_greedy_search.py', 87 | str(id_solver), '"'+dir_femm_temp+'"'], bufsize=-1) 88 | procs.append(proc) 89 | 90 | # This wait is working if you run this scirpt from sublime text 91 | for proc in procs: 92 | proc.wait() 93 | 94 | count_sec = 0 95 | while True: 96 | sleep(1) 97 | count_sec += 1 98 | if count_sec > 120: # two min 99 | raise Exception('It is highly likely that exception occurs during the solving of FEMM.') 100 | 101 | print('\nbegin waiting for eddy current solver...') 102 | for id_solver in list_solver_id[-number_of_instantces:]: 103 | 104 | if id_solver in list_done_id: 105 | continue 106 | 107 | fname = dir_femm_temp + "femm_temp_%d.txt"%(id_solver) 108 | # print fname 109 | if os.path.exists(fname): 110 | with open(fname, 'r') as f: 111 | data = f.readlines() 112 | # if data == []: 113 | # sleep(0.1) 114 | # data = f.readlines() 115 | # if data == []: 116 | # raise Exception('What takes you so long to write two float numbers?') 117 | list_slipfreq.append( float(data[0][:-1]) ) 118 | list_torque.append( float(data[1][:-1]) ) 119 | list_done_id.append(id_solver) 120 | 121 | if len(list_done_id) >= number_of_instantces: 122 | break 123 | 124 | # print('-----------------------') 125 | # print list_solver_id 126 | print('slip freq [Hz]:', list_slipfreq) 127 | print('torque [Nm]:', list_torque) 128 | 129 | # find the max 130 | list_torque_copy = list_torque[::] 131 | index_1st, breakdown_torque_1st = max(enumerate(list_torque_copy), key=operator.itemgetter(1)) 132 | breakdown_slipfreq_1st = list_slipfreq[index_1st] 133 | print('The max is #%d'%index_1st, breakdown_torque_1st, 'Nm') 134 | 135 | # 按Eric启发,这里可以添加一个判断,如果1st max是上一步的频率点,比如说 3 Hz 或者 4 Hz,那么说明最大点不在 1st max 和 2nd max 之间,而是在 1st max 和 3rd max之间。 136 | # 按Eric启发,这里可以添加一个判断,如果1st max是上一步的频率点,比如说 3 Hz 或者 4 Hz,那么说明最大点不在 1st max 和 2nd max 之间,而是在 1st max 和 3rd max之间。 137 | # 按Eric启发,这里可以添加一个判断,如果1st max是上一步的频率点,比如说 3 Hz 或者 4 Hz,那么说明最大点不在 1st max 和 2nd max 之间,而是在 1st max 和 3rd max之间。 138 | 139 | # find the 2nd max 140 | list_torque_copy[index_1st] = -999999 141 | index_2nd, breakdown_torque_2nd = max(enumerate(list_torque_copy), key=operator.itemgetter(1)) 142 | breakdown_slipfreq_2nd = list_slipfreq[index_2nd] 143 | print('2nd max is #%d'%index_2nd, breakdown_torque_2nd, 'Nm') 144 | 145 | print('Max slip freq error=', 0.5*(breakdown_slipfreq_1st - breakdown_slipfreq_2nd), 'Hz', ', 2*EPS=%g'%(VAREPSILON)) 146 | 147 | # find the two slip freq close enough then break.5 148 | if abs(breakdown_slipfreq_1st - breakdown_slipfreq_2nd) < VAREPSILON: # Hz 149 | the_index = list_solver_id[index_1st] 150 | print('Found it.', breakdown_slipfreq_1st, 'Hz', breakdown_torque_1st, 'Nm', 'The index is', the_index) 151 | remove_files(list_solver_id, dir_femm_temp, suffix='.fem', id_solver_femm_found=the_index) 152 | remove_files(list_solver_id, dir_femm_temp, suffix='.ans', id_solver_femm_found=the_index) 153 | 154 | 155 | 156 | with open(dir_femm_temp + 'femm_found.csv', 'w') as f: 157 | f.write('%g\n%g\n'%(breakdown_slipfreq_1st, breakdown_torque_1st)) #, Qs_stator_slot_area, Qr_rotor_slot_area)) 158 | break 159 | 160 | else: 161 | print('Not yet.') 162 | count_loop += 1 163 | if count_loop > 100: 164 | os.system('pause') 165 | 166 | # not found yet, try new frequencies. 167 | if breakdown_slipfreq_1st > breakdown_slipfreq_2nd: 168 | if breakdown_slipfreq_1st == list_slipfreq[-1]: 169 | freq_begin = breakdown_slipfreq_1st + 1. 170 | freq_end = freq_begin + number_of_instantces - 1. 171 | else: 172 | freq_begin = breakdown_slipfreq_1st 173 | freq_end = breakdown_slipfreq_2nd 174 | 175 | elif breakdown_slipfreq_1st < breakdown_slipfreq_2nd: 176 | freq_begin = breakdown_slipfreq_1st 177 | freq_end = breakdown_slipfreq_2nd 178 | 179 | # freq_step can be negative! 180 | freq_step = (freq_end - freq_begin) / (2 + number_of_instantces-1) 181 | freq_begin += freq_step 182 | freq_end -= freq_step 183 | print('try: freq_begin=%g, freq_end=%g.' % (freq_begin, freq_end)) 184 | 185 | remove_files(list_solver_id, dir_femm_temp, suffix='.txt') 186 | if bool_remove_files: 187 | os.remove(dir_femm_temp + "femm_temp.fem") 188 | 189 | femm.mi_close() 190 | femm.closefemm() 191 | 192 | if DEBUG_MODE == True: 193 | os.system('pause') 194 | 195 | -------------------------------------------------------------------------------- /_femm/codes3/pyfemm_script.py: -------------------------------------------------------------------------------- 1 | # coding:utf-8 2 | #execfile('D:/OneDrive - UW-Madison/c/codes/pyfemm_script.py') 3 | #execfile(r'K:\jchen782\JMAG\c\codes/pyfemm_script.py') 4 | 5 | ''' 1. General Information & Packages Loading 6 | ''' 7 | # execfile('D:/OneDrive - UW-Madison/c/codes/default_setting.py') # Absolute path is needed for running in JMAG 8 | # exec(compile(open('./default_setting.py').read(), './default_setting.py', 'exec')) # Relative path is enough if run outside JMAG 9 | filename = './default_setting.py' 10 | exec(compile(open(filename, "rb").read(), filename, 'exec'), globals(), locals()) 11 | 12 | 13 | # Debug 14 | # if os.path.exists('d:/femm42/PS_Qr32_NoEndRing_M19Gauge29_DPNV_1e3Hz'): 15 | # os.system('bash -c "rm -r /mnt/d/femm42/PS_Qr32_NoEndRing_M19Gauge29_DPNV_1e3Hz"') 16 | # if os.path.exists('d:/OneDrive - UW-Madison/c/pop/Tran2TSS_PS_Opti.txt'): 17 | # os.system('bash -c "mv /mnt/d/OneDrive\ -\ UW-Madison/c/pop/Tran2TSS_PS_Opti.txt /mnt/d/OneDrive\ -\ UW-Madison/c/pop/initial_design.txt"') 18 | 19 | logger = utility.myLogger(fea_config_dict['dir_codes'], prefix='iemdc_') 20 | 21 | fea_config_dict['flag_optimization'] = True # we need to generate and exploit sw.init_pop 22 | fea_config_dict['Active_Qr'] = 36 23 | 24 | run_list = [1,1,1,1,0] # Static FEA with JMAG is too slow, so use FEMM to do that part 25 | # run_list = [1,1,1,0,0] # TranRef is replaced by Tran2TSSProlong 26 | 27 | run_folder = r'run#99/' # Test run for single one design 28 | run_folder = r'run#98/' # Test run for the loop 29 | run_folder = r'run#97/' # Test run for the loop 30 | run_folder = r'run#96/' # Test run for the loop 31 | run_folder = r'run#95/' # Test run for the loop 32 | run_folder = r'run#94/' # Test run for the loop 33 | 34 | run_folder = r'run#93/' # get TranRef back and build rotor current plot 35 | 36 | if 'Severson' in fea_config_dict['pc_name']: 37 | # check number_cycles_prolonged is applied in number_of_total_steps (o) 38 | fea_config_dict['number_cycles_prolonged'] = 0 #150 # 1 39 | # app.Show() (o) 40 | fea_config_dict['designer.Show'] = True 41 | 42 | # serverson01 43 | if '01' in fea_config_dict['pc_name']: 44 | # run_folder = r'run#299/' # some bug 45 | 46 | fea_config_dict['number_cycles_prolonged'] = 150 47 | run_folder = r'run#298/' # 2 deg, 24 steps, 32 steps 48 | 49 | # fea_config_dict['number_cycles_prolonged'] = 0 50 | # fea_config_dict['number_of_steps_2ndTTS'] = 400 51 | # run_folder = r'run#297/' # sensitivity of solving steps (fine step case): 0.5 deg, 48 steps, 400 steps (error occurs: refarray is 3 not 5) 52 | # run_folder = r'run#296/' # sensitivity of solving steps (fine step case): 0.5 deg, 48 steps, 400 steps 53 | # run_folder = r'run#295/' 54 | 55 | # serverson02 56 | elif '02' in fea_config_dict['pc_name']: 57 | # run_folder = r'run#399/' # some bug 58 | # run_folder = r'run#398/' # 2 deg, 24 steps, 32 steps 59 | 60 | fea_config_dict['number_of_steps_2ndTTS'] = 16 61 | run_folder = r'run#397/' # This is not used 62 | run_folder = r'run#395/' # sensitivity of solving steps (coarse step case): 5 deg, 12 steps, 16 steps 63 | else: 64 | raise Exception('Where are you?') 65 | 66 | fea_config_dict['run_folder'] = run_folder 67 | fea_config_dict['jmag_run_list'] = run_list 68 | fea_config_dict['DPNV_separate_winding_implementation'] = True 69 | 70 | # rebuild the name 71 | build_model_name_prefix(fea_config_dict) 72 | 73 | # fea_config_dict['femm_deg_per_step'] = 0.25 * (360/4) / utility.lcm(24/4., fea_config_dict['Active_Qr']/4.) # at least half period 74 | # fea_config_dict['femm_deg_per_step'] = 1 * (360/4) / utility.lcm(24/4., fea_config_dict['Active_Qr']/4.) # at least half period 75 | fea_config_dict['femm_deg_per_step'] = 2 #0.5 #0.1 # deg # 5 deg will cause error when DFT getting iron loss results 76 | logger.info('femm_deg_per_step is %g deg (Qs=24, p=2).'%(fea_config_dict['femm_deg_per_step'])) 77 | 78 | fea_config_dict['ec_rotate_divisions_per_slot_pitch'] = 24 79 | logger.info('ec_rotate_divisions_per_slot_pitch is %g deg (Qs=24, p=2).'%(fea_config_dict['ec_rotate_divisions_per_slot_pitch'])) 80 | 81 | ''' 2. Initilize Swarm and Initial Pyrhonen's Design (Run this part in JMAG) 82 | ''' # 1e-1也还是太小了(第三次报错),至少0.5mm长吧 # 1e-1 is the least geometry value. a 1e-2 will leads to:转子闭口槽极限,会导致edge过小,从而报错:small arc entity exists.png 83 | de_config_dict = { 'bounds': [[3,9], [0.5,4], [5e-1,3], [2.5, 6], [5e-1,3], [1,10], [5e-1,3]], 84 | 'mut': 0.8, 85 | 'crossp': 0.7, 86 | 'popsize': 50, # 100 87 | 'iterations': 20 } # begin at 5 88 | # get initial design as im 89 | sw = population.swarm(fea_config_dict, de_config_dict=de_config_dict) 90 | # sw.show(which='all') 91 | # print sw.im.show() 92 | 93 | 94 | # generate the initial generation 95 | sw.generate_pop() 96 | 97 | im_initial = sw.im 98 | # print im_initial.l21 99 | # print im_initial.l22 100 | 101 | ''' 3. Initialize FEMM Solver 102 | ''' 103 | # define problem 104 | logger.info('Running Script for FEMM with %s'%(run_folder)) 105 | solver_jmag = FEMM_Solver.FEMM_Solver(im_initial, flag_read_from_jmag=True, freq=0) # static 106 | solver_femm = FEMM_Solver.FEMM_Solver(im_initial, flag_read_from_jmag=False, freq=2.23) # eddy+static 107 | 108 | 109 | 110 | # # debug 111 | # if not solver_femm.has_results(solver_femm.dir_run + 'sweeping/'): 112 | # solver_femm.run_frequency_sweeping(range(1,6)) 113 | # data_femm = solver_femm.show_results(bool_plot=False) # this write rotor currents to file, which will be used later for static FEA 114 | # else: 115 | # solver_femm.show_results_eddycurrent(True) # get right slip 116 | # print solver_femm.get_iron_loss(MAX_FREQUENCY=50e3) 117 | # print solver_femm.get_iron_loss(MAX_FREQUENCY=30e3) 118 | # print solver_femm.get_iron_loss(MAX_FREQUENCY=10e3) 119 | # print solver_femm.get_iron_loss(MAX_FREQUENCY=5e3) 120 | # from pylab import show; show() 121 | # quit() 122 | # solver_femm.read_current_conditions_from_FEMM() 123 | # solver_femm.get_copper_loss() 124 | # quit() 125 | 126 | # solver_femm.keep_collecting_static_results_for_optimization() 127 | # # # # quit() 128 | # # # # # load Arnon5 from file 129 | # # # # sw.print_array() 130 | # # # # quit() 131 | 132 | 133 | 134 | 135 | 136 | # 50 Random Design Evaluation for IEMDC 2019 137 | from time import time as clock_time 138 | from time import sleep 139 | import numpy as np 140 | from pylab import show 141 | from collections import OrderedDict 142 | 143 | min_b, max_b = np.asarray(sw.de_config_dict['bounds']).T 144 | diff = np.fabs(min_b - max_b) 145 | pop_denorm = min_b + sw.init_pop * diff 146 | 147 | for ind, individual_denorm in enumerate(pop_denorm): 148 | 149 | im_variant = population.bearingless_induction_motor_design.local_design_variant(im_initial, \ 150 | 0, ind, individual_denorm) # due to compatability issues: a new child class is used instead 151 | 152 | if not sw.has_results(im_variant): 153 | # break 154 | sw.run(im_variant, individual_index=ind, run_list=run_list) 155 | # im_variant.csv_previous_solve = sw.dir_csv_output_folder + im_variant.get_individual_name() + u"Freq" + '_circuit_current.csv' 156 | 157 | # FEMM Static Solver with pre-determined rotor currents from JMAG 158 | tic = clock_time() 159 | solver_jmag = FEMM_Solver.FEMM_Solver(im_variant, individual_index=ind, flag_read_from_jmag=True, freq=0, bool_static_fea_loss=False) # static 160 | if not solver_jmag.has_results(): 161 | print('run_rotating_static_FEA') 162 | # utility.blockPrint() 163 | solver_jmag.run_rotating_static_FEA() 164 | solver_jmag.parallel_solve() 165 | # utility.enablePrint() 166 | 167 | # collecting parasolve with post-process 168 | # wait for .ans files 169 | # data_solver_jmag = solver_jmag.show_results_static(bool_plot=False) # this will wait as well? 170 | while not solver_jmag.has_results(): 171 | print(clock_time()) 172 | sleep(3) 173 | results_dict = {} 174 | for f in [f for f in os.listdir(solver_jmag.dir_run) if 'static_results' in f]: 175 | data = np.loadtxt(solver_jmag.dir_run + f, unpack=True, usecols=(0,1,2,3)) 176 | for i in range(len(data[0])): 177 | results_dict[data[0][i]] = (data[1][i], data[2][i], data[3][i]) 178 | keys_without_duplicates = [key for key, item in results_dict.items()] 179 | keys_without_duplicates.sort() 180 | with open(solver_jmag.dir_run + "no_duplicates.txt", 'w') as fw: 181 | for key in keys_without_duplicates: 182 | fw.writelines('%g %g %g %g\n' % (key, results_dict[key][0], results_dict[key][1], results_dict[key][2])) 183 | data_solver_jmag = np.array([ keys_without_duplicates, 184 | [results_dict[key][0] for key in keys_without_duplicates], 185 | [results_dict[key][1] for key in keys_without_duplicates], 186 | [results_dict[key][2] for key in keys_without_duplicates]]) 187 | # print data_solver_jmag 188 | toc = clock_time() 189 | print(ind, 'tic: %g. toc: %g. diff:%g' % (tic, toc, toc-tic)) 190 | 191 | 192 | 193 | # for iemdc 2019 Qr36rotor_current 194 | # sw.show_results(femm_solver_data=data_solver_jmag) 195 | # data = solver_jmag.show_results(bool_plot=False) 196 | # sw.show_results(femm_solver_data=data) 197 | sw.show_results_iemdc19(im_variant, femm_solver_data=data_solver_jmag, femm_rotor_current_function=solver_jmag.get_rotor_current_function()) 198 | # sw.timeStepSensitivity() 199 | from pylab import show 200 | show() 201 | quit() 202 | 203 | 204 | # JMAG results (EC-Rotate and Tran2TSS and Tran2TSSProlongRef) 205 | data_results = utility.collect_jmag_Tran2TSSProlong_results(im_variant, sw.dir_csv_output_folder, sw.fea_config_dict, sw.axeses, femm_solver_data=data_solver_jmag) 206 | # show() 207 | # quit() 208 | sw.fig_main.savefig(sw.dir_run + im_variant.get_individual_name() + 'results.png', dpi=150) 209 | utility.pyplot_clear(sw.axeses) 210 | 211 | # write to file for inspection 212 | with open(sw.dir_run + 'iemdc_data.txt', 'a') as f: 213 | f.write(','.join(['%g'%(el) for el in [ind] + data_results]) + '\n') 214 | 215 | # break 216 | 217 | # 绘制K线图表征最大误差和最小误差 218 | exec(compile(open('./iemdc_random_design_plot.py').read(), './iemdc_random_design_plot.py', 'exec')) 219 | quit() 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | 232 | ''' 4. Show results, if not exist then produce it 233 | ''' 234 | from numpy import arange 235 | if True: # this generate plots for iemdc19 236 | data = solver_jmag.show_results(bool_plot=False) 237 | # sw.show_results(femm_solver_data=data) 238 | sw.show_results_iemdc19(femm_solver_data=data, femm_rotor_current_function=solver_jmag.get_rotor_current_function()) 239 | # sw.timeStepSensitivity() 240 | else: 241 | # FEMM only 242 | # FEMM Static Solver with pre-determined rotor currents from FEMM 243 | if not solver_femm.has_results(): 244 | solver_femm.run_frequency_sweeping(arange(0.5,5.1,0.5)) 245 | data_femm = solver_femm.show_results(bool_plot=False) # this write rotor currents to file, which will be used later for static FEA 246 | 247 | quit() 248 | # solver_femm.run_rotating_static_FEA() 249 | # solver_femm.parallel_solve() 250 | 251 | 252 | # JMAG 253 | if not sw.has_results(im_initial, 'Freq'): 254 | sw.run(im_initial, run_list=sw.fea_config_dict['jmag_run_list']) 255 | if not sw.has_results(im_initial, 'Freq'): 256 | raise Exception('Something went south with JMAG.') 257 | 258 | print('Rotor current solved by FEMM is shown here:') 259 | solver_femm.read_current_conditions_from_FEMM() 260 | 261 | print('Rotor current solved by JMAG is shown here:') 262 | solver_jmag.read_current_from_EC_FEA() 263 | for key, item in solver_jmag.dict_rotor_current_from_EC_FEA.items(): 264 | if '1' in key: 265 | from math import sqrt 266 | print(key, sqrt(item[0]**2+item[1]**2)) 267 | 268 | # FEMM Static Solver with pre-determined rotor currents from JMAG 269 | if not solver_jmag.has_results(): 270 | solver_jmag.run_rotating_static_FEA() 271 | solver_jmag.parallel_solve() 272 | 273 | # Compare JMAG and FEMM's rotor currents to see DPNV is implemented correctly in bot JMAG and FEMM 274 | data_femm = solver_femm.show_results_static(bool_plot=False) 275 | data_jmag = solver_jmag.show_results_static(bool_plot=False) 276 | 277 | if data_femm is None or data_jmag is None: 278 | if data_femm is None: 279 | print('data_femm is', data_femm, 'try run again') 280 | if data_jmag is None: 281 | print('data_jmag is', data_jmag, 'try run again') 282 | else: 283 | from pylab import subplots 284 | fig, axes = subplots(3, 1, sharex=True) 285 | for data in [data_femm, data_jmag]: 286 | ax = axes[0]; ax.plot(data[0]*0.1, data[1], alpha=0.5, label='torque'); ax.legend(); ax.grid() 287 | ax = axes[1]; ax.plot(data[0]*0.1, data[2], alpha=0.5, label='Fx'); ax.legend(); ax.grid() 288 | ax = axes[2]; ax.plot(data[0]*0.1, data[3], alpha=0.5, label='Fy'); ax.legend(); ax.grid() 289 | 290 | 291 | 292 | # sw.write_to_file_fea_config_dict() 293 | from pylab import show; show() 294 | 295 | 296 | 297 | 298 | 299 | # Run JCF from command linie instead of GUI 300 | # if not sw.has_results(im_initial, study_type='Tran2TSS'): 301 | # os.system(r'set InsDir=D:\Program Files\JMAG-Designer17.1/') 302 | # os.system(r'set WorkDir=D:\JMAG_Files\JCF/') 303 | # os.system(r'cd /d "%InsDir%"') 304 | # for jcf_file in os.listdir(sw.dir_jcf): 305 | # if 'Tran2TSS' in jcf_file and 'Mesh' in jcf_file: 306 | # os.system('ExecSolver "%WorkDir%' + jcf_file + '"') 307 | if False: # Test and Debug 308 | 309 | ''' 3. Eddy Current FEA with FEMM 310 | ''' 311 | solver = FEMM_Solver.FEMM_Solver(deg_per_step, im_initial, dir_codes, dir_femm_files + run_folder) 312 | 313 | solver.read_current_from_EC_FEA() 314 | for key, item in solver.dict_rotor_current_from_EC_FEA.items(): 315 | if '1' in key: 316 | from math import sqrt 317 | print(key, sqrt(item[0]**2+item[1]**2)) 318 | 319 | if solver.has_results(): 320 | solver.show_results() 321 | else: 322 | solver.run_frequency_sweeping(arange(2, 5.1, 0.25), fraction=2) 323 | solver.parallel_solve(6, bool_watchdog_postproc='JMAG' not in dir_interpreter) 324 | 325 | 326 | ''' 327 | Two Shared process - Max CPU occupation 32.6% 328 | Freq: 2:16 (13 Steps) 329 | Tran2TSS: 3:38 (81 Steps) 330 | Freq-FFVRC: 1:33 (10 Steps) 331 | TranRef: 1:49:02 (3354 Steps) -> 3:18:19 if no MultiCPU 332 | StaticJMAG: 333 | StaticFEMM: 15 sec one eddy current solve 334 | 7 sec one static solve 335 | ''' 336 | 337 | a=''' Loss Study of Transient FEA 338 | # -*- coding: utf-8 -*- 339 | app = designer.GetApplication() 340 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P1").SetValue(u"BasicFrequencyType", 1) 341 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P1").SetValue(u"RevolutionSpeed", 15000) 342 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P1").SetValue(u"StressType", 0) 343 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P1").ClearParts() 344 | sel = app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P1").GetSelection() 345 | sel.SelectPart(35) 346 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P1").AddSelected(sel) 347 | app.SetCurrentStudy(u"Loss_Tran2TSS-Prolong") 348 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").CreateCondition(u"Ironloss", u"P2") 349 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P2").SetValue(u"BasicFrequencyType", 2) 350 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P2").SetValue(u"BasicFrequency", 3) 351 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P2").SetValue(u"StressType", 0) 352 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P2").ClearParts() 353 | sel = app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P2").GetSelection() 354 | sel.SelectPart(2) 355 | app.GetModel(u"PS_ID32").GetStudy(u"Loss_Tran2TSS-Prolong").GetCondition(u"P2").AddSelected(sel) 356 | app.SetCurrentStudy(u"Loss_Tran2TSS-Prolong") 357 | ''' 358 | 359 | -------------------------------------------------------------------------------- /_femm/codes3/spec_Prototype2poleOD150mm500Hz_SpecifyTipSpeed.py: -------------------------------------------------------------------------------- 1 | # import pyrhonen_procedure_as_function 2 | #~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~ 3 | # Design Specification 4 | # 1. Specify desgin_specification 5 | # 2. Give a run folder 6 | # 3. Is it sensitivity analysis or not 7 | # 4. Does it use refined bounds or it is local tuning with local bounds based on the best design from another run 8 | #~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~*~ 9 | p = 1 10 | spec = pyrhonen_procedure_as_function.desgin_specification( 11 | PS_or_SC = True, # Pole Specific or Squirrel Cage 12 | DPNV_or_SEPA = True, # Dual purpose no voltage or Separate winding 13 | p = p, 14 | ps = 2 if p==1 else 1, 15 | mec_power = 50e3, # kW 16 | ExcitationFreq = 500, # Hz 17 | ExcitationFreqSimulated = 500, # Hz This sets to DriveW_Freq that is actually used in FE simulation. 18 | VoltageRating = 480, # Vrms (line-to-line, Wye-Connect) 19 | TangentialStress = 12000, # Pa 20 | Qs = 24, 21 | Qr = 16, 22 | Js = 4e6, # Arms/m^2 23 | Jr = 7.25e6, #7.5e6, #6.575e6, # Arms/m^2 24 | Steel = 'M19Gauge29', # Arnon-7 25 | lamination_stacking_factor_kFe = 0.95, # from http://www.femm.info/wiki/spmloss # 0.91 for Arnon 26 | Coil = 'Cu', 27 | space_factor_kCu = 0.5, # Stator slot fill/packign factor 28 | Conductor = 'Cu', 29 | space_factor_kAl = 1.0, # Rotor slot fill/packing factor 30 | Temperature = 75, # deg Celsius 31 | stator_tooth_flux_density_B_ds = 1.4, # Tesla 32 | rotor_tooth_flux_density_B_dr = 1.5, # Tesla 33 | stator_yoke_flux_density_Bys = 1.2, # Tesla 34 | rotor_yoke_flux_density_Byr = 1.1 + 0.3 if p==1 else 1.1, # Tesla 35 | guess_air_gap_flux_density = 0.8, # 0.8, # Tesla | 0.7 ~ 0.9 | Table 6.3 36 | guess_efficiency = 0.95, 37 | guess_power_factor = 0.7 if p==1 else 0.6, 38 | safety_factor_to_yield = None, # use this or use tip speed 39 | safety_factor_to_critical_speed = 1.5, 40 | use_drop_shape_rotor_bar = True, # round bar 41 | tip_speed = 97, # m/s, use this or use safety_factor_to_yield 42 | debug_or_release = True, # 如果是debug,数据库里有记录就删掉重新跑;如果release且有记录,那就报错。 43 | bool_skew_stator = None, 44 | bool_skew_rotor = None, 45 | ) 46 | # self.show() 47 | print(spec.build_name()) 48 | spec.bool_bad_specifications = spec.pyrhonen_procedure(fea_config_dict['pc_name']) 49 | print(spec.build_name()) # TODO:自动修正转子电流密度的设置值? 50 | -------------------------------------------------------------------------------- /_femm/codes3/utility_moo.py: -------------------------------------------------------------------------------- 1 | import pygmo as pg 2 | from pylab import plt, np 3 | def my_plot_non_dominated_fronts(points, marker='o', comp=[0, 1], up_to_rank_no=None): 4 | # We plot 5 | fronts, _, _, _ = pg.fast_non_dominated_sorting(points) 6 | 7 | # We define the colors of the fronts (grayscale from black to white) 8 | if up_to_rank_no is None: 9 | cl = list(zip(np.linspace(0.1, 0.9, len(fronts)), 10 | np.linspace(0.1, 0.9, len(fronts)), 11 | np.linspace(0.1, 0.9, len(fronts)))) 12 | else: 13 | cl = list(zip(np.linspace(0.1, 0.9, up_to_rank_no), 14 | np.linspace(0.1, 0.9, up_to_rank_no), 15 | np.linspace(0.1, 0.9, up_to_rank_no))) 16 | 17 | fig, ax = plt.subplots() 18 | 19 | count = 0 20 | for ndr, front in enumerate(fronts): 21 | count += 1 22 | # We plot the points 23 | for idx in front: 24 | ax.plot(points[idx][comp[0]], points[idx][ 25 | comp[1]], marker=marker, color=cl[ndr]) 26 | # We plot the fronts 27 | # Frist compute the points coordinates 28 | x = [points[idx][comp[0]] for idx in front] 29 | y = [points[idx][comp[1]] for idx in front] 30 | # Then sort them by the first objective 31 | tmp = [(a, b) for a, b in zip(x, y)] 32 | tmp = sorted(tmp, key=lambda k: k[0]) 33 | # Now plot using step 34 | ax.step([c[0] for c in tmp], [c[1] 35 | for c in tmp], color=cl[ndr], where='post') 36 | if up_to_rank_no is None: 37 | pass 38 | else: 39 | if count >= up_to_rank_no: 40 | break 41 | 42 | return ax 43 | def my_2p5d_plot_non_dominated_fronts(points, marker='o', comp=[0, 1], up_to_rank_no=1, no_text=True): 44 | # from pylab import mpl 45 | # mpl.rcParams['font.family'] = ['Times New Roman'] 46 | # mpl.rcParams['font.size'] = 16.0 47 | 48 | full_comp = [0, 1, 2] 49 | full_comp.remove(comp[0]) 50 | full_comp.remove(comp[1]) 51 | z_comp = full_comp[0] 52 | 53 | # We plot 54 | # fronts, dl, dc, ndr = pg.fast_non_dominated_sorting(points) 55 | fronts, _, _, _= pg.fast_non_dominated_sorting(points) 56 | 57 | # We define the colors of the fronts (grayscale from black to white) 58 | cl = list(zip(np.linspace(0.9, 0.1, len(fronts)), 59 | np.linspace(0.9, 0.1, len(fronts)), 60 | np.linspace(0.9, 0.1, len(fronts)))) 61 | 62 | fig, ax = plt.subplots(constrained_layout=False) 63 | plt.subplots_adjust(left=None, bottom=None, right=0.85, top=None, wspace=None, hspace=None) 64 | 65 | count = 0 66 | for ndr, front in enumerate(fronts): 67 | count += 1 68 | 69 | # Frist compute the points coordinates 70 | x_scale = 1 71 | y_scale = 1 72 | z_scale = 1 73 | if comp[0] == 1: # efficency 74 | x_scale = 100 75 | if comp[1] == 1: # efficency 76 | y_scale = 100 77 | if z_comp == 1: # efficency 78 | z_scale = 100 79 | x = [points[idx][comp[0]]*x_scale for idx in front] 80 | y = [points[idx][comp[1]]*y_scale for idx in front] 81 | z = [points[idx][z_comp] *z_scale for idx in front] 82 | 83 | # # We plot the points 84 | # for idx in front: 85 | # ax.plot(points[idx][comp[0]], points[idx][comp[1]], marker=marker, color=cl[ndr]) 86 | 87 | # Then sort them by the first objective 88 | tmp = [(a, b, c) for a, b, c in zip(x, y, z)] 89 | tmp = sorted(tmp, key=lambda k: k[0]) 90 | # Now plot using step 91 | ax.step([coords[0] for coords in tmp], 92 | [coords[1] for coords in tmp], color=cl[ndr], where='post') 93 | 94 | # Now add color according to the value of the z-axis variable usign scatter 95 | scatter_handle = ax.scatter(x, y, c=z, alpha=0.5, cmap='Spectral', marker=marker, zorder=99) #'viridis' 96 | # color bar 97 | cbar_ax = fig.add_axes([0.875, 0.15, 0.02, 0.7]) 98 | cbar_ax.get_yaxis().labelpad = 10 99 | clb = fig.colorbar(scatter_handle, cax=cbar_ax) 100 | if z_comp == 0: 101 | z_label = r'$-\rm {TRV}$ [Nm/m^3]' 102 | z_text = '%.0f' 103 | elif z_comp == 1: 104 | z_label = r'$-\eta$ [%]' 105 | z_text = '%.1f' 106 | elif z_comp == 2: 107 | z_label = r'$O_C$ [1]' 108 | z_text = '%.1f' 109 | clb.ax.set_ylabel(z_label, rotation=270) 110 | 111 | 112 | if z_comp == 2: # when OC as z-axis 113 | print('-----------------------------------------------------') 114 | print('-----------------------------------------------------') 115 | print('-----------------------------------------------------') 116 | # Add index next to the points 117 | for x_coord, y_coord, z_coord, idx in zip(x, y, z, front): 118 | if no_text: 119 | pass 120 | else: 121 | ax.annotate( z_text%(z_coord) + ' #%d'%(idx), (x_coord, y_coord) ) 122 | else: 123 | # text next scatter showing the value of the 3rd objective 124 | for i, val in enumerate(z): 125 | if no_text: 126 | pass 127 | else: 128 | ax.annotate( z_text%(val), (x[i], y[i]) ) 129 | 130 | # refine the plotting 131 | if comp[0] == 0: 132 | ax.set_xlabel(r'$-\rm {TRV}$ [Nm/m^3]') 133 | elif comp[0] == 1: 134 | ax.set_xlabel(r'$-\eta$ [%]') 135 | elif comp[0] == 2: 136 | ax.set_xlabel(r'$O_C$ [1]') 137 | 138 | if comp[1] == 0: 139 | ax.set_ylabel(r'$-\rm {TRV}$ [Nm/m^3]') 140 | elif comp[1] == 1: 141 | ax.set_ylabel(r'$-\eta$ [%]') 142 | elif comp[1] == 2: 143 | ax.set_ylabel(r'$O_C$ [1]') 144 | ax.grid() 145 | 146 | # plot up to which domination rank? 147 | if up_to_rank_no is None: 148 | pass 149 | else: 150 | if count >= up_to_rank_no: 151 | break 152 | # Y730 153 | # fig.savefig(r'C:\Users\horyc\Desktop/'+ '2p5D-%d%d.png'%(comp[0],comp[1]), dpi=300) 154 | return ax 155 | def my_3d_plot_non_dominated_fronts(pop, paretoPoints, fea_config_dict, az=180, comp=[0, 1, 2], plot_option=1): 156 | """ 157 | Plots solutions to the DTLZ problems in three dimensions. The Pareto Front is also 158 | visualized if the problem id is 2,3 or 4. 159 | Args: 160 | pop (:class:`~pygmo.population`): population of solutions to a dtlz problem 161 | az (``float``): angle of view on which the 3d-plot is created 162 | comp (``list``): indexes the fitness dimension for x,y and z axis in that order 163 | Returns: 164 | ``matplotlib.axes.Axes``: the current ``matplotlib.axes.Axes`` instance on the current figure 165 | Raises: 166 | ValueError: if *pop* does not contain a DTLZ problem (veryfied by its name only) or if *comp* is not of length 3 167 | Examples: 168 | >>> import pygmo as pg 169 | >>> udp = pg.dtlz(prob_id = 1, fdim =3, dim = 5) 170 | >>> pop = pg.population(udp, 40) 171 | >>> udp.plot(pop) # doctest: +SKIP 172 | """ 173 | from mpl_toolkits.mplot3d import axes3d 174 | import matplotlib.pyplot as plt 175 | import numpy as np 176 | # from pylab import mpl 177 | # mpl.rcParams['font.family'] = ['Times New Roman'] 178 | # mpl.rcParams['font.size'] = 16.0 179 | 180 | # if (pop.problem.get_name()[:-1] != "DTLZ"): 181 | # raise(ValueError, "The problem seems not to be from the DTLZ suite") 182 | 183 | if (len(comp) != 3): 184 | raise(ValueError, "The kwarg *comp* needs to contain exactly 3 elements (ids for the x,y and z axis)") 185 | 186 | # Create a new figure 187 | fig = plt.figure(figsize=(12,8)) 188 | ax = fig.add_subplot(111, projection='3d') 189 | 190 | # plot the points 191 | fits = np.transpose(pop.get_f()) 192 | try: 193 | pass 194 | # ax.plot(fits[comp[0]], fits[comp[1]], fits[comp[2]], 'ro') 195 | except IndexError: 196 | print('Error. Please choose correct fitness dimensions for printing!') 197 | 198 | if False: 199 | # Plot pareto front for dtlz 1 200 | if plot_option==1: # (pop.problem.get_name()[-1] in ["1"]): 201 | 202 | X, Y = np.meshgrid(np.linspace(0, 0.5, 100), np.linspace(0, 0.5, 100)) 203 | Z = - X - Y + 0.5 204 | # remove points not in the simplex 205 | for i in range(100): 206 | for j in range(100): 207 | if X[i, j] < 0 or Y[i, j] < 0 or Z[i, j] < 0: 208 | Z[i, j] = float('nan') 209 | 210 | ax.set_xlim(0, 1.) 211 | ax.set_ylim(0, 1.) 212 | ax.set_zlim(0, 1.) 213 | 214 | ax.plot_wireframe(X, Y, Z, rstride=10, cstride=10) 215 | plt.plot([0, 0.5], [0.5, 0], [0, 0]) 216 | 217 | # Plot pareto fronts for dtlz 2,3,4 218 | if plot_option == 2: # (pop.problem.get_name()[-1] in ["2", "3", "4"]): 219 | # plot the wireframe of the known optimal pareto front 220 | thetas = np.linspace(0, (np.pi / 2.0), 30) 221 | # gammas = np.linspace(-np.pi / 4, np.pi / 4, 30) 222 | gammas = np.linspace(0, (np.pi / 2.0), 30) 223 | 224 | x_frame = np.outer(np.cos(thetas), np.cos(gammas)) 225 | y_frame = np.outer(np.cos(thetas), np.sin(gammas)) 226 | z_frame = np.outer(np.sin(thetas), np.ones(np.size(gammas))) 227 | 228 | ax.set_autoscalex_on(False) 229 | ax.set_autoscaley_on(False) 230 | ax.set_autoscalez_on(False) 231 | 232 | ax.set_xlim(0, 1.8) 233 | ax.set_ylim(0, 1.8) 234 | ax.set_zlim(0, 1.8) 235 | 236 | ax.plot_wireframe(x_frame, y_frame, z_frame) 237 | 238 | # https://stackoverflow.com/questions/37000488/how-to-plot-multi-objectives-pareto-frontier-with-deap-in-python 239 | # def simple_cull(inputPoints, dominates): 240 | # paretoPoints = set() 241 | # candidateRowNr = 0 242 | # dominatedPoints = set() 243 | # while True: 244 | # candidateRow = inputPoints[candidateRowNr] 245 | # inputPoints.remove(candidateRow) 246 | # rowNr = 0 247 | # nonDominated = True 248 | # while len(inputPoints) != 0 and rowNr < len(inputPoints): 249 | # row = inputPoints[rowNr] 250 | # if dominates(candidateRow, row): 251 | # # If it is worse on all features remove the row from the array 252 | # inputPoints.remove(row) 253 | # dominatedPoints.add(tuple(row)) 254 | # elif dominates(row, candidateRow): 255 | # nonDominated = False 256 | # dominatedPoints.add(tuple(candidateRow)) 257 | # rowNr += 1 258 | # else: 259 | # rowNr += 1 260 | 261 | # if nonDominated: 262 | # # add the non-dominated point to the Pareto frontier 263 | # paretoPoints.add(tuple(candidateRow)) 264 | 265 | # if len(inputPoints) == 0: 266 | # break 267 | # return paretoPoints, dominatedPoints 268 | # def dominates(row, candidateRow): 269 | # return sum([row[x] >= candidateRow[x] for x in range(len(row))]) == len(row) 270 | # import random 271 | # print(inputPoints) 272 | # inputPoints = [[random.randint(70,100) for i in range(3)] for j in range(500)] 273 | # print(inputPoints) 274 | # quit() 275 | # inputPoints = [(x,y,z) for x,y,z in zip(fits[comp[0]], fits[comp[1]], fits[comp[2]])] 276 | # paretoPoints, dominatedPoints = simple_cull(inputPoints, dominates) 277 | x = [coords[0]/1000 for coords in paretoPoints] 278 | y = [coords[1] for coords in paretoPoints] 279 | z = [coords[2] for coords in paretoPoints] 280 | 281 | # from surface_fitting import surface_fitting 282 | # surface_fitting(x,y,z) 283 | # quit() 284 | 285 | if False: 286 | pass 287 | else: 288 | import pandas as pd 289 | from pylab import cm 290 | print(dir(cm)) 291 | df = pd.DataFrame({'x': x, 'y': y, 'z': z}) 292 | 293 | # 只有plot_trisurf这一个函数,输入是三个以为序列的,其他都要meshgrid得到二维数组的(即ndim=2的数组) 294 | # # https://jakevdp.github.io/PythonDataScienceHandbook/04.12-three-dimensional-plotting.html 295 | # surf = ax.plot_trisurf(df.x, df.y, df.z, cmap=cm.magma, linewidth=0.1, edgecolor='none') 296 | # surf = ax.plot_trisurf(x, y, z, cmap='viridis', edgecolor='none') 297 | # surf = ax.plot_trisurf(df.x, df.y, df.z, cmap=cm.magma, linewidth=0.1) 298 | surf = ax.plot_trisurf(df.x, df.y*100, df.z, cmap=cm.Spectral, linewidth=0.1) 299 | 300 | with open('./%s_PF_points.txt'%(fea_config_dict['run_folder'][:-1]), 'w') as f: 301 | f.write('TRV,eta,OC\n') 302 | f.writelines(['%g,%g,%g\n'%(a,b,c) for a,b,c in zip(df.x, df.y*100, df.z)]) 303 | # quit() 304 | 305 | fig.colorbar(surf, shrink=0.5, aspect=5) 306 | 307 | ax.set_xlabel(' \n$\\rm -TRV$ [$\\rm kNm/m^3$]') 308 | ax.set_ylabel(' \n$-\\eta$ [%]') 309 | ax.set_yticks(np.arange(-96,-93.5,0.5)) 310 | ax.set_zlabel(r'$O_C$ [1]') 311 | 312 | # Try to export data from plot_trisurf # https://github.com/WoLpH/numpy-stl/issues/19 313 | # print(surf.get_vector()) 314 | 315 | # plt.savefig('./plots/avgErrs_vs_C_andgamma_type_%s.png'%(k)) 316 | # plt.show() 317 | 318 | # # rotate the axes and update 319 | # for angle in range(0, 360): 320 | # ax.view_init(30, angle) 321 | # plt.draw() 322 | # plt.pause(.001) 323 | 324 | ax.view_init(azim=245, elev=15) 325 | # fig.tight_layout() 326 | 327 | # Y730 328 | # fig.savefig(r'C:\Users\horyc\Desktop/3D-plot.png', dpi=300, layout='tight') 329 | 330 | # ax.view_init(azim=az) 331 | # ax.set_xlim(0, 1.) 332 | # ax.set_ylim(0, 1.) 333 | # ax.set_zlim(0, 10.) 334 | return ax 335 | def my_plot(fits, vectors, ndf): 336 | plt.rcParams['mathtext.fontset'] = 'stix' # 'cm' 337 | plt.rcParams["font.family"] = "Times New Roman" 338 | if True: 339 | # for fit in fits: 340 | # print(fit) 341 | # ax = pg.plot_non_dominated_fronts(fits) 342 | 343 | # ax = my_plot_non_dominated_fronts(fits, comp=[0,1], marker='o', up_to_rank_no=3) 344 | # ax = my_plot_non_dominated_fronts(fits, comp=[0,2], marker='o', up_to_rank_no=3) 345 | # ax = my_plot_non_dominated_fronts(fits, comp=[1,2], marker='o', up_to_rank_no=3) 346 | 347 | pass 348 | 349 | ax = my_2p5d_plot_non_dominated_fronts(fits, comp=[0,1], marker='o', up_to_rank_no=1) 350 | # # for studying LSA population (whether or not the optimal is on Rank 1 Pareto Front) 351 | # x = fits[0][0]/1e3 352 | # y = fits[0][1] 353 | # z = fits[0][2] 354 | # ax.plot(x, y, color='k', marker='s') 355 | # ax.annotate(r'$x_{\rm optm}$', xy=(x, y), xytext=(x+1, y+0.0005), arrowprops=dict(facecolor='black', shrink=0.05),) 356 | ax = my_2p5d_plot_non_dominated_fronts(fits, comp=[0,2], marker='o', up_to_rank_no=1) 357 | ax = my_2p5d_plot_non_dominated_fronts(fits, comp=[1,2], marker='o', up_to_rank_no=1) 358 | 359 | else: 360 | # Obselete. Use ax.step instead to plot 361 | print('Valid for 2D objective function space only for now.') 362 | fig, axes = plt.subplots(ncols=2, nrows=1, dpi=150, facecolor='w', edgecolor='k'); 363 | ax = axes[0] 364 | 365 | for index, xy in enumerate(vectors): 366 | ax.plot(*xy, 's', color='0') 367 | ax.text(*xy, '#%d'%(index), color='0') 368 | ax.title.set_text("Decision Vector Space") 369 | 370 | ax = axes[1] 371 | 372 | for index, front in enumerate(ndf): 373 | print('Rank/Tier', index, front) 374 | the_color = '%g'%(index/len(ndf)) 375 | for individual in front: # individual is integer here 376 | ax.plot(*fits[individual], 'o', color=the_color) 377 | ax.text(*fits[individual], '#%d'%(individual), color=the_color) 378 | 379 | front = front.tolist() 380 | front.sort(key = lambda individual: fits[individual][1]) # sort by y-axis value # individual is integer here 381 | for individual_A, individual_B in zip(front[:-1], front[1:]): # front is already sorted 382 | fits_A = fits[individual_A] 383 | fits_B = fits[individual_B] 384 | ax.plot([fits_A[0], fits_B[0]], 385 | [fits_B[1], fits_B[1]], color=the_color, lw=0.25) # 取高的点的Y 386 | ax.plot([fits_A[0], fits_A[0]], 387 | [fits_A[1], fits_B[1]], color=the_color, lw=0.25) # 取低的点的X 388 | ax.title.set_text("Pareto Front | Objective Function Space") 389 | def my_print(ad, pop, _): 390 | # ndf, dl, dc, ndr = pg.fast_non_dominated_sorting(fits) 391 | # extract and print non-dominated fronts 392 | # - ndf (list of 1D NumPy int array): the non dominated fronts 393 | # - dl (list of 1D NumPy int array): the domination list 394 | # - dc (1D NumPy int array): the domination count 395 | # - ndr (1D NumPy int array): the non domination ranks 396 | fits, vectors = pop.get_f(), pop.get_x() 397 | ndf, dl, dc, ndr = pg.fast_non_dominated_sorting(fits) 398 | 399 | with open(ad.solver.output_dir+'MOO_log.txt', 'a', encoding='utf-8') as fname: 400 | print('-'*40, 'Generation:', _, file=fname) 401 | for rank_minus_1, front in enumerate(ndf): 402 | print('Rank/Tier', rank_minus_1+1, front, file=fname) 403 | index = 0 404 | for domination_list, domination_count, non_domination_rank in zip(dl, dc, ndr): 405 | print('Individual #%d\t'%(index), 'Belong to Rank #%d\t'%(non_domination_rank), 'Dominating', domination_count, 'and they are', domination_list, file=fname) 406 | index += 1 407 | 408 | # print(fits, vectors, ndf) 409 | print(pop, file=fname) 410 | 411 | 412 | def learn_about_the_archive(prob, swarm_data, popsize, fea_config_dict, len_s01=None, len_s02=None, bool_plot_and_show=False): 413 | number_of_chromosome = len(swarm_data) 414 | print('Archive size:', number_of_chromosome) 415 | # for el in swarm_data: 416 | # print('\t', el) 417 | 418 | pop_archive = pg.population(prob, size=number_of_chromosome) 419 | for i in range(number_of_chromosome): 420 | pop_archive.set_xf(i, swarm_data[i][:-3], swarm_data[i][-3:]) 421 | 422 | sorted_index = pg.sort_population_mo(points=pop_archive.get_f()) 423 | print('Sorted by domination rank and crowding distance:', len(sorted_index)) 424 | print('\t', sorted_index) 425 | 426 | # 这段代码对于重建种群来说不是必须的,单单sort_population_mo(包含fast_non_dominated_sorting和crowding_distance)就够了, 427 | # 只是我想看看,具体的crowding_distance是多少,然后我想知道排在前面的多少个是属于domination rank 1的。 428 | if True: 429 | fits, vectors = pop_archive.get_f(), pop_archive.get_x() 430 | ndf, dl, dc, ndr = pg.fast_non_dominated_sorting(fits) 431 | 432 | ind1, ind2 = 0, 0 433 | for rank_minus_1, front in enumerate(ndf): 434 | 435 | ind2 += len(front) 436 | sorted_index_at_this_front = sorted_index[ind1:ind2] 437 | fits_at_this_front = [fits[point] for point in sorted_index_at_this_front] 438 | 439 | # Rank 1 Pareto Front 440 | if ind1 == 0: 441 | rank1_ParetoPoints = fits_at_this_front 442 | if len(front) < popsize: 443 | print('There are not enough chromosomes (%d) belonging to domination rank 1 (the best Pareto front).\nWill use rank 2 or lower to reach popsize of %d.'%(len(front), popsize)) 444 | 445 | # this crwdsit should be already sorted as well 446 | if len(fits_at_this_front) >= 2: # or else error: A non dominated front must contain at least two points: 1 detected. 447 | crwdst = pg.crowding_distance(fits_at_this_front) 448 | else: 449 | print('A non dominated front must contain at least two points: 1 detected.') 450 | crwdst = [999999] 451 | 452 | 453 | print('\nRank/Tier', rank_minus_1+1, 'chromosome count:', len(front), len(sorted_index_at_this_front)) 454 | # print('\t', sorted_index_at_this_front.tolist()) 455 | # print('\t', crwdst) 456 | print('\tindex in pop\t|\tcrowding distance') 457 | for index, cd in zip(sorted_index_at_this_front, crwdst): 458 | print('\t', index, '\t\t\t|', cd) 459 | ind1 = ind2 460 | 461 | sorted_vectors = [vectors[index].tolist() for index in sorted_index] 462 | sorted_fits = [fits[index].tolist() for index in sorted_index] 463 | 464 | if bool_plot_and_show: 465 | my_plot(pop_archive.get_f(), pop_archive.get_x(), ndf) 466 | my_3d_plot_non_dominated_fronts(pop_archive, rank1_ParetoPoints, fea_config_dict, plot_option=1) 467 | plt.show() 468 | 469 | swarm_data_on_pareto_front = [design_parameters_denorm + fits for design_parameters_denorm, fits in zip(sorted_vectors, sorted_fits)] 470 | return swarm_data_on_pareto_front 471 | 472 | def pyx_draw_model(im): 473 | import matplotlib.patches as mpatches 474 | import matplotlib.pyplot as plt 475 | plt.rcParams["font.family"] = "Times New Roman" 476 | 477 | myfontsize = 13.5 478 | plt.rcParams.update({'font.size': myfontsize}) 479 | 480 | # # 示意图而已,改改尺寸吧 481 | # im.Radius_OuterStatorYoke -= 37 482 | # im.Radius_InnerStatorYoke -= 20 483 | # im.Radius_Shaft += 20 484 | # # im.Location_RotorBarCenter2 += 5 # this will change the shape of rotor slot 485 | 486 | import VanGogh 487 | vg = VanGogh.VanGogh_pyPlotter(im, VanGogh.CUSTOM) 488 | vg.draw_model() 489 | 490 | # PyX 491 | import pyx 492 | vg.tikz.c = pyx.canvas.canvas() # clear the canvas because we want to redraw 90 deg with the data vg.tikz.track_path 493 | from copy import deepcopy 494 | def pyx_draw_path(vg, path, sign=1): 495 | if len(path) == 4: 496 | vg.tikz.draw_line(path[:2], path[2:4], untrack=True) 497 | else: 498 | vg.tikz.draw_arc(path[:2], path[2:4], path[4:6], relangle=sign*path[6], untrack=True) 499 | def rotate(_, x, y): 500 | return np.cos(_)*x + np.sin(_)*y, -np.sin(_)*x + np.cos(_)*y 501 | def is_at_stator(im, path): 502 | return np.sqrt(path[0]**2 + path[1]**2) > im.Radius_OuterRotor + 0.5*im.Length_AirGap 503 | 504 | for path in (vg.tikz.track_path): # track_path is passed by reference and is changed by mirror 505 | path_mirror = deepcopy(path) 506 | # for mirror copy (along x-axis) 507 | path_mirror[1] = path[1]*-1 508 | path_mirror[3] = path[3]*-1 509 | 510 | # rotate path and plot 511 | if is_at_stator(im, path): 512 | Q = im.Qs 513 | else: 514 | Q = im.Qr 515 | _ = 2*np.pi/Q 516 | path[0], path[1] = rotate(0.5*np.pi - 0.5*_, path[0], path[1]) 517 | path[2], path[3] = rotate(0.5*np.pi - 0.5*_, path[2], path[3]) 518 | pyx_draw_path(vg, path, sign=1) 519 | 520 | path_mirror[0], path_mirror[1] = rotate(0.5*np.pi - 0.5*_, path_mirror[0], path_mirror[1]) 521 | path_mirror[2], path_mirror[3] = rotate(0.5*np.pi - 0.5*_, path_mirror[2], path_mirror[3]) 522 | pyx_draw_path(vg, path_mirror, sign=-1) 523 | 524 | # 注意,所有 tack_path 中的 path 都已经转动了90度了! 525 | # for mirror copy (along y-axis) 526 | path[0] *= -1 527 | path[2] *= -1 528 | pyx_draw_path(vg, path, sign=-1) 529 | 530 | path_mirror[0] *= -1 531 | path_mirror[2] *= -1 532 | pyx_draw_path(vg, path_mirror, sign=1) 533 | 534 | 535 | # # 整体转动90度。 536 | # for path in vg.tikz.track_path: 537 | # if is_at_stator(im, path): 538 | # Q = im.Qs 539 | # else: 540 | # Q = im.Qr 541 | # _ = 2*np.pi/Q 542 | # path[0], path[1] = rotate(0.5*np.pi - _, path[0], path[1]) 543 | # path[2], path[3] = rotate(0.5*np.pi - _, path[2], path[3]) 544 | # pyx_draw_path(vg, path) 545 | # track_path_backup = deepcopy(vg.tikz.track_path) 546 | 547 | # # Rotate Copy 548 | # for path in deepcopy(vg.tikz.track_path): 549 | # if is_at_stator(im, path): 550 | # Q = im.Qs 551 | # else: 552 | # Q = im.Qr 553 | # _ = 2*np.pi/Q 554 | # path[0], path[1] = rotate(_, path[0], path[1]) 555 | # path[2], path[3] = rotate(_, path[2], path[3]) 556 | # pyx_draw_path(vg, path) 557 | 558 | # # Rotate Copy 559 | # for path in (vg.tikz.track_path): 560 | # # if np.sqrt(path[0]**2 + path[1]**2) > im.Radius_OuterRotor + 0.5*im.Length_AirGap: 561 | # if is_at_stator(im, path): 562 | # Q = im.Qs 563 | # else: 564 | # Q = im.Qr 565 | # _ = 2*np.pi/Q 566 | # path[0], path[1] = rotate(_, path[0], path[1]) 567 | # path[2], path[3] = rotate(_, path[2], path[3]) 568 | # pyx_draw_path(vg, path, sign=-1) 569 | 570 | vg.tikz.c.writePDFfile("selected_otimal_design%s"%(im.ID)) 571 | # vg.tikz.c.writeEPSfile("pyx_output") 572 | print('Write to pdf file: selected_otimal_design%s.pdf.'%(im.ID)) 573 | quit() 574 | 575 | -------------------------------------------------------------------------------- /_femm/codes3/winding_layout.py: -------------------------------------------------------------------------------- 1 | 2 | class winding_layout(object): 3 | def __init__(self, DPNV_or_SEPA, Qs, p): 4 | 5 | # separate winding 6 | if DPNV_or_SEPA == False \ 7 | and Qs == 24 \ 8 | and p == 2: 9 | self.l41=[ 'W', 'W', 'U', 'U', 'V', 'V', 'W', 'W', 'U', 'U', 'V', 'V', 'W', 'W', 'U', 'U', 'V', 'V', 'W', 'W', 'U', 'U', 'V', 'V', ] 10 | self.l42=[ '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', ] 11 | # separate style for one phase: ---- ++++ 12 | self.l21=[ 'U', 'U', 'V', 'V', 'V', 'V', 'W', 'W', 'W', 'W', 'U', 'U', 'U', 'U', 'V', 'V', 'V', 'V', 'W', 'W', 'W', 'W', 'U', 'U', ] 13 | self.l22=[ '-', '-', '+', '+', '+', '+', '-', '-', '-', '-', '+', '+', '+', '+', '-', '-', '-', '-', '+', '+', '+', '+', '-', '-', ] 14 | self.coil_pitch = 6 # = Qs / poles for single layer 15 | self.CommutatingSequenceD = 0 16 | self.CommutatingSequenceB = 0 17 | self.number_parallel_branch = 1. 18 | self.bool_3PhaseCurrentSource = True 19 | self.no_winding_layer = 1 # for troque winding 20 | 21 | # combined winding 22 | if DPNV_or_SEPA == True \ 23 | and Qs == 24 \ 24 | and p == 2: 25 | # DPNV winding implemented as DPNV winding (GroupAC means it experiences flip phasor excitation from suspension inverter, while GroupBD does not.) 26 | # U-GrBD U-GrBD W-GrBD W-GrBD V-GrBD V-GrBD 27 | # W-GrAC V-GrAC V-GrAC U-GrAC U-GrAC W-GrAC : flip phases 19-14??? slot of phase U??? (这个例子的这句话看不懂) 28 | self.l_rightlayer1 = ['U', 'U', 'W', 'W', 'V', 'V', 'U', 'U', 'W', 'W', 'V', 'V', 'U', 'U', 'W', 'W', 'V', 'V', 'U', 'U', 'W', 'W', 'V', 'V'] # ExampleQ24p2m3ps1: torque winding outer layer 29 | self.l_rightlayer2 = ['+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-'] 30 | self.l_leftlayer1 = self.l_rightlayer1[::] # ExampleQ24p2m3ps1: torque winding inner layer 31 | self.l_leftlayer2 = self.l_rightlayer2[::] 32 | self.grouping_AC = [ 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0] # 只取决于outerlayer/rightlayer的反相情况 33 | self.coil_pitch = 6 # left layer can be inferred from coil pitch and right layer diagram 34 | self.CommutatingSequenceD = 1 35 | self.CommutatingSequenceB = 0 36 | self.number_parallel_branch = 2. 37 | self.bool_3PhaseCurrentSource = False # 3PhaseCurrentSource is a macro in circuit setup of JMAG 38 | self.no_winding_layer = 2 # for troque winding and this means there could be a short pitch 39 | 40 | # backward compatibility 41 | self.l41 = self.l_rightlayer1 42 | self.l42 = self.l_rightlayer2 43 | self.l21 = self.l_leftlayer1 44 | self.l22 = self.l_leftlayer2 45 | 46 | # combined winding 47 | if DPNV_or_SEPA == True \ 48 | and Qs == 24 \ 49 | and p == 1: 50 | # DPNV winding implemented as DPNV winding (GroupAC means it experiences flip phasor excitation from suspension inverter, while GroupBD does not.) 51 | # U-GroupBD V-GroupBD W-GroupBD 52 | # W-GroupAC U-GroupAC V-GroupAC : flip phases 13-16 slot of phase U 53 | self.l_rightlayer1 = ['U', 'U', 'U', 'U', 'W', 'W', 'W', 'W', 'V', 'V', 'V', 'V', 'U', 'U', 'U', 'U', 'W', 'W', 'W', 'W', 'V', 'V', 'V', 'V'] # ExampleQ24p1m3ps2: torque winding outer layer 54 | self.l_rightlayer2 = ['+', '+', '+', '+', '-', '-', '-', '-', '+', '+', '+', '+', '-', '-', '-', '-', '+', '+', '+', '+', '-', '-', '-', '-'] 55 | self.l_leftlayer1 = ['U', 'W', 'W', 'W', 'W', 'V', 'V', 'V', 'V', 'U', 'U', 'U', 'U', 'W', 'W', 'W', 'W', 'V', 'V', 'V', 'V', 'U', 'U', 'U'] # ExampleQ24p1m3ps2: torque winding inner layer 56 | self.l_leftlayer2 = ['+', '-', '-', '-', '-', '+', '+', '+', '+', '-', '-', '-', '-', '+', '+', '+', '+', '-', '-', '-', '-', '+', '+', '+'] 57 | self.grouping_AC = [ 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1] # 只取决于rightlayer的反相情况 58 | self.coil_pitch = 9 # left layer can be inferred from coil pitch and right layer diagram 59 | self.CommutatingSequenceD = 1 60 | self.CommutatingSequenceB = 0 61 | self.number_parallel_branch = 2. 62 | self.bool_3PhaseCurrentSource = False # 3PhaseCurrentSource is a macro in circuit setup of JMAG 63 | self.no_winding_layer = 2 # for troque winding and this means there could be a short pitch 64 | self.initial_excitation_bias_compensation_deg = 360/24*0.5 # for troque winding 65 | 66 | # backward compatibility 67 | self.l41 = self.l_rightlayer1 68 | self.l42 = self.l_rightlayer2 69 | self.l21 = self.l_leftlayer1 70 | self.l22 = self.l_leftlayer2 71 | 72 | 73 | # PMSM 74 | 75 | # combined winding 76 | if DPNV_or_SEPA == True \ 77 | and Qs == 6 \ 78 | and p == 2: 79 | # DPNV winding implemented as DPNV winding (GroupAC means it experiences flip phasor excitation from suspension inverter, while GroupBD does not.) 80 | self.l_rightlayer1 = ['U', 'V', 'W', 'U', 'V', 'W'] # torque winding right layer 81 | self.l_rightlayer2 = ['+', '+', '+', '+', '+', '+'] 82 | self.l_leftlayer1 = ['W', 'U', 'V', 'W', 'U', 'V'] 83 | self.l_leftlayer2 = ['-', '-', '-', '-', '-', '-'] 84 | self.grouping_AC = [ 1, 0, 0, 0, 1, 1] # 只取决于outerlayer/rightlayer的反相情况,AC是在悬浮逆变器激励下会反相的 85 | self.coil_pitch = -1 # left layer can be inferred from coil pitch and right layer diagram 86 | self.CommutatingSequenceD = 1 87 | self.CommutatingSequenceB = 0 88 | self.number_parallel_branch = 2. 89 | self.bool_3PhaseCurrentSource = False # 3PhaseCurrentSource is a macro in circuit setup of JMAG 90 | self.no_winding_layer = 2 # for troque winding and this means there could be a short pitch 91 | 92 | # backward compatibility 93 | self.l41 = self.l_rightlayer1 94 | self.l42 = self.l_rightlayer2 95 | self.l21 = self.l_leftlayer1 96 | self.l22 = self.l_leftlayer2 97 | 98 | try: 99 | self.coil_pitch 100 | self.distributed_or_concentrated = False if abs(self.coil_pitch) == 1 else True 101 | except: 102 | raise Exception('Error: Not implemented for this winding.') 103 | 104 | 105 | # # combined winding 106 | # if DPNV_or_SEPA == True \ 107 | # and Qs == 24 \ 108 | # and p == 2: 109 | # # DPNV winding implemented as separate winding 110 | # # if self.fea_config_dict['DPNV_separate_winding_implementation'] == True or self.fea_config_dict['DPNV'] == False: 111 | # # You may see this msg because there are more than one designs in the initial_design.txt file. 112 | # # msg = 'Not implemented error. In fact, this equivalent implementation works for 4 pole motor only.' 113 | # # logging.getLogger(__name__).warn(msg) 114 | 115 | # # this is legacy codes for easy implementation in FEMM 116 | # self.l41=[ 'W', 'W', 'U', 'U', 'V', 'V', 'W', 'W', 'U', 'U', 'V', 'V', 'W', 'W', 'U', 'U', 'V', 'V', 'W', 'W', 'U', 'U', 'V', 'V'] 117 | # self.l42=[ '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-', '+', '+', '-', '-'] 118 | # # DPNV style for one phase: -- oo ++ oo 119 | # self.l21=[ 'U', 'U', 'W', 'W', 'V', 'V', 120 | # 'U', 'U', 'W', 'W', 'V', 'V', 121 | # 'U', 'U', 'W', 'W', 'V', 'V', 122 | # 'U', 'U', 'W', 'W', 'V', 'V'] 123 | # self.l22=[ '-', '-', 'o', 'o', '+', '+', # 横着读和竖着读都是负零正零。 124 | # 'o', 'o', '-', '-', 'o', 'o', 125 | # '+', '+', 'o', 'o', '-', '-', 126 | # 'o', 'o', '+', '+', 'o', 'o'] 127 | # self.coil_pitch = 6 128 | # self.CommutatingSequenceD = 0 129 | # self.CommutatingSequenceB = 0 130 | # self.number_parallel_branch = 1. 131 | # self.bool_3PhaseCurrentSource = True 132 | # self.no_winding_layer = 1 # for troque winding 133 | -------------------------------------------------------------------------------- /_femm/release/OneReport/OneReport_TEX/OneReport.tex: -------------------------------------------------------------------------------- 1 | \documentclass[]{interact} 2 | \usepackage{epstopdf}% To incorporate .eps illustrations using PDFLaTeX, etc. 3 | \usepackage[caption=false]{subfig}% Support for small, `sub' figures and tables 4 | \usepackage{makecell} % for new line in table 5 | \renewcommand\theadalign{bc} 6 | \renewcommand\theadfont{\bfseries} 7 | \renewcommand\theadgape{\Gape[4pt]} 8 | \renewcommand\cellgape{\Gape[4pt]} 9 | \begin{document} 10 | \articletype{RESEARCH REPORT}% Specify the article type or omit as appropriate 11 | \title{Bearingless Induction Motor Design} 12 | \author{ 13 | \name{Jiahao Chen\textsuperscript{a}\thanks{CONTACT Jiahao Chen by email: horychen@qq.com} } 14 | \affil{\textsuperscript{a}WEMPEC, 1415 Engineering Dr., Madison, WI, USA}} 15 | \maketitle 16 | \begin{abstract} 17 | This is a automatically generated report. 18 | \end{abstract} 19 | \begin{keywords} 20 | Bearingless motors, induction motors. 21 | \end{keywords} 22 | %\tableofcontents 23 | 24 | \section{Design for Bearingless Induction Motor} 25 | 26 | %We use full pitch winding here, but we skew the rotor for one rotor slot pitch. %(4.77), skew_s = slot_pitch_tau_u 27 | 28 | \subsection{Design Procedure by Pyrhonen} 29 | \input{./contents/pyrhonen_procedure_s01} 30 | \input{./contents/pyrhonen_procedure_s02} 31 | \input{./contents/pyrhonen_procedure_s03} 32 | \input{./contents/pyrhonen_procedure_s04} 33 | \input{./contents/pyrhonen_procedure_s05} 34 | \input{./contents/pyrhonen_procedure_s06} 35 | \input{./contents/pyrhonen_procedure_s07} 36 | \input{./contents/pyrhonen_procedure_s08} 37 | \input{./contents/pyrhonen_procedure_s09} 38 | \input{./contents/pyrhonen_procedure_s10} 39 | \input{./contents/pyrhonen_procedure_s11} 40 | \input{./contents/pyrhonen_procedure_s12} 41 | \input{./contents/pyrhonen_procedure_s13} 42 | \begin{table}[!t] 43 | \caption{Permitted flux densities of the magnetic circuit for $50$ Hz induction machines \cite[Table6.1]{2009-Pyrhonen.Jokinen.ea-Book-Designrotatingelectrical}} % title of Table 44 | \centering % used for centering the whole table 45 | \begin{tabular}{cc} 46 | % after \\: \hline or \cline{col1-col2} \cline{col3-col4} ... 47 | \hline 48 | \hline 49 | Location & Flux Density \\ 50 | \hline 51 | Air gap & $\hat B_{\delta}=0.7 \sim 0.9$ T. \\ 52 | Stator yoke & $\hat B_{ys}=1.4\sim 1.7$ T. \\ 53 | Rotor yoke & $\hat B_{yr}=1.0\sim 1.6$ T. \\ 54 | Stator tooth & $\hat B_{ds}=1.4\sim 2.1$ T. \\ 55 | Rotor tooth & $\hat B_{dr}=1.5\sim 2.2$ T. \\ 56 | \hline 57 | \end{tabular} 58 | \label{tab:6.1} % is used to refer this table in the text 59 | \end{table} 60 | \begin{table}[!t] 61 | \caption{Correction coefficients kFe,n for the definition of iron losses for sinusoidal supply induction machines \cite[Table3.2]{2009-Pyrhonen.Jokinen.ea-Book-Designrotatingelectrical}} % title of Table 62 | \centering % used for centering the whole table 63 | \begin{tabular}{cc} 64 | % after \\: \hline or \cline{col1-col2} \cline{col3-col4} ... 65 | \hline 66 | \hline 67 | Location & Correction coefficient $k_{{\rm Fe},n}$ \\ 68 | \hline 69 | Tooth & $1.8$ \\ 70 | Yoke & $1.5\sim 1.7$ \\ 71 | \hline 72 | \end{tabular} 73 | \label{tab:3.2} % is used to refer this table in the text 74 | \end{table} 75 | \input{./contents/pyrhonen_procedure_s14} 76 | \input{./contents/pyrhonen_procedure_s15} 77 | \input{./contents/pyrhonen_procedure_s16} 78 | \input{./contents/pyrhonen_procedure_s17} 79 | 80 | \subsubsection{Mechanical Limits Check} 81 | This has been down in Sec. \ref{subsubsec:machine_sizing}. 82 | \[\begin{array}{l} 83 | {\sigma _{yield}} = C'\rho r_r^2{\Omega ^2}\\ 84 | C' = \frac{{3 + 0.29}}{4}\\ 85 | {r_{r,\max }} = \sqrt {\frac{{{\sigma _{yield}}}}{{C'\rho {\Omega ^2}}}} \\ 86 | l_{\max }^2 = {n^2}\frac{{{\pi ^2}}}{{k\Omega }}\sqrt {\frac{{EI}}{{\rho S}}} 87 | \end{array}\] 88 | %\subsection{The selection of rotor shape} 89 | %Suggested by Gerada11, we will have a drop shape rotor slots. 90 | %%转子齿宽和转子槽数的关系。 91 | %%转子齿宽由齿部磁密最大值来确定。齿宽确定后,转子槽宽也相继确定。然后,根据转子导条的电密来确定,槽的高度。 92 | %%所以,如果发现转子槽很窄长,说明设定的转子槽数可能过多了。 93 | %\section{Constraints} 94 | %Qs != Qr 95 | %\section{Other Suggestions} 96 | %A special tooth design is shown in Figure 3.6(c) to reduce the flux tip at slot opening so as to reduce losses. 97 | 98 | 99 | %\input{./contents/pyrhonen_procedure_s20} 100 | 101 | % 102 | %\begin{table*}[!t] 103 | % \caption{Statistical data of the 50 random designs from Fig.~\ref{fig:05}.} 104 | % \centering 105 | % \begin{tabular}{cccccc} 106 | % \hline 107 | % \hline 108 | % \thead{FEA model\\w/ regular step} & 109 | % \thead{Torque diff.\\\relax[p.u.]} & 110 | % \thead{Torque ripple\\\relax diff. [\%]} & 111 | % \thead{Force mag.\\\relax diff. [p.u.]} & 112 | % \thead{Force err. mag.\\\relax diff. [\%]} & 113 | % \thead{Force err. angle\\\relax diff. [deg]} \\ 114 | % \hline 115 | % Tran. w/ 2 Sections & $-0.042(9.7\times10^{-5})^*$ & $4.8(24)$ & $0.0068(0.001)$ & $-1(4.2)$ & $-0.52(1.3)$ \\ 116 | % Eddy Current FEA & $0.023(5.1\times10^{-4})$ & $-6.4(50)$ & $0.09(0.035)$ & $-10(150)$ & $-6.1(75)$ \\ 117 | % Static FEA & $-0.008(2.4\times10^{-4})$ & $-1.7(22)$ & $-0.01(0.0042)$ & $6.1(39)$ & $4.9(51)$ \\ 118 | % \hline 119 | % \vspace{-2.5ex} 120 | % \\ 121 | % \multicolumn{6}{l}{*Note: all statistical data are in the format of ``mean(variance)''. The FEA model is better if its data are closer to 0.} 122 | % \end{tabular} 123 | % \label{tab:002} % is used to refer this table in the text 124 | % \vspace{-3ex} 125 | %\end{table*} 126 | 127 | \end{document} 128 | -------------------------------------------------------------------------------- /_femm/release/OneReport/OneReport_TEX/epsfig.sty: -------------------------------------------------------------------------------- 1 | %% 2 | %% This is file `epsfig.sty', 3 | %% generated with the docstrip utility. 4 | %% 5 | %% The original source files were: 6 | %% 7 | %% epsfig.dtx (with options: `package') 8 | %% 9 | %% epsfig.dtx Copyright (C) 1994-1996 1999 Sebastian Rahtz 10 | %% 11 | %% This file is part of the Standard LaTeX `Graphics Bundle'. 12 | %% It may be distributed under the terms of the LaTeX Project Public 13 | %% License, as described in lppl.txt in the base LaTeX distribution. 14 | %% Either version 1.3 or, at your option, any later version. 15 | %% 16 | \NeedsTeXFormat{LaTeX2e}[1994/06/01] 17 | \ProvidesPackage{epsfig} 18 | [1999/02/16 v1.7a (e)psfig emulation (SPQR)] 19 | \DeclareOption*{\PassOptionsToPackage{\CurrentOption}{graphicx}} 20 | \ProcessOptions 21 | \RequirePackage{graphicx} 22 | \def\psfig#1{% 23 | \let\Gin@ewidth\Gin@exclamation\let\Gin@eheight\Gin@ewidth 24 | \def\Gin@req@sizes{% 25 | \def\Gin@scalex{1}\let\Gin@scaley\Gin@exclamation 26 | \Gin@req@height\Gin@nat@height 27 | \Gin@req@width\Gin@nat@width}% 28 | \begingroup 29 | \let\Gfigname\relax 30 | \@tempswafalse 31 | \toks@{\Ginclude@graphics{\Gfigname}}% 32 | \setkeys{Gin}{#1}% 33 | \Gin@esetsize 34 | \ifx\Gfigname\relax\ErrorNoFile\else 35 | \the\toks@ 36 | \fi 37 | \endgroup} 38 | \define@key{Gin}{figure}{\def\Gfigname{#1}} 39 | \define@key{Gin}{file}{\def\Gfigname{#1}} 40 | \define@key{Gin}{prolog}{\typeout{epsfig: header files are not needed}} 41 | \define@key{Gin}{silent}[]{} 42 | \def\psdraft{\Gin@drafttrue} 43 | \def\psfull{\Gin@draftfalse} 44 | \def\pssilent{\typeout{epsfig option `silent' ignored}} 45 | \def\psnoisy{\typeout{epsfig option `noisy' ignored}} 46 | \let\epsfig\psfig 47 | \def\psfigdriver#1{\makeatletter\input{#1.def}\makeatother} 48 | \newdimen\epsfxsize 49 | \newdimen\epsfysize 50 | \epsfysize\z@ 51 | \epsfxsize\z@ 52 | \def\epsfsize#1#2{\epsfxsize} 53 | \def\epsfbox{% 54 | \@ifnextchar[% 55 | {\Gin@bboxtrue\epsf@bb@box}% 56 | {\Gin@bboxfalse\epsf@box}% 57 | } 58 | \def\epsf@bb@box[#1#2]{% 59 | \expandafter\Gread@parse@bb#1#2 \\ 60 | \epsf@box} 61 | \def\epsf@box#1{% 62 | \bgroup 63 | \def\Gin@req@sizes{% 64 | \epsfxsize\epsfsize{\Gin@nat@width}{\Gin@nat@height}% 65 | \ifdim\epsfxsize=\z@ 66 | \ifdim\epsfysize=\z@ 67 | \Gin@req@height\Gin@nat@height 68 | \Gin@req@width\Gin@nat@width 69 | \else 70 | \let\Gin@scalex\Gin@exclamation 71 | \Gin@req@height\epsfysize 72 | \Gscale@div\Gin@scaley\Gin@req@height\Gin@nat@height 73 | \Gin@req@width\Gin@scaley\Gin@nat@width 74 | \fi 75 | \else 76 | \Gin@req@width\epsfxsize 77 | \Gscale@div\Gin@scalex\Gin@req@width\Gin@nat@width 78 | \ifdim\epsfysize=\z@ 79 | \let\Gin@scaley\Gin@exclamation 80 | \Gin@req@height\Gin@scalex\Gin@nat@height 81 | \else 82 | \Gin@req@height\epsfysize 83 | \Gscale@div\Gin@scaley\Gin@req@height\Gin@nat@height 84 | \fi 85 | \fi 86 | }% 87 | \Ginclude@graphics{#1}% 88 | \egroup 89 | \epsfysize\z@ 90 | \epsfxsize\z@ 91 | } 92 | \let\epsffile\epsfbox 93 | \def\epsfclipon{\Gin@cliptrue} 94 | \def\epsfclipoff{\Gin@clipfalse} 95 | \def\epsfverbosetrue{\typeout{epsf verbose option ignored}} 96 | \def\epsfverbosefalse{\typeout{epsf verbose option ignored}} 97 | 98 | \endinput 99 | %% 100 | %% End of file `epsfig.sty'. 101 | -------------------------------------------------------------------------------- /_femm/release/OneReport/OneReport_TEX/interact.cls: -------------------------------------------------------------------------------- 1 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 2 | %% 3 | %% This is file 'interact.cls' 4 | %% 5 | %% This file is part of a Taylor & Francis 'Interact' LaTeX bundle. 6 | %% 7 | %% v1.05 - 2017/07/31 8 | %% 9 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 10 | % 11 | \NeedsTeXFormat{LaTeX2e} 12 | \ProvidesClass{interact}[2017/07/31 v1.05 Interact LaTeX document class] 13 | % 14 | \newif\iflargeformat 15 | \newif\ifsuppldata 16 | % 17 | \DeclareOption{largeformat}{\largeformattrue} 18 | \DeclareOption{suppldata}{\suppldatatrue} 19 | \DeclareOption*{\PassOptionsToClass{\CurrentOption}{article}} 20 | \ExecuteOptions{a4paper,oneside,onecolumn,final} 21 | \ProcessOptions 22 | % 23 | \LoadClass[11pt,a4paper]{article} 24 | % 25 | \RequirePackage{amsmath,amssymb,amsfonts,amsbsy,amsthm,booktabs,epsfig,graphicx,rotating} 26 | % 27 | \iflargeformat 28 | \RequirePackage[left=1in,right=1in,top=1in,bottom=1in]{geometry} 29 | \else 30 | \RequirePackage[textwidth=34pc,textheight=650pt]{geometry} 31 | \setlength\parindent{12pt} 32 | \fi 33 | % 34 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Fonts %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 35 | % 36 | \def\abstractfont{\fontsize{9}{10}\selectfont\leftskip1pc\rightskip5pc}% 37 | \def\affilfont{\fontsize{10}{12}\selectfont\raggedright}% 38 | \def\articletypefont{\fontsize{12}{14}\selectfont\MakeUppercase}% 39 | \def\authorfont{\fontsize{11}{13}\selectfont\raggedright}% 40 | \def\extractfont{\fontsize{10}{12}\selectfont\leftskip12pt\rightskip12pt}% 41 | \def\figcaptionfont{\fontsize{8}{10}\selectfont}% 42 | \def\fignumfont{\fontsize{8}{10}\selectfont\bfseries}% 43 | \def\historyfont{\fontsize{9}{10}\selectfont\leftskip1pc\rightskip5pc plus1fill}% 44 | \def\keywordfont{\fontsize{9}{10}\selectfont\leftskip1pc\rightskip5pc plus1fill}% 45 | \def\receivedfont{\fontsize{9}{12}\selectfont\leftskip1pc\rightskip5pc}% 46 | \def\sectionfont{\fontsize{11}{13}\selectfont\bfseries\raggedright\boldmath}% 47 | \def\subsectionfont{\fontsize{11}{13}\selectfont\bfseries\itshape\raggedright\boldmath}% 48 | \def\subsubsectionfont{\fontsize{11}{13}\selectfont\itshape\raggedright}% 49 | \def\paragraphfont{\fontsize{11}{13}\selectfont\bfseries\boldmath}% 50 | \def\tablecaptionfont{\fontsize{8}{10}\selectfont\leftskip\tabledim\rightskip\tabledim}% 51 | \def\tablefont{\fontsize{8}{9}\selectfont}% 52 | \def\tablenumfont{\fontsize{8}{10}\selectfont\bfseries}% 53 | \def\tabnotefont{\fontsize{8}{9}\selectfont}% 54 | \def\thanksfont{\fontsize{8}{10}\selectfont}% 55 | \def\titlefont{\fontsize{13}{16}\selectfont\bfseries\raggedright\boldmath}% 56 | % 57 | \def\@xpt{10} 58 | \def\@xipt{11} 59 | \def\@xiiipt{13} 60 | \def\@xivpt{14} 61 | \def\@xvipt{16} 62 | \def\@xviiipt{18} 63 | % 64 | \renewcommand\normalsize{% 65 | \@setfontsize\normalsize\@xipt\@xiiipt 66 | \abovedisplayskip 13\p@ \@plus2\p@ minus.5pt 67 | \abovedisplayshortskip \abovedisplayskip 68 | \belowdisplayskip 13\p@ \@plus2\p@ minus.5pt 69 | \belowdisplayshortskip\belowdisplayskip 70 | \let\@listi\@listI} 71 | % 72 | \renewcommand\small{% 73 | \@setfontsize\small\@xpt{11}% 74 | \abovedisplayskip 8.5\p@ \@plus3\p@ 75 | \abovedisplayshortskip \z@ \@plus2\p@ 76 | \belowdisplayshortskip 4\p@ \@plus2\p@ 77 | \def\@list1{\leftmargin\leftmargin1 78 | \topsep 6\p@ \@plus2\p@ 79 | \parsep 2\p@ \@plus\p@ 80 | \itemsep \parsep}% 81 | \belowdisplayskip \abovedisplayskip\setSmallDelims} 82 | % 83 | \def\setSmallDelims{% 84 | \def\big##1{{\hbox{$\left##1\vbox to7.5\p@{}\right.\n@space$}}}% 85 | \def\Big##1{{\hbox{$\left##1\vbox to10.5\p@{}\right.\n@space$}}}% 86 | \def\bigg##1{{\hbox{$\left##1\vbox to13.5\p@{}\right.\n@space$}}}% 87 | \def\Bigg##1{{\hbox{$\left##1\vbox to16.5\p@{}\right.\n@space$}}}% 88 | \def\biggg##1{{\hbox{$\left##1\vbox to19.5\p@{}\right.\n@space$}}}% 89 | \def\Biggg##1{{\hbox{$\left##1\vbox to22.5\p@{}\right.\n@space$}}}% 90 | } 91 | % 92 | \renewcommand\footnotesize{% 93 | \@setfontsize\footnotesize\@viiipt{10}% 94 | \abovedisplayskip 6\p@ \@plus2\p@ 95 | \abovedisplayshortskip \z@ \@plus\p@ 96 | \belowdisplayshortskip 3\p@ \@plus\p@ 97 | \def\@listi{\leftmargin\leftmargini 98 | \topsep 6\p@ \@plus\p@ 99 | \parsep 2\p@ \@plus\p@ 100 | \itemsep \parsep}% 101 | \belowdisplayskip \abovedisplayskip\setFootnotesizeDelims 102 | } 103 | % 104 | \def\setFootnotesizeDelims{% 105 | \def\big##1{{\hbox{$\left##1\vbox to6.5\p@{}\right.\n@space$}}}% 106 | \def\Big##1{{\hbox{$\left##1\vbox to9.5\p@{}\right.\n@space$}}}% 107 | \def\bigg##1{{\hbox{$\left##1\vbox to12.5\p@{}\right.\n@space$}}}% 108 | \def\Bigg##1{{\hbox{$\left##1\vbox to15.5\p@{}\right.\n@space$}}}% 109 | \def\biggg##1{{\hbox{$\left##1\vbox to18.5\p@{}\right.\n@space$}}}% 110 | \def\Biggg##1{{\hbox{$\left##1\vbox to21.5\p@{}\right.\n@space$}}}% 111 | } 112 | % 113 | \def\capsdefault{caps}% 114 | \DeclareRobustCommand\capsshape 115 | {\not@math@alphabet\capsshape\mathrm 116 | \fontshape\capsdefault\selectfont} 117 | % 118 | \DeclareOldFontCommand{\bi}{\bfseries\itshape}{\bfseries\itshape} 119 | \renewcommand{\cal}{\protect\pcal}% 120 | \newcommand{\pcal}{\@fontswitch{\relax}{\mathcal}} 121 | \renewcommand{\mit}{\protect\pmit}% 122 | \newcommand{\pmit}{\@fontswitch{\relax}{\mathnormal}} 123 | % 124 | \renewcommand\rmdefault{cmr} 125 | \newcommand\rmmathdefault{cmr} 126 | % 127 | \DeclareFontFamily{OT1}{Clearface}{} 128 | \DeclareFontShape{OT1}{Clearface}{m}{n}{ <-> Clearface-Regular }{} 129 | \DeclareFontShape{OT1}{Clearface}{m}{it}{ <-> Clearface-RegularItalic }{} 130 | \def\encodingdefault{OT1}% 131 | \fontencoding{OT1}% 132 | % 133 | \def\boldmath{\mathversion{bold}} 134 | \def\bm#1{\mathchoice 135 | {\mbox{\boldmath$\displaystyle#1$}}% 136 | {\mbox{\boldmath$#1$}}% 137 | {\mbox{\boldmath$\scriptstyle#1$}}% 138 | {\mbox{\boldmath$\scriptscriptstyle#1$}}} 139 | % 140 | \providecommand{\mathch}[2]{% 141 | \begingroup 142 | \let\@nomath\@gobble \mathversion{#1}% 143 | \math@atom{#2}{% 144 | \mathchoice% 145 | {\hbox{$\m@th\displaystyle#2$}}% 146 | {\hbox{$\m@th\textstyle#2$}}% 147 | {\hbox{$\m@th\scriptstyle#2$}}% 148 | {\hbox{$\m@th\scriptscriptstyle#2$}}}% 149 | \endgroup} 150 | % 151 | \DeclareFontFamily{OML}{eur}{\skewchar\font'177} 152 | \DeclareFontShape{OML}{eur}{m}{n}{ 153 | <5> <6> <7> <8> <9> gen * eurm 154 | <10> <10.95> <12> <14.4> <17.28> <20.74> <24.88> eurm10 155 | }{} 156 | \DeclareFontShape{OML}{eur}{b}{n}{ 157 | <5> <6> <7> <8> <9> gen * eurb 158 | <10> <10.95> <12> <14.4> <17.28> <20.74> <24.88> eurb10 159 | }{} 160 | % 161 | \DeclareMathVersion{upright} 162 | \DeclareMathVersion{boldupright} 163 | \SetSymbolFont{letters}{upright} {OML}{eur}{m}{n} 164 | \SetSymbolFont{letters}{boldupright}{OML}{eur}{b}{n} 165 | \DeclareRobustCommand{\mathup}[1]{\mathch{upright}{#1}} 166 | \DeclareRobustCommand{\mathbup}[1]{\mathch{boldupright}{#1}} 167 | % 168 | \newcommand\ualpha{\mathup{\alpha}} 169 | \newcommand\ubeta{\mathup{\beta}} 170 | \newcommand\ugamma{\mathup{\gamma}} 171 | \newcommand\udelta{\mathup{\delta}} 172 | \newcommand\uepsilon{\mathup{\epsilon}} 173 | \newcommand\uzeta{\mathup{\zeta}} 174 | \newcommand\ueta{\mathup{\eta}} 175 | \newcommand\utheta{\mathup{\theta}} 176 | \newcommand\uiota{\mathup{\iota}} 177 | \newcommand\ukappa{\mathup{\kappa}} 178 | \newcommand\ulambda{\mathup{\lambda}} 179 | \newcommand\umu{\mathup{\mu}} 180 | \newcommand\unu{\mathup{\nu}} 181 | \newcommand\uxi{\mathup{\xi}} 182 | \newcommand\upi{\mathup{\pi}} 183 | \newcommand\urho{\mathup{\rho}} 184 | \newcommand\usigma{\mathup{\sigma}} 185 | \newcommand\utau{\mathup{\tau}} 186 | \newcommand\uupsilon{\mathup{\upsilon}} 187 | \newcommand\uphi{\mathup{\phi}} 188 | \newcommand\uchi{\mathup{\chi}} 189 | \newcommand\upsi{\mathup{\psi}} 190 | \newcommand\uomega{\mathup{\omega}} 191 | \newcommand\uvarepsilon{\mathup{\varepsilon}} 192 | \newcommand\uvartheta{\mathup{\vartheta}} 193 | \newcommand\uvarpi{\mathup{\varpi}} 194 | \let\uvarrho\varrho 195 | \let\uvarsigma\varsigma 196 | \newcommand\uvarphi{\mathup{\varphi}} 197 | \newcommand\ubalpha{\mathbup{\alpha}} 198 | \newcommand\ubbeta{\mathbup{\beta}} 199 | \newcommand\ubgamma{\mathbup{\gamma}} 200 | \newcommand\ubdelta{\mathbup{\delta}} 201 | \newcommand\ubepsilon{\mathbup{\epsilon}} 202 | \newcommand\ubzeta{\mathbup{\zeta}} 203 | \newcommand\uboldeta{\mathbup{\eta}} 204 | \newcommand\ubtheta{\mathbup{\theta}} 205 | \newcommand\ubiota{\mathbup{\iota}} 206 | \newcommand\ubkappa{\mathbup{\kappa}} 207 | \newcommand\ublambda{\mathbup{\lambda}} 208 | \newcommand\ubmu{\mathbup{\mu}} 209 | \newcommand\ubnu{\mathbup{\nu}} 210 | \newcommand\ubxi{\mathbup{\xi}} 211 | \newcommand\ubpi{\mathbup{\pi}} 212 | \newcommand\ubrho{\mathbup{\rho}} 213 | \newcommand\ubsigma{\mathbup{\sigma}} 214 | \newcommand\ubtau{\mathbup{\tau}} 215 | \newcommand\ubupsilon{\mathbup{\upsilon}} 216 | \newcommand\ubphi{\mathbup{\phi}} 217 | \newcommand\ubchi{\mathbup{\chi}} 218 | \newcommand\ubpsi{\mathbup{\psi}} 219 | \newcommand\ubomega{\mathbup{\omega}} 220 | \newcommand\ubvarepsilon{\mathbup{\varepsilon}} 221 | \newcommand\ubvartheta{\mathbup{\vartheta}} 222 | \newcommand\ubvarpi{\mathbup{\varpi}} 223 | \newcommand\ubvarrho{\boldsymbol{\varrho}} 224 | \newcommand\ubvarsigma{\boldsymbol{\varsigma}} 225 | \newcommand\ubvarphi{\mathbup{\varphi}} 226 | \newcommand\upartial {\mathup{\partial}} 227 | \newcommand\ubpartial{\mathbup{\partial}} 228 | % 229 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Fonts %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 230 | 231 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Page styles %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 232 | % 233 | \def\endpage#1{\gdef\@endpage{#1}} 234 | \endpage{}% 235 | \def\jname#1{\gdef\@jname{#1}} 236 | \gdef\@jname{} 237 | \def\jvol#1{\gdef\@jvol{#1}} 238 | \gdef\@jvol{00} 239 | \def\jnum#1{\gdef\@jnum{#1}} 240 | \gdef\@jnum{00} 241 | \def\jmonth#1{\gdef\@jmonth{#1}} 242 | \gdef\@jmonth{Month} 243 | \def\jyear#1{\gdef\@jyear{#1}} 244 | \gdef\@jyear{20XX} 245 | \def\doi#1{\gdef\@doi{#1}} 246 | \gdef\@doi{} 247 | % 248 | \def\ps@title{% 249 | \let\@oddfoot\@empty 250 | \let\@evenfoot\@empty 251 | \def\@evenhead{}% 252 | \def\@oddhead{}% 253 | \let\@mkboth\@gobbletwo 254 | \let\sectionmark\@gobble 255 | \let\subsectionmark\@gobble 256 | } 257 | % 258 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Page styles %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 259 | 260 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Title commands %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 261 | % 262 | \def\articletype#1{\gdef\@articletype{{#1}}\MakeUppercase} 263 | \def\articletype#1{\gdef\@articletype{#1}} 264 | \gdef\@articletype{\ } 265 | \def\title#1{\gdef\@title{{#1}}} 266 | \def\author#1{\def\and{and }\gdef\@author{#1}} 267 | \def\received#1{\gdef\@received{#1}} 268 | \def\history#1{\gdef\@received{#1}} 269 | \gdef\@history{\bfseries{ARTICLE HISTORY\\}\par} 270 | \gdef\@received{Compiled \today} 271 | % 272 | \long\def\name#1{#1\\\vspace{6pt}}% 273 | \long\def\affil#1{\affilfont{#1}\\} 274 | \long\def\email#1{#1\\} 275 | % 276 | \def\thanks#1{\begingroup 277 | \def\protect{\noexpand\protect\noexpand}\xdef\@thanks{\@thanks% 278 | \protect\footnotetext[\the\c@footnote]{\thanksfont#1}}\endgroup} 279 | % 280 | \renewcommand\maketitle{\par% 281 | \renewcommand\thefootnote{}% 282 | \begingroup 283 | \@maketitle% 284 | \thispagestyle{title} 285 | \endgroup 286 | \@thanks 287 | \let\@maketitle\relax 288 | \gdef\@thanks{}\gdef\@author{}\gdef\@title{}\gdef\@articletype{}% 289 | \renewcommand\thefootnote{\arabic{footnote}}% 290 | \@afterheading} 291 | % 292 | \def\@maketitle{\thispagestyle{plain} 293 | \clearpage 294 | \null 295 | \bgroup 296 | \parindent0pt 297 | \vspace*{36pt} 298 | {\articletypefont{\@articletype}\par}% 299 | \vskip13pt 300 | {\titlefont{\@title}\par}% 301 | \vskip13pt 302 | {\authorfont\@author\par}% 303 | \ifsuppldata\else 304 | \vskip17pt 305 | {\receivedfont{\bfseries ARTICLE HISTORY\\}\@received\par}% 306 | \fi 307 | \vskip13pt 308 | \egroup} 309 | % 310 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Title commands %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 311 | 312 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%% Sectioning commands %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 313 | % 314 | \setcounter{secnumdepth}{5} 315 | %\newcounter {part} 316 | %\newcounter {section} 317 | %\newcounter {subsection}[section] 318 | %\newcounter {subsubsection}[subsection] 319 | %\newcounter {paragraph}[subsubsection] 320 | %\newcounter {subparagraph}[paragraph] 321 | \renewcommand\thepart {\arabic{part}} 322 | \renewcommand\thesection {\arabic{section}} 323 | \renewcommand\thesubsection {\thesection.\arabic{subsection}} 324 | \renewcommand\thesubsubsection {\thesubsection.\arabic{subsubsection}} 325 | \renewcommand\theparagraph {\thesubsubsection.\arabic{paragraph}} 326 | \renewcommand\thesubparagraph {\theparagraph.\arabic{subparagraph}} 327 | % 328 | \renewcommand\section{\@startsection {section}{1}{\z@}% 329 | {-26pt \@plus-4pt \@minus-2pt}% 330 | {13pt}% 331 | {\sectionfont}}% 332 | \renewcommand\subsection{\@startsection{subsection}{2}{\z@}% 333 | {-24pt \@plus-3pt \@minus-2pt}% 334 | {7pt}% 335 | {\subsectionfont}}% 336 | \renewcommand\subsubsection{\@startsection{subsubsection}{3}{\z@}% 337 | {18pt \@plus2pt \@minus2pt}% 338 | {6pt}% 339 | {\subsubsectionfont}}% 340 | \renewcommand\paragraph{\@startsection{paragraph}{4}{\z@}% 341 | {18pt \@plus1pt \@minus1pt}% 342 | {-6pt}% 343 | {\paragraphfont}}% 344 | \renewcommand\subparagraph{\@startsection{subparagraph}{5}{\z@}% 345 | {3.25ex \@plus1ex}% 346 | {-1em}% 347 | {\reset@font\normalsize}}% 348 | % 349 | \def\@startsection#1#2#3#4#5#6{% 350 | \if@noskipsec \leavevmode \fi 351 | \par 352 | \@tempskipa #4\relax 353 | \ifdim \@tempskipa <\z@ 354 | \@tempskipa -\@tempskipa \@afterindentfalse 355 | \fi 356 | \if@nobreak 357 | \ifnum#2=3 358 | \vskip4pt 359 | \fi 360 | \everypar{}% 361 | \else 362 | \addpenalty\@secpenalty\addvspace\@tempskipa 363 | \fi 364 | \@ifstar 365 | {\@ssect{#3}{#4}{#5}{#6}}% 366 | {\@dblarg{\@sect{#1}{#2}{#3}{#4}{#5}{#6}}}} 367 | % 368 | \def\@sseccntformat#1{\csname the#1\endcsname.\hskip 0.5em} 369 | \def\@appseccntformat#1{\appendixname\ \csname the#1\endcsname.\ } 370 | \def\@seccntformat#1{\csname the#1\endcsname.\hskip 0.5em} 371 | \def\@sect#1#2#3#4#5#6[#7]#8{\ifnum #2>\c@secnumdepth 372 | \let\@svsec\@empty\else 373 | \refstepcounter{#1}% 374 | \let\@@protect\protect 375 | \def\protect{\noexpand\protect\noexpand}% 376 | \ifnum#2>\@ne\edef\@svsec{\@sseccntformat{#1}}\else\edef\@svsec{\@seccntformat{#1}}\fi% 377 | \let\protect\@@protect\fi 378 | \@tempskipa #5\relax 379 | \ifdim \@tempskipa>\z@ 380 | \begingroup #6\relax 381 | \ifnum#2=1 382 | \@hangfrom{\hskip #3\relax\@svsec}% 383 | {\interlinepenalty \@M {#8}\par}% 384 | \else 385 | \ifnum#2=2 386 | \@hangfrom{\hskip #3\relax\@svsec}% 387 | {\interlinepenalty \@M #8\par}% 388 | \else 389 | \@hangfrom{\hskip #3\relax\@svsec}% 390 | {\interlinepenalty \@M #8\par}% 391 | \fi 392 | \fi 393 | \endgroup 394 | \csname #1mark\endcsname{#7} 395 | \addcontentsline 396 | {toc}{#1}{\ifnum #2>\c@secnumdepth \else 397 | \protect\numberline{\csname the#1\endcsname}\fi 398 | #7}% 399 | \else% 400 | \def\@svsechd{#6\hskip #3\relax 401 | \em\@svsec #8.\csname #1mark\endcsname 402 | {#7}\addcontentsline 403 | {toc}{#1}{\ifnum #2>\c@secnumdepth \else 404 | \protect\numberline{\csname the#1\endcsname}% 405 | \fi 406 | #7}}\fi 407 | \@xsect{#5}} 408 | % 409 | %%%%%%%%%%%%%%%%%%%%%%%%%%% End Sectioning commands %%%%%%%%%%%%%%%%%%%%%%%%%%%%% 410 | 411 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Lists %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 412 | % 413 | \newdimen\LabelSep 414 | \LabelSep.5em 415 | \newskip\TopSep 416 | \TopSep 6\p@ %\@plus2\p@% \@minus1\p@ 417 | % 418 | \def\@listI{\leftmargin\leftmargini 419 | \listparindent\parindent 420 | \parsep \z@\labelsep\LabelSep 421 | \topsep\TopSep 422 | \itemsep0\p@} 423 | % 424 | \let\@listi\@listI 425 | \@listi 426 | % 427 | \def\@listii {\leftmargin\leftmarginii 428 | \labelwidth\leftmarginii 429 | \listparindent\parindent 430 | \parsep \z@\labelsep\LabelSep 431 | \topsep 0pt%6\p@ \@plus2\p@ \@minus1\p@ 432 | \parsep\z@\itemsep\z@} 433 | \def\@listiii{\leftmargin\leftmarginiii 434 | \listparindent\parindent 435 | \labelwidth\leftmarginiii 436 | \topsep 0pt 437 | \parsep \z@ 438 | \partopsep0pt 439 | \itemsep0pt} 440 | \def\@listiv {\leftmargin\leftmarginiv 441 | \labelwidth\leftmarginiv 442 | \advance\labelwidth-\labelsep} 443 | \def\@listv {\leftmargin\leftmarginv 444 | \labelwidth\leftmarginv 445 | \advance\labelwidth-\labelsep} 446 | \def\@listvi {\leftmargin\leftmarginvi 447 | \labelwidth\leftmarginvi 448 | \advance\labelwidth-\labelsep} 449 | % 450 | \setlength\leftmargini {2.5em} 451 | \leftmargin \leftmargini 452 | \setlength\leftmarginii {2.2em} 453 | \setlength\leftmarginiii {1.87em} 454 | \setlength\leftmarginiv {1.7em} 455 | \setlength\leftmarginv {1em} 456 | \setlength\leftmarginvi {1em} 457 | \setlength \labelsep {.5em} 458 | \setlength \labelwidth{\leftmargini} 459 | \addtolength\labelwidth{-\labelsep} 460 | \@beginparpenalty -\@lowpenalty 461 | \@endparpenalty -\@lowpenalty 462 | \@itempenalty -\@lowpenalty 463 | \renewcommand\theenumi{\@arabic\c@enumi} 464 | \renewcommand\theenumii{\@alph\c@enumii} 465 | \renewcommand\theenumiii{\@roman\c@enumiii} 466 | \renewcommand\theenumiv{\@Alph\c@enumiv} 467 | \renewcommand\labelenumi{(\theenumi)} 468 | \renewcommand\labelenumii{(\theenumii)} 469 | \renewcommand\labelenumiii{(\theenumiii)} 470 | \renewcommand\labelenumiv{(\theenumiv)} 471 | \renewcommand\p@enumii{\theenumi} 472 | \renewcommand\p@enumiii{\theenumi(\theenumii)} 473 | \renewcommand\p@enumiv{\p@enumiii\theenumiii} 474 | \renewcommand\labelitemi{$\m@th\bullet$} 475 | \renewcommand\labelitemii{$\m@th\circ$} 476 | \renewcommand\labelitemiii{\normalfont\textendash} 477 | \renewcommand\labelitemiv{$\m@th\ast$} 478 | % 479 | %\renewenvironment{description}% 480 | % {\list{}{\labelwidth\z@ \itemindent-\leftmargin 481 | % \let\makelabel\descriptionlabel}} 482 | % {\endlist} 483 | %\renewcommand*\descriptionlabel[1]{\hspace\labelsep 484 | % \normalfont\bfseries #1} 485 | % 486 | \renewenvironment{abstract}{% 487 | \par\addvspace{0pt plus2pt minus1pt} 488 | \abstractfont\noindent{\bfseries \abstractname\\}\ignorespaces% 489 | }{% 490 | \par\addvspace{13pt plus2pt minus1pt} 491 | \@endparenv} 492 | % 493 | \newenvironment{abbreviations}{% 494 | \par\addvspace{13pt plus2pt minus1pt} 495 | \abstractfont\noindent{\bfseries \abbreviationsname: }\ignorespaces% 496 | }{% 497 | \par\addvspace{13pt plus2pt minus1pt} 498 | \@endparenv} 499 | % 500 | \newenvironment{keywords}{% 501 | \par\addvspace{13pt plus2pt minus1pt} 502 | \keywordfont\noindent{\bfseries \keywordsname\\}\ignorespaces% 503 | }{% 504 | \par\addvspace{13pt plus2pt minus1pt} 505 | \@endparenv} 506 | % 507 | \newenvironment{amscode}{% 508 | \par\addvspace{13pt plus2pt minus1pt} 509 | \keywordfont\noindent{\bfseries \amscodename\\}\ignorespaces% 510 | }{% 511 | \par\addvspace{13pt plus2pt minus1pt} 512 | \@endparenv} 513 | % 514 | \newenvironment{jelcode}{% 515 | \par\addvspace{13pt plus2pt minus1pt} 516 | \keywordfont\noindent{\bfseries \jelcodename\\}\ignorespaces% 517 | }{% 518 | \par\addvspace{13pt plus2pt minus1pt} 519 | \@endparenv} 520 | % 521 | \newenvironment{pacscode}{% 522 | \par\addvspace{13pt plus2pt minus1pt} 523 | \keywordfont\noindent{\bfseries \pacscodename\\}\ignorespaces% 524 | }{% 525 | \par\addvspace{13pt plus2pt minus1pt} 526 | \@endparenv} 527 | % 528 | \renewenvironment{quote}{% 529 | \par\addvspace{13pt plus2pt minus1pt} 530 | \extractfont\noindent\ignorespaces 531 | }{% 532 | \par\addvspace{13pt plus2pt minus1pt} 533 | \@endparenv} 534 | % 535 | \renewenvironment{quote}{% 536 | \par\addvspace{6pt}\let\itemize\Itemize\let\enditemize\endItemize 537 | \extractfont\noindent\ignorespaces 538 | }{% 539 | \par\addvspace{6pt} 540 | \@endparenv} 541 | % 542 | \renewenvironment{quotation}{% 543 | \par\addvspace{13pt plus2pt minus1pt} 544 | \extractfont\ignorespaces 545 | }{% 546 | \par\addvspace{13pt plus2pt minus1pt} 547 | \@endparenv} 548 | % 549 | \renewenvironment{quotation}{% 550 | \par\addvspace{6pt}\let\itemize\Itemize\let\enditemize\endItemize 551 | \extractfont\ignorespaces 552 | }{% 553 | \par\addvspace{6pt} 554 | \@endparenv} 555 | % 556 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Lists %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 557 | 558 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Appendix %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 559 | % 560 | \renewcommand\appendix{% 561 | \let\@seccntformat\@appseccntformat 562 | \setcounter{equation}{0}\renewcommand\theequation{\thesection\arabic{equation}}% 563 | \setcounter{section}{0}\renewcommand\thesection{\Alph{section}}% 564 | \setcounter{subsection}{0}\renewcommand\thesubsection{\thesection.\arabic{subsection}}% 565 | \setcounter{table}{0}\renewcommand\thetable{\thesection\@arabic\c@table}% 566 | \setcounter{figure}{0}\renewcommand\thefigure{\thesection\@arabic\c@figure}% 567 | \@addtoreset{equation}{section} 568 | \@addtoreset{table}{section} 569 | \@addtoreset{figure}{section} 570 | } 571 | % 572 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Appendix %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 573 | 574 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Figures %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 575 | % 576 | \def\fnum@figure{\figurename\nobreakspace\thefigure.}% 577 | \renewenvironment{figure}% 578 | {\figcaptionfont\@float{figure}} 579 | {\end@float} 580 | \renewenvironment{figure*}% 581 | {\figcaptionfont\@dblfloat{figure}} 582 | {\end@dblfloat} 583 | % 584 | \def\ArtDir{art/}% 585 | \def\ArtPiece{\@ifnextchar[{\@ArtPiece}{\@ArtPiece[]}}% 586 | \def\@ArtPiece[#1]#2{\def\@tempa{#1}% 587 | \hbox{\ifx\@tempa\@empty\else\epsfscale#1\fi 588 | \noindent{\epsfbox{\ArtDir#2}}}}% 589 | % 590 | \newdimen\figheight 591 | \newdimen\figwidth 592 | % 593 | \let\figformat\centerline 594 | % 595 | \def\figurebox#1#2#3#4{% 596 | \global\figheight#1\global\figwidth#2 597 | \def\@tempa{#4}% 598 | \leavevmode 599 | \ifx\@tempa\empty 600 | \figformat{\figbox}% 601 | \else 602 | \figformat{\ArtPiece[#3]{#4}}% 603 | \fi\par} 604 | % 605 | \def\figbox{\hbox{\vbox{\hsize\figwidth 606 | \hrule 607 | \hbox to\figwidth{\vrule\hss 608 | \vbox to \figheight{\vfill}% 609 | \vrule}\hrule}}}% 610 | % 611 | \def\figformat#1{\footnotesize#1}% 612 | % 613 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Figures %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 614 | 615 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Tables %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 616 | % 617 | \def\fnum@table{\tablename\nobreakspace\thetable.}% 618 | \renewenvironment{table}% 619 | {\@float{table}} 620 | {\vskip5pt\end@float} 621 | \renewenvironment{table*}% 622 | {\@dblfloat{table}} 623 | {\end@dblfloat} 624 | % 625 | \newdimen\tabledim 626 | % 627 | \long\def\tbl#1#2{% 628 | \setbox\@tempboxa\hbox{\tablefont #2}% 629 | \tabledim\hsize\advance\tabledim by -\wd\@tempboxa 630 | \global\divide\tabledim\tw@ 631 | \caption{#1} 632 | \centerline{\box\@tempboxa} 633 | }% 634 | % 635 | \newenvironment{tabnote}{% 636 | \par\vskip5pt\tabnotefont 637 | \@ifnextchar[{\@tabnote}{\@tabnote[]}}{% 638 | \par\vskip-5pt} 639 | \def\@tabnote[#1]{\def\@Tempa{#1}\leftskip\tabledim\rightskip\leftskip%\hspace*{9pt}% 640 | \ifx\@Tempa\@empty\else{\itshape #1:}\ \fi\ignorespaces} 641 | % 642 | \def\x{@{\extracolsep{\fill}}} 643 | \renewcommand\toprule{\\[-5.5pt]\hline\\[-5pt]} 644 | \renewcommand\midrule{\\[-7.5pt]\hline\\[-5pt]} 645 | \renewcommand\bottomrule{\\[-7.5pt]\hline} 646 | % 647 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Tables %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 648 | 649 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Captions %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 650 | % 651 | \setlength\abovecaptionskip{12\p@} 652 | \setlength\belowcaptionskip{0\p@} 653 | % 654 | \def\FigName{figure} 655 | % 656 | \long\def\@caption#1[#2]#3{\par\begingroup 657 | \@parboxrestore 658 | \normalsize 659 | \@makecaption{\csname fnum@#1\endcsname}{\ignorespaces #3}\par 660 | \endgroup} 661 | % 662 | \long\def\@makecaption#1#2{% 663 | \ifx\FigName\@captype 664 | \vskip\abovecaptionskip 665 | \setbox\@tempboxa\hbox{\figcaptionfont{\fignumfont#1}\hskip4pt#2}% 666 | \ifdim \wd\@tempboxa >\hsize 667 | {\figcaptionfont\noindent{\fignumfont#1}\hskip7pt\ignorespaces#2\par}% 668 | \else 669 | \global \@minipagefalse 670 | \hb@xt@\hsize{\hfil\box\@tempboxa\hfil}% 671 | \fi 672 | \else 673 | {\tablecaptionfont 674 | {\tablenumfont#1}\hskip7pt\ignorespaces{#2}\par}% 675 | \vskip\belowcaptionskip 676 | \fi} 677 | % 678 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Captions %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 679 | 680 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Footnotes %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 681 | % 682 | \renewcommand\footnoterule{% 683 | \kern2pt 684 | \hrule width\textwidth height.25pt 685 | \kern4pt} 686 | \renewcommand\@makefntext[1]{% 687 | \parindent 0.5em% 688 | \noindent 689 | \hb@xt@1em{\hss\@makefnmark}#1} 690 | % 691 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End Footnotes %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 692 | 693 | %%%%%%%%%%%%%%%%%%%%%%%%%%%% Theorem-like structures %%%%%%%%%%%%%%%%%%%%%%%%%%%% 694 | % 695 | \renewenvironment{proof}[1][\proofname]{\par 696 | \pushQED{\qed}% 697 | \normalfont \topsep6\p@\@plus6\p@\relax 698 | \trivlist 699 | \item[\hskip\labelsep 700 | \bfseries\itshape 701 | #1\@addpunct{.}]\ignorespaces 702 | }{\popQED\endtrivlist\@endpefalse} 703 | % 704 | \newtheoremstyle{plain} 705 | {9pt}{9pt}{\itshape}{}{\bfseries}{.}{0.5em}{} 706 | % 707 | \newtheoremstyle{definition} 708 | {9pt}{9pt}{}{}{\bfseries}{.}{0.5em}{} 709 | % 710 | \newtheoremstyle{remark} 711 | {9pt}{9pt}{}{}{\bfseries}{.}{0.5em}{} 712 | % 713 | %%%%%%%%%%%%%%%%%%%%%%%%%% End Theorem-like structures %%%%%%%%%%%%%%%%%%%%%%%%%% 714 | % 715 | \renewcommand\abstractname{ABSTRACT} 716 | \newcommand\abbreviationsname{Abbreviations} 717 | \newcommand\keywordsname{KEYWORDS} 718 | \newcommand\amscodename{AMS CLASSIFICATION} 719 | \newcommand\jelcodename{JEL CLASSIFICATION} 720 | \newcommand\pacscodename{PACS CLASSIFICATION} 721 | % 722 | \setlength\parskip{0\p@} 723 | \setlength\columnsep{12\p@} 724 | \setlength\columnseprule{0\p@} 725 | \pagestyle{plain} 726 | \pagenumbering{arabic} 727 | \frenchspacing 728 | \sloppy 729 | \onecolumn 730 | % 731 | \endinput 732 | -------------------------------------------------------------------------------- /_femm/release/OneReport/OneReport_TEX/subfig.sty: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/horychen/ACMSIMC_TUT/cfbd62782ba858955d1212f9ee21c00aac48cb1e/_femm/release/OneReport/OneReport_TEX/subfig.sty -------------------------------------------------------------------------------- /_femm/release/OneReport/OneReport_TEX/z.bat: -------------------------------------------------------------------------------- 1 | latex --synctex=1 OneReport 2 | ::bibtex OneReport >nul 3 | latex --synctex=1 OneReport >nul 4 | ::latex --synctex=1 OneReport >nul 5 | dvipdfm OneReport -------------------------------------------------------------------------------- /_femm/release/OneReport/OneReport_TEX/z_nul.bat: -------------------------------------------------------------------------------- 1 | ::latex --synctex=1 OneReport 2 | ::bibtex OneReport 3 | ::latex --synctex=1 OneReport 4 | ::latex --synctex=1 OneReport 5 | ::dvipdfm OneReport 6 | 7 | pdflatex --synctex=1 OneReport >nul 8 | ::bibtex OneReport >nul 9 | ::pdflatex --synctex=1 OneReport >nul 10 | @pdflatex --synctex=1 OneReport >nul 11 | ::dvipdfm OneReport 12 | -------------------------------------------------------------------------------- /commissioning.c: -------------------------------------------------------------------------------- 1 | #include "ACMSim.h" 2 | 3 | struct CommissioningDataStruct COMM; 4 | 5 | void COMM_init(){ 6 | COMM.timebase = 0.0; 7 | 8 | COMM.PID_id.Kp = CURRENT_LOOP_PID_PROPORTIONAL_GAIN; // cutoff frequency of 1530 rad/s 9 | COMM.PID_id.Ti = CURRENT_LOOP_PID_INTEGRAL_TIME_CONSTANT; 10 | COMM.PID_id.Ki = COMM.PID_id.Kp/COMM.PID_id.Ti*TS; // =0.025 11 | COMM.PID_id.i_limit = CURRENT_LOOP_LIMIT_VOLTS; //350.0; // unit: Volt 12 | COMM.PID_id.i_state = 0.0; 13 | printf("Current PID: Kp=%g, Ki=%g, limit=%g V\n", COMM.PID_id.Kp, COMM.PID_id.Ki/TS, COMM.PID_id.i_limit); 14 | 15 | COMM.PID_iq.Kp = CURRENT_LOOP_PID_PROPORTIONAL_GAIN; 16 | COMM.PID_iq.Ti = CURRENT_LOOP_PID_INTEGRAL_TIME_CONSTANT; 17 | COMM.PID_iq.Ki = COMM.PID_iq.Kp/COMM.PID_iq.Ti*TS; 18 | COMM.PID_iq.i_limit = CURRENT_LOOP_LIMIT_VOLTS; // unit: Volt, 350V->max 1300rpm 19 | COMM.PID_iq.i_state = 0.0; 20 | 21 | // R 22 | COMM.current_sum = 0.0; 23 | COMM.voltage_sum = 0.0; 24 | COMM.counterSS = 0; 25 | COMM.bool_collecting = false; 26 | int i; 27 | for(i=0;i<100;++i){ 28 | COMM.iv_data[i][0] = 0.0; 29 | COMM.iv_data[i][1] = 0.0; 30 | } 31 | 32 | // L 33 | COMM.L = 0.999; 34 | } 35 | 36 | /* standard lib */ 37 | #include // printf #include // bool for _Bool and true for 1 38 | #include // for clrscr, and getch() 39 | #include "stdlib.h" // for rand() 40 | #include "math.h" 41 | 42 | #define SS_RATED_CURRENT_RATIO 1e-2 43 | #define SS_CEILING ((long int)(0.2/TS)) 44 | int reachSteadyStateCurrent(double current_error, double rated_current){ 45 | static long int counterSS = 0; 46 | 47 | if(fabs(current_error) < rated_current * SS_RATED_CURRENT_RATIO){ 48 | counterSS += 1; 49 | 50 | // Avoid to collect over-shoot data 51 | if(counterSS > SS_CEILING){ 52 | counterSS = 0; 53 | return true; // 目前是一旦判断为稳态,就永远返回true。当然,也可以设计成回差的形式,达到稳态后还要判断是否脱离稳态。 54 | } 55 | } 56 | return false; 57 | } 58 | 59 | struct CommissioningDataStruct COMM; 60 | 61 | /* event array and enum below must be in sync! */ 62 | enum state_codes { _nameplateData=0, _currentSensor=1, _resistanceId=2, _inductanceId=3, _initialPosId=4, _PMFluxLinkageId=5, _inertiaId=6, _unexpected=7, _end=8 }; 63 | enum ret_codes { ok=0, repeat=1, quit=2 }; 64 | 65 | int event_nameplateData(void){ 66 | printf("Start self-commissioning!\n"); 67 | COMM.npp = 2; 68 | COMM.IN = 8; 69 | printf("Name plate data: npp=%d, IN=%g.\n", COMM.npp, COMM.IN); 70 | 71 | CTRL.ual = 0.0; 72 | CTRL.ube = 0.0; 73 | 74 | return ok; 75 | } 76 | int event_currentSensor(void){ 77 | static long int counterEntered = 0; 78 | if(counterEntered++==0) 79 | printf("Current Sensor Calibration (pass).\n"); 80 | 81 | CTRL.ual = 0.0; 82 | CTRL.ube = 0.0; 83 | 84 | return ok; 85 | } 86 | int event_resistanceId(void){ 87 | static long int counterEntered = 0; 88 | if(counterEntered++==0) 89 | printf("Resistance Identification.\n Current [A] | Voltage [V]\n"); 90 | 91 | #define RS_ID_NUMBER_OF_STAIRS 10 92 | #define RS_ID_MAXIMUM_CURRENT COMM.IN 93 | double current_increase_per_step = RS_ID_MAXIMUM_CURRENT / RS_ID_NUMBER_OF_STAIRS; 94 | static int i = 0; 95 | COMM.current_command = - RS_ID_MAXIMUM_CURRENT; 96 | COMM.current_command += current_increase_per_step*i; 97 | 98 | double error = IS_C(0) - COMM.current_command; 99 | CTRL.ual = - PID(&COMM.PID_id, error); 100 | CTRL.ube = 0.0; 101 | 102 | // collect steady state data 103 | if(COMM.bool_collecting){ 104 | COMM.current_sum += IS_C(0); 105 | COMM.voltage_sum += CTRL.ual; 106 | COMM.counterSS += 1; 107 | 108 | if(COMM.counterSS>800){ 109 | COMM.iv_data[i][0] = COMM.current_sum/(double)COMM.counterSS; 110 | COMM.iv_data[i][1] = COMM.voltage_sum/(double)COMM.counterSS; 111 | printf("%f, %f\n", COMM.iv_data[i][0], COMM.iv_data[i][1]); 112 | COMM.bool_collecting = false; 113 | ++i; 114 | } 115 | }else{ 116 | // reset 117 | COMM.current_sum = 0.0; 118 | COMM.voltage_sum = 0.0; 119 | COMM.counterSS = 0; 120 | 121 | // check steady state and assign boolean variable 122 | if(reachSteadyStateCurrent(error, RS_ID_MAXIMUM_CURRENT)){ 123 | if(COMM.current_command > RS_ID_MAXIMUM_CURRENT){ 124 | 125 | // Get resistance value 126 | COMM.R = (COMM.iv_data[0][1] - COMM.iv_data[1][1]) / (COMM.iv_data[0][0] - COMM.iv_data[1][0]); 127 | // COMM.R = (COMM.iv_data[18+0][1] - COMM.iv_data[18+1][1]) / (COMM.iv_data[18+0][0] - COMM.iv_data[18+1][0]); 128 | printf("R=%g Ohm (including inverter's on-resistance)\n", COMM.R); 129 | return ok; 130 | } 131 | 132 | COMM.bool_collecting = true; 133 | } 134 | } 135 | 136 | return repeat; 137 | } 138 | int event_inductanceId(void){ 139 | static double last_voltage_command; 140 | static long int counterEntered = 0; 141 | if(counterEntered++==0){ 142 | printf("Inductance Identification.\n"); 143 | last_voltage_command = CTRL.ual; 144 | } 145 | 146 | double Delta_IS_al; 147 | double Delta_US_al; 148 | double IS_slope; 149 | 150 | Delta_US_al = 0.5*last_voltage_command; 151 | Delta_IS_al = IS_C(0) - IS_P(0); 152 | IS_slope = Delta_IS_al / TS; 153 | 154 | if(counterEntered<20){ 155 | printf("L=%g\n", Delta_US_al/IS_slope ); 156 | if(Delta_US_al/IS_slope < COMM.L){ 157 | COMM.L = Delta_US_al/IS_slope; 158 | } 159 | }else{ 160 | if(counterEntered==20){ 161 | printf("COMM.L = %g\n", COMM.L); 162 | } 163 | } 164 | 165 | CTRL.ual = last_voltage_command + Delta_US_al; 166 | CTRL.ube = 0.0; 167 | 168 | if(counterEntered>800){ 169 | return ok; 170 | }else{ 171 | return repeat; 172 | } 173 | } 174 | int event_initialPosId(void){ 175 | printf("Initial Position Identification (pass).\n"); 176 | return ok; 177 | } 178 | int event_PMFluxLinkageId(void){ 179 | static long int counterEntered = 0; 180 | if(counterEntered++==0) 181 | printf("PM Flux Linkage Identification.\n"); 182 | 183 | double rpm_speed_command = 100; 184 | double ud_cmd; 185 | double uq_cmd; 186 | ud_cmd = CTRL.ud_cmd; 187 | uq_cmd = CTRL.uq_cmd; 188 | control(rpm_speed_command, 0); 189 | COMM.KE = (uq_cmd - COMM.R*CTRL.iq__fb) / (rpm_speed_command*RPM_2_RAD_PER_SEC) - COMM.L*CTRL.id__fb; 190 | // printf("KE = %g\n", COMM.KE); 191 | return repeat; 192 | } 193 | int event_inertiaId(void){ 194 | printf("Inertia Identification (pass).\n"); 195 | return ok; 196 | } 197 | int event_unexpected(void){ 198 | printf("Debug!"); 199 | return quit; 200 | } 201 | int event_end(void){ 202 | printf("Exit!"); 203 | printf("END."); 204 | return quit; 205 | } 206 | 207 | // Reference: https://www.geeksforgeeks.org/enumeration-enum-c/ 208 | int (* event[])(void) = { event_nameplateData, event_currentSensor, event_resistanceId, event_inductanceId, event_initialPosId, 209 | event_PMFluxLinkageId, event_inertiaId, event_unexpected, event_end }; 210 | int lookup_transitions[][3] = { 211 | // return codes: 212 | // ok repeat quit 213 | [_nameplateData] = {_currentSensor, _nameplateData , _end}, 214 | [_currentSensor] = {_resistanceId , _currentSensor , _end}, 215 | [_resistanceId] = {_inductanceId , _resistanceId , _end}, 216 | [_inductanceId] = {_initialPosId , _inductanceId , _end}, 217 | [_initialPosId] = {_PMFluxLinkageId , _initialPosId , _end}, 218 | [_PMFluxLinkageId] = {_inertiaId , _PMFluxLinkageId , _end}, 219 | [_inertiaId] = {_end , _inertiaId , _end}, 220 | [_unexpected] = {_end , _unexpected , _end}, 221 | /* transitions from end state aren't needed */ 222 | }; 223 | 224 | #define ENTRY_STATE _nameplateData 225 | #define END_STATE _end 226 | 227 | void commissioning(){ 228 | 229 | static enum state_codes cur_state = ENTRY_STATE; 230 | static enum ret_codes rc; 231 | static int (* state_func)(void); 232 | 233 | if(cur_state!=END_STATE){ 234 | state_func = event[cur_state]; 235 | rc = state_func(); 236 | cur_state = lookup_transitions[cur_state][rc]; 237 | } 238 | 239 | IS_P(0) = IS_C(0); 240 | IS_P(1) = IS_C(1); 241 | } 242 | -------------------------------------------------------------------------------- /commissioning.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef COMMISSIONING_H 3 | #define COMMISSIONING_H 4 | 5 | struct CommissioningDataStruct{ 6 | 7 | double timebase; 8 | 9 | int npp; // number of pole pairs 10 | double IN; // rated line current in Ampere RMS 11 | 12 | double R; 13 | double L; 14 | // double Ld; 15 | // double Lq; 16 | double KE; 17 | double Js; // shaft inertia 18 | 19 | struct PID_Reg PID_speed; 20 | struct PID_Reg PID_id; 21 | struct PID_Reg PID_iq; 22 | 23 | double current_command; 24 | 25 | double current_sum; 26 | double voltage_sum; 27 | long int counterSS; 28 | int bool_collecting; 29 | double iv_data[100][2]; 30 | }; 31 | extern struct CommissioningDataStruct COMM; 32 | 33 | void COMM_init(); 34 | void commissioning(); 35 | 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /controller.c: -------------------------------------------------------------------------------- 1 | #include "ACMSim.h" 2 | 3 | /* PI Control 4 | * */ 5 | #define INCREMENTAL_PID TRUE 6 | #if INCREMENTAL_PID 7 | double PID(struct PID_Reg *r, double err){ 8 | 9 | #define O_STATE r->o_state 10 | #define E_STATE r->e_state 11 | #define I_LIMIT r->i_limit 12 | 13 | double delta_u_n; 14 | delta_u_n = r->Kp * ( err - E_STATE ) + r->Ki * err; 15 | 16 | double output; 17 | output = O_STATE + delta_u_n; 18 | 19 | if(output > I_LIMIT) 20 | output = I_LIMIT; 21 | else if(output < -I_LIMIT) 22 | output = -I_LIMIT; 23 | 24 | E_STATE = err; 25 | O_STATE = output; 26 | 27 | return output; 28 | 29 | #undef O_STATE 30 | #undef E_STATE 31 | #undef I_LIMIT 32 | } 33 | #else 34 | double PID(struct PID_Reg *r, double err){ 35 | 36 | #define DYNAMIC_CLAPMING TRUE 37 | 38 | #define I_STATE r->i_state 39 | #define I_LIMIT r->i_limit 40 | double output; 41 | double P_output; 42 | 43 | P_output = err * r->Kp; // 比例 44 | 45 | I_STATE += err * r->Ki; // 积分 46 | 47 | // 添加积分饱和特性 48 | #if DYNAMIC_CLAPMING 49 | // dynamic clamping 50 | if( I_STATE > I_LIMIT - P_output) 51 | I_STATE = I_LIMIT - P_output; 52 | else if( I_STATE < -I_LIMIT - P_output) 53 | I_STATE = -I_LIMIT - P_output; 54 | #else 55 | // static clamping 56 | if( I_STATE > I_LIMIT) 57 | I_STATE = I_LIMIT; 58 | else if( I_STATE < -I_LIMIT) 59 | I_STATE = -I_LIMIT; 60 | #endif 61 | 62 | output = I_STATE + P_output; 63 | 64 | if(output > I_LIMIT) 65 | output = I_LIMIT; 66 | else if(output < -I_LIMIT) 67 | output = -I_LIMIT; 68 | return output; 69 | #undef I_STATE 70 | #undef I_LIMIT 71 | } 72 | #endif 73 | 74 | /* Initialization */ 75 | struct ControllerForExperiment CTRL; 76 | void CTRL_init(){ 77 | int i=0,j=0; 78 | 79 | CTRL.timebase = 0.0; 80 | 81 | CTRL.ual = 0.0; 82 | CTRL.ube = 0.0; 83 | 84 | CTRL.R = ACM.R; 85 | CTRL.KE = ACM.KE; 86 | CTRL.Ld = ACM.Ld; 87 | CTRL.Lq = ACM.Lq; 88 | 89 | // CTRL.Tload = 0.0; 90 | // CTRL.rpm_cmd = 0.0; 91 | 92 | CTRL.npp = ACM.npp; 93 | CTRL.Js = ACM.Js; 94 | CTRL.Js_inv = 1.0 / CTRL.Js; 95 | 96 | CTRL.omg__fb = 0.0; 97 | CTRL.ial__fb = 0.0; 98 | CTRL.ibe__fb = 0.0; 99 | CTRL.psi_mu_al__fb = 0.0; 100 | CTRL.psi_mu_be__fb = 0.0; 101 | 102 | CTRL.rotor_flux_cmd = 0.0; // id=0 control 103 | 104 | CTRL.omg_ctrl_err = 0.0; 105 | CTRL.speed_ctrl_err = 0.0; 106 | 107 | CTRL.cosT = 1.0; 108 | CTRL.sinT = 0.0; 109 | 110 | CTRL.omega_syn = 0.0; 111 | 112 | CTRL.theta_d__fb = 0.0; 113 | CTRL.id__fb = 0.0; 114 | CTRL.iq__fb = 0.0; 115 | CTRL.ud_cmd = 0.0; 116 | CTRL.uq_cmd = 0.0; 117 | CTRL.id_cmd = 0.0; 118 | CTRL.iq_cmd = 0.0; 119 | 120 | CTRL.Tem = 0.0; 121 | CTRL.Tem_cmd = 0.0; 122 | 123 | // ver. IEMDC 124 | CTRL.PID_speed.Kp = SPEED_LOOP_PID_PROPORTIONAL_GAIN; 125 | CTRL.PID_speed.Ti = SPEED_LOOP_PID_INTEGRAL_TIME_CONSTANT; 126 | CTRL.PID_speed.Ki = CTRL.PID_speed.Kp / CTRL.PID_speed.Ti * (TS*SPEED_LOOP_CEILING); // 4.77 = 1 / (npp*1/60*2*pi) 127 | CTRL.PID_speed.i_limit = SPEED_LOOP_LIMIT_NEWTON_METER; 128 | CTRL.PID_speed.i_state = 0.0; 129 | printf("Speed PID: Kp=%g, Ki=%g, limit=%g Nm\n", CTRL.PID_speed.Kp, CTRL.PID_speed.Ki/TS, CTRL.PID_speed.i_limit); 130 | 131 | CTRL.PID_id.Kp = CURRENT_LOOP_PID_PROPORTIONAL_GAIN; // cutoff frequency of 1530 rad/s 132 | CTRL.PID_id.Ti = CURRENT_LOOP_PID_INTEGRAL_TIME_CONSTANT; 133 | CTRL.PID_id.Ki = CTRL.PID_id.Kp/CTRL.PID_id.Ti*TS; // =0.025 134 | CTRL.PID_id.i_limit = CURRENT_LOOP_LIMIT_VOLTS; //350.0; // unit: Volt 135 | CTRL.PID_id.i_state = 0.0; 136 | printf("Current PID: Kp=%g, Ki=%g, limit=%g V\n", CTRL.PID_id.Kp, CTRL.PID_id.Ki/TS, CTRL.PID_id.i_limit); 137 | 138 | CTRL.PID_iq.Kp = CURRENT_LOOP_PID_PROPORTIONAL_GAIN; 139 | CTRL.PID_iq.Ti = CURRENT_LOOP_PID_INTEGRAL_TIME_CONSTANT; 140 | CTRL.PID_iq.Ki = CTRL.PID_iq.Kp/CTRL.PID_iq.Ti*TS; 141 | CTRL.PID_iq.i_limit = CURRENT_LOOP_LIMIT_VOLTS; // unit: Volt, 350V->max 1300rpm 142 | CTRL.PID_iq.i_state = 0.0; 143 | } 144 | double theta_d_harnefors = 0.0; 145 | double omg_harnefors = 0.0; 146 | void harnefors_scvm(){ 147 | #define KE_MISMATCH 1.0 // 0.7 148 | double d_axis_emf; 149 | double q_axis_emf; 150 | #define LAMBDA 2 // 2 151 | #define CJH_TUNING_A 25 // 1 152 | #define CJH_TUNING_B 1 // 1 153 | double lambda_s = LAMBDA * sign(omg_harnefors); 154 | double alpha_bw_lpf = CJH_TUNING_A*0.1*(1500*RPM_2_RAD_PER_SEC) + CJH_TUNING_B*2*LAMBDA*fabs(omg_harnefors); 155 | // d_axis_emf = CTRL.ud_cmd - 1*CTRL.R*CTRL.id_cmd + omg_harnefors*1.0*CTRL.Lq*CTRL.iq_cmd; // If Ld=Lq. 156 | // q_axis_emf = CTRL.uq_cmd - 1*CTRL.R*CTRL.iq_cmd - omg_harnefors*1.0*CTRL.Ld*CTRL.id_cmd; // If Ld=Lq. 157 | d_axis_emf = CTRL.ud_cmd - 1*CTRL.R*CTRL.id_cmd + omg_harnefors*1.0*CTRL.Lq*CTRL.iq_cmd; // eemf 158 | q_axis_emf = CTRL.uq_cmd - 1*CTRL.R*CTRL.iq_cmd - omg_harnefors*1.0*CTRL.Lq*CTRL.id_cmd; // eemf 159 | // Note it is bad habit to write numerical integration explictly like this. The states on the right may be accencidentally modified on the run. 160 | theta_d_harnefors += TS * omg_harnefors; 161 | omg_harnefors += TS * alpha_bw_lpf * ( (q_axis_emf - lambda_s*d_axis_emf)/(CTRL.KE*KE_MISMATCH+(CTRL.Ld-CTRL.Lq)*CTRL.id_cmd) - omg_harnefors ); 162 | while(theta_d_harnefors>M_PI) theta_d_harnefors-=2*M_PI; 163 | while(theta_d_harnefors<-M_PI) theta_d_harnefors+=2*M_PI; 164 | } 165 | void control(double speed_cmd, double speed_cmd_dot){ 166 | // Input 1 is feedback: estimated speed/position or measured speed/position 167 | #if SENSORLESS_CONTROL 168 | #if SENSORLESS_CONTROL_HFSI 169 | CTRL.omg__fb = hfsi.omg_elec; 170 | CTRL.theta_d__fb = hfsi.theta_d; 171 | #else 172 | // getch("Not Implemented"); 173 | // CTRL.omg__fb ; 174 | // CTRL.omega_syn ; 175 | 176 | // CTRL.omg__fb = OB_OMG; 177 | // CTRL.theta_d__fb = OB_POS; 178 | 179 | harnefors_scvm(); 180 | CTRL.omg__fb = omg_harnefors; 181 | CTRL.theta_d__fb = theta_d_harnefors; 182 | #endif 183 | #else 184 | 185 | // from measurement() in main.c 186 | CTRL.omg__fb = sm.omg_elec; 187 | CTRL.theta_d__fb = sm.theta_d; 188 | #endif 189 | 190 | // Input 2 is feedback: measured current 191 | CTRL.ial__fb = IS_C(0); 192 | CTRL.ibe__fb = IS_C(1); 193 | 194 | // Input 3 is the flux linkage command 195 | #if CONTROL_STRATEGY == NULL_D_AXIS_CURRENT_CONTROL 196 | CTRL.rotor_flux_cmd = 0.0; 197 | CTRL.cosT = cos(CTRL.theta_d__fb); 198 | CTRL.sinT = sin(CTRL.theta_d__fb); 199 | #else 200 | getch("Not Implemented"); 201 | #endif 202 | 203 | // d-axis current command 204 | CTRL.id_cmd = CTRL.rotor_flux_cmd / CTRL.Ld; 205 | 206 | // q-axis current command 207 | static int vc_count = 0; 208 | if(vc_count++ == SPEED_LOOP_CEILING){ 209 | // velocity control loop execution frequency is 40 times slower than current control loop execution frequency 210 | vc_count = 0; 211 | CTRL.omg_ctrl_err = CTRL.omg__fb - speed_cmd*RPM_2_RAD_PER_SEC; 212 | CTRL.iq_cmd = - PID(&CTRL.PID_speed, CTRL.omg_ctrl_err); 213 | 214 | // for plot 215 | CTRL.speed_ctrl_err = CTRL.omg_ctrl_err * RAD_PER_SEC_2_RPM; 216 | } 217 | 218 | // Measured current in d-q frame 219 | CTRL.id__fb = AB2M(CTRL.ial__fb, CTRL.ibe__fb, CTRL.cosT, CTRL.sinT); 220 | CTRL.iq__fb = AB2T(CTRL.ial__fb, CTRL.ibe__fb, CTRL.cosT, CTRL.sinT); 221 | 222 | // For luenberger position observer for HFSI 223 | CTRL.Tem = CTRL.npp * (CTRL.KE*CTRL.iq__fb + (CTRL.Ld-CTRL.Lq)*CTRL.id__fb*CTRL.iq__fb); 224 | CTRL.Tem_cmd = CTRL.npp * (CTRL.KE*CTRL.iq_cmd + (CTRL.Ld-CTRL.Lq)*CTRL.id_cmd*CTRL.iq_cmd); 225 | 226 | // Voltage command in d-q frame 227 | double vd, vq; 228 | vd = - PID(&CTRL.PID_id, CTRL.id__fb-CTRL.id_cmd); 229 | vq = - PID(&CTRL.PID_iq, CTRL.iq__fb-CTRL.iq_cmd); 230 | 231 | // Current loop decoupling (skipped for now) 232 | CTRL.ud_cmd = vd; 233 | CTRL.uq_cmd = vq; 234 | 235 | #ifdef HFSI_ON 236 | // Extra excitation for observation 237 | { 238 | static int dfe_counter = 0; 239 | if(dfe_counter++==HFSI_CEILING){ 240 | dfe_counter = 0; 241 | hfsi.square_wave_internal_register *= -1; 242 | } 243 | // hfsi.square_wave_internal_register *= -1; 244 | CTRL.ud_cmd += HFSI_VOLTAGE*hfsi.square_wave_internal_register; 245 | } 246 | #endif 247 | 248 | // Voltage command in alpha-beta frame 249 | CTRL.ual = MT2A(CTRL.ud_cmd, CTRL.uq_cmd, CTRL.cosT, CTRL.sinT); 250 | CTRL.ube = MT2B(CTRL.ud_cmd, CTRL.uq_cmd, CTRL.cosT, CTRL.sinT); 251 | } 252 | 253 | 254 | 255 | /* Command */ 256 | void cmd_fast_speed_reversal(double timebase, double instant, double interval, double rpm_cmd){ 257 | if(timebase > instant+2*interval){ 258 | ACM.rpm_cmd = 1*1500 + rpm_cmd; 259 | }else if(timebase > instant+interval){ 260 | ACM.rpm_cmd = 1*1500 + -rpm_cmd; 261 | }else if(timebase > instant){ 262 | ACM.rpm_cmd = 1*1500 + rpm_cmd; 263 | }else{ 264 | ACM.rpm_cmd = 20; // default initial command 265 | } 266 | } 267 | 268 | -------------------------------------------------------------------------------- /controller.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef CONTROLLER_H 3 | #define CONTROLLER_H 4 | 5 | 6 | struct PID_Reg{ 7 | double Kp; // Proportional gain 8 | double Ti; // Integral time constant 9 | double Ki; // Ki = Kp/Ti*TS (note TS is included here for ease of discrete implementaion) 10 | double i_state; // Integral internal state 11 | double i_limit; // Output limit 12 | 13 | double e_state; // last error internal state 14 | double o_state; // last output internal state 15 | }; 16 | double PID(struct PID_Reg *r, double err); 17 | 18 | struct ControllerForExperiment{ 19 | 20 | double timebase; 21 | 22 | double ual; 23 | double ube; 24 | 25 | double R; 26 | double KE; 27 | double Ld; 28 | double Lq; 29 | 30 | // double Tload; 31 | // double rpm_cmd; 32 | 33 | double npp; 34 | double Js; 35 | double Js_inv; 36 | 37 | double omg__fb; 38 | double ial__fb; 39 | double ibe__fb; 40 | double psi_mu_al__fb; 41 | double psi_mu_be__fb; 42 | 43 | double rotor_flux_cmd; 44 | 45 | double omg_ctrl_err; 46 | double speed_ctrl_err; 47 | 48 | double cosT; 49 | double sinT; 50 | 51 | double omega_syn; 52 | 53 | double theta_d__fb; 54 | double id__fb; 55 | double iq__fb; 56 | double ud_cmd; 57 | double uq_cmd; 58 | double id_cmd; 59 | double iq_cmd; 60 | 61 | double Tem; 62 | double Tem_cmd; 63 | 64 | // double theta_M; 65 | // double iMs; 66 | // double iTs; 67 | // double uMs_cmd; 68 | // double uTs_cmd; 69 | // double iMs_cmd; 70 | // double iTs_cmd; 71 | 72 | struct PID_Reg PID_speed; 73 | struct PID_Reg PID_id; 74 | struct PID_Reg PID_iq; 75 | }; 76 | extern struct ControllerForExperiment CTRL; 77 | 78 | void CTRL_init(); 79 | void control(double speed_cmd, double speed_cmd_dot); 80 | 81 | 82 | void cmd_fast_speed_reversal(double timebase, double instant, double interval, double rpm_cmd); 83 | void cmd_slow_speed_reversal(double timebase, double instant, double interval, double rpm_cmd); 84 | #endif 85 | -------------------------------------------------------------------------------- /inverter.c: -------------------------------------------------------------------------------- 1 | #include "ACMSim.h" 2 | 3 | #if INVERTER_NONLINEARITY 4 | 5 | void InverterNonlinearity_SKSul96(double ual, double ube, double ial, double ibe){ 6 | double ua,ub,uc; 7 | double ia,ib,ic; 8 | double Udist; 9 | double TM; 10 | double Rce=0.04958, Rdiode=0.05618; 11 | 12 | TM = _Toff - _Ton - _Tdead + _Tcomp; // Sul1996 13 | Udist = (_Udc*TM*TS_INVERSE - _Vce0 - _Vd0) / 6.0; // Udist = (_Udc*TM/1e-4 - _Vce0 - _Vd0) / 6.0; 14 | // Udist = (_Udc*TM*TS_INVERSE) / 6.0; 15 | // Udist = 0.0; 16 | 17 | ia = SQRT_2_SLASH_3 * ( ial ); 18 | ib = SQRT_2_SLASH_3 * (-0.5 * ial - SIN_DASH_2PI_SLASH_3 * ibe ); 19 | ic = SQRT_2_SLASH_3 * (-0.5 * ial - SIN_2PI_SLASH_3 * ibe ); 20 | 21 | /* compute in abc frame */ 22 | // ua = SQRT_2_SLASH_3 * ( ual ); 23 | // ub = SQRT_2_SLASH_3 * (-0.5 * ual - SIN_DASH_2PI_SLASH_3 * ube ); 24 | // uc = SQRT_2_SLASH_3 * (-0.5 * ual - SIN_2PI_SLASH_3 * ube ); 25 | // ua += Udist * (2*sign(ia) - sign(ib) - sign(ic)) - 0.5*(Rce+Rdiode)*ia; 26 | // ub += Udist * (2*sign(ib) - sign(ic) - sign(ia)) - 0.5*(Rce+Rdiode)*ib; 27 | // uc += Udist * (2*sign(ic) - sign(ia) - sign(ib)) - 0.5*(Rce+Rdiode)*ic; 28 | // UAL_C_DIST = SQRT_2_SLASH_3 * (ua - 0.5*ub - 0.5*uc); // sqrt(2/3.) 29 | // UBE_C_DIST = 0.70710678118654746 * ( ub - uc); // sqrt(2/3.)*sin(2*pi/3) = sqrt(2/3.)*(sqrt(3)/2) 30 | 31 | /* directly compute in alpha-beta frame */ 32 | // CHECK the sign of the distortion voltage! 33 | // Sul把Udist视为补偿的电压(假定上升下降时间都已经知道了而且是“补偿”上去的) 34 | UAL_C_DIST = ual + sqrtf(1.5)*Udist*(2*sign(ia) - sign(ib) - sign(ic)) - 0.5*(Rce+Rdiode)*ial; 35 | UBE_C_DIST = ube + 3/sqrtf(2)*Udist*( sign(ib) - sign(ic)) - 0.5*(Rce+Rdiode)*ibe; 36 | 37 | } 38 | 39 | 40 | #endif -------------------------------------------------------------------------------- /inverter.h: -------------------------------------------------------------------------------- 1 | /* 2 | * inverter.h 3 | * 4 | * By: Hory Chen 5 | * Email: horychen@qq.com 6 | * Created on: June 27th 2017 7 | * 8 | * Tips: Do not declare any variables in h files. 9 | */ 10 | 11 | #ifndef INVERTER_H 12 | #define INVERTER_H 13 | 14 | void InverterNonlinearity_SKSul96(double ual, double ube, double ial, double ibe); 15 | 16 | // Inverter Model 17 | #define _Vce0 1.8 // V 18 | #define _Vd0 1.3 // V 19 | #define _Udc 300 // V 20 | #define _Toff 0.32e-6 // sec 21 | #define _Ton 0.15e-6 // sec 22 | #define _Tdead 3.30e-6 // sec 23 | #define _Tcomp 0.0*(_Tdead+_Ton-_Toff) //3.13e-6; //8e-6; // 过补偿 //3.13e-6; // 只补偿死区 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /libsatlut.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/horychen/ACMSIMC_TUT/cfbd62782ba858955d1212f9ee21c00aac48cb1e/libsatlut.a -------------------------------------------------------------------------------- /main.c: -------------------------------------------------------------------------------- 1 | #include "ACMSim.h" 2 | 3 | double sign(double x){ 4 | return (x > 0) - (x < 0); 5 | } 6 | double fabs(double x){ 7 | return (x >= 0) ? x : -x; 8 | } 9 | 10 | struct SynchronousMachineSimulated ACM; 11 | void Machine_init(){ 12 | 13 | ACM.Ts = MACHINE_TS; 14 | 15 | int i; 16 | for(i=0;i M_PI){ 113 | ACM.theta_d -= 2*M_PI; 114 | }else if(ACM.theta_d < -M_PI){ 115 | ACM.theta_d += 2*M_PI; // 反转! 116 | } 117 | ACM.x[3] = ACM.theta_d; 118 | 119 | // currents 120 | ACM.id = ACM.x[0]; 121 | ACM.iq = ACM.x[1]; 122 | ACM.ial = MT2A(ACM.id, ACM.iq, cos(ACM.theta_d), sin(ACM.theta_d)); 123 | ACM.ibe = MT2B(ACM.id, ACM.iq, cos(ACM.theta_d), sin(ACM.theta_d)); 124 | 125 | // speed 126 | ACM.omg_elec = ACM.x[2]; 127 | ACM.rpm = ACM.x[2] * 60 / (2 * M_PI * ACM.npp); 128 | 129 | // extended emf 130 | ACM.eemf_q = (ACM.Ld-ACM.Lq) * (ACM.omg_elec*ACM.id - ACM.x_dot[1]) + ACM.omg_elec*ACM.KE; 131 | ACM.eemf_al = ACM.eemf_q * -sin(ACM.theta_d); 132 | ACM.eemf_be = ACM.eemf_q * cos(ACM.theta_d); 133 | // ACM.theta_d__eemf = atan2(-ACM.eemf_al, ACM.eemf_be); 134 | ACM.theta_d__eemf = atan2(-ACM.eemf_al*sign(ACM.omg_elec), ACM.eemf_be*sign(ACM.omg_elec)); 135 | 136 | // detect bad simulation 137 | if(isNumber(ACM.rpm)){ 138 | return false; 139 | }else{ 140 | printf("ACM.rpm is %g\n", ACM.rpm); 141 | return true; 142 | } 143 | } 144 | 145 | void dynamics_lpf_local(double input, double *state, double *derivative){ 146 | derivative[0] = (50*2*M_PI) * ( input - *state ); 147 | } 148 | void measurement(){ 149 | // Executed every TS 150 | 151 | // Voltage measurement 152 | US_C(0) = CTRL.ual; 153 | US_C(1) = CTRL.ube; 154 | US_P(0) = US_C(0); 155 | US_P(1) = US_C(1); 156 | 157 | // Current measurement 158 | IS_C(0) = ACM.ial; 159 | IS_C(1) = ACM.ibe; 160 | 161 | // Position and speed measurement 162 | sm.theta_d = ACM.x[3]; // + 30.0/180*M_PI; 163 | sm.omg_elec = ACM.x[2]; 164 | sm.omg_mech = sm.omg_elec * sm.npp_inv; 165 | } 166 | void inverter_model(){ 167 | 168 | // 根据给定电压CTRL.ual和实际的电机电流ACM.ial,计算畸变的逆变器输出电压ACM.ual。 169 | #if INVERTER_NONLINEARITY 170 | 171 | InverterNonlinearity_SKSul96(CTRL.ual, CTRL.ube, ACM.ial, ACM.ibe); 172 | // InverterNonlinearity_Tsuji01 173 | ACM.ual = UAL_C_DIST; 174 | ACM.ube = UBE_C_DIST; 175 | 176 | // Distorted voltage (for visualization purpose) 177 | DIST_AL = ACM.ual - CTRL.ual; 178 | DIST_BE = ACM.ube - CTRL.ube; 179 | #else 180 | ACM.ual = CTRL.ual; 181 | ACM.ube = CTRL.ube; 182 | #endif 183 | 184 | // 仿真是在永磁体磁场定向系下仿真的哦 185 | ACM.ud = AB2M(ACM.ual, ACM.ube, cos(ACM.theta_d), sin(ACM.theta_d)); 186 | ACM.uq = AB2T(ACM.ual, ACM.ube, cos(ACM.theta_d), sin(ACM.theta_d)); 187 | } 188 | 189 | int main(){ 190 | if(SENSORLESS_CONTROL==true){ 191 | printf("Sensorless using observer.\n"); 192 | }else{ 193 | printf("Sensored control.\n"); 194 | } 195 | printf("NUMBER_OF_STEPS: %d\n\n", NUMBER_OF_STEPS); 196 | 197 | /* Initialization */ 198 | Machine_init(); 199 | CTRL_init(); 200 | sm_init(); 201 | // ob_init(); 202 | COMM_init(); 203 | 204 | FILE *fw; 205 | fw = fopen(DATA_FILE_NAME, "w"); 206 | printf("%s\n", DATA_FILE_NAME); 207 | write_header_to_file(fw); 208 | 209 | /* MAIN LOOP */ 210 | clock_t begin, end; 211 | begin = clock(); 212 | int _; // _ for the outer iteration 213 | int dfe_counter=0; // dfe_counter for down frequency execution 214 | for(_=0;_14){ 222 | ACM.rpm_cmd = 900; // 40 double e_state; // Integral internal state 223 | 224 | }else if(CTRL.timebase>12){ 225 | ACM.rpm_cmd = 40; // 40 226 | }else if(CTRL.timebase>9){ 227 | ACM.rpm_cmd = 0; 228 | }else if(CTRL.timebase>6){ 229 | ACM.rpm_cmd = -40; 230 | }else if(CTRL.timebase>3){ 231 | // ACM.rpm_cmd = -20; 232 | ACM.rpm_cmd = 1 * RAD_PER_SEC_2_RPM; 233 | }else{ 234 | ACM.rpm_cmd = -10*0; 235 | } 236 | 237 | /* Load Torque */ 238 | // ACM.Tload = 0 * sign(ACM.rpm); // No-load test 239 | // ACM.Tload = ACM.Tem; // Blocked-rotor test 240 | // ACM.Tload = 2 * ACM.rpm/20; // speed-dependent load 241 | ACM.Tload = 0 * sign(ACM.rpm); // speed-direction-dependent load 242 | 243 | /* Simulated ACM */ 244 | if(machine_simulation()){ 245 | printf("Break the loop.\n"); 246 | break; 247 | } 248 | 249 | if(++dfe_counter == TS_UPSAMPLING_FREQ_EXE_INVERSE){ 250 | dfe_counter = 0; 251 | 252 | /* Time in DSP */ 253 | CTRL.timebase += TS; 254 | 255 | measurement(); 256 | 257 | // observation(); 258 | 259 | write_data_to_file(fw); 260 | 261 | control(ACM.rpm_cmd, 0); 262 | 263 | // commissioning(); 264 | } 265 | 266 | inverter_model(); 267 | } 268 | end = clock(); printf("The simulation in C costs %g sec.\n", (double)(end - begin)/CLOCKS_PER_SEC); 269 | fclose(fw); 270 | 271 | /* Fade out */ 272 | system("python ./ACMPlot.py"); 273 | // getch(); 274 | // system("pause"); 275 | // system("exit"); 276 | return 0; 277 | } 278 | 279 | /* Utility */ 280 | void write_header_to_file(FILE *fw){ 281 | // no space is allowed! 282 | fprintf(fw, "x0(id)[A],x1(iq)[A],x2(speed)[rpm],x3(position)[rad],ud_cmd[V],uq_cmd[V],id[A],id_err[A],iq_cmd[A],iq_err[A],CTRL_POS_ERR,MEAS_POS_ERR,theta_d_harnefors,POS_ERR_Harnefors,omg_harnefors,OMG_ERR_Harnefors\n"); 283 | // fprintf(fw, "x0(id)[A],x1(iq)[A],x2(speed)[rpm],x3(position)[rad],ud[V],uq[V],IS_C(0),CTRL.ual,ACM.ual,ACM.theta_d,DIST_AL,COMM.KE\n"); 284 | { 285 | FILE *fw2; 286 | fw2 = fopen("info.dat", "w"); 287 | fprintf(fw2, "TS,DOWN_SAMPLE,DATA_FILE_NAME\n"); 288 | fprintf(fw2, "%g, %d, %s\n", TS, DOWN_SAMPLE, DATA_FILE_NAME); 289 | fclose(fw2); 290 | } 291 | } 292 | extern double theta_d_harnefors; 293 | extern double omg_harnefors; 294 | void write_data_to_file(FILE *fw){ 295 | static int bool_animate_on = false; 296 | static int j=0,jj=0; // j,jj for down sampling 297 | 298 | 299 | // if(CTRL.timebase>20) 300 | { 301 | if(++j == DOWN_SAMPLE) 302 | { 303 | j=0; 304 | fprintf(fw, "%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g\n", 305 | ACM.x[0], ACM.x[1], ACM.x[2]*RAD_PER_SEC_2_RPM, ACM.x[3], CTRL.ud_cmd, CTRL.uq_cmd, 306 | CTRL.id__fb, CTRL.id__fb-CTRL.id_cmd, CTRL.iq_cmd, CTRL.iq__fb-CTRL.iq_cmd, difference_between_two_angles(ACM.x[3], CTRL.theta_d__fb)/M_PI*180, difference_between_two_angles(ACM.x[3], sm.theta_d)/M_PI*180, 307 | theta_d_harnefors, difference_between_two_angles(ACM.theta_d, theta_d_harnefors)/M_PI*180, omg_harnefors*RAD_PER_SEC_2_RPM, (sm.omg_elec-omg_harnefors)*RAD_PER_SEC_2_RPM 308 | ); 309 | // fprintf(fw, "%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g\n", 310 | // ACM.x[0], ACM.x[1], ACM.x[2]*RAD_PER_SEC_2_RPM, ACM.x[3], ACM.ud, ACM.uq, 311 | // IS_C(0), CTRL.ual, ACM.ual, ACM.theta_d, DIST_AL, COMM.KE 312 | // ); 313 | } 314 | } 315 | 316 | // if(bool_animate_on==false){ 317 | // bool_animate_on = true; 318 | // printf("Start ACMAnimate\n"); 319 | // system("start python ./ACMAnimate.py"); 320 | // } 321 | } 322 | 323 | int isNumber(double x){ 324 | // This looks like it should always be true, 325 | // but it's false if x is an NaN (1.#QNAN0). 326 | return (x == x); 327 | // see https://www.johndcook.com/blog/IEEE_exceptions_in_cpp/ cb: https://stackoverflow.com/questions/347920/what-do-1-inf00-1-ind00-and-1-ind-mean 328 | } 329 | 330 | 331 | 332 | -------------------------------------------------------------------------------- /noloadtest.py: -------------------------------------------------------------------------------- 1 | import pandas as pd 2 | df = pd.read_csv('./noload.dat', header=None) 3 | print(df) 4 | 5 | 6 | from pylab import plt, np 7 | x = np.array(df[3].values)**2 8 | y = df[5].values 9 | # The first two points are not in no-load condition 10 | x = x[2:] 11 | y = y[2:] 12 | print(x,y) 13 | # The first several points in no-load condition are not really in linear region due to leakage inductance 14 | x = x[9:] # 多使用低电压的点,可以对线性部分进行更准确地拟合 15 | y = y[9:] # 多使用低电压的点,可以对线性部分进行更准确地拟合 16 | y += 100 # [W] friction and windage loss 17 | print(x,y) 18 | plt.plot(x, y, 'ko-') 19 | 20 | 21 | import statsmodels.api as sm 22 | # Ordinary least squares regression 23 | print('Start OLS...') 24 | model_Simple = sm.OLS(y, x).fit() 25 | print(model_Simple.summary()) 26 | print('Parameters: ', model_Simple.params) 27 | 28 | # Add a constant term like so: 29 | print('\n', '-'*40) 30 | print('Start OLS with a constant term (intercept)...') 31 | model = sm.OLS(y, sm.add_constant(x)).fit() 32 | print(model.summary()) 33 | print('Parameters: ', model.params) 34 | 35 | x = [0] + x.tolist() 36 | print(x) 37 | 38 | plt.plot(x, np.array(x)*model_Simple.params[0], 'bs--') 39 | plt.plot(x, np.array(x)*model.params[1] + model.params[0], 'rs--') 40 | 41 | plt.xlabel('Voltage Squared [$\\rm V^2$]') 42 | plt.ylabel('Power [W]') 43 | 44 | plt.grid() 45 | plt.show() 46 | 47 | 48 | -------------------------------------------------------------------------------- /observer.c: -------------------------------------------------------------------------------- 1 | #include "ACMSim.h" 2 | 3 | 4 | struct SynchronousMachine sm; 5 | struct Observer ob; 6 | 7 | void sm_init(){ 8 | int i; 9 | for(i=0; i<2; ++i){ 10 | sm.us[i] = 0; 11 | sm.is[i] = 0; 12 | sm.us_curr[i] = 0; 13 | sm.is_curr[i] = 0; 14 | sm.us_prev[i] = 0; 15 | sm.is_prev[i] = 0; 16 | sm.is_lpf[i] = 0; 17 | sm.is_hpf[i] = 0; 18 | sm.is_bpf[i] = 0; 19 | 20 | sm.current_lpf_register[i] = 0; 21 | sm.current_hpf_register[i] = 0; 22 | sm.current_bpf_register1[i] = 0; 23 | sm.current_bpf_register2[i] = 0; 24 | } 25 | 26 | sm.npp = PMSM_NUMBER_OF_POLE_PAIRS; 27 | sm.npp_inv = 1.0/sm.npp; 28 | 29 | sm.R = PMSM_RESISTANCE; 30 | sm.Ld = PMSM_D_AXIS_INDUCTANCE; 31 | sm.Ld_inv = 1/sm.Ld; 32 | sm.Lq = PMSM_Q_AXIS_INDUCTANCE; 33 | sm.KE = PMSM_PERMANENT_MAGNET_FLUX_LINKAGE; // Vs/rad 34 | 35 | sm.Js = PMSM_SHAFT_INERTIA; 36 | sm.Js_inv = 1./sm.Js; 37 | 38 | sm.omg_elec = 0.0; 39 | sm.omg_mech = sm.omg_elec * sm.npp_inv; 40 | sm.theta_d = 0.0; 41 | } 42 | 43 | 44 | double difference_between_two_angles(double first, double second){ 45 | while(first>2*M_PI){ 46 | first-=2*M_PI; 47 | } 48 | while(second>2*M_PI){ 49 | second-=2*M_PI; 50 | } 51 | 52 | while(first<0.0){ 53 | first+=2*M_PI; 54 | } 55 | while(second<0.0){ 56 | second+=2*M_PI; 57 | } 58 | 59 | if(fabs(first-second)second){ 63 | return first-2*M_PI-second; 64 | }else{ 65 | return first+2*M_PI-second; 66 | } 67 | } 68 | } 69 | 70 | 71 | -------------------------------------------------------------------------------- /observer.h: -------------------------------------------------------------------------------- 1 | #ifndef ADD_OBSERVER_H 2 | #define ADD_OBSERVER_H 3 | 4 | #define OB_COEF_K1 (1*1000) //(10*1000) 5 | #define OB_COEF_K2 (4*20000) //(10*20000) 6 | #define OB_COEF_GAMMA (0.5*1e8) //(160*1e8) 7 | 8 | /* Macro for External Access Interface */ 9 | #define US(X) sm.us[X] 10 | #define IS(X) sm.is[X] 11 | #define US_C(X) sm.us_curr[X] 12 | #define IS_C(X) sm.is_curr[X] 13 | #define US_P(X) sm.us_prev[X] 14 | #define IS_P(X) sm.is_prev[X] 15 | 16 | #define IS_LPF(X) sm.is_lpf[X] 17 | #define IS_HPF(X) sm.is_hpf[X] 18 | #define IS_BPF(X) sm.is_bpf[X] 19 | 20 | #define OB_EEMF_AL ob.eemf_al 21 | #define OB_EEMF_BE ob.eemf_be 22 | #define OB_POS ob.theta_d 23 | #define OB_OMG ob.xOmg 24 | #define OB_LD ob.Ld 25 | #define OB_LQ ob.Lq 26 | #define OB_R ob.R 27 | 28 | struct SynchronousMachine{ 29 | double us[2]; 30 | double is[2]; 31 | double us_curr[2]; 32 | double is_curr[2]; 33 | double us_prev[2]; 34 | double is_prev[2]; 35 | double is_lpf[2]; 36 | double is_hpf[2]; 37 | double is_bpf[2]; 38 | 39 | double current_lpf_register[2]; 40 | double current_hpf_register[2]; 41 | double current_bpf_register1[2]; 42 | double current_bpf_register2[2]; 43 | 44 | double npp; 45 | double npp_inv; 46 | 47 | double R; 48 | double Ld; 49 | double Ld_inv; 50 | double Lq; 51 | double KE; 52 | 53 | double Js; 54 | double Js_inv; 55 | 56 | double omg_elec; // omg_elec = npp * omg_mech 57 | double omg_mech; 58 | double theta_d; 59 | }; 60 | extern struct SynchronousMachine sm; 61 | 62 | struct Observer{ 63 | 64 | double R; 65 | double Ld; 66 | double Ld_inv; 67 | double Lq; 68 | double KE; // psi_PM; 69 | 70 | double DeltaL; 71 | 72 | double Js; 73 | double Js_inv; 74 | 75 | double omg_elec; // omg_elec = npp * omg_mech 76 | double omg_mech; 77 | double theta_d; 78 | 79 | double eemf_al; 80 | double eemf_be; 81 | 82 | 83 | 84 | double xPsi[2]; 85 | double xChi[2]; 86 | 87 | double xEta[2]; 88 | double xVarSigma[2]; 89 | 90 | double xUpsilon[2]; 91 | double xZeta[2]; 92 | 93 | double xOmg; 94 | 95 | 96 | double output_error[2]; 97 | double output_error_eff[2]; 98 | 99 | double k1; 100 | double k2; 101 | double gamma_omega; 102 | }; 103 | extern struct Observer ob; 104 | 105 | 106 | void sm_init(); 107 | void ob_init(); 108 | void observation(); 109 | 110 | 111 | double difference_between_two_angles(double first, double second); 112 | 113 | #endif 114 | 115 | -------------------------------------------------------------------------------- /satlut-makefile-staticLIB.bat: -------------------------------------------------------------------------------- 1 | gcc -c satlut.c -o satlut.o 2 | ar rcs libsatlut.a satlut.o 3 | pause 4 | -------------------------------------------------------------------------------- /satlut.h: -------------------------------------------------------------------------------- 1 | #ifndef SATURATION_LOOPUPTABLE_H 2 | #define SATURATION_LOOPUPTABLE_H 3 | 4 | 5 | #define IZ_STEP 0.01 6 | #define IZ_STEP_INV 100 7 | 8 | float sat_lookup(double iz, float satLUT[]); 9 | 10 | extern float satLUT[]; 11 | 12 | 13 | 14 | 15 | #endif --------------------------------------------------------------------------------