diff --git a/.gitignore b/.gitignore index eb48f105..236f30ad 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,5 @@ -build/* !build/hover.hex +.pio/ +.pioenvs/ +.vscode/ +01_Matlab/slprj/ diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 00000000..83cabc8b --- /dev/null +++ b/.travis.yml @@ -0,0 +1,55 @@ +notifications: + email: true + +sudo: false + +matrix: + fast_finish: true + include: + + - name: make (gcc-arm-none-eabi-7) + script: make + language: c + addons: + apt: + packages: + - libc6-i386 + install: + - pushd . + - cd ~ + - mkdir arm-gcc-toolchain + - wget -O $HOME/arm-gcc-toolchain/gcc.tar.bz2 https://developer.arm.com/-/media/Files/downloads/gnu-rm/7-2018q2/gcc-arm-none-eabi-7-2018-q2-update-linux.tar.bz2?revision=bc2c96c0-14b5-4bb4-9f18-bceb4050fee7?product=GNU%20Arm%20Embedded%20Toolchain,64-bit,,Linux,7-2018-q2-update + - cd arm-gcc-toolchain + - tar -jxf gcc.tar.bz2 --strip=1 + - popd + - export PATH=$HOME/arm-gcc-toolchain/bin:$PATH + before_script: arm-none-eabi-gcc --version + + - name: make (gcc-arm-none-eabi-5) + script: make + language: c + addons: + apt: + packages: + - libc6-i386 + install: + - pushd . + - cd ~ + - mkdir arm-gcc-toolchain + - wget -O $HOME/arm-gcc-toolchain/gcc.tar.bz2 https://developer.arm.com/-/media/Files/downloads/gnu-rm/5_4-2016q3/gcc-arm-none-eabi-5_4-2016q3-20160926-linux.tar.bz2?revision=111dee36-f88b-4672-8ac6-48cf41b4d375?product=GNU%20Arm%20Embedded%20Toolchain,32-bit,,Linux,5-2016-q3-update + - cd arm-gcc-toolchain + - tar -jxf gcc.tar.bz2 --strip=1 + - popd + - export PATH=$HOME/arm-gcc-toolchain/bin:$PATH + before_script: arm-none-eabi-gcc --version + + - name: pio genericSTM32F103RC + script: platformio run -e genericSTM32F103RC + language: python + python: + - "2.7" + install: + - pip install -U platformio + - platformio update + cache: + - directories: "~/.platformio" diff --git a/01_Matlab/01_Libraries/01_Controller/BLDC_controller_Lib.slx b/01_Matlab/01_Libraries/01_Controller/BLDC_controller_Lib.slx new file mode 100644 index 00000000..44acdceb Binary files /dev/null and b/01_Matlab/01_Libraries/01_Controller/BLDC_controller_Lib.slx differ diff --git a/01_Matlab/01_Libraries/02_Plant/BLDC_model_sf.mexw64 b/01_Matlab/01_Libraries/02_Plant/BLDC_model_sf.mexw64 new file mode 100644 index 00000000..da535332 Binary files /dev/null and b/01_Matlab/01_Libraries/02_Plant/BLDC_model_sf.mexw64 differ diff --git a/01_Matlab/01_Libraries/02_Plant/BLDCmotorControl_data.mat b/01_Matlab/01_Libraries/02_Plant/BLDCmotorControl_data.mat new file mode 100644 index 00000000..564bc35e Binary files /dev/null and b/01_Matlab/01_Libraries/02_Plant/BLDCmotorControl_data.mat differ diff --git a/01_Matlab/01_Libraries/02_Plant/PWM_generator_sf.mexw64 b/01_Matlab/01_Libraries/02_Plant/PWM_generator_sf.mexw64 new file mode 100644 index 00000000..cb7c501e Binary files /dev/null and b/01_Matlab/01_Libraries/02_Plant/PWM_generator_sf.mexw64 differ diff --git a/01_Matlab/02_Figures/control_methods.png b/01_Matlab/02_Figures/control_methods.png new file mode 100644 index 00000000..3f8ad604 Binary files /dev/null and b/01_Matlab/02_Figures/control_methods.png differ diff --git a/01_Matlab/99_RecycleBin/BLDC_controller_Lib_AccelerationBased.slx b/01_Matlab/99_RecycleBin/BLDC_controller_Lib_AccelerationBased.slx new file mode 100644 index 00000000..ff4e6519 Binary files /dev/null and b/01_Matlab/99_RecycleBin/BLDC_controller_Lib_AccelerationBased.slx differ diff --git a/01_Matlab/99_RecycleBin/BLDC_controller_Lib_CounterBased.slx b/01_Matlab/99_RecycleBin/BLDC_controller_Lib_CounterBased.slx new file mode 100644 index 00000000..f7c76e27 Binary files /dev/null and b/01_Matlab/99_RecycleBin/BLDC_controller_Lib_CounterBased.slx differ diff --git a/01_Matlab/99_RecycleBin/BLDCmotorDerating_R2017b.slx b/01_Matlab/99_RecycleBin/BLDCmotorDerating_R2017b.slx new file mode 100644 index 00000000..bf9de567 Binary files /dev/null and b/01_Matlab/99_RecycleBin/BLDCmotorDerating_R2017b.slx differ diff --git a/01_Matlab/99_RecycleBin/bldc_motor_derating.c b/01_Matlab/99_RecycleBin/bldc_motor_derating.c new file mode 100644 index 00000000..bee1d1ee --- /dev/null +++ b/01_Matlab/99_RecycleBin/bldc_motor_derating.c @@ -0,0 +1,258 @@ +/* +* This file has been re-implemented with 4 new selectable motor control methods. +* Recommended control method: 3 = Sinusoidal 3rd order. This control method offers superior performanace +* compared to previous method. The new method features: +* ► reduced noise and vibrations +* ► smooth torque output +* ► improved motor efficiency -> lower energy consumption +* +* Copyright (C) 2019 Emanuel FERU +* +* This program is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with this program. If not, see . +*/ + +#include "stm32f1xx_hal.h" +#include "defines.h" +#include "setup.h" +#include "config.h" + +// Matlab includes and defines - from auto-code generation +// ############################################################################### +#include "BLDC_controller.h" /* Model's header file */ +#include "rtwtypes.h" + +extern RT_MODEL *const rtM_Left; +extern RT_MODEL *const rtM_Right; + +extern DW rtDW_Left; /* Observable states */ +extern ExtU rtU_Left; /* External inputs */ +extern ExtY rtY_Left; /* External outputs */ + +extern DW rtDW_Right; /* Observable states */ +extern ExtU rtU_Right; /* External inputs */ +extern ExtY rtY_Right; /* External outputs */ +// ############################################################################### + + +volatile int pwml = 0; +volatile int pwmr = 0; + +int pwm_limiter = 1024; + +extern volatile adc_buf_t adc_buffer; + +extern volatile uint32_t timeout; + +uint8_t buzzerFreq = 0; +uint8_t buzzerPattern = 0; +static uint32_t buzzerTimer = 0; + +uint8_t enable = 0; + +static const uint16_t pwm_res = 64000000 / 2 / PWM_FREQ; // = 2000 +static float pwml_lim = 0; +static float curl_filt = 0; +float CUR; + +static int offsetcount = 0; +static int offsetrl1 = 2000; +static int offsetrl2 = 2000; +static int offsetrr1 = 2000; +static int offsetrr2 = 2000; +static int offsetdcl = 2000; +static int offsetdcr = 2000; + +float batteryVoltage = BAT_NUMBER_OF_CELLS * 4.0; + +//scan 8 channels with 2ADCs @ 20 clk cycles per sample +//meaning ~80 ADC clock cycles @ 8MHz until new DMA interrupt =~ 100KHz +//=640 cpu cycles +void DMA1_Channel1_IRQHandler(void) { + + DMA1->IFCR = DMA_IFCR_CTCIF1; + // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1); + // HAL_GPIO_TogglePin(LED_PORT, LED_PIN); + + if(offsetcount < 1000) { // calibrate ADC offsets + offsetcount++; + offsetrl1 = (adc_buffer.rl1 + offsetrl1) / 2; + offsetrl2 = (adc_buffer.rl2 + offsetrl2) / 2; + offsetrr1 = (adc_buffer.rr1 + offsetrr1) / 2; + offsetrr2 = (adc_buffer.rr2 + offsetrr2) / 2; + offsetdcl = (adc_buffer.dcl + offsetdcl) / 2; + offsetdcr = (adc_buffer.dcr + offsetdcr) / 2; + return; + } + + if (buzzerTimer % 1000 == 0) { // because you get float rounding errors if it would run every time + batteryVoltage = batteryVoltage * 0.99f + ((float)adc_buffer.batt1 * ((float)BAT_CALIB_REAL_VOLTAGE / (float)BAT_CALIB_ADC)) * 0.01f; + } + + // //disable PWM when current limit is reached (current chopping) + // if(ABS((adc_buffer.dcl - offsetdcl) * MOTOR_AMP_CONV_DC_AMP) > DC_CUR_LIMIT || timeout > TIMEOUT || enable == 0) { + // LEFT_TIM->BDTR &= ~TIM_BDTR_MOE; + // //HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1); + // } else { + // LEFT_TIM->BDTR |= TIM_BDTR_MOE; + // //HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0); + // } + + // if(ABS((adc_buffer.dcr - offsetdcr) * MOTOR_AMP_CONV_DC_AMP) > DC_CUR_LIMIT || timeout > TIMEOUT || enable == 0) { + // RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE; + // } else { + // RIGHT_TIM->BDTR |= TIM_BDTR_MOE; + // } + + //disable PWM when current limit is reached (current chopping) + if(timeout > TIMEOUT || enable == 0) { + LEFT_TIM->BDTR &= ~TIM_BDTR_MOE; + //HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1); + } else { + LEFT_TIM->BDTR |= TIM_BDTR_MOE; + //HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0); + } + + if(timeout > TIMEOUT || enable == 0) { + RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE; + } else { + RIGHT_TIM->BDTR |= TIM_BDTR_MOE; + } + + // pwml_lim = pwml_lim + 0.001f * (ABS((adc_buffer.dcr - offsetdcr) * MOTOR_AMP_CONV_DC_AMP) - DC_CUR_LIMIT); + // pwml_lim = CLAMP(pwml_lim, 0, ABS(pwmr)); + // pwmr = (int) (pwmr - SIGN(pwmr) * pwml_lim); + + // if (ABS((adc_buffer.dcl - offsetdcl) * MOTOR_AMP_CONV_DC_AMP) > DC_CUR_LIMIT) + // pwml_lim = pwml_lim + 0.00001f; + // else + // pwml_lim = pwml_lim - 0.00001f; (pwml_lim * (1.0f - FILTER) + cmd2 * FILTER) + + float CUR_FILTER = 0.1f; // 0.00001f; + curl_filt = ((100.0f - CUR_FILTER) * curl_filt + CUR_FILTER * ABS((adc_buffer.dcl - offsetdcl) * MOTOR_AMP_CONV_DC_AMP)) / 100; + // curl_filt = ABS((adc_buffer.dcl - offsetdcl) * MOTOR_AMP_CONV_DC_AMP); + // pwml_lim = pwml_lim + 1 * (curl_filt - DC_CUR_LIMIT); + pwml_lim = 2 * (curl_filt - DC_CUR_LIMIT); + pwml_lim = CLAMP(pwml_lim, 0, ABS(pwml)); + pwml = (int) (pwml - SIGN(pwml) * pwml_lim); + + // if(curl_filt > DC_CUR_LIMIT) { + // pwml_lim+=0.1f; + // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1); // Derating active + // } else { + // pwml_lim-=0.1f; + // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0); // Derating deactive + // } + // pwml_lim = CLAMP(pwml_lim/1000, 0, ABS(pwml)); + // pwml = (int) (pwml - SIGN(pwml) * pwml_lim); + + + // DC_CUR = MAX(ABS((adc_buffer.dcl - offsetdcl) * MOTOR_AMP_CONV_DC_AMP), ABS((adc_buffer.dcr - offsetdcr) * MOTOR_AMP_CONV_DC_AMP)); + +// CUR = curl_filt; + CUR = (adc_buffer.rl1 - offsetrl1) * MOTOR_AMP_CONV_DC_AMP; + // if(ABS((adc_buffer.dcl - offsetdcl) * MOTOR_AMP_CONV_DC_AMP) > DC_CUR_LIMIT) { + // pwm_limiter--; + // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1); // Derating active + // } else { + // pwm_limiter++; + // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0); // Derating deactive + // } + // pwm_limiter = CLAMP(pwm_limiter, 0, 1024); + // pwml = (pwm_limiter*pwml) >> 10; + // pwmr = CLAMP(pwmr, -pwm_lim, pwm_lim); + + //create square wave for buzzer + buzzerTimer++; + if (buzzerFreq != 0 && (buzzerTimer / 5000) % (buzzerPattern + 1) == 0) { + if (buzzerTimer % buzzerFreq == 0) { + HAL_GPIO_TogglePin(BUZZER_PORT, BUZZER_PIN); + } + } else { + HAL_GPIO_WritePin(BUZZER_PORT, BUZZER_PIN, 0); + } + + // ############################### MOTOR CONTROL ############################### + + static boolean_T OverrunFlag = false; + /* Check for overrun */ + if (OverrunFlag) { + return; + } + OverrunFlag = true; + + int ul, vl, wl; + int ur, vr, wr; + // ========================= LEFT MOTOR ============================ + // Get hall sensors values + uint8_t hall_ul = !(LEFT_HALL_U_PORT->IDR & LEFT_HALL_U_PIN); + uint8_t hall_vl = !(LEFT_HALL_V_PORT->IDR & LEFT_HALL_V_PIN); + uint8_t hall_wl = !(LEFT_HALL_W_PORT->IDR & LEFT_HALL_W_PIN); + + /* Set motor inputs here */ + rtU_Left.b_hallA = hall_ul; + rtU_Left.b_hallB = hall_vl; + rtU_Left.b_hallC = hall_wl; + rtU_Left.r_DC = pwml; + + /* Step the controller */ + BLDC_controller_step(rtM_Left); + + /* Get motor outputs here */ + ul = rtY_Left.DC_phaA; + vl = rtY_Left.DC_phaB; + wl = rtY_Left.DC_phaC; + // motSpeedLeft = rtY_Left.n_mot; + // motAngleLeft = rtY_Left.a_elecAngle; + + /* Apply commands */ + LEFT_TIM->LEFT_TIM_U = (uint16_t)CLAMP(ul + pwm_res / 2, 10, pwm_res-10); + LEFT_TIM->LEFT_TIM_V = (uint16_t)CLAMP(vl + pwm_res / 2, 10, pwm_res-10); + LEFT_TIM->LEFT_TIM_W = (uint16_t)CLAMP(wl + pwm_res / 2, 10, pwm_res-10); + // ================================================================= + + + // ========================= RIGHT MOTOR =========================== + // Get hall sensors values + uint8_t hall_ur = !(RIGHT_HALL_U_PORT->IDR & RIGHT_HALL_U_PIN); + uint8_t hall_vr = !(RIGHT_HALL_V_PORT->IDR & RIGHT_HALL_V_PIN); + uint8_t hall_wr = !(RIGHT_HALL_W_PORT->IDR & RIGHT_HALL_W_PIN); + + /* Set motor inputs here */ + rtU_Right.b_hallA = hall_ur; + rtU_Right.b_hallB = hall_vr; + rtU_Right.b_hallC = hall_wr; + rtU_Right.r_DC = pwmr; + + /* Step the controller */ + BLDC_controller_step(rtM_Right); + + /* Get motor outputs here */ + ur = rtY_Right.DC_phaA; + vr = rtY_Right.DC_phaB; + wr = rtY_Right.DC_phaC; + // motSpeedRight = rtY_Right.n_mot; + // motAngleRight = rtY_Right.a_elecAngle; + + /* Apply commands */ + RIGHT_TIM->RIGHT_TIM_U = (uint16_t)CLAMP(ur + pwm_res / 2, 10, pwm_res-10); + RIGHT_TIM->RIGHT_TIM_V = (uint16_t)CLAMP(vr + pwm_res / 2, 10, pwm_res-10); + RIGHT_TIM->RIGHT_TIM_W = (uint16_t)CLAMP(wr + pwm_res / 2, 10, pwm_res-10); + // ================================================================= + + /* Indicate task complete */ + OverrunFlag = false; + + // ############################################################################### + +} diff --git a/01_Matlab/99_RecycleBin/init_model.m b/01_Matlab/99_RecycleBin/init_model.m new file mode 100644 index 00000000..2985c9ad --- /dev/null +++ b/01_Matlab/99_RecycleBin/init_model.m @@ -0,0 +1,214 @@ + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% This file is part of the hoverboard-new-firmware-hack project +% Compared to previouse commutation method, this project offers +% 3 more additional control method for BLDC motors. +% The new control methods offers superior performanace +% compared to previous method featuring: +% >> reduced noise and vibrations +% >> smooth torque output +% >> improved motor efficiency -> lower energy consumption +% +% Author: Emanuel FERU +% Copyright 2019 Emanuel FERU +% +% This program is free software: you can redistribute it and/or modify +% it under the terms of the GNU General Public License as published by +% the Free Software Foundation, either version 3 of the License, or +% (at your option) any later version. +% +% This program is distributed in the hope that it will be useful, +% but WITHOUT ANY WARRANTY; without even the implied warranty of +% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +% GNU General Public License for more details. +% +% You should have received a copy of the GNU General Public License +% along with this program. If not, see . +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% Clear workspace +close all +clear +clc + +% Load model parameters +load BLDCmotorControl_data; +Ts = 5e-6; % [s] Model samplind time (200 kHz) +Ts_ctrl = 6e-5; % [s] Controller samplid time (~16 kHz) +% Ts_ctrl = 12e-5; % [s] Controller samplid time (~8 kHz) + +% BLDC control parameters +CTRL_COMM = 0; % Commutation +CTRL_TRAP = 1; % Pure Trapezoidal +CTRL_SIN = 2; % Sinusoidal +CTRL_SIN3 = 3; % Sinusoidal 3rd armonic + +z_ctrlTypSel = CTRL_SIN3; % Control method selection + +% Motor Parameters +n_polePairs = 15; % [-] Number of pole pairs +a_elecPeriod = 360; % [deg] Electrical angle period +a_elecAngle = 60; % [deg] Electrical angle between two Hall sensor changing events +a_mechAngle = a_elecAngle / n_polePairs; % [deg] Mechanical angle + +%% F01_Preliminary_Calculations + +z_hallDebSteps = 3; % [-] Hall debounce time steps + +% Position Calculation Parameters +% Hall = 4*hA + 2*hB + hC +% Hall = [0 1 2 3 4 5 6 7] +vec_hallToPos = [0 5 3 4 1 0 2 0]; % [-] Mapping Hall signal to position + +% Speed Calculation Parameters +f_ctrl = 1/Ts_ctrl; % [Hz] Controller frequency = 1/Ts_ctrl +cf_speedCoef = round(f_ctrl * a_mechAngle * (pi/180) * (30/pi)); % [-] Speed calculation coefficient (factors are due to conversions rpm <-> rad/s) +cf_speedFilt = 10; % [%] Speed filter in percent [1, 100]. Lower values mean softer filter +z_maxCntRst = 1000; % [-] Maximum counter value for reset (works also as time-out to detect standing still) +% z_nrEdgeSpdAcv = 2; % [-] Number of edge detections to activate speed calculation +% cf_speedSca = 3e7; % [-] Scaling factor for speed calculation +% cf_speedCoef = round(cf_speedSca /(f_ctrl * a_mechAngle * (pi/180) * (30/pi))); + +%% F02_Electrical_Angle_Calculation +b_phaAdvEna = 1; % [-] Phase advance enable parameter: 0 = disable, 1 = enable + +% The map below was experimentaly calibrated on the real motor. Objectives: minimum noise and minimum torque ripple +a_phaAdv_M1 = [0 0 7 2 2 2 4 5 9 16 25]; % [deg] Phase advance angle +r_phaAdvDC_XA = [0 100 200 300 400 500 600 700 800 900 1000]; % [-] Phase advance Duty Cycle grid +% plot(r_phaAdvDC_XA, a_phaAdv_M1); + +%% F03_Speed_Control +n_commAcvLo = 30; % [rpm] Commutation method activation speed low +n_commDeacvHi = 50; % [rpm] Commutation method deactivation speed high +r_commDCDeacv = 80; % [-] Commutation method deactivation Duty Cycle threshold (arbitrary small number) +z_errCtrlRstHi = 20; % [-] Error counter reset. Above this value the control resets to Commudation method (only during high dynamics) +z_errCtrlRstLo = 12; + +sca_factor = 1000; % [-] scalling factor (to avoid truncation approximations on integer data type) +% Commutation method +z_commutMap_M1 = sca_factor*[ 1 1 0 -1 -1 0; % Phase A + -1 0 1 1 0 -1 ; % Phase B + 0 -1 -1 0 1 1]; % Phase C [-] Commutation method map + +% Trapezoidal method +a_trapElecAngle_XA = [0 60 120 180 240 300 360]; % [deg] Electrical angle grid +r_trapPhaA_M1 = sca_factor*[ 1 1 1 -1 -1 -1 1]; +r_trapPhaB_M1 = sca_factor*[-1 -1 1 1 1 -1 -1]; +r_trapPhaC_M1 = sca_factor*[ 1 -1 -1 -1 1 1 1]; + +% Sinusoidal method +a_sinElecAngle_XA = 0:10:360; +omega = a_sinElecAngle_XA*(pi/180); +pha_adv = 30; % [deg] Phase advance to mach commands with the Hall position +r_sinPhaA_M1 = sin(omega + pha_adv*(pi/180)); +r_sinPhaB_M1 = sin(omega - 120*(pi/180) + pha_adv*(pi/180)); +r_sinPhaC_M1 = sin(omega + 120*(pi/180) + pha_adv*(pi/180)); + +% Sinusoidal 3rd armonic method +A = 1.15; % Sine amplitude (tunable to get the Saddle sin maximum to value 1000) +sin3Arm = 0.22*sin(3*(omega + pha_adv*(pi/180))); % 3rd armonic +r_sin3PhaA_M1 = sin3Arm + A*r_sinPhaA_M1; +r_sin3PhaB_M1 = sin3Arm + A*r_sinPhaB_M1; +r_sin3PhaC_M1 = sin3Arm + A*r_sinPhaC_M1; + +% Rounding for representation on integer data type +r_sinPhaA_M1 = round(sca_factor * r_sinPhaA_M1); +r_sinPhaB_M1 = round(sca_factor * r_sinPhaB_M1); +r_sinPhaC_M1 = round(sca_factor * r_sinPhaC_M1); +r_sin3PhaA_M1 = round(sca_factor * r_sin3PhaA_M1); +r_sin3PhaB_M1 = round(sca_factor * r_sin3PhaB_M1); +r_sin3PhaC_M1 = round(sca_factor * r_sin3PhaC_M1); + +disp('---- BLDC_controller: Initialization OK ----'); + +%% 2nd Harmonic vs 3rd Harmonic +% figure +% subplot(211) +% a1= (0.22*sin(3*(omega + (pi/180)))); +% b = A*sin(omega + 1*(pi/180)); +% plot(a_sinElecAngle_XA, a1+b,'b', 'Linewidth', lw); hold on +% a2 = abs(0.3*sin(2*(omega + (pi/180)))); +% b = 0.85*sin(omega + 1*(pi/180)); +% plot(a_sinElecAngle_XA,sign(b).*a2+b,'g', 'Linewidth', lw) +% grid +% legend('3rd harmonic', '2nd harmonic'); +% subplot(212) +% plot(a_sinElecAngle_XA,a1,'b', 'Linewidth', lw); hold on +% plot(a_sinElecAngle_XA,sign(b).*a2,'g', 'Linewidth', lw); +% plot(a_sinElecAngle_XA,b,'r', 'Linewidth', lw); +% legend('3rd harmonic', '2nd harmonic','Main sine wave'); +% grid + +%% Plot control methods + +show_fig = 0; +if show_fig + + hall_A = [1 1 1 0 0 0 0] + 4; + hall_B = [0 0 1 1 1 0 0] + 2; + hall_C = [1 0 0 0 1 1 1]; + + color = ['m' 'g' 'b']; + lw = 1.5; + figure + s1 = subplot(321); hold on + stairs(a_trapElecAngle_XA, hall_A, color(1), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_B, color(2), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_C, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + yticks(0:5); + yticklabels({'0','1','0','1','0','1'}); + title('Hall sensors'); + legend('Phase A','Phase B','Phase C','Location','NorthWest'); + + s2 = subplot(322); hold on + stairs(a_trapElecAngle_XA, hall_A, color(1), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_B, color(2), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_C, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + yticks(0:5); + yticklabels({'0','1','0','1','0','1'}); + title('Hall sensors'); + legend('Phase A','Phase B','Phase C','Location','NorthWest'); + + s3 = subplot(323); hold on + stairs(a_trapElecAngle_XA, [z_commutMap_M1(1,:) z_commutMap_M1(1,end)] + 6000, color(1), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, [z_commutMap_M1(2,:) z_commutMap_M1(1,end)] + 3000, color(2), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, [z_commutMap_M1(3,:) z_commutMap_M1(1,end)], color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + yticks(-1000:1000:7000); + yticklabels({'-1000','0','1000','-1000','0','1000','-1000','0','1000'}); + ylim([-1000 7000]); + grid + title('Commutation method [0]'); + + s5 = subplot(325); hold on + plot(a_trapElecAngle_XA, r_trapPhaA_M1, color(1), 'Linewidth', lw); + plot(a_trapElecAngle_XA, r_trapPhaB_M1, color(2), 'Linewidth', lw); + plot(a_trapElecAngle_XA, r_trapPhaC_M1, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + title('Pure trapezoidal method [1]'); + xlabel('Electrical angle [deg]'); + + s4 = subplot(324); hold on + plot(a_sinElecAngle_XA, r_sinPhaA_M1, color(1), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sinPhaB_M1, color(2), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sinPhaC_M1, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + title('Sinusoidal method [2]'); + + s6 = subplot(326); hold on + plot(a_sinElecAngle_XA, r_sin3PhaA_M1, color(1), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sin3PhaB_M1, color(2), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sin3PhaC_M1, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + title('Sinusoidal 3rd armonic [3]'); + xlabel('Electrical angle [deg]'); + linkaxes([s1 s2 s3 s4 s5 s6],'x'); + xlim([0 360]); +end diff --git a/01_Matlab/99_RecycleBin/init_model_derating.m b/01_Matlab/99_RecycleBin/init_model_derating.m new file mode 100644 index 00000000..a31c4565 --- /dev/null +++ b/01_Matlab/99_RecycleBin/init_model_derating.m @@ -0,0 +1,15 @@ + + +Ts_ctrl = 6e-5; % [s] Controller samplid time (~16 kHz) +% Ts_ctrl = 12e-5; % [s] Controller samplid time (~8 kHz) +f_ctrl = 1/Ts_ctrl; % [Hz] Controller frequency = 1/Ts_ctrl + +%% Motor Current Derating Parameters +PWM_LIM_MAX = 1000; +t_DC_CUR_DER = 2000; % [ms] +t_DC_CUR_REC = 2000; +DC_CUR_LIM_CONT = 15; +DC_CUR_LIM_PEAK = 20; + +dt_curLimDer = PWM_LIM_MAX / t_DC_CUR_DER / (f_ctrl / 1000); +dt_curLimRec = - PWM_LIM_MAX / t_DC_CUR_REC / (f_ctrl / 1000); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/stylesheets/combined.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/stylesheets/combined.css new file mode 100644 index 00000000..e69de29b diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/LICENSE b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/LICENSE new file mode 100644 index 00000000..caffa60b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/LICENSE @@ -0,0 +1,190 @@ +dgrid is available under *either* the terms of the modified BSD license *or* the +Academic Free License version 2.1. As a recipient of dgrid, you may choose which +license to receive this code under. + +The text of the AFL and BSD licenses is reproduced below. + +------------------------------------------------------------------------------- +The "New" BSD License: +********************** + +Copyright (c) 2010-2013, The Dojo Foundation +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of the Dojo Foundation nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +------------------------------------------------------------------------------- +The Academic Free License, v. 2.1: +********************************** + +This Academic Free License (the "License") applies to any original work of +authorship (the "Original Work") whose owner (the "Licensor") has placed the +following notice immediately following the copyright notice for the Original +Work: + +Licensed under the Academic Free License version 2.1 + +1) Grant of Copyright License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license to do the +following: + +a) to reproduce the Original Work in copies; + +b) to prepare derivative works ("Derivative Works") based upon the Original +Work; + +c) to distribute copies of the Original Work and Derivative Works to the +public; + +d) to perform the Original Work publicly; and + +e) to display the Original Work publicly. + +2) Grant of Patent License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license, under patent +claims owned or controlled by the Licensor that are embodied in the Original +Work as furnished by the Licensor, to make, use, sell and offer for sale the +Original Work and Derivative Works. + +3) Grant of Source Code License. The term "Source Code" means the preferred +form of the Original Work for making modifications to it and all available +documentation describing how to modify the Original Work. Licensor hereby +agrees to provide a machine-readable copy of the Source Code of the Original +Work along with each copy of the Original Work that Licensor distributes. +Licensor reserves the right to satisfy this obligation by placing a +machine-readable copy of the Source Code in an information repository +reasonably calculated to permit inexpensive and convenient access by You for as +long as Licensor continues to distribute the Original Work, and by publishing +the address of that information repository in a notice immediately following +the copyright notice that applies to the Original Work. + +4) Exclusions From License Grant. Neither the names of Licensor, nor the names +of any contributors to the Original Work, nor any of their trademarks or +service marks, may be used to endorse or promote products derived from this +Original Work without express prior written permission of the Licensor. Nothing +in this License shall be deemed to grant any rights to trademarks, copyrights, +patents, trade secrets or any other intellectual property of Licensor except as +expressly stated herein. No patent license is granted to make, use, sell or +offer to sell embodiments of any patent claims other than the licensed claims +defined in Section 2. No right is granted to the trademarks of Licensor even if +such marks are included in the Original Work. Nothing in this License shall be +interpreted to prohibit Licensor from licensing under different terms from this +License any Original Work that Licensor otherwise would have a right to +license. + +5) This section intentionally omitted. + +6) Attribution Rights. You must retain, in the Source Code of any Derivative +Works that You create, all copyright, patent or trademark notices from the +Source Code of the Original Work, as well as any notices of licensing and any +descriptive text identified therein as an "Attribution Notice." You must cause +the Source Code for any Derivative Works that You create to carry a prominent +Attribution Notice reasonably calculated to inform recipients that You have +modified the Original Work. + +7) Warranty of Provenance and Disclaimer of Warranty. Licensor warrants that +the copyright in and to the Original Work and the patent rights granted herein +by Licensor are owned by the Licensor or are sublicensed to You under the terms +of this License with the permission of the contributor(s) of those copyrights +and patent rights. Except as expressly stated in the immediately proceeding +sentence, the Original Work is provided under this License on an "AS IS" BASIS +and WITHOUT WARRANTY, either express or implied, including, without limitation, +the warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY OF THE ORIGINAL WORK IS WITH YOU. +This DISCLAIMER OF WARRANTY constitutes an essential part of this License. No +license to Original Work is granted hereunder except under this disclaimer. + +8) Limitation of Liability. Under no circumstances and under no legal theory, +whether in tort (including negligence), contract, or otherwise, shall the +Licensor be liable to any person for any direct, indirect, special, incidental, +or consequential damages of any character arising as a result of this License +or the use of the Original Work including, without limitation, damages for loss +of goodwill, work stoppage, computer failure or malfunction, or any and all +other commercial damages or losses. This limitation of liability shall not +apply to liability for death or personal injury resulting from Licensor's +negligence to the extent applicable law prohibits such limitation. Some +jurisdictions do not allow the exclusion or limitation of incidental or +consequential damages, so this exclusion and limitation may not apply to You. + +9) Acceptance and Termination. If You distribute copies of the Original Work or +a Derivative Work, You must make a reasonable effort under the circumstances to +obtain the express assent of recipients to the terms of this License. Nothing +else but this License (or another written agreement between Licensor and You) +grants You permission to create Derivative Works based upon the Original Work +or to exercise any of the rights granted in Section 1 herein, and any attempt +to do so except under the terms of this License (or another written agreement +between Licensor and You) is expressly prohibited by U.S. copyright law, the +equivalent laws of other countries, and by international treaty. Therefore, by +exercising any of the rights granted to You in Section 1 herein, You indicate +Your acceptance of this License and all of its terms and conditions. + +10) Termination for Patent Action. This License shall terminate automatically +and You may no longer exercise any of the rights granted to You by this License +as of the date You commence an action, including a cross-claim or counterclaim, +against Licensor or any licensee alleging that the Original Work infringes a +patent. This termination provision shall not apply for an action alleging +patent infringement by combinations of the Original Work with other software or +hardware. + +11) Jurisdiction, Venue and Governing Law. Any action or suit relating to this +License may be brought only in the courts of a jurisdiction wherein the +Licensor resides or in which Licensor conducts its primary business, and under +the laws of that jurisdiction excluding its conflict-of-law provisions. The +application of the United Nations Convention on Contracts for the International +Sale of Goods is expressly excluded. Any use of the Original Work outside the +scope of this License or after its termination shall be subject to the +requirements and penalties of the U.S. Copyright Act, 17 U.S.C. § 101 et +seq., the equivalent laws of other countries, and international treaty. This +section shall survive the termination of this License. + +12) Attorneys Fees. In any action to enforce the terms of this License or +seeking damages relating thereto, the prevailing party shall be entitled to +recover its costs and expenses, including, without limitation, reasonable +attorneys' fees and costs incurred in connection with such action, including +any appeal of such action. This section shall survive the termination of this +License. + +13) Miscellaneous. This License represents the complete agreement concerning +the subject matter hereof. If any provision of this License is held to be +unenforceable, such provision shall be reformed only to the extent necessary to +make it enforceable. + +14) Definition of "You" in This License. "You" throughout this License, whether +in upper or lower case, means an individual or a legal entity exercising rights +under, and complying with all of the terms of, this License. For legal +entities, "You" includes any entity that controls, is controlled by, or is +under common control with you. For purposes of this definition, "control" means +(i) the power, direct or indirect, to cause the direction or management of such +entity, whether by contract or otherwise, or (ii) ownership of fifty percent +(50%) or more of the outstanding shares, or (iii) beneficial ownership of such +entity. + +15) Right to Use. You may use the Original Work in all ways not otherwise +restricted or conditioned by this License or by law, and Licensor promises not +to interfere with or be responsible for such uses by You. + +This license is Copyright (C) 2003-2004 Lawrence E. Rosen. All rights reserved. +Permission is hereby granted to copy and distribute this license without +modification. This license may not be modified without the express written +permission of its copyright owner. diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/TouchScroll.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/TouchScroll.css new file mode 100644 index 00000000..207389e7 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/TouchScroll.css @@ -0,0 +1 @@ +.touchscroll-x, .touchscroll-y {display: none; overflow: hidden; position: absolute; opacity: 0.7;}.touchscroll-fadeout .touchscroll-x, .touchscroll-fadeout .touchscroll-y {opacity: 0; -webkit-transition: opacity 0.3s ease-out 0.1s; -moz-transition: opacity 0.3s ease-out 0.1s; -o-transition: opacity 0.3s ease-out 0.1s; transition: opacity 0.3s ease-out 0.1s;}.touchscroll-bar {background-color: rgba(88,88,88,0.97); border: 1px solid rgba(88,88,88,1); border-radius: 3px; -webkit-box-shadow: 0 0 1px rgba(88,88,88,0.4);}.touchscroll-x {left: 1px; right: 3px; bottom: 1px; height: 5px;}.touchscroll-y {top: 1px; bottom: 3px; right: 1px; width: 5px;}.touchscroll-scrollable-x .touchscroll-x, .touchscroll-scrollable-y .touchscroll-y {display: block;}.touchscroll-bar {-webkit-transition: transform cubic-bezier(0.33, 0.66, 0.66, 1); -moz-transition: transform cubic-bezier(0.33, 0.66, 0.66, 1); -o-transition: transform cubic-bezier(0.33, 0.66, 0.66, 1); transition: transform cubic-bezier(0.33, 0.66, 0.66, 1);}#dgrid-css-TouchScroll-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/columnset.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/columnset.css new file mode 100644 index 00000000..57907f03 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/columnset.css @@ -0,0 +1 @@ +.dgrid-column-set {overflow: hidden; width: 100%; position: relative; height: 100%;}.dgrid-column-set-cell {vertical-align: top; height: 100%;}.dgrid-column-set-scroller-container {font-size: 0; position: absolute; bottom: 0;}.dgrid-autoheight .dgrid-column-set-scroller-container {position: relative;}.dgrid-column-set-scroller {display: inline-block; overflow-x: auto; overflow-y: hidden;}.dgrid-column-set-scroller-content {height: 1px;}html.has-mozilla .dgrid-column-set *:focus, html.has-safari .dgrid-column-set *:focus {border: 1px dotted black; outline: 1px dotted black;}html.has-ie-7 .dgrid-column-set {width: auto;}html.has-quirks .dgrid-column-set {width: 100%;}#dgrid-css-columnset-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/dgrid.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/dgrid.css new file mode 100644 index 00000000..95711d17 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/dgrid.css @@ -0,0 +1 @@ +.dgrid {position: relative; overflow: hidden; border: 1px solid #ddd; height: 30em; display: block;}.dgrid-header {background-color: #eee;}.dgrid-header-row {position: absolute; right: 17px; left: 0;}.dgrid-header-scroll {position: absolute; top: 0; right: 0;}.dgrid-footer {position: absolute; bottom: 0; width: 100%;}.dgrid-header-hidden,html.has-quirks .dgrid-header-hidden .dgrid-cell {font-size: 0; height: 0 !important; border-top: none !important; border-bottom: none !important; margin-top: 0 !important; margin-bottom: 0 !important; padding-top: 0 !important; padding-bottom: 0 !important;}.dgrid-footer-hidden {display: none;}.dgrid-sortable {cursor: pointer;}.dgrid-header, .dgrid-header-row, .dgrid-footer {overflow: hidden; background-color: #eee;}.dgrid-row-table {border-collapse: collapse; border: none; table-layout: fixed; empty-cells: show; width: 100%; height: 100%;}.dgrid-cell {padding: 0px; text-align: left; overflow: hidden; vertical-align: top; border: 1px solid #ddd; border-top-style: none; box-sizing: border-box; -moz-box-sizing: border-box; -ms-box-sizing: border-box; -webkit-box-sizing: border-box;}.dgrid-cell-padding {padding: 3px;}.dgrid-content {position: relative; height: 99%;}.dgrid-scroller {overflow-x: auto; overflow-y: scroll; position: absolute; top: 0px; margin-top: 25px; bottom: 0px; width: 100%;}.dgrid-preload {font-size: 0; line-height: 0;}.dgrid-loading {position: relative; height: 100%;}.dgrid-above {position: absolute; bottom: 0;}.ui-icon {width: 16px; height: 16px; background-image: url('images/ui-icons_222222_256x240.png');}.ui-icon-triangle-1-e {background-position: -32px -16px;}.ui-icon-triangle-1-se {background-position: -48px -16px;}.dgrid-expando-icon {width: 16px; height: 16px;}.dgrid-tree-container {-webkit-transition-duration: 0.3s; -moz-transition-duration: 0.3s; -ms-transition-duration: 0.3s; -o-transition-duration: 0.3s; transition-duration: 0.3s; overflow: hidden;}.dgrid-tree-container.dgrid-tree-resetting {-webkit-transition-duration: 0; -moz-transition-duration: 0; -ms-transition-duration: 0; -o-transition-duration: 0; transition-duration: 0;}.dgrid-sort-arrow {background-position: -64px -16px; display: block; float: right; margin: 0 4px 0 5px; height: 12px;}.dgrid-sort-up .dgrid-sort-arrow {background-position: 0px -16px;}.dgrid-selected {background-color: #bfd6eb;}.dgrid-input {width: 99%;}html.has-mozilla .dgrid *:focus, html.has-opera .dgrid *:focus {outline: 1px dotted;}html.has-ie-6-7.has-no-quirks .dgrid-row-table {width: auto;}html.has-quirks .dgrid-row-table, html.has-ie-6 .dgrid-row-table {height: auto;}html.has-quirks .dgrid-header-scroll,html.has-ie-6 .dgrid-header-scroll {font-size: 0;}html.has-mozilla .dgrid-focus {outline-offset: -1px;}.dgrid-scrollbar-measure {width: 100px; height: 100px; overflow: scroll; position: absolute; top: -9999px;}.dgrid-autoheight {height: auto;}.dgrid-autoheight .dgrid-scroller {position: relative; overflow-y: hidden;}.dgrid-autoheight .dgrid-header-scroll {display: none;}.dgrid-autoheight .dgrid-header {right: 0;}#dgrid-css-dgrid-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/dgrid_rtl.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/dgrid_rtl.css new file mode 100644 index 00000000..a6048716 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/dgrid_rtl.css @@ -0,0 +1 @@ +.dgrid-rtl-swap .dgrid-header-row {right: 0; left: 17px;}.dgrid-rtl-swap .dgrid-header-scroll {left: 0px; right: auto;}.dgrid-rtl .dgrid-cell {text-align: right;}.dgrid-rtl .dgrid-sort-arrow {float: left; margin: 0 5px 0 4px;}.dgrid-rtl .ui-icon-triangle-1-e {background-position: -96px -16px;}.dgrid-rtl .ui-icon-triangle-1-se {background-position: -80px -16px;}.dgrid-rtl .dgrid-pagination .dgrid-status {float: right;}.dgrid-rtl .dgrid-pagination .dgrid-page-size {float: right;}.dgrid-rtl .dgrid-pagination .dgrid-navigation {float: left;}.dgrid-rtl.dgrid-autoheight .dgrid-header {left: 0;}.has-ie-6 .dgrid-rtl .dgrid-header-row {left: auto; right: auto;}#dgrid-css-dgrid_rtl-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnHider.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnHider.css new file mode 100644 index 00000000..f74d4680 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnHider.css @@ -0,0 +1 @@ +.dgrid-hider-toggle {background-position: 0 -192px; background-color: transparent; border: none; cursor: pointer; position: absolute; right: 0; top: 0;}.dgrid-rtl-swap .dgrid-hider-toggle {right: auto; left: 0;}.dgrid-hider-menu {position: absolute; top: 0; right: 17px; width: 184px; background-color: #fff; border: 1px solid black; z-index: 99999; padding: 4px; overflow-x: hidden; overflow-y: auto;}.dgrid-rtl-swap .dgrid-hider-menu {right: auto; left: 17px;}.dgrid-hider-menu-row {position: relative; padding: 2px;}.dgrid-hider-menu-check {position: absolute; top: 2px; left: 2px; padding: 0;}.dgrid-hider-menu-label {display: block; padding-left: 20px;}html.has-quirks .dgrid-hider-menu-check,html.has-ie-6-7 .dgrid-hider-menu-check {top: 0; left: 0;}#dgrid-css-extensions-ColumnHider-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnReorder.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnReorder.css new file mode 100644 index 00000000..ed4ebecf --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnReorder.css @@ -0,0 +1 @@ +.dgrid-header .dojoDndContainer .dgrid-cell {display: table-cell;}.dgrid-header .dojoDndItemBefore {border-left: 2px dotted #000 !important;}.dgrid-header .dojoDndItemAfter {border-right: 2px dotted #000 !important;}#dgrid-css-extensions-ColumnReorder-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnResizer.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnResizer.css new file mode 100644 index 00000000..ba1096ea --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/ColumnResizer.css @@ -0,0 +1 @@ +.dgrid-column-resizer {cursor: col-resize; position: absolute; width: 2px; background-color: #666; z-index: 1000;}.dgrid-resize-guard {cursor: col-resize; position: absolute; bottom: 0; left: 0; right: 0; top: 0;}.dgrid-resize-handle {height: 100px; width: 0; position: absolute; right: -4px; top:-4px; cursor: col-resize; z-index: 999; border-left: 5px solid transparent; outline: none;}html.has-ie-6 .dgrid-resize-handle {border-color: pink; filter: chroma(color=pink);}html.has-mozilla .dgrid .dgrid-resize-handle:focus,html.has-opera .dgrid .dgrid-resize-handle:focus {outline: none;}.dgrid-resize-header-container {height:100%;}html.has-touch .dgrid-resize-handle {border-left: 20px solid transparent;}html.has-touch .dgrid-column-resizer {width: 2px;}html.has-no-quirks .dgrid-resize-header-container {position: relative;}html.has-ie-6 .dgrid-resize-header-container {position: static;}.dgrid-header .dgrid-cell-padding {overflow: hidden;}html.has-ie-6 .dgrid-header .dgrid-cell-padding {margin-right: 4px;}html.has-ie-6 .dgrid-header .dgrid-sort-arrow {margin-right: 0;}html.has-quirks .dgrid-header .dgrid-cell-padding, html.has-ie-6 .dgrid-header .dgrid-cell {position:relative;}#dgrid-css-extensions-ColumnResizer-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/CompoundColumns.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/CompoundColumns.css new file mode 100644 index 00000000..37939279 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/CompoundColumns.css @@ -0,0 +1 @@ +.dgrid-spacer-row {height: 0;}.dgrid-spacer-row th {padding-top: 0; padding-bottom: 0; border-top: none; border-bottom: none;}#dgrid-css-extensions-CompoundColumns-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/Pagination.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/Pagination.css new file mode 100644 index 00000000..fdb31edd --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/extensions/Pagination.css @@ -0,0 +1 @@ +.dgrid-status {padding: 2px;}.dgrid-pagination .dgrid-status {float: left;}.dgrid-pagination .dgrid-navigation, .dgrid-pagination .dgrid-page-size {float: right;}.dgrid-navigation .dgrid-page-link {cursor: pointer; font-weight: bold; text-decoration: none; color: inherit; padding: 0 4px;}.dgrid-first, .dgrid-last, .dgrid-next, .dgrid-previous {font-size: 130%;}.dgrid-pagination .dgrid-page-disabled,.has-ie-6-7 .dgrid-navigation .dgrid-page-disabled,.has-ie.has-quirks .dgrid-navigation .dgrid-page-disabled {color: #aaa; cursor: default;}.dgrid-page-input {margin-top: 1px; width: 2em; text-align: center;}.dgrid-page-size {margin: 1px 4px 0 4px;}#dgrid-css-extensions-Pagination-loaded {display: none;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/images/ui-icons_222222_256x240.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/images/ui-icons_222222_256x240.png new file mode 100644 index 00000000..b273ff11 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/images/ui-icons_222222_256x240.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/images/ui-icons_ffffff_256x240.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/images/ui-icons_ffffff_256x240.png new file mode 100644 index 00000000..5c386cf5 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/images/ui-icons_ffffff_256x240.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/cactus.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/cactus.css new file mode 100644 index 00000000..1662470a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/cactus.css @@ -0,0 +1 @@ +.cactus .dgrid-content {border: none; background: #faffef; color: #000;}.cactus .dgrid-header-row {border-bottom: none;}.cactus .dgrid-header,.cactus .dgrid-footer {color: #fff; background: #333; background: -moz-linear-gradient(top, #4e4e4e 0%, #555555 12%, #636363 25%, #505050 39%, #303030 49%, #000000 50%, #1c1c1c 60%, #292929 76%, #1e1e1e 91%, #141414 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#4e4e4e), color-stop(12%,#555555), color-stop(25%,#636363), color-stop(39%,#505050), color-stop(49%,#303030), color-stop(50%,#000000), color-stop(60%,#1c1c1c), color-stop(76%,#292929), color-stop(91%,#1e1e1e), color-stop(100%,#141414)); background: -webkit-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: -o-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: -ms-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#4e4e4e', endColorstr='#141414',GradientType=0 );}.cactus .dgrid-header th {padding: 7px 3px; font-weight: bold; color: #fff; text-shadow: 0 -1px 0 rgba(0,0,0,.9); border-color: #111; text-transform: uppercase;}.cactus .dgrid-cell {border-color: #bbc581; border-top: none; border-right: none; border-left: none;}.cactus .dgrid-row-even {border-top: 1px solid #FFF;}.cactus .dgrid-row-odd {background: #9a6; background-image: -moz-linear-gradient(top, rgba(185,203,127,1) 0%, rgba(143,160,91,1) 100%); background-image: -webkit-gradient(linear, left top, left bottom, color-stop(0%,rgba(185,203,127,1)), color-stop(100%,rgba(143,160,91,1))); background-image: -webkit-linear-gradient(top, rgba(185,203,127,1) 0%,rgba(143,160,91,1) 100%); background-image: -o-linear-gradient(top, rgba(185,203,127,1) 0%,rgba(143,160,91,1) 100%); background-image: -ms-linear-gradient(top, rgba(185,203,127,1) 0%,rgba(143,160,91,1) 100%); background-image: linear-gradient(top, rgba(185,203,127,1) 0%,rgba(143,160,91,1) 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#b9cb7f', endColorstr='#8fa05b',GradientType=0 ); text-shadow: 0 1px 0 rgba(255,255,255,.9); border-top: 1px solid #ccd595; color: #FFF; text-shadow: 0 -1px 0 rgba(0,0,0,.3);}.cactus .dgrid-row-odd .dgrid-cell {border-top: 1px solid #e9efbd;}.cactus .dgrid-row:hover,.cactus .dgrid-row:hover .dgrid-cell {background: #555; color: #fff; text-shadow: 0 -1px 0 rgba(0,0,0,.9); border-color: #555;}.cactus .dgrid-selected,.cactus .dgrid-selected .dgrid-cell {background: #333; color: #fff; text-shadow: 0 -1px 0 rgba(0,0,0,.9); border-color: #333;}.cactus .dgrid-selected:hover {background: #333; border-color: #333;}.cactus .dgrid-highlight {background: #d6e5a5; filter: none; color: #000; text-shadow: none;}.cactus .dgrid-sort-arrow {background-image: url("../images/ui-icons_ffffff_256x240.png");}.cactus .dgrid-header .dojoDndItemBefore {border-left: 2px dotted #fff !important;}.cactus .dgrid-header .dojoDndItemAfter {border-right: 2px dotted #fff !important;}.has-ie-6-7 .cactus .dgrid-navigation a,.has-ie.has-quirks .cactus .dgrid-navigation a {color: #fff;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/claro.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/claro.css new file mode 100644 index 00000000..a6140a62 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/claro.css @@ -0,0 +1 @@ +.claro .dgrid {border: 1px solid #aaa; background: #fff; color: #000;}.claro .dgrid-header {font-weight: bold;}.claro .dgrid-header,.claro .dgrid-footer {background: #ebf0f5; background: -moz-linear-gradient(top, #ebf0f5 0%, #d5e0ea 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#ebf0f5), color-stop(100%,#d5e0ea)); background: -webkit-linear-gradient(top, #ebf0f5 0%,#d5e0ea 100%); background: -o-linear-gradient(top, #ebf0f5 0%,#d5e0ea 100%); background: -ms-linear-gradient(top, #ebf0f5 0%,#d5e0ea 100%); background: linear-gradient(top, #ebf0f5 0%,#d5e0ea 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#ebf0f5', endColorstr='#d5e0ea',GradientType=0 );}.claro .dgrid-header .dgrid-cell:hover {background: #ebf1f6; background: -moz-linear-gradient(top, #ffffff 0%, #d2e0eb 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#ffffff), color-stop(100%,#d2e0eb)); background: -webkit-linear-gradient(top, #ffffff 0%,#d2e0eb 100%); background: -o-linear-gradient(top, #ffffff 0%,#d2e0eb 100%); background: -ms-linear-gradient(top, #ffffff 0%,#d2e0eb 100%); background: linear-gradient(top, #ffffff 0%,#d2e0eb 100%);}.claro .dgrid-row {-webkit-transition-duration: 0.2s; -moz-transition-duration: 0.2s; -o-transition-duration: 0.2s; transition-duration: 0.2s; -webkit-transition-property: background-color, border-color; -moz-transition-property: background-color, border-color; -o-transition-property: background-color, border-color; transition-property: background-color, border-color; background: url("images/row_back.png") #fff repeat-x;}.has-ie-6 .claro .dgrid-row {background-image: none;}.claro .dgrid-row:hover {background-color: #e9f2fe;}.claro .dgrid-selected {background-color: #cee6fa;}.claro .dgrid-selected:hover {background-color: #9bc6f2;}.claro .dgrid-highlight {background-color: #ff6;}.claro .dgrid-cell {border-color: #edc;}.claro .dgrid-header .dgrid-cell {border-color: #bbb;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/images/row_back.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/images/row_back.png new file mode 100644 index 00000000..b283068d Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/images/row_back.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/nihilo.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/nihilo.css new file mode 100644 index 00000000..4c9a27b1 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/nihilo.css @@ -0,0 +1 @@ +.nihilo .dgrid {border-color: #bba;}.nihilo .dgrid-content {background: #fff; color: #000;}.nihilo .dgrid-header {background: #fff; border-bottom-color: #919191;}.nihilo .dgrid-footer {background: #fff; border-top: 1px solid #919191;}.nihilo .dgrid-header .dgrid-cell {border-right-color: #acab99;}.nihilo .dgrid-selected {background-color: #aec7e3;}.nihilo .dgrid-row:hover {background-color: #ffe284;}.nihilo .dgrid-highlight {background-color: #ff6;}.nihilo .dgrid-cell {border-color: #ddc;}.nihilo .dgrid-header .dgrid-cell {border-color: #bba;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/sage.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/sage.css new file mode 100644 index 00000000..231a6dcd --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/sage.css @@ -0,0 +1 @@ +.sage .dgrid-content {border: none; background: #fff; color: #000; text-shadow: 0 1px 0 rgba(255,255,255,.9);}.sage .dgrid-header-row {border-bottom: none;}.sage .dgrid-header,.sage .dgrid-footer {color: #fff; background: #333; background: -moz-linear-gradient(top, #4e4e4e 0%, #555555 12%, #636363 25%, #505050 39%, #303030 49%, #000000 50%, #1c1c1c 60%, #292929 76%, #1e1e1e 91%, #141414 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#4e4e4e), color-stop(12%,#555555), color-stop(25%,#636363), color-stop(39%,#505050), color-stop(49%,#303030), color-stop(50%,#000000), color-stop(60%,#1c1c1c), color-stop(76%,#292929), color-stop(91%,#1e1e1e), color-stop(100%,#141414)); background: -webkit-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: -o-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: -ms-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#4e4e4e', endColorstr='#141414',GradientType=0 );}.sage .dgrid-header th {padding: 7px 3px; font-weight: bold; color: #fff; text-shadow: 0 -1px 0 rgba(0,0,0,.9); border-color: #111; text-transform: uppercase;}.sage .dgrid-cell {border-color: #bbc581; border-top: none; border-right: none; border-left: none;}.sage .dgrid-row-odd {background: #f2f7e8;}.sage .dgrid-row:hover {background: #c5dca6; color: #333; text-shadow: 0 1px 0 rgba(255,255,255,.5);}.sage .dgrid-row {-webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s; -webkit-transition-property: background-color, border-color; -moz-transition-property: background-color, border-color; transition-property: background-color, border-color;}.sage .dgrid-selected,.sage .dgrid-selected:hover {background: #b3d18b; text-shadow: 0 1px 0 rgba(255,255,255,.6);}.sage .dgrid-highlight {background-color: #d5e8bd;}.sage .dgrid-sort-arrow {background-image: url("../images/ui-icons_ffffff_256x240.png");}.sage .dgrid-header .dojoDndItemBefore {border-left: 2px dotted #fff !important;}.sage .dgrid-header .dojoDndItemAfter {border-right: 2px dotted #fff !important;}.has-ie-6-7 .sage .dgrid-navigation a,.has-ie.has-quirks .sage .dgrid-navigation a {color: #fff;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/slate.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/slate.css new file mode 100644 index 00000000..2ddb60d7 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/slate.css @@ -0,0 +1 @@ +.slate .dgrid-content {background: #fff; color: #000; text-shadow: 0 1px 0 rgba(255,255,255,.9);}.slate .dgrid-header-row {border-bottom: none;}.slate .dgrid-header,.slate .dgrid-footer {color: #fff; background: #333; background: -moz-linear-gradient(top, #4e4e4e 0%, #555555 12%, #636363 25%, #505050 39%, #303030 49%, #000000 50%, #1c1c1c 60%, #292929 76%, #1e1e1e 91%, #141414 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#4e4e4e), color-stop(12%,#555555), color-stop(25%,#636363), color-stop(39%,#505050), color-stop(49%,#303030), color-stop(50%,#000000), color-stop(60%,#1c1c1c), color-stop(76%,#292929), color-stop(91%,#1e1e1e), color-stop(100%,#141414)); background: -webkit-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: -o-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: -ms-linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); background: linear-gradient(top, #4e4e4e 0%,#555555 12%,#636363 25%,#505050 39%,#303030 49%,#000000 50%,#1c1c1c 60%,#292929 76%,#1e1e1e 91%,#141414 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#4e4e4e', endColorstr='#141414',GradientType=0 );}.slate .dgrid-header th {padding: 7px 3px; font-weight: bold; color: #FFF; text-shadow: 0 -1px 0 rgba(0,0,0,.9); border-color: #111; text-transform: uppercase;}.slate .dgrid-row-odd {background-color: #f7f7f7;}.slate .dgrid-row:hover {background-color: #ddd;}.slate .dgrid-selected,.slate .dgrid-selected:hover {background-color: #555; color: #fff; text-shadow: 0 -1px 0 rgba(0,0,0,.5);}.slate .dgrid-highlight {background-color: #999;}.slate .dgrid-sort-arrow {background-image: url("../images/ui-icons_ffffff_256x240.png");}.slate .dgrid-header .dojoDndItemBefore {border-left: 2px dotted #fff !important;}.slate .dgrid-header .dojoDndItemAfter {border-right: 2px dotted #fff !important;}.has-ie-6-7 .slate .dgrid-navigation a,.has-ie.has-quirks .slate .dgrid-navigation a {color: #fff;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/soria.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/soria.css new file mode 100644 index 00000000..64261684 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/soria.css @@ -0,0 +1 @@ +.soria .dgrid {border-color: #bba;}.soria .dgrid-content {background: #fff; color: #000;}.soria .dgrid-header,.soria .dgrid-footer {background: #f2f4fe; background: -moz-linear-gradient(top, #f2f4fe 0%, #d0dff5 50%, #c6d8f0 51%, #c2d5ef 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#f2f4fe), color-stop(50%,#d0dff5), color-stop(51%,#c6d8f0), color-stop(100%,#c2d5ef)); background: -webkit-linear-gradient(top, #f2f4fe 0%,#d0dff5 50%,#c6d8f0 51%,#c2d5ef 100%); background: -o-linear-gradient(top, #f2f4fe 0%,#d0dff5 50%,#c6d8f0 51%,#c2d5ef 100%); background: -ms-linear-gradient(top, #f2f4fe 0%,#d0dff5 50%,#c6d8f0 51%,#c2d5ef 100%); background: linear-gradient(top, #f2f4fe 0%,#d0dff5 50%,#c6d8f0 51%,#c2d5ef 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#f2f4fe', endColorstr='#c2d5ef',GradientType=0 );}.soria .dgrid-header th:hover {background: #d4deec; background: -moz-linear-gradient(top, #dae2ed 0%, #b2c7e8 49%, #a8c1eb 50%, #9ebaec 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#dae2ed), color-stop(49%,#b2c7e8), color-stop(50%,#a8c1eb), color-stop(100%,#9ebaec)); background: -webkit-linear-gradient(top, #dae2ed 0%,#b2c7e8 49%,#a8c1eb 50%,#9ebaec 100%); background: -o-linear-gradient(top, #dae2ed 0%,#b2c7e8 49%,#a8c1eb 50%,#9ebaec 100%); background: -ms-linear-gradient(top, #dae2ed 0%,#b2c7e8 49%,#a8c1eb 50%,#9ebaec 100%); background: linear-gradient(top, #dae2ed 0%,#b2c7e8 49%,#a8c1eb 50%,#9ebaec 100%);}.soria .dgrid-selected {background-color: #aec7e3;}.soria .dgrid-row:hover {background-color: #60a1ea;}.soria .dgrid-highlight {background-color: #ff6;}.soria .dgrid-cell {border-color: #ddc;}.soria .dgrid-header .dgrid-cell {border-color: #bba;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/squid.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/squid.css new file mode 100644 index 00000000..d5e8cab5 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/squid.css @@ -0,0 +1 @@ +.squid .dgrid-content {border: 1px solid #555; background: #000; color: #fff; text-shadow: 0 -1px 0 rgba(0,0,0,.7);}.squid .ui-icon {background-image: url("../images/ui-icons_ffffff_256x240.png");}.squid .dgrid-header {padding: 0 1px;}.squid .dgrid-header,.squid .dgrid-footer {color: #fff; background: #2d1f14; background: -moz-linear-gradient(top, #140e09 0%, #2d1f14 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#140e09), color-stop(100%,#2d1f14)); background: -webkit-linear-gradient(top, #140e09 0%,#2d1f14 100%); background: -o-linear-gradient(top, #140e09 0%,#2d1f14 100%); background: -ms-linear-gradient(top, #140e09 0%,#2d1f14 100%); background: linear-gradient(top, #140e09 0%,#2d1f14 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#140e09', endColorstr='#2d1f14',GradientType=0 ); color: #fff; font-weight: bold;}.squid .dgrid-header:hover {background: #000; background: -moz-linear-gradient(top, #000000 0%, #2d1f14 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#000000), color-stop(100%,#2d1f14)); background: -webkit-linear-gradient(top, #000000 0%,#2d1f14 100%); background: -o-linear-gradient(top, #000000 0%,#2d1f14 100%); background: -ms-linear-gradient(top, #000000 0%,#2d1f14 100%); background: linear-gradient(top, #000000 0%,#2d1f14 100%);}.squid .dgrid-row {-webkit-transition-duration: 0.2s; -moz-transition-duration: 0.2s; transition-duration: 0.2s; -webkit-transition-property: background-color, border-color; -moz-transition-property: background-color, border-color; transition-property: background-color, border-color; background: url("images/row_back.png") #000 repeat-x;}.squid .dgrid-row:hover {background-color: #444;}.has-ie-6 .squid .dgrid-row {background-image: none;}.squid .dgrid-selected {background-color: #64390d; text-shadow: 0 -1px 0 rgba(0,0,0,.3);}.squid .dgrid-selected:hover {background-color: #8b6b4a;}.squid .dgrid-highlight {background-color: #666;}.squid .dgrid-cell {border-color: #ccc;}.squid .dgrid-header .dojoDndItemBefore {border-left: 2px dotted #fff !important;}.squid .dgrid-header .dojoDndItemAfter {border-right: 2px dotted #fff !important;}.has-ie-6-7 .squid .dgrid-navigation a,.has-ie.has-quirks .squid .dgrid-navigation a {color: #fff;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/tundra.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/tundra.css new file mode 100644 index 00000000..63c09924 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dgrid/css/skins/tundra.css @@ -0,0 +1 @@ +.tundra .dgrid {border-color: #bba;}.tundra .dgrid-content {background: #fff; color: #000;}.tundra .dgrid-header, .tundra .dgrid-footer {background: #e8e8e8; background: -moz-linear-gradient(top, #ffffff 0%, #e8e8e8 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#ffffff), color-stop(100%,#e8e8e8)); background: -webkit-linear-gradient(top, #ffffff 0%,#e8e8e8 100%); background: -o-linear-gradient(top, #ffffff 0%,#e8e8e8 100%); background: -ms-linear-gradient(top, #ffffff 0%,#e8e8e8 100%); background: linear-gradient(top, #ffffff 0%,#e8e8e8 100%); filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#ffffff', endColorstr='#e8e8e8',GradientType=0 ); font-weight: bold;}.tundra .dgrid-header th:hover {background: #f6f6f6; background: -moz-linear-gradient(top, #ffffff 0%, #eeeeee 100%); background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#ffffff), color-stop(100%,#eeeeee)); background: -webkit-linear-gradient(top, #ffffff 0%,#eeeeee 100%); background: -o-linear-gradient(top, #ffffff 0%,#eeeeee 100%); background: -ms-linear-gradient(top, #ffffff 0%,#eeeeee 100%); background: linear-gradient(top, #ffffff 0%,#eeeeee 100%);}.tundra .dgrid-selected {background-color: #aec7e3;}.tundra .dgrid-row:hover {background-color: #60a1ea;}.tundra .dgrid-highlight {background-color: #ff6;}.tundra .dgrid-cell {border-color: #ddc;}.tundra .dgrid-header .dgrid-cell {border-color: #bba;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/LICENSE b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/LICENSE new file mode 100644 index 00000000..0f27d7f3 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/LICENSE @@ -0,0 +1,195 @@ +Dojo is available under *either* the terms of the modified BSD license *or* the +Academic Free License version 2.1. As a recipient of Dojo, you may choose which +license to receive this code under (except as noted in per-module LICENSE +files). Some modules may not be the copyright of the Dojo Foundation. These +modules contain explicit declarations of copyright in both the LICENSE files in +the directories in which they reside and in the code itself. No external +contributions are allowed under licenses which are fundamentally incompatible +with the AFL or BSD licenses that Dojo is distributed under. + +The text of the AFL and BSD licenses is reproduced below. + +------------------------------------------------------------------------------- +The "New" BSD License: +********************** + +Copyright (c) 2005-2016, The Dojo Foundation +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of the Dojo Foundation nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +------------------------------------------------------------------------------- +The Academic Free License, v. 2.1: +********************************** + +This Academic Free License (the "License") applies to any original work of +authorship (the "Original Work") whose owner (the "Licensor") has placed the +following notice immediately following the copyright notice for the Original +Work: + +Licensed under the Academic Free License version 2.1 + +1) Grant of Copyright License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license to do the +following: + +a) to reproduce the Original Work in copies; + +b) to prepare derivative works ("Derivative Works") based upon the Original +Work; + +c) to distribute copies of the Original Work and Derivative Works to the +public; + +d) to perform the Original Work publicly; and + +e) to display the Original Work publicly. + +2) Grant of Patent License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license, under patent +claims owned or controlled by the Licensor that are embodied in the Original +Work as furnished by the Licensor, to make, use, sell and offer for sale the +Original Work and Derivative Works. + +3) Grant of Source Code License. The term "Source Code" means the preferred +form of the Original Work for making modifications to it and all available +documentation describing how to modify the Original Work. Licensor hereby +agrees to provide a machine-readable copy of the Source Code of the Original +Work along with each copy of the Original Work that Licensor distributes. +Licensor reserves the right to satisfy this obligation by placing a +machine-readable copy of the Source Code in an information repository +reasonably calculated to permit inexpensive and convenient access by You for as +long as Licensor continues to distribute the Original Work, and by publishing +the address of that information repository in a notice immediately following +the copyright notice that applies to the Original Work. + +4) Exclusions From License Grant. Neither the names of Licensor, nor the names +of any contributors to the Original Work, nor any of their trademarks or +service marks, may be used to endorse or promote products derived from this +Original Work without express prior written permission of the Licensor. Nothing +in this License shall be deemed to grant any rights to trademarks, copyrights, +patents, trade secrets or any other intellectual property of Licensor except as +expressly stated herein. No patent license is granted to make, use, sell or +offer to sell embodiments of any patent claims other than the licensed claims +defined in Section 2. No right is granted to the trademarks of Licensor even if +such marks are included in the Original Work. Nothing in this License shall be +interpreted to prohibit Licensor from licensing under different terms from this +License any Original Work that Licensor otherwise would have a right to +license. + +5) This section intentionally omitted. + +6) Attribution Rights. You must retain, in the Source Code of any Derivative +Works that You create, all copyright, patent or trademark notices from the +Source Code of the Original Work, as well as any notices of licensing and any +descriptive text identified therein as an "Attribution Notice." You must cause +the Source Code for any Derivative Works that You create to carry a prominent +Attribution Notice reasonably calculated to inform recipients that You have +modified the Original Work. + +7) Warranty of Provenance and Disclaimer of Warranty. Licensor warrants that +the copyright in and to the Original Work and the patent rights granted herein +by Licensor are owned by the Licensor or are sublicensed to You under the terms +of this License with the permission of the contributor(s) of those copyrights +and patent rights. Except as expressly stated in the immediately proceeding +sentence, the Original Work is provided under this License on an "AS IS" BASIS +and WITHOUT WARRANTY, either express or implied, including, without limitation, +the warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY OF THE ORIGINAL WORK IS WITH YOU. +This DISCLAIMER OF WARRANTY constitutes an essential part of this License. No +license to Original Work is granted hereunder except under this disclaimer. + +8) Limitation of Liability. Under no circumstances and under no legal theory, +whether in tort (including negligence), contract, or otherwise, shall the +Licensor be liable to any person for any direct, indirect, special, incidental, +or consequential damages of any character arising as a result of this License +or the use of the Original Work including, without limitation, damages for loss +of goodwill, work stoppage, computer failure or malfunction, or any and all +other commercial damages or losses. This limitation of liability shall not +apply to liability for death or personal injury resulting from Licensor's +negligence to the extent applicable law prohibits such limitation. Some +jurisdictions do not allow the exclusion or limitation of incidental or +consequential damages, so this exclusion and limitation may not apply to You. + +9) Acceptance and Termination. If You distribute copies of the Original Work or +a Derivative Work, You must make a reasonable effort under the circumstances to +obtain the express assent of recipients to the terms of this License. Nothing +else but this License (or another written agreement between Licensor and You) +grants You permission to create Derivative Works based upon the Original Work +or to exercise any of the rights granted in Section 1 herein, and any attempt +to do so except under the terms of this License (or another written agreement +between Licensor and You) is expressly prohibited by U.S. copyright law, the +equivalent laws of other countries, and by international treaty. Therefore, by +exercising any of the rights granted to You in Section 1 herein, You indicate +Your acceptance of this License and all of its terms and conditions. + +10) Termination for Patent Action. This License shall terminate automatically +and You may no longer exercise any of the rights granted to You by this License +as of the date You commence an action, including a cross-claim or counterclaim, +against Licensor or any licensee alleging that the Original Work infringes a +patent. This termination provision shall not apply for an action alleging +patent infringement by combinations of the Original Work with other software or +hardware. + +11) Jurisdiction, Venue and Governing Law. Any action or suit relating to this +License may be brought only in the courts of a jurisdiction wherein the +Licensor resides or in which Licensor conducts its primary business, and under +the laws of that jurisdiction excluding its conflict-of-law provisions. The +application of the United Nations Convention on Contracts for the International +Sale of Goods is expressly excluded. Any use of the Original Work outside the +scope of this License or after its termination shall be subject to the +requirements and penalties of the U.S. Copyright Act, 17 U.S.C. § 101 et +seq., the equivalent laws of other countries, and international treaty. This +section shall survive the termination of this License. + +12) Attorneys Fees. In any action to enforce the terms of this License or +seeking damages relating thereto, the prevailing party shall be entitled to +recover its costs and expenses, including, without limitation, reasonable +attorneys' fees and costs incurred in connection with such action, including +any appeal of such action. This section shall survive the termination of this +License. + +13) Miscellaneous. This License represents the complete agreement concerning +the subject matter hereof. If any provision of this License is held to be +unenforceable, such provision shall be reformed only to the extent necessary to +make it enforceable. + +14) Definition of "You" in This License. "You" throughout this License, whether +in upper or lower case, means an individual or a legal entity exercising rights +under, and complying with all of the terms of, this License. For legal +entities, "You" includes any entity that controls, is controlled by, or is +under common control with you. For purposes of this definition, "control" means +(i) the power, direct or indirect, to cause the direction or management of such +entity, whether by contract or otherwise, or (ii) ownership of fifty percent +(50%) or more of the outstanding shares, or (iii) beneficial ownership of such +entity. + +15) Right to Use. You may use the Original Work in all ways not otherwise +restricted or conditioned by this License or by law, and Licensor promises not +to interfere with or be responsible for such uses by You. + +This license is Copyright (C) 2003-2004 Lawrence E. Rosen. All rights reserved. +Permission is hereby granted to copy and distribute this license without +modification. This license may not be modified without the express written +permission of its copyright owner. diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActDisabled.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActDisabled.png new file mode 100644 index 00000000..a348e3c1 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActDisabled.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActDisabled_rtl.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActDisabled_rtl.png new file mode 100644 index 00000000..d5e9ac8b Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActDisabled_rtl.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled.png new file mode 100644 index 00000000..be14bf0a Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled8bit.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled8bit.png new file mode 100644 index 00000000..20092f22 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled8bit.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled8bit_rtl.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled8bit_rtl.png new file mode 100644 index 00000000..7e504ff5 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled8bit_rtl.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled_rtl.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled_rtl.png new file mode 100644 index 00000000..23ff1a37 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/commonIconsObjActEnabled_rtl.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsDisabled.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsDisabled.png new file mode 100644 index 00000000..98160f43 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsDisabled.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsDisabled_rtl.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsDisabled_rtl.png new file mode 100644 index 00000000..a657ef95 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsDisabled_rtl.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsEnabled.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsEnabled.png new file mode 100644 index 00000000..bfc03b58 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsEnabled.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsEnabled_rtl.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsEnabled_rtl.png new file mode 100644 index 00000000..ed1768a9 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/editorIconsEnabled_rtl.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/loadingAnimation.gif b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/loadingAnimation.gif new file mode 100644 index 00000000..f297fcb9 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/loadingAnimation.gif differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/loadingAnimation_rtl.gif b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/loadingAnimation_rtl.gif new file mode 100644 index 00000000..a1aaf625 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/icons/images/loadingAnimation_rtl.gif differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ar/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ar/common.js new file mode 100644 index 00000000..d5cb387f --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ar/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/ar/common", ({ + buttonOk: "حسنا", + buttonCancel: "الغاء", + buttonSave: "حفظ", + itemClose: "اغلاق" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ar/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ar/loading.js new file mode 100644 index 00000000..2c639825 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ar/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/ar/loading", ({ + loadingState: "جاري التحميل...", + errorState: "عفوا، حدث خطأ" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/az/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/az/common.js new file mode 100644 index 00000000..ca676914 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/az/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/az/common", ({ + "buttonOk" : "Ok", + "buttonCancel" : "Ləğv et", + "buttonSave" : "Saxla", + "itemClose" : "Bağla" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/az/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/az/loading.js new file mode 100644 index 00000000..31c98056 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/az/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/az/loading", ({ + "loadingState" : "Yüklənir...", + "errorState" : "Problem yarandı" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bg/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bg/common.js new file mode 100644 index 00000000..edb7a7af --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bg/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/bg/common", ({ + buttonOk: "ОК", + buttonCancel: "Отмени", + buttonSave: "Запази", + itemClose: "Затвори" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bg/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bg/loading.js new file mode 100644 index 00000000..48216190 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bg/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/bg/loading", ({ + loadingState: "Зареждане...", + errorState: "Съжаляваме, възникна грешка" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bs/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bs/common.js new file mode 100644 index 00000000..cb4cb79f --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bs/common.js @@ -0,0 +1,9 @@ +define("dijit/nls/bs/common", { +//begin v1.x content + buttonOk: "OK", + buttonCancel: "Odustani", + buttonSave: "Spremi", + itemClose: "Zatvori" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bs/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bs/loading.js new file mode 100644 index 00000000..76c1aa7c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/bs/loading.js @@ -0,0 +1,7 @@ +define("dijit/nls/bs/loading", { +//begin v1.x content + loadingState: "Učitavanje...", + errorState: "Izvinite, došlo je do greške" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ca/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ca/common.js new file mode 100644 index 00000000..1cc649b9 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ca/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/ca/common", ({ + buttonOk: "D'acord", + buttonCancel: "Cancel·la", + buttonSave: "Desa", + itemClose: "Tanca" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ca/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ca/loading.js new file mode 100644 index 00000000..8beed26d --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ca/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/ca/loading", ({ + loadingState: "S'està carregant...", + errorState: "Ens sap greu. S'ha produït un error." +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/common.js new file mode 100644 index 00000000..e0449ca9 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/common.js @@ -0,0 +1,49 @@ +define("dijit/nls/common", { root: +//begin v1.x content +({ + buttonOk: "OK", + buttonCancel: "Cancel", + buttonSave: "Save", + itemClose: "Close" +}) +//end v1.x content +, +"bs": true, +"mk": true, +"sr": true, +"zh": true, +"zh-tw": true, +"uk": true, +"tr": true, +"th": true, +"sv": true, +"sl": true, +"sk": true, +"ru": true, +"ro": true, +"pt": true, +"pt-pt": true, +"pl": true, +"nl": true, +"nb": true, +"ko": true, +"kk": true, +"ja": true, +"it": true, +"id": true, +"hu": true, +"hr": true, +"he": true, +"fr": true, +"fi": true, +"eu": true, +"es": true, +"el": true, +"de": true, +"da": true, +"cs": true, +"ca": true, +"bg": true, +"az": true, +"ar": true +}); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/cs/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/cs/common.js new file mode 100644 index 00000000..14f49d6b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/cs/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/cs/common", ({ + buttonOk: "OK", + buttonCancel: "Storno", + buttonSave: "Uložit", + itemClose: "Zavřít" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/cs/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/cs/loading.js new file mode 100644 index 00000000..2427fb00 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/cs/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/cs/loading", ({ + loadingState: "Probíhá načítání...", + errorState: "Omlouváme se, došlo k chybě" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/da/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/da/common.js new file mode 100644 index 00000000..77ee211e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/da/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/da/common", ({ + buttonOk: "OK", + buttonCancel: "Annullér", + buttonSave: "Gem", + itemClose: "Luk" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/da/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/da/loading.js new file mode 100644 index 00000000..e0424ee6 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/da/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/da/loading", ({ + loadingState: "Indlæser...", + errorState: "Der er opstået en fejl" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/de/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/de/common.js new file mode 100644 index 00000000..9be3f0f9 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/de/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/de/common", ({ + buttonOk: "OK", + buttonCancel: "Abbrechen", + buttonSave: "Speichern", + itemClose: "Schließen" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/de/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/de/loading.js new file mode 100644 index 00000000..0655f3f5 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/de/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/de/loading", ({ + loadingState: "Wird geladen...", + errorState: "Es ist ein Fehler aufgetreten." +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/el/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/el/common.js new file mode 100644 index 00000000..efcb6175 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/el/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/el/common", ({ + buttonOk: "ΟΚ", + buttonCancel: "Ακύρωση", + buttonSave: "Αποθήκευση", + itemClose: "Κλείσιμο" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/el/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/el/loading.js new file mode 100644 index 00000000..f19d8c64 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/el/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/el/loading", ({ + loadingState: "Φόρτωση...", + errorState: "Σας ζητούμε συγνώμη, παρουσιάστηκε σφάλμα" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/es/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/es/common.js new file mode 100644 index 00000000..5b6be809 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/es/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/es/common", ({ + buttonOk: "Aceptar", + buttonCancel: "Cancelar", + buttonSave: "Guardar", + itemClose: "Cerrar" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/es/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/es/loading.js new file mode 100644 index 00000000..2e0c84ab --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/es/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/es/loading", ({ + loadingState: "Cargando...", + errorState: "Lo siento, se ha producido un error" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/eu/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/eu/common.js new file mode 100644 index 00000000..edff323d --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/eu/common.js @@ -0,0 +1,9 @@ +define("dijit/nls/eu/common", { +//begin v1.x content + buttonOk: "Ados", + buttonCancel: "Utzi", + buttonSave: "Gorde", + itemClose: "Itxi" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/eu/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/eu/loading.js new file mode 100644 index 00000000..ee556098 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/eu/loading.js @@ -0,0 +1,7 @@ +define("dijit/nls/eu/loading", { +//begin v1.x content + loadingState: "Kargatzen...", + errorState: "Barkatu, errorea gertatu da" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fi/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fi/common.js new file mode 100644 index 00000000..1e6a6f42 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fi/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/fi/common", ({ + buttonOk: "OK", + buttonCancel: "Peruuta", + buttonSave: "Tallenna", + itemClose: "Sulje" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fi/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fi/loading.js new file mode 100644 index 00000000..aa118100 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fi/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/fi/loading", ({ + loadingState: "Lataus on meneillään...", + errorState: "On ilmennyt virhe." +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fr/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fr/common.js new file mode 100644 index 00000000..177690ba --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fr/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/fr/common", ({ + buttonOk: "OK", + buttonCancel: "Annuler", + buttonSave: "Enregistrer", + itemClose: "Fermer" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fr/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fr/loading.js new file mode 100644 index 00000000..12dee580 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/fr/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/fr/loading", ({ + loadingState: "Chargement...", + errorState: "Une erreur est survenue" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/he/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/he/common.js new file mode 100644 index 00000000..5a337ac6 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/he/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/he/common", ({ + buttonOk: "אישור", + buttonCancel: "ביטול", + buttonSave: "שמירה", + itemClose: "סגירה" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/he/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/he/loading.js new file mode 100644 index 00000000..6ee23ed6 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/he/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/he/loading", ({ + loadingState: "טעינה...‏", + errorState: "אירעה שגיאה" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hr/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hr/common.js new file mode 100644 index 00000000..80f3e618 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hr/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/hr/common", ({ + buttonOk: "OK", + buttonCancel: "Opoziv", + buttonSave: "Spremi", + itemClose: "Zatvori" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hr/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hr/loading.js new file mode 100644 index 00000000..75ef351a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hr/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/hr/loading", ({ + loadingState: "Učitavanje...", + errorState: "Žao nam je, došlo je do greške" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hu/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hu/common.js new file mode 100644 index 00000000..65803718 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hu/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/hu/common", ({ + buttonOk: "OK", + buttonCancel: "Mégse", + buttonSave: "Mentés", + itemClose: "Bezárás" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hu/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hu/loading.js new file mode 100644 index 00000000..9aa36871 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/hu/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/hu/loading", ({ + loadingState: "Betöltés...", + errorState: "Sajnálom, hiba történt" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/id/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/id/common.js new file mode 100644 index 00000000..6ee4a61b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/id/common.js @@ -0,0 +1,9 @@ +define( +"dijit/nls/id/common", ({ + buttonOk: "OK", + buttonCancel: "Batal", + buttonSave: "Simpan", + itemClose: "Tutup" +}) +); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/id/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/id/loading.js new file mode 100644 index 00000000..c23d54f1 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/id/loading.js @@ -0,0 +1,7 @@ +define( +"dijit/nls/id/loading", ({ + loadingState: "Memuatkan...", + errorState: "Maaf, terjadi kesalahan" +}) +); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/it/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/it/common.js new file mode 100644 index 00000000..41d3fd34 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/it/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/it/common", ({ + buttonOk: "Ok", + buttonCancel: "Annulla", + buttonSave: "Salva", + itemClose: "Chiudi" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/it/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/it/loading.js new file mode 100644 index 00000000..e2a4ea84 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/it/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/it/loading", ({ + loadingState: "Caricamento in corso...", + errorState: "Si è verificato un errore" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ja/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ja/common.js new file mode 100644 index 00000000..ae97a249 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ja/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/ja/common", ({ + buttonOk: "OK", + buttonCancel: "キャンセル", + buttonSave: "保存", + itemClose: "閉じる" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ja/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ja/loading.js new file mode 100644 index 00000000..245a150c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ja/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/ja/loading", ({ + loadingState: "ロード中...", + errorState: "エラーが発生しました。" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/kk/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/kk/common.js new file mode 100644 index 00000000..41b8a2a4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/kk/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/kk/common", ({ + buttonOk: "OK", + buttonCancel: "Болдырмау", + buttonSave: "Сақтау", + itemClose: "Жабу" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/kk/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/kk/loading.js new file mode 100644 index 00000000..2ca42618 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/kk/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/kk/loading", ({ + loadingState: "Қотарылуда...", + errorState: "Кешіріңіз, қате орын алды" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ko/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ko/common.js new file mode 100644 index 00000000..2fb94ce9 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ko/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/ko/common", ({ + buttonOk: "확인", + buttonCancel: "취소", + buttonSave: "저장", + itemClose: "닫기" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ko/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ko/loading.js new file mode 100644 index 00000000..1a1c019e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ko/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/ko/loading", ({ + loadingState: "로드 중...", + errorState: "죄송합니다. 오류가 발생했습니다." +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/loading.js new file mode 100644 index 00000000..288a80ad --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/loading.js @@ -0,0 +1,47 @@ +define("dijit/nls/loading", { root: +//begin v1.x content +({ + loadingState: "Loading...", + errorState: "Sorry, an error occurred" +}) +//end v1.x content +, +"bs": true, +"mk": true, +"sr": true, +"zh": true, +"zh-tw": true, +"uk": true, +"tr": true, +"th": true, +"sv": true, +"sl": true, +"sk": true, +"ru": true, +"ro": true, +"pt": true, +"pt-pt": true, +"pl": true, +"nl": true, +"nb": true, +"ko": true, +"kk": true, +"ja": true, +"it": true, +"id": true, +"hu": true, +"hr": true, +"he": true, +"fr": true, +"fi": true, +"eu": true, +"es": true, +"el": true, +"de": true, +"da": true, +"cs": true, +"ca": true, +"bg": true, +"az": true, +"ar": true +}); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/mk/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/mk/common.js new file mode 100644 index 00000000..384dcba3 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/mk/common.js @@ -0,0 +1,9 @@ +define("dijit/nls/mk/common", { +//begin v1.x content + buttonOk: "OK", + buttonCancel: "Откажи", + buttonSave: "Зачувај", + itemClose: "Затвори" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/mk/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/mk/loading.js new file mode 100644 index 00000000..8c21cbf2 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/mk/loading.js @@ -0,0 +1,7 @@ +define("dijit/nls/mk/loading", { +//begin v1.x content + loadingState: "Вчитување...", + errorState: "Се појави грешка" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nb/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nb/common.js new file mode 100644 index 00000000..a4ba51c8 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nb/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/nb/common", ({ + buttonOk: "OK", + buttonCancel: "Avbryt", + buttonSave: "Lagre", + itemClose: "Lukk" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nb/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nb/loading.js new file mode 100644 index 00000000..220b9049 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nb/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/nb/loading", ({ + loadingState: "Laster inn...", + errorState: "Det oppsto en feil" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nl/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nl/common.js new file mode 100644 index 00000000..6a1997d2 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nl/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/nl/common", ({ + buttonOk: "OK", + buttonCancel: "Annuleren", + buttonSave: "Opslaan", + itemClose: "Sluiten" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nl/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nl/loading.js new file mode 100644 index 00000000..3f2bd58d --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/nl/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/nl/loading", ({ + loadingState: "Bezig met laden...", + errorState: "Er is een fout opgetreden" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pl/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pl/common.js new file mode 100644 index 00000000..d02cbdd0 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pl/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/pl/common", ({ + buttonOk: "OK", + buttonCancel: "Anuluj", + buttonSave: "Zapisz", + itemClose: "Zamknij" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pl/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pl/loading.js new file mode 100644 index 00000000..96bcbf72 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pl/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/pl/loading", ({ + loadingState: "Ładowanie...", + errorState: "Niestety, wystąpił błąd" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt-pt/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt-pt/common.js new file mode 100644 index 00000000..1205cb28 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt-pt/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/pt-pt/common", ({ + buttonOk: "OK", + buttonCancel: "Cancelar", + buttonSave: "Guardar", + itemClose: "Fechar" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt-pt/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt-pt/loading.js new file mode 100644 index 00000000..5409c558 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt-pt/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/pt-pt/loading", ({ + loadingState: "A carregar...", + errorState: "Lamentamos, mas ocorreu um erro" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt/common.js new file mode 100644 index 00000000..e63ec18c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/pt/common", ({ + buttonOk: "OK", + buttonCancel: "Cancelar", + buttonSave: "Salvar", + itemClose: "Fechar" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt/loading.js new file mode 100644 index 00000000..72e1f8d9 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/pt/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/pt/loading", ({ + loadingState: "Carregando...", + errorState: "Desculpe, ocorreu um erro" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ro/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ro/common.js new file mode 100644 index 00000000..bd68178c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ro/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/ro/common", ({ + buttonOk: "OK", + buttonCancel: "Anulare", + buttonSave: "Salvare", + itemClose: "Închidere" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ro/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ro/loading.js new file mode 100644 index 00000000..1fe120e4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ro/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/ro/loading", ({ + loadingState: "Încărcare...", + errorState: "Ne pare rău, a apărut o eroare " +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ru/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ru/common.js new file mode 100644 index 00000000..354a7c88 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ru/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/ru/common", ({ + buttonOk: "OK", + buttonCancel: "Отмена", + buttonSave: "Сохранить", + itemClose: "Закрыть" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ru/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ru/loading.js new file mode 100644 index 00000000..8861e02a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/ru/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/ru/loading", ({ + loadingState: "Загрузка...", + errorState: "Извините, возникла ошибка" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sk/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sk/common.js new file mode 100644 index 00000000..9b9398f6 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sk/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/sk/common", ({ + buttonOk: "OK", + buttonCancel: "Zrušiť", + buttonSave: "Uložiť", + itemClose: "Zatvoriť" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sk/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sk/loading.js new file mode 100644 index 00000000..cd633acf --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sk/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/sk/loading", ({ + loadingState: "Zavádza sa...", + errorState: "Ľutujeme, ale vyskytla sa chyba" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sl/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sl/common.js new file mode 100644 index 00000000..d12fbbd4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sl/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/sl/common", ({ + buttonOk: "V redu", + buttonCancel: "Prekliči", + buttonSave: "Shrani", + itemClose: "Zapri" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sl/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sl/loading.js new file mode 100644 index 00000000..bdd063c2 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sl/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/sl/loading", ({ + loadingState: "Nalaganje ...", + errorState: "Oprostite, prišlo je do napake." +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sr/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sr/common.js new file mode 100644 index 00000000..743c248a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sr/common.js @@ -0,0 +1,9 @@ +define("dijit/nls/sr/common", { +//begin v1.x content + buttonOk: "U redu", + buttonCancel: "Otkaži", + buttonSave: "Sačuvaj", + itemClose: "Zatvori" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sr/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sr/loading.js new file mode 100644 index 00000000..8fe1a542 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sr/loading.js @@ -0,0 +1,7 @@ +define("dijit/nls/sr/loading", { +//begin v1.x content + loadingState: "Učitavanje...", + errorState: "Nažalost, došlo je do greške" +//end v1.x content +}); + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sv/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sv/common.js new file mode 100644 index 00000000..beee35a0 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sv/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/sv/common", ({ + buttonOk: "OK", + buttonCancel: "Avbryt", + buttonSave: "Spara", + itemClose: "Stäng" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sv/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sv/loading.js new file mode 100644 index 00000000..c839060e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/sv/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/sv/loading", ({ + loadingState: "Läser in...", + errorState: "Det har inträffat ett fel." +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/th/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/th/common.js new file mode 100644 index 00000000..9c6337e4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/th/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/th/common", ({ + buttonOk: "ตกลง", + buttonCancel: "ยกเลิก", + buttonSave: "บันทึก", + itemClose: "ปิด" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/th/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/th/loading.js new file mode 100644 index 00000000..9391c9ad --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/th/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/th/loading", ({ + loadingState: "กำลังโหลด...", + errorState: "ขออภัย เกิดข้อผิดพลาด" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/tr/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/tr/common.js new file mode 100644 index 00000000..bbe5754e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/tr/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/tr/common", ({ + buttonOk: "Tamam", + buttonCancel: "İptal", + buttonSave: "Kaydet", + itemClose: "Kapat" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/tr/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/tr/loading.js new file mode 100644 index 00000000..39ce2e99 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/tr/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/tr/loading", ({ + loadingState: "Yükleniyor...", + errorState: "Üzgünüz, bir hata oluştu" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/uk/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/uk/common.js new file mode 100644 index 00000000..9b2098e4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/uk/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/uk/common", ({ + buttonOk: "OK", + buttonCancel: "Скасувати", + buttonSave: "Зберегти", + itemClose: "Закрити" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/uk/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/uk/loading.js new file mode 100644 index 00000000..631a88d6 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/uk/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/uk/loading", ({ + loadingState: "Завантаження...", + errorState: "Сталася помилка" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh-tw/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh-tw/common.js new file mode 100644 index 00000000..856ff725 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh-tw/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/zh-tw/common", ({ + buttonOk: "確定", + buttonCancel: "取消", + buttonSave: "儲存", + itemClose: "關閉" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh-tw/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh-tw/loading.js new file mode 100644 index 00000000..4c7240c1 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh-tw/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/zh-tw/loading", ({ + loadingState: "載入中...", + errorState: "抱歉,發生錯誤" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh/common.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh/common.js new file mode 100644 index 00000000..77250ccd --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh/common.js @@ -0,0 +1,8 @@ +define( +"dijit/nls/zh/common", ({ + buttonOk: "确定", + buttonCancel: "取消", + buttonSave: "保存", + itemClose: "关闭" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh/loading.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh/loading.js new file mode 100644 index 00000000..9c9c1d18 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/nls/zh/loading.js @@ -0,0 +1,6 @@ +define( +"dijit/nls/zh/loading", ({ + loadingState: "正在加载...", + errorState: "对不起,发生了错误" +}) +); diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/claro.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/claro.css new file mode 100644 index 00000000..65812ee7 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/claro.css @@ -0,0 +1 @@ +.dijitReset {margin:0; border:0; padding:0; font: inherit; line-height:normal; color: inherit;}.dj_a11y .dijitReset {-moz-appearance: none;}.dijitInline {display:inline-block; #zoom: 1; #display:inline; border:0; padding:0; vertical-align:middle; #vertical-align: auto;}table.dijitInline {display:inline-table; box-sizing: content-box; -moz-box-sizing: content-box;}.dijitHidden {position: absolute; visibility: hidden;}.dijitHidden * {visibility: hidden !important;}.dijitVisible {display: block !important; position: relative; visibility: visible;}.dj_ie6 .dijitComboBox .dijitInputContainer,.dijitInputContainer {#zoom: 1; overflow: hidden; float: none !important; position: relative;}.dj_ie7 .dijitInputContainer {float: left !important; clear: left; display: inline-block !important;}.dj_ie .dijitSelect input,.dj_ie input.dijitTextBox,.dj_ie .dijitTextBox input {font-size: 100%;}.dijitSelect .dijitButtonText {float: left; vertical-align: top;}TABLE.dijitSelect {padding: 0 !important; border-collapse: separate;}.dijitTextBox .dijitSpinnerButtonContainer,.dijitTextBox .dijitArrowButtonContainer,.dijitValidationTextBox .dijitValidationContainer {float: right; text-align: center;}.dijitSelect input.dijitInputField,.dijitTextBox input.dijitInputField {padding-left: 0 !important; padding-right: 0 !important;}.dijitValidationTextBox .dijitValidationContainer {display: none;}.dijitTeeny {font-size:1px; line-height:1px;}.dijitOffScreen {position: absolute !important; left: -10000px !important; top: -10000px !important;}.dijitPopup {position: absolute; background-color: transparent; margin: 0; border: 0; padding: 0; -webkit-overflow-scrolling: touch;}.dijitPositionOnly {padding: 0 !important; border: 0 !important; background-color: transparent !important; background-image: none !important; height: auto !important; width: auto !important;}.dijitNonPositionOnly {float: none !important; position: static !important; margin: 0 0 0 0 !important; vertical-align: middle !important;}.dijitBackgroundIframe {position: absolute; left: 0; top: 0; width: 100%; height: 100%; z-index: -1; border: 0; padding: 0; margin: 0;}.dijitDisplayNone {display:none !important;}.dijitContainer {overflow: hidden;}.dj_a11y .dijitIcon,.dj_a11y div.dijitArrowButtonInner, .dj_a11y span.dijitArrowButtonInner,.dj_a11y img.dijitArrowButtonInner,.dj_a11y .dijitCalendarIncrementControl,.dj_a11y .dijitTreeExpando {display: none;}.dijitSpinner div.dijitArrowButtonInner {display: block;}.dj_a11y .dijitA11ySideArrow {display: inline !important; cursor: pointer;}.dj_a11y .dijitCalendarDateLabel {padding: 1px; border: 0px !important;}.dj_a11y .dijitCalendarSelectedDate .dijitCalendarDateLabel {border-style: solid !important; border-width: 1px !important; padding: 0;}.dj_a11y .dijitCalendarDateTemplate {padding-bottom: 0.1em !important; border: 0px !important;}.dj_a11y .dijitButtonNode {border: black outset medium !important; padding: 0 !important;}.dj_a11y .dijitArrowButton {padding: 0 !important;}.dj_a11y .dijitButtonContents {margin: 0.15em;}.dj_a11y .dijitTextBoxReadOnly .dijitInputField,.dj_a11y .dijitTextBoxReadOnly .dijitButtonNode {border-style: outset!important; border-width: medium!important; border-color: #999 !important; color:#999 !important;}.dijitButtonNode * {vertical-align: middle;}.dijitSelect .dijitArrowButtonInner,.dijitButtonNode .dijitArrowButtonInner {background: no-repeat center; width: 12px; height: 12px; direction: ltr;}.dijitLeft {background-position:left top; background-repeat:no-repeat;}.dijitStretch {white-space:nowrap; background-repeat:repeat-x;}.dijitRight {#display:inline; background-position:right top; background-repeat:no-repeat;}.dj_gecko .dj_a11y .dijitButtonDisabled .dijitButtonNode {opacity: 0.5;}.dijitToggleButton,.dijitButton,.dijitDropDownButton,.dijitComboButton {margin: 0.2em; vertical-align: middle;}.dijitButtonContents {display: block;}td.dijitButtonContents {display: table-cell;}.dijitButtonNode img {vertical-align:middle;}.dijitToolbar .dijitComboButton {border-collapse: separate;}.dijitToolbar .dijitToggleButton,.dijitToolbar .dijitButton,.dijitToolbar .dijitDropDownButton,.dijitToolbar .dijitComboButton {margin: 0;}.dijitToolbar .dijitButtonContents {padding: 1px 2px;}.dj_webkit .dijitToolbar .dijitDropDownButton {padding-left: 0.3em;}.dj_gecko .dijitToolbar .dijitButtonNode::-moz-focus-inner {padding:0;}.dijitSelect {border:1px solid gray;}.dijitButtonNode {border:1px solid gray; margin:0; line-height:normal; vertical-align: middle; #vertical-align: auto; text-align:center; white-space: nowrap;}.dj_webkit .dijitSpinner .dijitSpinnerButtonContainer {line-height:inherit;}.dijitTextBox .dijitButtonNode {border-width: 0;}.dijitSelect,.dijitSelect *,.dijitButtonNode,.dijitButtonNode * {cursor: pointer; -webkit-tap-highlight-color: transparent;}.dj_ie .dijitButtonNode {zoom: 1;}.dj_ie .dijitButtonNode button {overflow: visible;}div.dijitArrowButton {float: right;}.dijitTextBox {border: solid black 1px; #overflow: hidden; width: 15em; vertical-align: middle;}.dijitTextBoxReadOnly,.dijitTextBoxDisabled {color: gray;}.dj_safari .dijitTextBoxDisabled input {color: #B0B0B0;}.dj_safari textarea.dijitTextAreaDisabled {color: #333;}.dj_gecko .dijitTextBoxReadOnly input.dijitInputField, .dj_gecko .dijitTextBoxDisabled input {-moz-user-input: none;}.dijitPlaceHolder {color: #AAAAAA; font-style: italic; position: absolute; top: 0; left: 0; #filter: ""; white-space: nowrap; pointer-events: none;}.dijitTimeTextBox {width: 8em;}.dijitTextBox input:focus {outline: none;}.dijitTextBoxFocused {outline: 5px -webkit-focus-ring-color;}.dijitSelect input,.dijitTextBox input {float: left;}.dj_ie6 input.dijitTextBox,.dj_ie6 .dijitTextBox input {float: none;}.dijitInputInner {border:0 !important; background-color:transparent !important; width:100% !important; padding-left: 0 !important; padding-right: 0 !important; margin-left: 0 !important; margin-right: 0 !important;}.dj_a11y .dijitTextBox input {margin: 0 !important;}.dijitValidationTextBoxError input.dijitValidationInner,.dijitSelect input,.dijitTextBox input.dijitArrowButtonInner {text-indent: -2em !important; direction: ltr !important; text-align: left !important; height: auto !important; #text-indent: 0 !important; #letter-spacing: -5em !important; #text-align: right !important;}.dj_ie .dijitSelect input,.dj_ie .dijitTextBox input,.dj_ie input.dijitTextBox {overflow-y: visible; line-height: normal;}.dijitSelect .dijitSelectLabel span {line-height: 100%;}.dj_ie .dijitSelect .dijitSelectLabel {line-height: normal;}.dj_ie6 .dijitSelect .dijitSelectLabel,.dj_ie7 .dijitSelect .dijitSelectLabel,.dj_ie8 .dijitSelect .dijitSelectLabel,.dj_iequirks .dijitSelect .dijitSelectLabel,.dijitSelect td,.dj_ie6 .dijitSelect input,.dj_iequirks .dijitSelect input,.dj_ie6 .dijitSelect .dijitValidationContainer,.dj_ie6 .dijitTextBox input,.dj_ie6 input.dijitTextBox,.dj_iequirks .dijitTextBox input.dijitValidationInner,.dj_iequirks .dijitTextBox input.dijitArrowButtonInner,.dj_iequirks .dijitTextBox input.dijitSpinnerButtonInner,.dj_iequirks .dijitTextBox input.dijitInputInner,.dj_iequirks input.dijitTextBox {line-height: 100%;}.dj_a11y input.dijitValidationInner,.dj_a11y input.dijitArrowButtonInner {text-indent: 0 !important; width: 1em !important; #text-align: left !important; color: black !important;}.dijitValidationTextBoxError .dijitValidationContainer {display: inline; cursor: default;}.dijitSpinner .dijitSpinnerButtonContainer,.dijitComboBox .dijitArrowButtonContainer {border-width: 0 0 0 1px !important;}.dj_a11y .dijitSelect .dijitArrowButtonContainer,.dijitToolbar .dijitComboBox .dijitArrowButtonContainer {border-width: 0 !important;}.dijitComboBoxMenu {list-style-type: none;}.dijitSpinner .dijitSpinnerButtonContainer .dijitButtonNode {border-width: 0;}.dj_ie .dj_a11y .dijitSpinner .dijitSpinnerButtonContainer .dijitButtonNode {clear: both;}.dj_ie .dijitToolbar .dijitComboBox {vertical-align: middle;}.dijitTextBox .dijitSpinnerButtonContainer {width: 1em; position: relative !important; overflow: hidden;}.dijitSpinner .dijitSpinnerButtonInner {width:1em; visibility:hidden !important; overflow-x:hidden;}.dijitComboBox .dijitButtonNode,.dijitSpinnerButtonContainer .dijitButtonNode {border-width: 0;}.dj_a11y .dijitSpinnerButtonContainer .dijitButtonNode {border-width: 0px !important; border-style: solid !important;}.dj_a11y .dijitTextBox .dijitSpinnerButtonContainer,.dj_a11y .dijitSpinner .dijitArrowButtonInner,.dj_a11y .dijitSpinnerButtonContainer input {width: 1em !important;}.dj_a11y .dijitSpinner .dijitArrowButtonInner {margin: 0 auto !important;}.dj_ie .dj_a11y .dijitSpinner .dijitArrowButtonInner .dijitInputField {padding-left: 0.3em !important; padding-right: 0.3em !important; margin-left: 0.3em !important; margin-right: 0.3em !important; width: 1.4em !important;}.dj_ie7 .dj_a11y .dijitSpinner .dijitArrowButtonInner .dijitInputField {padding-left: 0 !important; padding-right: 0 !important; width: 1em !important;}.dj_ie6 .dj_a11y .dijitSpinner .dijitArrowButtonInner .dijitInputField {margin-left: 0.1em !important; margin-right: 0.1em !important; width: 1em !important;}.dj_iequirks .dj_a11y .dijitSpinner .dijitArrowButtonInner .dijitInputField {margin-left: 0 !important; margin-right: 0 !important; width: 2em !important;}.dijitSpinner .dijitSpinnerButtonContainer .dijitArrowButton {padding: 0; position: absolute !important; right: 0; float: none; height: 50%; width: 100%; bottom: auto; left: 0; right: auto;}.dj_iequirks .dijitSpinner .dijitSpinnerButtonContainer .dijitArrowButton {width: auto;}.dj_a11y .dijitSpinnerButtonContainer .dijitArrowButton {overflow: visible !important;}.dijitSpinner .dijitSpinnerButtonContainer .dijitDownArrowButton {top: 50%; border-top-width: 1px !important;}.dijitSpinner .dijitSpinnerButtonContainer .dijitUpArrowButton {#bottom: 50%; top: 0;}.dijitSpinner .dijitArrowButtonInner {margin: auto; overflow-x: hidden; height: 100% !important;}.dj_iequirks .dijitSpinner .dijitArrowButtonInner {height: auto !important;}.dijitSpinner .dijitArrowButtonInner .dijitInputField {-moz-transform: scale(0.5); -moz-transform-origin: center top; -webkit-transform: scale(0.5); -webkit-transform-origin: center top; -o-transform: scale(0.5); -o-transform-origin: center top; transform: scale(0.5); transform-origin: left top; padding-top: 0; padding-bottom: 0; padding-left: 0 !important; padding-right: 0 !important; width: 100%; visibility: hidden;}.dj_ie .dijitSpinner .dijitArrowButtonInner .dijitInputField {zoom: 50%;}.dijitSpinner .dijitSpinnerButtonContainer .dijitArrowButtonInner {overflow: hidden;}.dj_a11y .dijitSpinner .dijitSpinnerButtonContainer .dijitArrowButton {width: 100%;}.dj_iequirks .dj_a11y .dijitSpinner .dijitSpinnerButtonContainer .dijitArrowButton {width: 1em;}.dj_a11y .dijitSpinner .dijitArrowButtonInner .dijitInputField {vertical-align:top; visibility: visible;}.dj_a11y .dijitSpinnerButtonContainer {width: 1em;}.dijitCheckBox,.dijitRadio,.dijitCheckBoxInput {padding: 0; border: 0; width: 16px; height: 16px; background-position:center center; background-repeat:no-repeat; overflow: hidden;}.dijitCheckBox input,.dijitRadio input {margin: 0; padding: 0; display: block;}.dijitCheckBoxInput {opacity: 0;}.dj_ie .dijitCheckBoxInput {filter: alpha(opacity=0);}.dj_a11y .dijitCheckBox,.dj_a11y .dijitRadio {width: auto !important; height: auto !important;}.dj_a11y .dijitCheckBoxInput {opacity: 1; filter: none; width: auto; height: auto;}.dj_a11y .dijitFocusedLabel {border: 1px dotted; outline: 0px !important;}.dijitProgressBar {z-index: 0;}.dijitProgressBarEmpty {position:relative;overflow:hidden; border:1px solid black; z-index:0;}.dijitProgressBarFull {position:absolute; overflow:hidden; z-index:-1; top:0; width:100%;}.dj_ie6 .dijitProgressBarFull {height:1.6em;}.dijitProgressBarTile {position:absolute; overflow:hidden; top:0; left:0; bottom:0; right:0; margin:0; padding:0; width: 100%; height:auto; background-color:#aaa; background-attachment: fixed;}.dj_a11y .dijitProgressBarTile {border-width:2px; border-style:solid; background-color:transparent !important;}.dj_ie6 .dijitProgressBarTile {position:static; height:1.6em;}.dijitProgressBarIndeterminate .dijitProgressBarTile {}.dijitProgressBarIndeterminateHighContrastImage {display:none;}.dj_a11y .dijitProgressBarIndeterminate .dijitProgressBarIndeterminateHighContrastImage {display:block; position:absolute; top:0; bottom:0; margin:0; padding:0; width:100%; height:auto;}.dijitProgressBarLabel {display:block; position:static; width:100%; text-align:center; background-color:transparent !important;}.dijitTooltip {position: absolute; z-index: 2000; display: block; left: 0; top: -10000px; overflow: visible;}.dijitTooltipContainer {border: solid black 2px; background: #b8b5b5; color: black; font-size: small;}.dijitTooltipFocusNode {padding: 2px 2px 2px 2px;}.dijitTooltipConnector {position: absolute;}.dj_a11y .dijitTooltipConnector {display: none;}.dijitTooltipData {display:none;}.dijitLayoutContainer {position: relative; display: block; overflow: hidden;}.dijitAlignTop,.dijitAlignBottom,.dijitAlignLeft,.dijitAlignRight {position: absolute; overflow: hidden;}body .dijitAlignClient {position: absolute;}.dijitBorderContainer, .dijitBorderContainerNoGutter {position:relative; overflow: hidden; z-index: 0;}.dijitBorderContainerPane,.dijitBorderContainerNoGutterPane {position: absolute !important; z-index: 2;}.dijitBorderContainer > .dijitTextArea {resize: none;}.dijitGutter {position: absolute; font-size: 1px;}.dijitSplitter {position: absolute; overflow: hidden; z-index: 10; background-color: #fff; border-color: gray; border-style: solid; border-width: 0;}.dj_ie .dijitSplitter {z-index: 1;}.dijitSplitterActive {z-index: 11 !important;}.dijitSplitterCover {position:absolute; z-index:-1; top:0; left:0; width:100%; height:100%;}.dijitSplitterCoverActive {z-index:3 !important;}.dj_ie .dijitSplitterCover {background: white; opacity: 0;}.dj_ie6 .dijitSplitterCover,.dj_ie7 .dijitSplitterCover,.dj_ie8 .dijitSplitterCover {filter: alpha(opacity=0);}.dijitSplitterH {height: 7px; border-top:1px; border-bottom:1px; cursor: row-resize; -webkit-tap-highlight-color: transparent;}.dijitSplitterV {width: 7px; border-left:1px; border-right:1px; cursor: col-resize; -webkit-tap-highlight-color: transparent;}.dijitSplitContainer {position: relative; overflow: hidden; display: block;}.dijitSplitPane {position: absolute;}.dijitSplitContainerSizerH,.dijitSplitContainerSizerV {position:absolute; font-size: 1px; background-color: ThreeDFace; border: 1px solid; border-color: ThreeDHighlight ThreeDShadow ThreeDShadow ThreeDHighlight; margin: 0;}.dijitSplitContainerSizerH .thumb, .dijitSplitterV .dijitSplitterThumb {overflow:hidden; position:absolute; top:49%;}.dijitSplitContainerSizerV .thumb, .dijitSplitterH .dijitSplitterThumb {position:absolute; left:49%;}.dijitSplitterShadow,.dijitSplitContainerVirtualSizerH,.dijitSplitContainerVirtualSizerV {font-size: 1px; background-color: ThreeDShadow; -moz-opacity: 0.5; opacity: 0.5; filter: Alpha(Opacity=50); margin: 0;}.dijitSplitContainerSizerH, .dijitSplitContainerVirtualSizerH {cursor: col-resize;}.dijitSplitContainerSizerV, .dijitSplitContainerVirtualSizerV {cursor: row-resize;}.dj_a11y .dijitSplitterH {border-top:1px solid #d3d3d3 !important; border-bottom:1px solid #d3d3d3 !important;}.dj_a11y .dijitSplitterV {border-left:1px solid #d3d3d3 !important; border-right:1px solid #d3d3d3 !important;}.dijitContentPane {display: block; overflow: auto; -webkit-overflow-scrolling: touch;}.dijitContentPaneSingleChild {overflow: hidden;}.dijitContentPaneLoading .dijitIconLoading,.dijitContentPaneError .dijitIconError {margin-right: 9px;}.dijitTitlePane {display: block; overflow: hidden;}.dijitFieldset {border: 1px solid gray;}.dijitTitlePaneTitle, .dijitFieldsetTitle {cursor: pointer; -webkit-tap-highlight-color: transparent;}.dijitTitlePaneTitleFixedOpen, .dijitTitlePaneTitleFixedClosed,.dijitFieldsetTitleFixedOpen, .dijitFieldsetTitleFixedClosed {cursor: default;}.dijitTitlePaneTitle * {vertical-align: middle;}.dijitTitlePane .dijitArrowNodeInner, .dijitFieldset .dijitArrowNodeInner {display: none;}.dj_a11y .dijitTitlePane .dijitArrowNodeInner, .dj_a11y .dijitFieldset .dijitArrowNodeInner {display: inline; font-family: monospace;}.dj_a11y .dijitTitlePane .dijitArrowNode, .dj_a11y .dijitFieldset .dijitArrowNode {display: none;}.dijitTitlePaneTitleFixedOpen .dijitArrowNode, .dijitTitlePaneTitleFixedOpen .dijitArrowNodeInner,.dijitTitlePaneTitleFixedClosed .dijitArrowNode, .dijitTitlePaneTitleFixedClosed .dijitArrowNodeInner,.dijitFieldsetTitleFixedOpen .dijitArrowNode, .dijitFieldsetTitleFixedOpen .dijitArrowNodeInner,.dijitFieldsetTitleFixedClosed .dijitArrowNode, .dijitFieldsetTitleFixedClosed .dijitArrowNodeInner {display: none !important;}.dj_ie6 .dijitTitlePaneContentOuter,.dj_ie6 .dijitTitlePane .dijitTitlePaneTitle {zoom: 1;}.dijitColorPalette {border: 1px solid #999; background: #fff; position: relative;}.dijitColorPalette .dijitPaletteTable {padding: 2px 3px 3px 3px; position: relative; overflow: hidden; outline: 0; border-collapse: separate;}.dj_ie6 .dijitColorPalette .dijitPaletteTable,.dj_ie7 .dijitColorPalette .dijitPaletteTable,.dj_iequirks .dijitColorPalette .dijitPaletteTable {padding: 0; margin: 2px 3px 3px 3px;}.dijitColorPalette .dijitPaletteCell {font-size: 1px; vertical-align: middle; text-align: center; background: none;}.dijitColorPalette .dijitPaletteImg {padding: 1px; border: 1px solid #999; margin: 2px 1px; cursor: default; font-size: 1px;}.dj_gecko .dijitColorPalette .dijitPaletteImg {padding-bottom: 0;}.dijitColorPalette .dijitColorPaletteSwatch {width: 14px; height: 12px;}.dijitPaletteTable td {padding: 0;}.dijitColorPalette .dijitPaletteCell:hover .dijitPaletteImg {border: 1px solid #000;}.dijitColorPalette .dijitPaletteCell:active .dijitPaletteImg,.dijitColorPalette .dijitPaletteTable .dijitPaletteCellSelected .dijitPaletteImg {border: 2px solid #000; margin: 1px 0;}.dj_a11y .dijitColorPalette .dijitPaletteTable,.dj_a11y .dijitColorPalette .dijitPaletteTable * {background-color: transparent !important;}.dijitAccordionContainer {border:1px solid #b7b7b7; border-top:0 !important;}.dijitAccordionTitle {cursor: pointer; -webkit-tap-highlight-color: transparent;}.dijitAccordionTitleSelected {cursor: default;}.dijitAccordionTitle .arrowTextUp,.dijitAccordionTitle .arrowTextDown {display: none; font-size: 0.65em; font-weight: normal !important;}.dj_a11y .dijitAccordionTitle .arrowTextUp,.dj_a11y .dijitAccordionTitleSelected .arrowTextDown {display: inline;}.dj_a11y .dijitAccordionTitleSelected .arrowTextUp {display: none;}.dijitAccordionChildWrapper {overflow: hidden;}.dijitCalendarContainer table {width: auto; clear: both;}.dijitCalendarContainer th, .dijitCalendarContainer td {padding: 0; vertical-align: middle;}.dijitCalendarMonthContainer {text-align: center;}.dijitCalendarDecrementArrow {float: left;}.dijitCalendarIncrementArrow {float: right;}.dijitCalendarYearLabel {white-space: nowrap;}.dijitCalendarNextYear {margin:0 0 0 0.55em;}.dijitCalendarPreviousYear {margin:0 0.55em 0 0;}.dijitCalendarIncrementControl {vertical-align: middle;}.dijitCalendarIncrementControl,.dijitCalendarDateTemplate,.dijitCalendarMonthLabel,.dijitCalendarPreviousYear,.dijitCalendarNextYear {cursor: pointer; -webkit-tap-highlight-color: transparent;}.dijitCalendarDisabledDate {color: gray; text-decoration: line-through; cursor: default;}.dijitSpacer {position: relative; height: 1px; overflow: hidden; visibility: hidden;}.dijitCalendarMonthMenu .dijitCalendarMonthLabel {text-align:center;}.dijitMenu {border:1px solid black; background-color:white;}.dijitMenuTable {border-collapse:collapse; border-width:0; background-color:white;}.dj_webkit .dijitMenuTable td[colspan="2"]{border-right:hidden;}.dijitMenuItem {text-align: left; white-space: nowrap; padding:.1em .2em; cursor:pointer; -webkit-tap-highlight-color: transparent;}.dijitMenuItem:focus {outline: none}.dijitMenuPassive .dijitMenuItemHover,.dijitMenuItemSelected {background-color:black; color:white;}.dijitMenuItemIcon, .dijitMenuExpand {background-repeat: no-repeat;}.dijitMenuItemDisabled * {opacity:0.5; cursor:default;}.dj_ie .dj_a11y .dijitMenuItemDisabled,.dj_ie .dj_a11y .dijitMenuItemDisabled *,.dj_ie .dijitMenuItemDisabled * {color: gray; filter: alpha(opacity=35);}.dijitMenuItemLabel {vertical-align: middle;}.dj_a11y .dijitMenuItemSelected {border: 1px dotted black !important;}.dj_a11y .dijitMenuItemSelected .dijitMenuItemLabel {border-width: 1px; border-style: solid;}.dj_ie8 .dj_a11y .dijitMenuItemLabel {position:static;}.dijitMenuExpandA11y {display: none;}.dj_a11y .dijitMenuExpandA11y {display: inline;}.dijitMenuSeparator td {border: 0; padding: 0;}.dijitMenuSeparatorTop {height: 50%; margin: 0; margin-top:3px; font-size: 1px;}.dijitMenuSeparatorBottom {height: 50%; margin: 0; margin-bottom:3px; font-size: 1px;}.dijitMenuItemIconChar {display: none; visibility: hidden;}.dj_a11y .dijitMenuItemIconChar {display: inline;}.dijitCheckedMenuItemChecked .dijitMenuItemIconChar,.dijitRadioMenuItemChecked .dijitMenuItemIconChar {visibility: visible;}.dj_ie .dj_a11y .dijitMenuBar .dijitMenuItem {margin: 0;}.dijitStackController .dijitToggleButtonChecked * {cursor: default;}.dijitTabContainer {z-index: 0; overflow: visible;}.dj_ie6 .dijitTabContainer {overflow: hidden;}.dijitTabContainerNoLayout {width: 100%;}.dijitTabContainerBottom-tabs,.dijitTabContainerTop-tabs,.dijitTabContainerLeft-tabs,.dijitTabContainerRight-tabs {z-index: 1; overflow: visible !important;}.dijitTabController {z-index: 1;}.dijitTabContainerBottom-container,.dijitTabContainerTop-container,.dijitTabContainerLeft-container,.dijitTabContainerRight-container {z-index:0; overflow: hidden; border: 1px solid black;}.nowrapTabStrip {width: 50000px; display: block; position: relative; text-align: left; z-index: 1;}.dijitTabListWrapper {overflow: hidden; z-index: 1;}.dj_a11y .tabStripButton img {display: none;}.dijitTabContainerTop-tabs {border-bottom: 1px solid black;}.dijitTabContainerTop-container {border-top: 0;}.dijitTabContainerLeft-tabs {border-right: 1px solid black; float: left;}.dijitTabContainerLeft-container {border-left: 0;}.dijitTabContainerBottom-tabs {border-top: 1px solid black;}.dijitTabContainerBottom-container {border-bottom: 0;}.dijitTabContainerRight-tabs {border-left: 1px solid black; float: left;}.dijitTabContainerRight-container {border-right: 0;}div.dijitTabDisabled, .dj_ie div.dijitTabDisabled {cursor: auto;}.dijitTab {position:relative; cursor:pointer; -webkit-tap-highlight-color: transparent; white-space:nowrap; z-index:3;}.dijitTab * {vertical-align: middle;}.dijitTabChecked {cursor: default;}.dijitTabContainerTop-tabs .dijitTab {top: 1px;}.dijitTabContainerBottom-tabs .dijitTab {top: -1px;}.dijitTabContainerLeft-tabs .dijitTab {left: 1px;}.dijitTabContainerRight-tabs .dijitTab {left: -1px;}.dijitTabContainerTop-tabs .dijitTab,.dijitTabContainerBottom-tabs .dijitTab {display:inline-block; #zoom: 1; #display:inline;}.tabStripButton {z-index: 12;}.dijitTabButtonDisabled .tabStripButton {display: none;}.dijitTabCloseButton {margin-left: 1em;}.dijitTabCloseText {display:none;}.dijitTab .tabLabel {min-height: 15px; display: inline-block;}.dijitNoIcon {display: none;}.dj_ie6 .dijitTab .dijitNoIcon {display: inline; height: 15px; width: 1px;}.dj_a11y .dijitTabCloseButton {background-image: none !important; width: auto !important; height: auto !important;}.dj_a11y .dijitTabCloseText {display: inline;}.dijitTabPane,.dijitStackContainer-child,.dijitAccordionContainer-child {border: none !important;}.dijitInlineEditBoxDisplayMode {border: 1px solid transparent; cursor: text;}.dj_a11y .dijitInlineEditBoxDisplayMode,.dj_ie6 .dijitInlineEditBoxDisplayMode {border: none;}.dijitInlineEditBoxDisplayModeHover,.dj_a11y .dijitInlineEditBoxDisplayModeHover,.dj_ie6 .dijitInlineEditBoxDisplayModeHover {background-color: #e2ebf2; border: solid 1px black;}.dijitInlineEditBoxDisplayModeDisabled {cursor: default;}.dijitTree {overflow: auto; -webkit-tap-highlight-color: transparent;}.dijitTreeContainer {float: left;}.dijitTreeIndent {width: 19px;}.dijitTreeRow, .dijitTreeContent {white-space: nowrap;}.dj_ie .dijitTreeLabel:focus {outline: 1px dotted black;}.dijitTreeRow img {vertical-align: middle;}.dijitTreeContent {cursor: default;}.dijitExpandoText {display: none;}.dj_a11y .dijitExpandoText {display: inline; padding-left: 10px; padding-right: 10px; font-family: monospace; border-style: solid; border-width: thin; cursor: pointer;}.dijitTreeLabel {margin: 0 4px;}.dijitDialog {position: absolute; z-index: 999; overflow: hidden;}.dijitDialogTitleBar {cursor: move;}.dijitDialogFixed .dijitDialogTitleBar {cursor:default;}.dijitDialogCloseIcon {cursor: pointer; -webkit-tap-highlight-color: transparent;}.dijitDialogPaneContent {-webkit-overflow-scrolling: touch;}.dijitDialogUnderlayWrapper {position: absolute; left: 0; top: 0; z-index: 998; display: none; background: transparent !important;}.dijitDialogUnderlay {background: #eee; opacity: 0.5;}.dj_ie .dijitDialogUnderlay {filter: alpha(opacity=50);}.dj_a11y .dijitSpinnerButtonContainer,.dj_a11y .dijitDialog {opacity: 1 !important; background-color: white !important;}.dijitDialog .closeText {display:none; position:absolute;}.dj_a11y .dijitDialog .closeText {display:inline;}.dijitSliderMoveable {z-index:99; position:absolute !important; display:block; vertical-align:middle;}.dijitSliderMoveableH {right:0;}.dijitSliderMoveableV {right:50%;}.dj_a11y div.dijitSliderImageHandle,.dijitSliderImageHandle {margin:0; padding:0; position:relative !important; border:8px solid gray; width:0; height:0; cursor: pointer; -webkit-tap-highlight-color: transparent;}.dj_iequirks .dj_a11y .dijitSliderImageHandle {font-size: 0;}.dj_ie7 .dijitSliderImageHandle {overflow: hidden;}.dj_ie7 .dj_a11y .dijitSliderImageHandle {overflow: visible;}.dj_a11y .dijitSliderFocused .dijitSliderImageHandle {border:4px solid #000; height:8px; width:8px;}.dijitSliderImageHandleV {top:-8px; right: -50%;}.dijitSliderImageHandleH {left:50%; top:-5px; vertical-align:top;}.dijitSliderBar {border-style:solid; border-color:black; cursor: pointer; -webkit-tap-highlight-color: transparent;}.dijitSliderBarContainerV {position:relative; height:100%; z-index:1;}.dijitSliderBarContainerH {position:relative; z-index:1;}.dijitSliderBarH {height:4px; border-width:1px 0;}.dijitSliderBarV {width:4px; border-width:0 1px;}.dijitSliderProgressBar {background-color:red; z-index:1;}.dijitSliderProgressBarV {position:static !important; height:0; vertical-align:top; text-align:left;}.dijitSliderProgressBarH {position:absolute !important; width:0; vertical-align:middle; overflow:visible;}.dijitSliderRemainingBar {overflow:hidden; background-color:transparent; z-index:1;}.dijitSliderRemainingBarV {height:100%; text-align:left;}.dijitSliderRemainingBarH {width:100% !important;}.dijitSliderBumper {overflow:hidden; z-index:1;}.dijitSliderBumperV {width:4px; height:8px; border-width:0 1px;}.dijitSliderBumperH {width:8px; height:4px; border-width:1px 0;}.dijitSliderBottomBumper,.dijitSliderLeftBumper {background-color:red;}.dijitSliderTopBumper,.dijitSliderRightBumper {background-color:transparent;}.dijitSliderDecoration {text-align:center;}.dijitSliderDecorationC,.dijitSliderDecorationV {position: relative;}.dijitSliderDecorationH {width: 100%;}.dijitSliderDecorationV {height: 100%; white-space: nowrap;}.dijitSliderButton {font-family:monospace; margin:0; padding:0; display:block;}.dj_a11y .dijitSliderButtonInner {visibility:visible !important;}.dijitSliderButtonContainer {text-align:center; height:0;}.dijitSliderButtonContainer * {cursor: pointer; -webkit-tap-highlight-color: transparent;}.dijitSlider .dijitButtonNode {padding:0; display:block;}.dijitRuleContainer {position:relative; overflow:visible;}.dijitRuleContainerV {height:100%; line-height:0; float:left; text-align:left;}.dj_opera .dijitRuleContainerV {line-height:2%;}.dj_ie .dijitRuleContainerV {line-height:normal;}.dj_gecko .dijitRuleContainerV {margin:0 0 1px 0;}.dijitRuleMark {position:absolute; border:1px solid black; line-height:0; height:100%;}.dijitRuleMarkH {width:0; border-top-width:0 !important; border-bottom-width:0 !important; border-left-width:0 !important;}.dijitRuleLabelContainer {position:absolute;}.dijitRuleLabelContainerH {text-align:center; display:inline-block;}.dijitRuleLabelH {position:relative; left:-50%;}.dijitRuleLabelV {text-overflow: ellipsis; white-space: nowrap; overflow: hidden;}.dijitRuleMarkV {height:0; border-right-width:0 !important; border-bottom-width:0 !important; border-left-width:0 !important; width:100%; left:0;}.dj_ie .dijitRuleLabelContainerV {margin-top:-.55em;}.dj_a11y .dijitSliderReadOnly,.dj_a11y .dijitSliderDisabled {opacity:0.6;}.dj_ie .dj_a11y .dijitSliderReadOnly .dijitSliderBar,.dj_ie .dj_a11y .dijitSliderDisabled .dijitSliderBar {filter: alpha(opacity=40);}.dj_a11y .dijitSlider .dijitSliderButtonContainer div {font-family: monospace; font-size: 1em; line-height: 1em; height: auto; width: auto; margin: 0 4px;}.dj_a11y .dijitButtonContents .dijitButtonText,.dj_a11y .dijitTab .tabLabel {display: inline !important;}.dj_a11y .dijitSelect .dijitButtonText {display: inline-block !important;}.dijitTextArea {width:100%; overflow-y: auto;}.dijitTextArea[cols] {width:auto;}.dj_ie .dijitTextAreaCols {width:auto;}.dijitExpandingTextArea {resize: none;}.dijitToolbarSeparator {height: 18px; width: 5px; padding: 0 1px; margin: 0;}.dijitIEFixedToolbar {position:absolute; top: expression(eval((document.documentElement||document.body).scrollTop));}.dijitEditor {display: block;}.dijitEditorDisabled,.dijitEditorReadOnly {color: gray;}.dijitTimePicker {background-color: white;}.dijitTimePickerItem {cursor:pointer; -webkit-tap-highlight-color: transparent;}.dijitTimePickerItemHover {background-color:gray; color:white;}.dijitTimePickerItemSelected {font-weight:bold; color:#333; background-color:#b7cdee;}.dijitTimePickerItemDisabled {color:gray; text-decoration:line-through;}.dijitTimePickerItemInner {text-align:center; border:0; padding:2px 8px 2px 8px;}.dijitTimePickerTick,.dijitTimePickerMarker {border-bottom:1px solid gray;}.dijitTimePicker .dijitDownArrowButton {border-top: none !important;}.dijitTimePickerTick {color:#CCC;}.dijitTimePickerMarker {color:black; background-color:#CCC;}.dj_a11y .dijitTimePickerItemSelected .dijitTimePickerItemInner {border: solid 4px black;}.dj_a11y .dijitTimePickerItemHover .dijitTimePickerItemInner {border: dashed 4px black;}.dijitToggleButtonIconChar {display:none !important;}.dj_a11y .dijitToggleButton .dijitToggleButtonIconChar {display:inline !important; visibility:hidden;}.dj_ie6 .dijitToggleButtonIconChar, .dj_ie6 .tabStripButton .dijitButtonText {font-family: "Arial Unicode MS";}.dj_a11y .dijitToggleButtonChecked .dijitToggleButtonIconChar {display: inline !important; visibility:visible !important;}.dijitArrowButtonChar {display:none !important;}.dj_a11y .dijitArrowButtonChar {display:inline !important;}.dj_a11y .dijitDropDownButton .dijitArrowButtonInner,.dj_a11y .dijitComboButton .dijitArrowButtonInner {display:none !important;}.dj_a11y .dijitSelect {border-collapse: separate !important; border-width: 1px; border-style: solid;}.dj_ie .dijitSelect {vertical-align: middle;}.dj_ie6 .dijitSelect .dijitValidationContainer,.dj_ie8 .dijitSelect .dijitButtonText {vertical-align: top;}.dj_ie6 .dijitTextBox .dijitInputContainer,.dj_iequirks .dijitTextBox .dijitInputContainer,.dj_ie6 .dijitTextBox .dijitArrowButtonInner,.dj_ie6 .dijitSpinner .dijitSpinnerButtonInner,.dijitSelect .dijitSelectLabel {vertical-align: baseline;}.dijitNumberTextBox {text-align: left; direction: ltr;}.dijitNumberTextBox .dijitInputInner {text-align: inherit;}.dijitNumberTextBox input.dijitInputInner,.dijitCurrencyTextBox input.dijitInputInner,.dijitSpinner input.dijitInputInner {text-align: right;}.dj_ie8 .dijitNumberTextBox input.dijitInputInner, .dj_ie9 .dijitNumberTextBox input.dijitInputInner,.dj_ie8 .dijitCurrencyTextBox input.dijitInputInner, .dj_ie9 .dijitCurrencyTextBox input.dijitInputInner,.dj_ie8 .dijitSpinner input.dijitInputInner, .dj_ie9 .dijitSpinner input.dijitInputInner {padding-right: 1px !important;}.dijitToolbar .dijitSelect {margin: 0;}.dj_webkit .dijitToolbar .dijitSelect {padding-left: 0.3em;}.dijitSelect .dijitButtonContents {padding: 0; white-space: nowrap; text-align: left; border-style: none solid none none; border-width: 1px;}.dijitSelectFixedWidth .dijitButtonContents {width: 100%;}.dijitSelectMenu .dijitMenuItemIcon {display:none;}.dj_ie6 .dijitSelectMenu .dijitMenuItemLabel,.dj_ie7 .dijitSelectMenu .dijitMenuItemLabel {position: static;}.dijitSelectLabel *{vertical-align: baseline;}.dijitSelectSelectedOption * {font-weight: bold;}.dijitSelectMenu {border-width: 1px;}.dijitForceStatic {position: static !important;}.dijitReadOnly *,.dijitDisabled *,.dijitReadOnly,.dijitDisabled {cursor: default;}.dojoDndItem {padding: 2px; -webkit-touch-callout: none; -webkit-user-select: none;}.dojoDndHorizontal .dojoDndItem {#display: inline; display: inline-block;}.dojoDndItemBefore,.dojoDndItemAfter {border: 0px solid #369;}.dojoDndItemBefore {border-width: 2px 0 0 0; padding: 0 2px 2px 2px;}.dojoDndItemAfter {border-width: 0 0 2px 0; padding: 2px 2px 0 2px;}.dojoDndHorizontal .dojoDndItemBefore {border-width: 0 0 0 2px; padding: 2px 2px 2px 0;}.dojoDndHorizontal .dojoDndItemAfter {border-width: 0 2px 0 0; padding: 2px 0 2px 2px;}.dojoDndItemOver {cursor:pointer;}.dj_gecko .dijitArrowButtonInner INPUT,.dj_gecko INPUT.dijitArrowButtonInner {-moz-user-focus:ignore;}.dijitFocused .dijitMenuItemShortcutKey {text-decoration: underline;}.dijitIconSave,.dijitIconPrint,.dijitIconCut,.dijitIconCopy,.dijitIconClear,.dijitIconDelete,.dijitIconUndo,.dijitIconEdit,.dijitIconNewTask,.dijitIconEditTask,.dijitIconEditProperty,.dijitIconTask,.dijitIconFilter,.dijitIconConfigure,.dijitIconSearch,.dijitIconApplication,.dijitIconBookmark,.dijitIconChart,.dijitIconConnector,.dijitIconDatabase,.dijitIconDocuments,.dijitIconMail,.dijitLeaf,.dijitIconFile,.dijitIconFunction,.dijitIconKey,.dijitIconPackage,.dijitIconSample,.dijitIconTable,.dijitIconUsers,.dijitFolderClosed,.dijitIconFolderClosed,.dijitFolderOpened,.dijitIconFolderOpen,.dijitIconError {background-image: url("../../icons/images/commonIconsObjActEnabled.png"); width: 16px; height: 16px;}.dj_ie6 .dijitIconSave,.dj_ie6 .dijitIconPrint,.dj_ie6 .dijitIconCut,.dj_ie6 .dijitIconCopy,.dj_ie6 .dijitIconClear,.dj_ie6 .dijitIconDelete,.dj_ie6 .dijitIconUndo,.dj_ie6 .dijitIconEdit,.dj_ie6 .dijitIconNewTask,.dj_ie6 .dijitIconEditTask,.dj_ie6 .dijitIconEditProperty,.dj_ie6 .dijitIconTask,.dj_ie6 .dijitIconFilter,.dj_ie6 .dijitIconConfigure,.dj_ie6 .dijitIconSearch,.dj_ie6 .dijitIconApplication,.dj_ie6 .dijitIconBookmark,.dj_ie6 .dijitIconChart,.dj_ie6 .dijitIconConnector,.dj_ie6 .dijitIconDatabase,.dj_ie6 .dijitIconDocuments,.dj_ie6 .dijitIconMail,.dj_ie6 .dijitLeaf,.dj_ie6 .dijitIconFile,.dj_ie6 .dijitIconFunction,.dj_ie6 .dijitIconKey,.dj_ie6 .dijitIconPackage,.dj_ie6 .dijitIconSample,.dj_ie6 .dijitIconTable,.dj_ie6 .dijitIconUsers,.dj_ie6 .dijitFolderClosed,.dj_ie6 .dijitIconFolderClosed,.dj_ie6 .dijitFolderOpened,.dj_ie6 .dijitIconFolderOpen,.dj_ie6 .dijitIconError {background-image: url("../../icons/images/commonIconsObjActEnabled8bit.png");}.dijitDisabled .dijitIconSave,.dijitDisabled .dijitIconPrint,.dijitDisabled .dijitIconCut,.dijitDisabled .dijitIconCopy,.dijitDisabled .dijitIconClear,.dijitDisabled .dijitIconDelete,.dijitDisabled .dijitIconUndo,.dijitDisabled .dijitIconEdit,.dijitDisabled .dijitIconNewTask,.dijitDisabled .dijitIconEditTask,.dijitDisabled .dijitIconEditProperty,.dijitDisabled .dijitIconTask,.dijitDisabled .dijitIconFilter,.dijitDisabled .dijitIconConfigure,.dijitDisabled .dijitIconSearch,.dijitDisabled .dijitIconApplication,.dijitDisabled .dijitIconBookmark,.dijitDisabled .dijitIconChart,.dijitDisabled .dijitIconConnector,.dijitDisabled .dijitIconDatabase,.dijitDisabled .dijitIconDocuments,.dijitDisabled .dijitIconMail,.dijitDisabled .dijitLeaf,.dijitDisabled .dijitIconFile,.dijitDisabled .dijitIconFunction,.dijitDisabled .dijitIconKey,.dijitDisabled .dijitIconPackage,.dijitDisabled .dijitIconSample,.dijitDisabled .dijitIconTable,.dijitDisabled .dijitIconUsers,.dijitDisabled .dijitFolderClosed,.dijitDisabled .dijitIconFolderClosed,.dijitDisabled .dijitFolderOpened,.dijitDisabled .dijitIconFolderOpen,.dijitDisabled .dijitIconError {background-image: url("../../icons/images/commonIconsObjActDisabled.png");}.dijitIconSave {background-position: 0;}.dijitIconPrint {background-position: -16px;}.dijitIconCut {background-position: -32px;}.dijitIconCopy {background-position: -48px;}.dijitIconClear {background-position: -64px;}.dijitIconDelete {background-position: -80px;}.dijitIconUndo {background-position: -96px;}.dijitIconEdit {background-position: -112px;}.dijitIconNewTask {background-position: -128px;}.dijitIconEditTask {background-position: -144px;}.dijitIconEditProperty {background-position: -160px;}.dijitIconTask {background-position: -176px;}.dijitIconFilter {background-position: -192px;}.dijitIconConfigure {background-position: -208px;}.dijitIconSearch {background-position: -224px;}.dijitIconError {background-position: -496px;} .dijitIconApplication {background-position: -240px;}.dijitIconBookmark {background-position: -256px;}.dijitIconChart {background-position: -272px;}.dijitIconConnector {background-position: -288px;}.dijitIconDatabase {background-position: -304px;}.dijitIconDocuments {background-position: -320px;}.dijitIconMail {background-position: -336px;}.dijitIconFile, .dijitLeaf {background-position: -352px;}.dijitIconFunction {background-position: -368px;}.dijitIconKey {background-position: -384px;}.dijitIconPackage{background-position: -400px;}.dijitIconSample {background-position: -416px;}.dijitIconTable {background-position: -432px;}.dijitIconUsers {background-position: -448px;}.dijitIconFolderClosed, .dijitFolderClosed {background-position: -464px;}.dijitIconFolderOpen, .dijitFolderOpened {background-position: -480px;}.dijitIconLoading {background: url("../../icons/images/loadingAnimation.gif") no-repeat; height: 20px; width: 20px;}.claro .dijitPopup {-webkit-box-shadow: 0 1px 5px rgba(0, 0, 0, 0.25); -moz-box-shadow: 0 1px 5px rgba(0, 0, 0, 0.25); box-shadow: 0 1px 5px rgba(0, 0, 0, 0.25);}.claro .dijitTooltipDialogPopup {-webkit-box-shadow: none; -moz-box-shadow: none; box-shadow: none;}.claro .dijitComboBoxHighlightMatch {background-color: #abd6ff;}.claro .dijitFocusedLabel {outline: 1px dotted #494949;}.claro .dojoDndItem {border-color: rgba(0, 0, 0, 0); -webkit-transition-duration: 0.25s; -moz-transition-duration: 0.25s; transition-duration: 0.25s; -webkit-transition-property: background-color, border-color; -moz-transition-property: background-color, border-color; transition-property: background-color, border-color;}.claro .dojoDndItemOver {background-color: #abd6ff; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 1px; border: solid 1px #759dc0; color: #000000;}.claro .dojoDndItemAnchor,.claro .dojoDndItemSelected {background-color: #cfe5fa; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 1px; border: solid 1px #759dc0; color: #000000;}.claro .dojoDndItemBefore,.claro .dojoDndItemAfter {border-color: #759dc0;}.claro table.dojoDndAvatar {border: 1px solid #b5bcc7; border-collapse: collapse; background-color: #ffffff; -webkit-box-shadow: 0 1px 3px rgba(0, 0, 0, 0.25); -moz-box-shadow: 0 1px 3px rgba(0, 0, 0, 0.25); box-shadow: 0 1px 3px rgba(0, 0, 0, 0.25);}.claro .dojoDndAvatarHeader td {height: 20px; padding-left: 21px;}.claro.dojoDndMove .dojoDndAvatarHeader,.claro.dojoDndCopy .dojoDndAvatarHeader {background-image: url("images/dnd.png"); background-repeat: no-repeat; background-position: 2px -122px;}.claro .dojoDndAvatarItem td {padding: 5px;}.claro.dojoDndMove .dojoDndAvatarHeader {background-color: #f58383; background-position: 2px -103px;}.claro.dojoDndCopy .dojoDndAvatarHeader {background-color: #f58383; background-position: 2px -68px;}.claro.dojoDndMove .dojoDndAvatarCanDrop .dojoDndAvatarHeader {background-color: #97e68d; background-position: 2px -33px;}.claro.dojoDndCopy .dojoDndAvatarCanDrop .dojoDndAvatarHeader {background-color: #97e68d; background-position: 2px 2px;}.claro .dijitTextBox,.claro .dijitInputInner {color: #000000;}.claro .dijitValidationTextBoxError .dijitValidationContainer {background-color: #d46464; background-image: url("form/images/error.png"); background-position: top center; border: solid #d46464 0; width: 9px;}.claro .dijitTextBoxError .dijitValidationContainer {border-left-width: 1px;}.claro .dijitValidationTextBoxError .dijitValidationIcon {width: 0; background-color: transparent;}.claro .dijitTextArea,.claro .dijitInputField .dijitPlaceHolder {padding: 2px;}.claro .dijitSelect .dijitInputField,.claro .dijitTextBox .dijitInputField {padding: 1px 2px;}.dj_gecko .claro .dijitTextBox .dijitInputInner,.dj_webkit .claro .dijitTextBox .dijitInputInner {padding-left: 1px; padding-right: 1px;}.claro .dijitSelect,.claro .dijitSelect .dijitButtonContents,.claro .dijitTextBox,.claro .dijitTextBox .dijitButtonNode {border-color: #b5bcc7; -webkit-transition-property: background-color, border; -moz-transition-property: background-color, border; transition-property: background-color, border; -webkit-transition-duration: 0.35s; -moz-transition-duration: 0.35s; transition-duration: 0.35s;}.claro .dijitSelect,.claro .dijitTextBox {background-color: #ffffff;}.claro .dijitSelectHover,.claro .dijitSelectHover .dijitButtonContents,.claro .dijitTextBoxHover,.claro .dijitTextBoxHover .dijitButtonNode {border-color: #759dc0; -webkit-transition-duration: 0.25s; -moz-transition-duration: 0.25s; transition-duration: 0.25s;}.claro .dijitTextBoxHover {background-color: #e5f2fe; background-image: -moz-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -webkit-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -o-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px);}.claro .dijitSelectError,.claro .dijitSelectError .dijitButtonContents,.claro .dijitTextBoxError,.claro .dijitTextBoxError .dijitButtonNode {border-color: #d46464;}.claro .dijitSelectFocused,.claro .dijitSelectFocused .dijitButtonContents,.claro .dijitTextBoxFocused,.claro .dijitTextBoxFocused .dijitButtonNode {border-color: #759dc0; -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.claro .dijitTextBoxFocused {background-color: #ffffff; background-image: -moz-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -webkit-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -o-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px);}.claro .dijitTextBoxFocused .dijitInputContainer {background: #ffffff;}.claro .dijitSelectErrorFocused,.claro .dijitSelectErrorFocused .dijitButtonContents,.claro .dijitTextBoxErrorFocused,.claro .dijitTextBoxErrorFocused .dijitButtonNode {border-color: #ce5050;}.claro .dijitSelectDisabled,.claro .dijitSelectDisabled .dijitButtonContents,.claro .dijitTextBoxDisabled,.claro .dijitTextBoxDisabled .dijitButtonNode {border-color: #d3d3d3;}.claro .dijitSelectDisabled,.claro .dijitTextBoxDisabled,.claro .dijitTextBoxDisabled .dijitInputContainer {background-color: #efefef; background-image: none;}.claro .dijitSelectDisabled,.claro .dijitTextBoxDisabled,.claro .dijitTextBoxDisabled .dijitInputInner {color: #818181;}.dj_webkit .claro .dijitDisabled input {color: #757575;}.dj_webkit .claro textarea.dijitTextAreaDisabled {color: #1b1b1b;}.claro .dijitSelect .dijitArrowButtonInner,.claro .dijitComboBox .dijitArrowButtonInner {background-image: url("form/images/commonFormArrows.png"); background-position: -35px 53%; background-repeat: no-repeat; margin: 0; width: 16px;}.claro .dijitComboBox .dijitArrowButtonInner {border: 1px solid #ffffff;}.claro .dijitToolbar .dijitComboBox .dijitArrowButtonInner {border: none;}.claro .dijitToolbar .dijitComboBox .dijitArrowButtonInner {border: none;}.claro .dijitSelectLabel,.claro .dijitTextBox .dijitInputInner,.claro .dijitValidationTextBox .dijitValidationContainer {padding: 1px 0;}.claro .dijitComboBox .dijitButtonNode {background-color: #efefef; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitComboBoxOpenOnClickHover .dijitButtonNode,.claro .dijitComboBox .dijitDownArrowButtonHover,.claro .dijitComboBoxFocused .dijitArrowButton {background-color: #abd6ff;}.claro .dijitComboBoxOpenOnClickHover .dijitArrowButtonInner,.claro .dijitComboBox .dijitDownArrowButtonHover .dijitArrowButtonInner {background-position: -70px 53%;}.claro .dijitComboBox .dijitHasDropDownOpen {background-color: #7dbdfa; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 1px;}.dj_iequirks .claro .dijitComboBox .dijitHasDropDownOpen {padding: 1px 0;}.claro .dijitComboBox .dijitHasDropDownOpen .dijitArrowButtonInner {background-position: -70px 53%; border: 0 none;}.claro div.dijitComboBoxDisabled .dijitArrowButtonInner {background-position: 0 50%; background-color: #efefef;}.dj_ff3 .claro .dijitInputField input[type="hidden"] {display: none; height: 0; width: 0;}.dj_borderbox .claro .dijitComboBox .dijitHasDropDownOpen .dijitArrowButtonInner {width: 18px;}.dj_borderbox .claro .dijitComboBoxFocused .dijitHasDropDownOpen .dijitArrowButtonInner {width: 16px;}.claro .dijitButtonNode {-webkit-transition-property: background-color; -moz-transition-property: background-color; transition-property: background-color; -webkit-transition-duration: 0.3s; -moz-transition-duration: 0.3s; transition-duration: 0.3s;}.claro .dijitButton .dijitButtonNode,.claro .dijitDropDownButton .dijitButtonNode,.claro .dijitComboButton .dijitButtonNode,.claro .dijitToggleButton .dijitButtonNode {border: 1px solid #759dc0; padding: 2px 4px 4px 4px; color: #000000; -moz-border-radius: 4px; border-radius: 4px; -webkit-box-shadow: 0 1px 1px rgba(0, 0, 0, 0.15); -moz-box-shadow: 0 1px 1px rgba(0, 0, 0, 0.15); box-shadow: 0 1px 1px rgba(0, 0, 0, 0.15); background-color: #bcd8f4; background-image: url("form/images/buttonEnabled.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0) 3px, rgba(255, 255, 255, 0.75) 100%); background-image: -webkit-linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0) 3px, rgba(255, 255, 255, 0.75) 100%); background-image: -o-linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0) 3px, rgba(255, 255, 255, 0.75) 100%); background-image: linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0) 3px, rgba(255, 255, 255, 0.75) 100%); _background-image: none;}.claro .dijitComboButton .dijitArrowButton {border-left-width: 0; padding: 4px 2px 4px 2px;}.claro .dijitArrowButtonInner {width: 15px; height: 15px; margin: 0 auto; background-image: url("form/images/buttonArrows.png"); background-repeat: no-repeat; background-position: -51px 53%;}.claro .dijitLeftArrowButton .dijitArrowButtonInner {background-position: -77px 53%;}.claro .dijitRightArrowButton .dijitArrowButtonInner {background-position: -26px 53%;}.claro .dijitUpArrowButton .dijitArrowButtonInner {background-position: 0 53%;}.claro .dijitDisabled .dijitArrowButtonInner {background-position: -151px 53%;}.claro .dijitDisabled .dijitLeftArrowButton .dijitArrowButtonInner {background-position: -177px 53%;}.claro .dijitDisabled .dijitRightArrowButton .dijitArrowButtonInner {background-position: -126px 53%;}.claro .dijitDisabled .dijitUpArrowButton .dijitArrowButtonInner {background-position: -100px 53%;}.claro .dijitButtonText {padding: 0 0.3em; text-align: center;}.claro .dijitButtonHover .dijitButtonNode,.claro .dijitDropDownButtonHover .dijitButtonNode,.claro .dijitComboButton .dijitButtonNodeHover,.claro .dijitComboButton .dijitDownArrowButtonHover,.claro .dijitToggleButtonHover .dijitButtonNode {background-color: #86bdf2; color: #000000; -webkit-transition-duration: 0.2s; -moz-transition-duration: 0.2s; transition-duration: 0.2s;}.claro .dijitButtonActive .dijitButtonNode,.claro .dijitDropDownButtonActive .dijitButtonNode,.claro .dijitComboButtonActive .dijitButtonNode,.claro .dijitToggleButtonActive .dijitButtonNode,.claro .dijitToggleButtonChecked .dijitButtonNode {background-color: #86bdf2; -webkit-box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2); -moz-box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2); box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2); -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.claro .dijitButtonDisabled,.claro .dijitDropDownButtonDisabled,.claro .dijitComboButtonDisabled,.claro .dijitToggleButtonDisabled {background-image: none; outline: none;}.claro .dijitButtonDisabled .dijitButtonNode,.claro .dijitDropDownButtonDisabled .dijitButtonNode,.claro .dijitComboButtonDisabled .dijitButtonNode,.claro .dijitToggleButtonDisabled .dijitButtonNode {background-color: #efefef; border: solid 1px #d3d3d3; color: #818181; -webkit-box-shadow: 0 0 0 rgba(0, 0, 0, 0); -moz-box-shadow: 0 0 0 rgba(0, 0, 0, 0); box-shadow: 0 0 0 rgba(0, 0, 0, 0); background-image: url("form/images/buttonDisabled.png"); background-image: -moz-linear-gradient(#ffffff 0%, rgba(255, 255, 255, 0) 40%); background-image: -webkit-linear-gradient(#ffffff 0%, rgba(255, 255, 255, 0) 40%); background-image: -o-linear-gradient(#ffffff 0%, rgba(255, 255, 255, 0) 40%); background-image: linear-gradient(#ffffff 0%, rgba(255, 255, 255, 0) 40%); _background-image: none;}.claro .dijitComboButtonDisabled .dijitArrowButton {border-left-width: 0;}.claro table.dijitComboButton {border-collapse: separate;}.claro .dijitComboButton .dijitStretch {-moz-border-radius: 4px 0 0 4px; border-radius: 4px 0 0 4px;}.claro .dijitComboButton .dijitArrowButton {-moz-border-radius: 0 4px 4px 0; border-radius: 0 4px 4px 0;}.claro .dijitToggleButton .dijitCheckBoxIcon {background-image: url("images/checkmarkNoBorder.png");}.dj_ie6 .claro .dijitToggleButton .dijitCheckBoxIcon {background-image: url("images/checkmarkNoBorder.gif");}.claro .dijitCheckBox,.claro .dijitCheckBoxIcon {background-image: url("form/images/checkboxRadioButtonStates.png"); background-repeat: no-repeat; width: 15px; height: 16px; margin: 0 2px 0 0; padding: 0;}.dj_ie6 .claro .dijitCheckBox,.dj_ie6 .claro .dijitCheckBoxIcon {background-image: url("form/images/checkboxAndRadioButtons_IE6.png");}.claro .dijitCheckBox,.claro .dijitToggleButton .dijitCheckBoxIcon {background-position: -15px;}.claro .dijitCheckBoxChecked,.claro .dijitToggleButtonChecked .dijitCheckBoxIcon {background-position: 0;}.claro .dijitCheckBoxDisabled {background-position: -75px;}.claro .dijitCheckBoxCheckedDisabled {background-position: -60px;}.claro .dijitCheckBoxHover {background-position: -45px;}.claro .dijitCheckBoxCheckedHover {background-position: -30px;}.claro .dijitToggleButton .dijitRadio,.claro .dijitToggleButton .dijitRadioIcon {background-image: url("form/images/checkboxRadioButtonStates.png");}.dj_ie6 .claro .dijitToggleButton .dijitRadio,.dj_ie6 .claro .dijitToggleButton .dijitRadioIcon {background-image: url("form/images/checkboxAndRadioButtons_IE6.png");}.claro .dijitRadio,.claro .dijitRadioIcon {background-image: url("form/images/checkboxRadioButtonStates.png"); background-repeat: no-repeat; width: 15px; height: 15px; margin: 0 2px 0 0; padding: 0;}.dj_ie6 .claro .dijitRadio,.dj_ie6 .claro .dijitRadioIcon {background-image: url("form/images/checkboxAndRadioButtons_IE6.png");}.claro .dijitRadio {background-position: -105px;}.claro .dijitToggleButton .dijitRadioIcon {background-position: -107px;}.claro .dijitRadioDisabled {background-position: -165px;}.claro .dijitRadioHover {background-position: -135px;}.claro .dijitRadioChecked {background-position: -90px;}.claro .dijitToggleButtonChecked .dijitRadioIcon {background-position: -92px;}.claro .dijitRadioCheckedHover {background-position: -120px;}.claro .dijitRadioCheckedDisabled {background-position: -150px;}.claro .dijitSelect .dijitArrowButtonContainer {border: 1px solid #ffffff;}.claro .dijitSelect .dijitArrowButton {padding: 0; background-color: #efefef; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitSelect .dijitArrowButton .dijitArrowButtonInner {height: 16px;}.claro .dijitSelectHover {background-color: #e5f2fe; background-image: -moz-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -webkit-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -o-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-repeat: repeat-x;}.claro .dijitSelectHover .dijitArrowButton {background-color: #abd6ff;}.claro .dijitSelectHover .dijitArrowButton .dijitArrowButtonInner {background-position: -70px 53%;}.claro .dijitSelectFocused .dijitArrowButton {background-color: #7dbefa; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitSelectFocused .dijitArrowButton {border: none; padding: 1px;}.claro .dijitSelectFocused .dijitArrowButton .dijitArrowButtonInner {background-position: -70px 53%;}.claro .dijitSelectDisabled {border-color: #d3d3d3; background-color: #efefef; background-image: none; color: #818181;}.claro .dijitSelectDisabled .dijitArrowButton .dijitArrowButtonInner {background-position: 0 53%;}.claro .dijitSelectMenu td.dijitMenuItemIconCell,.claro .dijitSelectMenu td.dijitMenuArrowCell {display: none;}.claro .dijitSelectMenu td.dijitMenuItemLabel {padding: 2px;}.claro .dijitSelectMenu .dijitMenuSeparatorTop {border-bottom: 1px solid #759dc0;}.claro .dijitTabPaneWrapper {background: #ffffff;}.claro .dijitTabPaneWrapper,.claro .dijitTabContainerTop-tabs,.claro .dijitTabContainerBottom-tabs,.claro .dijitTabContainerLeft-tabs,.claro .dijitTabContainerRight-tabs {border-color: #b5bcc7;}.claro .dijitTabCloseButton {background: url("layout/images/tabClose.png") no-repeat; width: 14px; height: 14px; margin-left: 5px; margin-right: -5px;}.claro .dijitTabCloseButtonHover {background-position: -14px;}.claro .dijitTabCloseButtonActive {background-position: -28px;}.claro .dijitTabSpacer {display: none;}.claro .dijitTab {border: 1px solid #b5bcc7; background-color: #efefef; -webkit-transition-property: background-color, border; -moz-transition-property: background-color, border; transition-property: background-color, border; -webkit-transition-duration: 0.35s; -moz-transition-duration: 0.35s; transition-duration: 0.35s; color: #494949;}.claro .dijitTabHover {border-color: #759dc0; background-color: #abd6ff; -webkit-transition-duration: 0.25s; -moz-transition-duration: 0.25s; transition-duration: 0.25s; color: #000000;}.claro .dijitTabActive {border-color: #759dc0; background-color: #7dbdfa; color: #000000; -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.claro .dijitTabChecked {border-color: #b5bcc7; background-color: #cfe5fa; color: #000000;}.claro .dijitTabDisabled {background-color: #d3d3d3;}.claro .tabStripButton {background-color: transparent; border: none;}.claro .dijitTabContainerTop-tabs .dijitTab {top: 1px; margin-right: 1px; padding: 3px 6px; border-bottom-width: 0; min-width: 60px; text-align: center; background-image: url("layout/images/tabTopUnselected.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); -webkit-box-shadow: 0 -1px 1px rgba(0, 0, 0, 0.04); -moz-box-shadow: 0 -1px 1px rgba(0, 0, 0, 0.04); box-shadow: 0 -1px 1px rgba(0, 0, 0, 0.04);}.claro .dijitTabContainerTop-tabs .dijitTabChecked {padding-bottom: 4px; padding-top: 9px; background-image: url("layout/images/tabTopSelected.png"); background-image: -moz-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); background-image: -webkit-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); background-image: -o-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); background-image: linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); -webkit-box-shadow: 0 -1px 2px rgba(0, 0, 0, 0.05); -moz-box-shadow: 0 -1px 2px rgba(0, 0, 0, 0.05); box-shadow: 0 -1px 2px rgba(0, 0, 0, 0.05);}.claro .dijitTabContainerBottom-tabs .dijitTab {top: -1px; margin-right: 1px; padding: 3px 6px; border-top-width: 0; min-width: 60px; text-align: center; background-image: url("layout/images/tabBottomUnselected.png"); background-repeat: repeat-x; background-position: bottom; background-image: -moz-linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); -webkit-box-shadow: 0 1px 1px rgba(0, 0, 0, 0.04); -moz-box-shadow: 0 1px 1px rgba(0, 0, 0, 0.04); box-shadow: 0 1px 1px rgba(0, 0, 0, 0.04);}.claro .dijitTabContainerBottom-tabs .dijitTabChecked {padding-bottom: 9px; padding-top: 4px; background-image: url("layout/images/tabBottomSelected.png"); background-image: -moz-linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); background-image: -webkit-linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); background-image: -o-linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); background-image: linear-gradient(bottom, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px, #ffffff 7px); -webkit-box-shadow: 0 1px 2px rgba(0, 0, 0, 0.05); -moz-box-shadow: 0 1px 2px rgba(0, 0, 0, 0.05); box-shadow: 0 1px 2px rgba(0, 0, 0, 0.05);}.claro .dijitTabContainerLeft-tabs .dijitTab {left: 1px; margin-bottom: 1px; padding: 3px 8px 4px 4px; background-image: url("layout/images/tabLeftUnselected.png"); background-repeat: repeat-y; background-image: -moz-linear-gradient(left, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(left, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(left, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(left, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%);}.claro .dijitTabContainerLeft-tabs .dijitTabChecked {border-right-width: 0; padding-right: 9px; background-image: url("layout/images/tabLeftSelected.png"); background-image: -moz-linear-gradient(left, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); background-image: -webkit-linear-gradient(left, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); background-image: -o-linear-gradient(left, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); background-image: linear-gradient(left, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); -webkit-box-shadow: -1px 0 2px rgba(0, 0, 0, 0.05); -moz-box-shadow: -1px 0 2px rgba(0, 0, 0, 0.05); box-shadow: -1px 0 2px rgba(0, 0, 0, 0.05);}.claro .dijitTabContainerRight-tabs .dijitTab {left: -1px; margin-bottom: 1px; padding: 3px 8px 4px 4px; background-image: url("layout/images/tabRightUnselected.png"); background-repeat: repeat-y; background-position: right; background-image: -moz-linear-gradient(right, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(right, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(right, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(right, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0.1) 2px, rgba(255, 255, 255, 0.6) 7px, rgba(255, 255, 255, 0) 100%);}.claro .dijitTabContainerRight-tabs .dijitTabChecked {padding-left: 5px; border-left-width: 0; background-image: url("layout/images/tabRightSelected.png"); background-image: -moz-linear-gradient(right, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); background-image: -webkit-linear-gradient(right, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); background-image: -o-linear-gradient(right, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); background-image: linear-gradient(right, rgba(255, 255, 255, 0.5) 0px, #ffffff 30px); -webkit-box-shadow: 1px 0 2px rgba(0, 0, 0, 0.07); -moz-box-shadow: 1px 0 2px rgba(0, 0, 0, 0.07); box-shadow: 1px 0 2px rgba(0, 0, 0, 0.07);}.claro .dijitTabContainerTop-tabs .dijitTab {-moz-border-radius: 2px 2px 0 0; border-radius: 2px 2px 0 0;}.claro .dijitTabContainerBottom-tabs .dijitTab {-moz-border-radius: 0 0 2px 2px; border-radius: 0 0 2px 2px;}.claro .dijitTabContainerLeft-tabs .dijitTab {-moz-border-radius: 2px 0 0 2px; border-radius: 2px 0 0 2px;}.claro .dijitTabContainerRight-tabs .dijitTab {-moz-border-radius: 0 2px 2px 0; border-radius: 0 2px 2px 0;}.claro .tabStripButton {background-color: #e5f2fe; border: 1px solid #b5bcc7;}.claro .dijitTabListContainer-top .tabStripButton {padding: 4px 3px; margin-top: 7px; background-image: -moz-linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%);}.claro .dijitTabListContainer-bottom .tabStripButton {padding: 4px 3px; margin-bottom: 7px; background-image: -moz-linear-gradient(bottom, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(bottom, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(bottom, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(bottom, #ffffff 0px, rgba(255, 255, 255, 0.1) 1px, rgba(255, 255, 255, 0.6) 6px, rgba(255, 255, 255, 0) 100%);}.claro .tabStripButtonHover {background-color: #abd6ff;}.claro .tabStripButtonActive {background-color: #7dbdfa;}.claro .dijitTabStripIcon {height: 15px; width: 15px; margin: 0 auto; background: url("form/images/buttonArrows.png") no-repeat -75px 50%; background-color: transparent;}.claro .dijitTabStripSlideRightIcon {background-position: -24px 50%;}.claro .dijitTabStripMenuIcon {background-position: -51px 50%;}.claro .dijitTabListContainer-top .tabStripButtonDisabled,.claro .dijitTabListContainer-bottom .tabStripButtonDisabled {background-color: #d3d3d3; border: 1px solid #b5bcc7;}.claro .tabStripButtonDisabled .dijitTabStripSlideLeftIcon {background-position: -175px 50%;}.claro .tabStripButtonDisabled .dijitTabStripSlideRightIcon {background-position: -124px 50%;}.claro .tabStripButtonDisabled .dijitTabStripMenuIcon {background-position: -151px 50%;}.claro .dijitTabContainerNested .dijitTabListWrapper {height: auto;}.claro .dijitTabContainerNested .dijitTabContainerTop-tabs {border-bottom: solid 1px #b5bcc7; padding: 2px 2px 4px;}.claro .dijitTabContainerTabListNested .dijitTab {background-color: rgba(255, 255, 255, 0); border: none; padding: 4px; border-color: rgba(118, 157, 192, 0); -webkit-transition-property: background-color, border-color; -moz-transition-property: background-color, border-color; transition-property: background-color, border-color; -webkit-transition-duration: 0.3s; -moz-transition-duration: 0.3s; transition-duration: 0.3s; -moz-border-radius: 2px; border-radius: 2px; top: 0; -webkit-box-shadow: none; -moz-box-shadow: none; box-shadow: none; background-image: url("layout/images/tabNested.png") repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.61) 0%, rgba(255, 255, 255, 0) 17%, rgba(255, 255, 255, 0) 83%, rgba(255, 255, 255, 0.61) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.61) 0%, rgba(255, 255, 255, 0) 17%, rgba(255, 255, 255, 0) 83%, rgba(255, 255, 255, 0.61) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.61) 0%, rgba(255, 255, 255, 0) 17%, rgba(255, 255, 255, 0) 83%, rgba(255, 255, 255, 0.61) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.61) 0%, rgba(255, 255, 255, 0) 17%, rgba(255, 255, 255, 0) 83%, rgba(255, 255, 255, 0.61) 100%);}.claro .dijitTabContainerTabListNested .dijitTabHover {background-color: #e5f2fe; border: solid 1px #cfe5fa; padding: 3px; -webkit-transition-duration: 0.2s; -moz-transition-duration: 0.2s; transition-duration: 0.2s;}.claro .dijitTabContainerTabListNested .dijitTabHover .tabLabel {text-decoration: none;}.claro .dijitTabContainerTabListNested .dijitTabActive {border: solid 1px #759dc0; padding: 3px; -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.claro .dijitTabContainerTabListNested .dijitTabChecked {padding: 3px; border: solid 1px #759dc0; background-color: #cfe5fa;}.claro .dijitTabContainerTabListNested .dijitTabChecked .tabLabel {text-decoration: none; background-image: none;}.claro .dijitTabPaneWrapperNested {border: none;}.claro .dijitTabContainer .dijitTab,.claro .dijitTabContainer .tabStripButton {_background-image: none;}.claro .dijitDialog {border: 1px solid #759dc0; -webkit-box-shadow: 0 1px 5px rgba(0, 0, 0, 0.25); -moz-box-shadow: 0 1px 5px rgba(0, 0, 0, 0.25); box-shadow: 0 1px 5px rgba(0, 0, 0, 0.25);}.claro .dijitDialogPaneContent {background: #ffffff repeat-x top left; border-top: 1px solid #759dc0; padding: 10px 8px; position: relative;}.claro .dijitDialogPaneContentArea {margin: -10px -8px; padding: 10px 8px;}.claro .dijitDialogPaneActionBar {background-color: #efefef; padding: 3px 5px 2px 7px; text-align: right; border-top: 1px solid #d3d3d3;}.claro .dijitDialogPaneContent .dijitDialogPaneActionBar {margin: 10px -8px -10px;}.claro .dijitTooltipDialog .dijitDialogPaneActionBar {-webkit-border-bottom-right-radius: 4px; -webkit-border-bottom-left-radius: 4px; border-bottom-right-radius: 4px; border-bottom-left-radius: 4px; -moz-border-radius-bottomright: 4px; -moz-border-radius-bottomleft: 4px; margin: 10px -10px -8px;}.claro .dijitDialogPaneActionBar .dijitButton {float: none;}.claro .dijitDialogTitleBar {border: 1px solid #ffffff; border-top: none; background-color: #abd6ff; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 5px 7px 4px 7px;}.claro .dijitDialogTitle {padding: 0 1px; font-size: 1.091em; color: #000000;}.claro .dijitDialogCloseIcon {background: url("images/dialogCloseIcon.png"); background-repeat: no-repeat; position: absolute; right: 5px; height: 15px; width: 21px;}.dj_ie6 .claro .dijitDialogCloseIcon {background-image: url("images/dialogCloseIcon8bit.png");}.claro .dijitDialogCloseIconHover {background-position: -21px;}.claro .dijitDialogCloseIcon:active {background-position: -42px;}.claro .dijitTooltip,.claro .dijitTooltipDialog {background: transparent;}.dijitTooltipBelow {padding-top: 13px; padding-left: 3px; padding-right: 3px;}.dijitTooltipAbove {padding-bottom: 13px; padding-left: 3px; padding-right: 3px;}.claro .dijitTooltipContainer {background-color: #ffffff; background-image: -moz-linear-gradient(bottom, rgba(207, 229, 250, 0.1) 0px, #ffffff 10px); background-image: -webkit-linear-gradient(bottom, rgba(207, 229, 250, 0.1) 0px, #ffffff 10px); background-image: -o-linear-gradient(bottom, rgba(207, 229, 250, 0.1) 0px, #ffffff 10px); background-image: linear-gradient(bottom, rgba(207, 229, 250, 0.1) 0px, #ffffff 10px); background-position: bottom; border: 1px solid #759dc0; padding: 6px 8px; -moz-border-radius: 4px; border-radius: 4px; -webkit-box-shadow: 0 1px 3px rgba(0, 0, 0, 0.25); -moz-box-shadow: 0 1px 3px rgba(0, 0, 0, 0.25); box-shadow: 0 1px 3px rgba(0, 0, 0, 0.25); font-size: 1em; color: #000000;}.claro .dijitTooltipConnector {border: 0; z-index: 2; background-image: url("images/tooltip.png"); background-repeat: no-repeat; width: 16px; height: 14px;}.dj_ie6 .claro .dijitTooltipConnector {background-image: url("images/tooltip8bit.png");}.claro .dijitTooltipBelow .dijitTooltipConnector {top: 0; left: 3px; background-position: -31px 0; width: 16px; height: 14px;}.claro .dijitTooltipAbove .dijitTooltipConnector {bottom: 0; left: 3px; background-position: -15px 0; width: 16px; height: 14px;}.dj_ie7 .claro .dijitTooltipAbove .dijitTooltipConnector,.dj_ie6 .claro .dijitTooltipAbove .dijitTooltipConnector {bottom: -1px;}.claro .dijitTooltipABRight .dijitTooltipConnector {left: auto; right: 3px;}.claro .dijitTooltipLeft {padding-right: 14px;}.claro .dijitTooltipLeft .dijitTooltipConnector {right: 0; background-position: 0 0; width: 16px; height: 14px;}.claro .dijitTooltipRight {padding-left: 14px;}.claro .dijitTooltipRight .dijitTooltipConnector {left: 0; background-position: -48px 0; width: 16px; height: 14px;}.claro .dijitDialogUnderlay {background: #ffffff;}.claro .dijitAccordionContainer {border: none;}.claro .dijitAccordionInnerContainer {background-color: #efefef; border: solid 1px #b5bcc7; margin-bottom: 1px; -webkit-transition-property: background-color, border; -moz-transition-property: background-color, border; transition-property: background-color, border; -webkit-transition-duration: 0.3s; -moz-transition-duration: 0.3s; transition-duration: 0.3s; -webkit-transition-timing-function: linear; -moz-transition-timing-function: linear; transition-timing-function: linear;}.claro .dijitAccordionTitle {background-color: transparent; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 5px 7px 2px 7px; min-height: 17px; color: #494949;}.claro .dijitAccordionContainer .dijitAccordionChildWrapper {background-color: #ffffff; border: 1px solid #759dc0; margin: 0 2px 2px;}.claro .dijitAccordionContainer .dijitAccordionContainer-child {padding: 9px;}.claro .dijitAccordionInnerContainerHover {border: 1px solid #759dc0; background-color: #abd6ff; -webkit-transition-duration: 0.2s; -moz-transition-duration: 0.2s; transition-duration: 0.2s;}.claro .dijitAccordionInnerContainerHover .dijitAccordionTitle {color: #000000;}.claro .dijitAccordionInnerContainerActive {border: 1px solid #759dc0; background-color: #7dbdfa; -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.claro .dijitAccordionInnerContainerActive .dijitAccordionTitle {background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none; color: #000000;}.claro .dijitAccordionInnerContainerSelected {border-color: #759dc0; background-color: #cfe5fa;}.claro .dijitAccordionInnerContainerSelected .dijitAccordionTitle {color: #000000; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitContentPane {padding: 8px;}.claro .dijitTabContainerTop-dijitContentPane,.claro .dijitTabContainerLeft-dijitContentPane,.claro .dijitTabContainerBottom-dijitContentPane,.claro .dijitTabContainerRight-dijitContentPane,.claro .dijitAccordionContainer-dijitContentPane {background-color: #ffffff; padding: 8px;}.claro .dijitSplitContainer-dijitContentPane,.claro .dijitBorderContainer-dijitContentPane {background-color: #ffffff; padding: 8px;}.claro .dijitCalendar {border: solid 1px #b5bcc7; -moz-border-radius: 4px; border-radius: 4px; background-color: #cfe5fa; background-image: url("images/calendar.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0.4) 2px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0.4) 2px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0.4) 2px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(#ffffff 0px, rgba(255, 255, 255, 0.4) 2px, rgba(255, 255, 255, 0) 100%); text-align: center; padding: 6px 5px 3px 5px;}.dj_ie6 .claro .dijitCalendar {background-image: none;}.claro .dijitCalendar img {border: none;}.claro .dijitCalendarHover,.claro .dijitCalendar:hover,.claro .dijitCalendarActive {background-color: #abd6ff; border: solid 1px #759dc0;}.claro .dijitCalendar table {border-collapse: separate;}.claro .dijitCalendarMonthContainer th {text-align: center; padding-bottom: 4px; vertical-align: middle;}.claro .dijitCalendarMonthLabel {color: #000000; font-size: 1.091em; padding: 0 4px;}.claro .dijitCalendarIncrementControl {width: 18px; height: 16px; background-image: url("images/calendarArrows.png"); background-repeat: no-repeat;}.dj_ie6 .claro .dijitCalendarIncrementControl {background-image: url("images/calendarArrows8bit.png");}.claro .dijitCalendarIncrease {background-position: -18px 0;}.claro .dijitCalendarArrowHover .dijitCalendarDecrease,.claro .dijitCalendarArrow:hover .dijitCalendarDecrease {background-position: -36px 0;}.claro .dijitCalendarArrowHover .dijitCalendarIncrease,.claro .dijitCalendarArrow:hover .dijitCalendarIncrease {background-position: -55px 0;}.claro .dijitCalendarArrowActive .dijitCalendarDecrease,.claro .dijitCalendarArrow:active .dijitCalendarDecrease {background-position: -72px 0;}.claro .dijitCalendarArrowActive .dijitCalendarIncrease,.claro .dijitCalendarArrow:active .dijitCalendarIncrease {background-position: -91px 0;}.claro .dijitA11ySideArrow {display: none;}.claro .dijitCalendarDayLabelTemplate {padding-bottom: 0; text-align: center; border-bottom: 1px solid #b5bcc7; padding: 0 3px 2px;}.claro .dijitCalendarDayLabel {padding: 0 4px 0 4px; font-weight: bold; font-size: 0.909em; text-align: center; color: #000000;}.claro .dijitCalendarDateTemplate {background-color: #ffffff; border-bottom: 1px solid #d3d3d3; padding-top: 0; font-size: 0.909em; font-family: Arial; font-weight: bold; letter-spacing: .05em; text-align: center; color: #000000;}.dj_ie6 .claro .dijitCalendarDateTemplate {background-image: none;}.claro .dijitCalendarPreviousMonth,.claro .dijitCalendarNextMonth {background-color: #e5f2fe; background-image: none; border-bottom: solid 1px #d3d3d3;}.claro .dijitCalendarDateTemplate .dijitCalendarDateLabel {text-decoration: none; display: block; padding: 3px 5px 3px 4px; border: solid 1px #ffffff; background-color: rgba(171, 212, 251, 0); -webkit-transition-property: background-color, border; -moz-transition-property: background-color, border; transition-property: background-color, border; -webkit-transition-duration: 0.35s; -moz-transition-duration: 0.35s; transition-duration: 0.35s;}.claro .dijitCalendarPreviousMonth .dijitCalendarDateLabel,.claro .dijitCalendarNextMonth .dijitCalendarDateLabel {color: #759dc0; border-color: #e5f2fe;}.claro .dijitCalendarYearContainer {vertical-align: middle;}.claro .dijitCalendarYearControl {padding: 1px 2px 2px 2px;}.claro .dijitCalendarYearLabel {padding: 2px 0 0 0; margin: 0; font-size: 1.17em;}.claro .dijitCalendarYearLabel span {vertical-align: middle;}.claro .dijitCalendarSelectedYear {padding: 0 3px;}.claro .dijitCalendarNextYear,.claro .dijitCalendarPreviousYear {padding: 1px 6px 1px 6px; font-size: 0.909em;}.claro .dijitCalendarSelectedYear {font-size: 1.091em; color: #000000;}.claro .dijitCalendarHoveredDate .dijitCalendarDateLabel,.claro .dijitCalendarLite .dijitCalendarEnabledDate:hover .dijitCalendarDateLabel {background-color: #abd6ff; border: solid 1px #759dc0; color: #000000; -webkit-transition-duration: 0.2s; -moz-transition-duration: 0.2s; transition-duration: 0.2s;}.claro .dijitCalendarNextYearHover,.claro .dijitCalendarNextYear:hover,.claro .dijitCalendarPreviousYearHover,.claro .dijitCalendarPreviousYear:hover {color: #000000; border: solid 1px #ffffff; padding: 0 5px 0 5px; background-color: #e5f2fe;}.claro .dijitCalendarNextYearActive,.claro .dijitCalendarNextYear:active .claro .dijitCalendarPreviousYearActive,.claro .dijitCalendarPreviousYear:active {border: solid 1px #759dc0; padding: 0 5px 0 5px; background-color: #7dbdfa;}.claro .dijitCalendarActiveDate .dijitCalendarDateLabel,.claro .dijitCalendarEnabledDate:active .dijitCalendarDateLabel {background-color: #7dbdfa; border: solid 1px #ffffff; -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.dj_ie6 .claro .dijitCalendarActiveDate .dijitCalendarDateLabel {background-image: none;}.claro .dijitCalendarSelectedDate .dijitCalendarDateLabel {color: #000000; background-color: #abd6ff; border-color: #759dc0;}.claro .dijitCalendarDisabledDate .dijitCalendarDateLabel {color: #818181; text-decoration: line-through;}.claro .dijitCalendar .dijitDropDownButton {margin: 0;}.claro .dijitCalendar .dijitButtonText {padding: 1px 0 3px; margin-right: -4px;}.claro .dijitCalendar .dijitDropDownButton .dijitButtonNode {padding: 0 3px 0 2px; border: solid 1px #b5bcc7; -webkit-box-shadow: 0 0 0 rgba(0, 0, 0, 0); -moz-box-shadow: 0 0 0 rgba(0, 0, 0, 0); box-shadow: 0 0 0 rgba(0, 0, 0, 0); background-color: transparent; background-image: none;}.claro .dijitCalendar .dijitDropDownButtonHover .dijitButtonNode,.claro .dijitCalendar .dijitDropDownButton:hover .dijitButtonNode {background-color: #e5f2fe; border: solid 1px #ffffff;}.claro .dijitCalendarMonthMenu {border-color: #759dc0; background-color: #ffffff; text-align: center; background-image: none;}.claro .dijitCalendarMonthMenu .dijitCalendarMonthLabel {border-top: solid 1px #ffffff; border-bottom: solid 1px #ffffff; padding: 2px 0;}.claro .dijitCalendarMonthMenu .dijitCalendarMonthLabelHover,.claro .dijitCalendarMonthMenu .dijitCalendarMonthLabelActive {border-color: #759dc0; border-width: 1px 0; background-color: #abd6ff; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7), rgba(255, 255, 255, 0)); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7), rgba(255, 255, 255, 0)); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7), rgba(255, 255, 255, 0)); background-image: linear-gradient(rgba(255, 255, 255, 0.7), rgba(255, 255, 255, 0)); filter: progid:DXImageTransform.Microsoft.gradient(startColorstr= #ffffff , endColorstr= #abd6ff );}.claro .dijitMenuBar {border: 1px solid #b5bcc7; margin: 0; padding: 0; background-color: #efefef; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitMenu {background-color: #ffffff; border: 1px solid #759dc0;}.claro .dijitMenuItem {color: #000000;}.claro .dijitMenuBar .dijitMenuItem {padding: 6px 10px 7px; margin: -1px;}.claro .dijitMenuBar .dijitMenuItemHover,.claro .dijitMenuBar .dijitMenuItemSelected {border: solid 1px #759dc0; padding: 5px 9px 6px;}.claro .dijitMenuTable {border-collapse: separate; border-spacing: 0 0; padding: 0;}.claro .dijitMenu .dijitMenuItem td,.claro .dijitComboBoxMenu .dijitMenuItem {padding: 2px; border-width: 1px 0 1px 0; border-style: solid; border-color: #ffffff;}.claro .dijitMenu .dijitMenuItemHover td,.claro .dijitMenu .dijitMenuItemSelected td,.claro .dijitMenuItemHover,.claro .dijitComboBoxMenu .dijitMenuItemHover,.claro .dijitMenuItemSelected {border-color: #759dc0; background-color: #abd6ff; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitMenuItemActive {background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none;}.dj_ie .claro .dijitMenuActive .dijitMenuItemHover,.dj_ie .claro .dijitMenuActive .dijitMenuItemSelected,.dj_ie .claro .dijitMenuPassive .dijitMenuItemHover,.dj_ie .claro .dijitMenuPassive .dijitMenuItemSelected {padding-top: 6px; padding-bottom: 5px; margin-top: -3px;}.claro td.dijitMenuItemIconCell {padding: 2px; margin: 0 0 0 4px;}.claro td.dijitMenuItemLabel {padding-top: 5px; padding-bottom: 5px;}.claro .dijitMenuExpand {width: 7px; height: 7px; background-image: url("images/spriteArrows.png"); background-position: -14px 0; margin-right: 3px; margin-bottom: 4px;}.claro .dijitMenuSeparatorTop {height: auto; margin-top: 1px; border-bottom: 1px solid #b5bcc7;}.claro .dijitMenuSeparatorBottom {height: auto; margin-bottom: 1px;}.claro .dijitCheckedMenuItem .dijitMenuItemIcon,.claro .dijitRadioMenuItem .dijitMenuItemIcon {background-image: url("form/images/checkboxRadioButtonStates.png"); background-repeat: no-repeat; background-position: -15px 50%; width: 15px; height: 16px;}.dj_ie6 .claro .dijitCheckedMenuItem .dijitMenuItemIcon,.dj_ie6 .claro .dijitRadioMenuItem .dijitMenuItemIcon {background-image: url("form/images/checkboxAndRadioButtons_IE6.png");}.claro .dijitCheckedMenuItemChecked .dijitCheckedMenuItemIcon {background-position: 0 50%;}.claro .dijitRadioMenuItem .dijitMenuItemIcon {background-position: -105px 50%;}.claro .dijitRadioMenuItemChecked .dijitMenuItemIcon {background-position: -90px 50%;}.claro .dijitComboBoxMenu {margin-left: 0; background-image: none;}.claro .dijitMenu .dijitMenuItemSelected td,.claro .dijitComboBoxMenu .dijitMenuItemSelected {color: #000000; border-color: #759dc0; background-color: #abd6ff;}.claro .dijitComboBoxMenuActive .dijitMenuItemSelected {background-color: #7dbdfa;}.claro .dijitMenuPreviousButton,.claro .dijitMenuNextButton {font-style: italic;}.claro .dijitSliderBar {border-style: solid; outline: 1px;}.claro .dijitSliderFocused .dijitSliderBar {border-color: #759dc0;}.claro .dijitSliderHover .dijitSliderBar {border-color: #759dc0;}.claro .dijitSliderDisabled .dijitSliderBar {background-image: none; border-color: #d3d3d3;}.claro .dijitRuleLabelsContainer {color: #000000;}.claro .dijitRuleLabelsContainerH {padding: 2px 0;}.claro .dijitSlider .dijitSliderProgressBarH,.claro .dijitSlider .dijitSliderLeftBumper {border-color: #b5bcc7; background-color: #cfe5fa; background-image: -moz-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px); background-image: -webkit-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px); background-image: -o-linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px); background-image: linear-gradient(top, #ffffff 0px, #ffffff 1px, rgba(255, 255, 255, 0) 2px);}.claro .dijitSlider .dijitSliderRemainingBarH,.claro .dijitSlider .dijitSliderRightBumper {border-color: #b5bcc7; background-color: #ffffff;}.claro .dijitSliderRightBumper {border-right: solid 1px #b5bcc7;}.claro .dijitSliderLeftBumper {border-left: solid 1px #b5bcc7;}.claro .dijitSliderHover .dijitSliderProgressBarH,.claro .dijitSliderHover .dijitSliderLeftBumper {background-color: #abd6ff; border-color: #759dc0;}.claro .dijitSliderHover .dijitSliderRemainingBarH,.claro .dijitSliderHover .dijitSliderRightBumper {background-color: #ffffff; border-color: #759dc0;}.claro .dijitSliderFocused .dijitSliderProgressBarH,.claro .dijitSliderFocused .dijitSliderLeftBumper {background-color: #abd6ff; border-color: #759dc0; -webkit-box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2); -moz-box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2); box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2);}.claro .dijitSliderFocused .dijitSliderRemainingBarH,.claro .dijitSliderFocused .dijitSliderRightBumper {background-color: #ffffff; border-color: #759dc0; -webkit-box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2); -moz-box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2); box-shadow: inset 0px 1px 1px rgba(0, 0, 0, 0.2);}.claro .dijitSliderDisabled .dijitSliderProgressBarH,.claro .dijitSliderDisabled .dijitSliderLeftBumper {background-color: #d3d3d3; background-image: none;}.claro .dijitSliderDisabled .dijitSliderRemainingBarH,.claro .dijitSliderDisabled .dijitSliderRightBumper {background-color: #efefef;}.claro .dijitRuleLabelsContainerV {padding: 0 2px;}.claro .dijitSlider .dijitSliderProgressBarV,.claro .dijitSlider .dijitSliderBottomBumper {border-color: #b5bcc7; background-color: #cfe5fa; background-image: -moz-linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 1px); background-image: -webkit-linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 1px); background-image: -o-linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 1px); background-image: linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 1px);}.claro .dijitSlider .dijitSliderRemainingBarV,.claro .dijitSlider .dijitSliderTopBumper {border-color: #b5bcc7; background-color: #ffffff;}.claro .dijitSliderBottomBumper {border-bottom: solid 1px #b5bcc7;}.claro .dijitSliderTopBumper {border-top: solid 1px #b5bcc7;}.claro .dijitSliderHover .dijitSliderProgressBarV,.claro .dijitSliderHover .dijitSliderBottomBumper {background-color: #abd6ff; border-color: #759dc0;}.claro .dijitSliderHover .dijitSliderRemainingBarV,.claro .dijitSliderHover .dijitSliderTopBumper {background-color: #ffffff; border-color: #759dc0;}.claro .dijitSliderFocused .dijitSliderProgressBarV,.claro .dijitSliderFocused .dijitSliderBottomBumper {background-color: #abd6ff; border-color: #759dc0; -webkit-box-shadow: inset 1px 0px 1px rgba(0, 0, 0, 0.2); -moz-box-shadow: inset 1px 0px 1px rgba(0, 0, 0, 0.2); box-shadow: inset 1px 0px 1px rgba(0, 0, 0, 0.2);}.claro .dijitSliderFocused .dijitSliderRemainingBarV,.claro .dijitSliderFocused .dijitSliderTopBumper {background-color: #ffffff; border-color: #759dc0; -webkit-box-shadow: inset 1px 0px 1px rgba(0, 0, 0, 0.2); -moz-box-shadow: inset 1px 0px 1px rgba(0, 0, 0, 0.2); box-shadow: inset 1px 0px 1px rgba(0, 0, 0, 0.2);}.claro .dijitSliderDisabled .dijitSliderProgressBarV,.claro .dijitSliderDisabled .dijitSliderBottomBumper {background-color: #d3d3d3;}.claro .dijitSliderDisabled .dijitSliderRemainingBarV,.claro .dijitSliderDisabled .dijitSliderTopBumper {background-color: #efefef;}.claro .dijitSliderImageHandleH {border: 0; width: 18px; height: 16px; background-image: url("form/images/sliderThumbs.png"); background-repeat: no-repeat; background-position: 0 0;}.claro .dijitSliderHover .dijitSliderImageHandleH {background-position: -18px 0;}.claro .dijitSliderFocused .dijitSliderImageHandleH {background-position: -36px 0;}.claro .dijitSliderProgressBarH .dijitSliderThumbHover {background-position: -36px 0;}.claro .dijitSliderProgressBarH .dijitSliderThumbActive {background-position: -36px 0;}.claro .dijitSliderReadOnly .dijitSliderImageHandleH,.claro .dijitSliderDisabled .dijitSliderImageHandleH {background-position: -54px 0;}.claro .dijitSliderImageHandleV {border: 0; width: 18px; height: 16px; background-image: url("form/images/sliderThumbs.png"); background-repeat: no-repeat; background-position: -289px 0;}.claro .dijitSliderHover .dijitSliderImageHandleV {background-position: -307px 0;}.claro .dijitSliderFocused .dijitSliderImageHandleV {background-position: -325px 0;}.claro .dijitSliderProgressBarV .dijitSliderThumbHover {background-position: -325px 0;}.claro .dijitSliderProgressBarV .dijitSliderThumbActive {background-position: -325px 0;}.claro .dijitSliderReadOnly .dijitSliderImageHandleV,.claro .dijitSliderDisabled .dijitSliderImageHandleV {background-position: -343px 0;}.claro .dijitSliderButtonContainerH {padding: 1px 3px 1px 2px;}.claro .dijitSliderButtonContainerV {padding: 3px 1px 2px 1px;}.claro .dijitSliderDecrementIconH,.claro .dijitSliderIncrementIconH,.claro .dijitSliderDecrementIconV,.claro .dijitSliderIncrementIconV {background-image: url("form/images/commonFormArrows.png"); background-repeat: no-repeat; background-color: #efefef; -moz-border-radius: 2px; border-radius: 2px; border: solid 1px #b5bcc7; font-size: 1px;}.claro .dijitSliderDecrementIconH,.claro .dijitSliderIncrementIconH {height: 12px; width: 9px;}.claro .dijitSliderDecrementIconV,.claro .dijitSliderIncrementIconV {height: 9px; width: 12px;}.claro .dijitSliderActive .dijitSliderDecrementIconH,.claro .dijitSliderActive .dijitSliderIncrementIconH,.claro .dijitSliderActive .dijitSliderDecrementIconV,.claro .dijitSliderActive .dijitSliderIncrementIconV,.claro .dijitSliderHover .dijitSliderDecrementIconH,.claro .dijitSliderHover .dijitSliderIncrementIconH,.claro .dijitSliderHover .dijitSliderDecrementIconV,.claro .dijitSliderHover .dijitSliderIncrementIconV {border: solid 1px #759dc0; background-color: #ffffff;}.claro .dijitSliderDecrementIconH {background-position: -357px 50%;}.claro .dijitSliderActive .dijitSliderDecrementIconH .claro .dijitSliderHover .dijitSliderDecrementIconH {background-position: -393px 50%;}.claro .dijitSliderIncrementIconH {background-position: -251px 50%;}.claro .dijitSliderActive .dijitSliderIncrementIconH .claro .dijitSliderHover .dijitSliderIncrementIconH {background-position: -283px 50%;}.claro .dijitSliderDecrementIconV {background-position: -38px 50%;}.claro .dijitSliderActive .dijitSliderDecrementIconV .claro .dijitSliderHover .dijitSliderDecrementIconV {background-position: -73px 50%;}.claro .dijitSliderIncrementIconV {background-position: -143px 49%;}.claro .dijitSliderActive .dijitSliderIncrementIconV .claro .dijitSliderHover .dijitSliderIncrementIconV {background-position: -178px 49%;}.claro .dijitSliderButtonContainerV .dijitSliderDecrementButtonHover,.claro .dijitSliderButtonContainerH .dijitSliderDecrementButtonHover,.claro .dijitSliderButtonContainerV .dijitSliderIncrementButtonHover,.claro .dijitSliderButtonContainerH .dijitSliderIncrementButtonHover {background-color: #cfe5fa;}.claro .dijitSliderButtonContainerV .dijitSliderDecrementButtonActive,.claro .dijitSliderButtonContainerH .dijitSliderDecrementButtonActive,.claro .dijitSliderButtonContainerV .dijitSliderIncrementButtonActive,.claro .dijitSliderButtonContainerH .dijitSliderIncrementButtonActive {background-color: #abd6ff; border-color: #759dc0;}.claro .dijitSliderButtonInner {visibility: hidden;}.claro .dijitSliderDisabled .dijitSliderBar {border-color: #d3d3d3;}.claro .dijitSliderReadOnly *,.claro .dijitSliderDisabled * {border-color: #d3d3d3; color: #818181;}.claro .dijitSliderReadOnly .dijitSliderDecrementIconH,.claro .dijitSliderDisabled .dijitSliderDecrementIconH {background-position: -321px 50%; background-color: #efefef;}.claro .dijitSliderReadOnly .dijitSliderIncrementIconH,.claro .dijitSliderDisabled .dijitSliderIncrementIconH {background-position: -215px 50%; background-color: #efefef;}.claro .dijitSliderReadOnly .dijitSliderDecrementIconV,.claro .dijitSliderDisabled .dijitSliderDecrementIconV {background-position: -3px 49%; background-color: #efefef;}.claro .dijitSliderReadOnly .dijitSliderIncrementIconV,.claro .dijitSliderDisabled .dijitSliderIncrementIconV {background-position: -107px 49%; background-color: #efefef;}.claro .dijitColorPalette {border: 1px solid #b5bcc7; background: #ffffff; -moz-border-radius: 0; border-radius: 0;}.claro .dijitColorPalette .dijitPaletteImg {border: 1px solid #d3d3d3;}.claro .dijitColorPalette .dijitPaletteCell:hover .dijitPaletteImg {border: 1px solid #000000;}.claro .dijitColorPalette .dijitPaletteCell:active .dijitPaletteImg,.claro .dijitColorPalette .dijitPaletteTable .dijitPaletteCellSelected .dijitPaletteImg {border: 2px solid #000000;}.claro .dijitInlineEditBoxDisplayMode {border: 1px solid transparent;}.claro .dijitInlineEditBoxDisplayModeHover {background-color: #e5f2fe; border: solid 1px #759dc0;}.dj_ie6 .claro .dijitInlineEditBoxDisplayMode {border: none;}.claro .dijitProgressBar {margin: 2px 0 2px 0;}.claro .dijitProgressBarEmpty {background-color: #ffffff; border-color: #759dc0;}.claro .dijitProgressBarTile {background-color: #abd6ff; background-image: url("images/progressBarFull.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.93) 0px, rgba(255, 255, 255, 0.41) 1px, rgba(255, 255, 255, 0.7) 2px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.93) 0px, rgba(255, 255, 255, 0.41) 1px, rgba(255, 255, 255, 0.7) 2px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.93) 0px, rgba(255, 255, 255, 0.41) 1px, rgba(255, 255, 255, 0.7) 2px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.93) 0px, rgba(255, 255, 255, 0.41) 1px, rgba(255, 255, 255, 0.7) 2px, rgba(255, 255, 255, 0) 100%); background-attachment: scroll;}.dj_ie6 .claro .dijitProgressBarTile {background-image: none;}.claro .dijitProgressBarFull {border: 0px solid #759dc0; border-right-width: 1px; -webkit-transition-property: width; -moz-transition-property: width; transition-property: width; -webkit-transition-duration: 0.25s; -moz-transition-duration: 0.25s; transition-duration: 0.25s;}.claro .dijitProgressBarLabel {color: #000000;}.claro .dijitProgressBarIndeterminate .dijitProgressBarTile {background: #efefef url("images/progressBarAnim.gif") repeat-x top;}.claro .dijitTimePicker .dijitButtonNode {padding: 0 0; -moz-border-radius: 0; border-radius: 0;}.claro .dijitTimePicker {border: 1px #b5bcc7 solid; border-top: none; border-bottom: none; background-color: #fff;}.claro .dijitTimePickerItem {background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; border-top: solid 1px #b5bcc7; border-bottom: solid 1px #b5bcc7; margin-top: -1px;}.claro .dijitTimePickerTick {color: #818181; background-color: #efefef; font-size: 0.818em;}.claro .dijitTimePickerMarker {background-color: #e5f2fe; font-size: 1em; white-space: nowrap;}.claro .dijitTimePickerTickHover,.claro .dijitTimePickerMarkerHover,.claro .dijitTimePickerMarkerSelected,.claro .dijitTimePickerTickSelected {background-color: #7dbdfa; color: #000000;}.claro .dijitTimePickerMarkerSelected,.claro .dijitTimePickerTickSelected {font-size: 1em;}.claro .dijitTimePickerTick .dijitTimePickerItemInner {padding: 1px; margin: 0;}.claro .dijitTimePicker .dijitButtonNode {border-left: none; border-right: none; border-color: #b5bcc7; background-color: #efefef; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitTimePicker .dijitArrowButtonInner {height: 100%; background-image: url("form/images/commonFormArrows.png"); background-repeat: no-repeat; background-position: -140px 45%;}.claro .dijitTimePicker .dijitDownArrowButton .dijitArrowButtonInner {background-position: -35px 45%;}.claro .dijitTimePicker .dijitUpArrowHover,.claro .dijitTimePicker .dijitDownArrowHover {background-color: #abd6ff;}.claro .dijitTimePicker .dijitUpArrowHover .dijitArrowButtonInner {background-position: -175px 45%;}.claro .dijitTimePicker .dijitDownArrowHover .dijitArrowButtonInner {background-position: -70px 45%;}.claro .dijitBorderContainer {padding: 5px;}.claro .dijitSplitContainer-child,.claro .dijitBorderContainer-child {border: 1px #b5bcc7 solid;}.claro .dijitBorderContainer-dijitTabContainerTop,.claro .dijitBorderContainer-dijitTabContainerBottom,.claro .dijitBorderContainer-dijitTabContainerLeft,.claro .dijitBorderContainer-dijitTabContainerRight,.claro .dijitBorderContainer-dijitAccordionContainer {border: none;}.claro .dijitBorderContainer-dijitBorderContainer {border: 0; padding: 0;}.claro .dijitSplitterH,.claro .dijitGutterH {background: none; border: 0; height: 5px;}.dj_ios .claro .dijitSplitterH,.dj_android .claro .dijitSplitterH {height: 11px;}.claro .dijitSplitterH .dijitSplitterThumb {background: #b5bcc7 none; height: 1px; top: 2px; width: 19px;}.dj_ios .claro .dijitSplitterH .dijitSplitterThumb,.dj_android .claro .dijitSplitterH .dijitSplitterThumb {top: 5px;}.claro .dijitSplitterV,.claro .dijitGutterV {background: none; border: 0; width: 5px; margin: 0;}.dj_ios .claro .dijitSplitterV,.dj_android .claro .dijitSplitterV {width: 11px;}.claro .dijitSplitterV .dijitSplitterThumb {background: #b5bcc7 none; height: 19px; left: 2px; width: 1px; margin: 0;}.dj_ios .claro .dijitSplitterV .dijitSplitterThumb,.dj_android .claro .dijitSplitterV .dijitSplitterThumb {left: 5px;}.claro .dijitSplitterHHover,.claro .dijitSplitterVHover {font-size: 1px; background-color: #cfe5fa;}.claro .dijitSplitterHHover {background-image: -moz-linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%); background-image: -webkit-linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%); background-image: -o-linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%); background-image: linear-gradient(left, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%);}.claro .dijitSplitterVHover {background-image: -moz-linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%); background-image: -webkit-linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%); background-image: -o-linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%); background-image: linear-gradient(top, #ffffff 0px, rgba(255, 255, 255, 0) 50%, #ffffff 100%);}.claro .dijitSplitterHHover .dijitSplitterThumb,.claro .dijitSplitterVHover .dijitSplitterThumb {background: #759dc0 none;}.claro .dijitSplitterHActive,.claro .dijitSplitterVActive {font-size: 1px; background-color: #abd6ff; background-image: none;}.claro .dijitTreeNode {zoom: 1;}.claro .dijitTreeIsRoot {background-image: none;}.claro .dijitTreeRow,.claro .dijitTreeNode .dojoDndItemBefore,.claro .dijitTreeNode .dojoDndItemAfter {padding: 4px 0 2px 0; background-color: none; background-color: transparent; background-color: rgba(171, 214, 255, 0); background-position: 0 0; background-repeat: repeat-x; border: solid 0 transparent; color: #000000; -webkit-transition-property: background-color, border-color; -moz-transition-property: background-color, border-color; transition-property: background-color, border-color; -webkit-transition-duration: 0.25s; -moz-transition-duration: 0.25s; transition-duration: 0.25s; -webkit-transition-timing-function: ease-out; -moz-transition-timing-function: ease-out; transition-timing-function: ease-out;}.claro .dijitTreeRowSelected {background-color: #cfe5fa; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 3px 0 1px; border-color: #759dc0; border-width: 1px 0; color: #000000;}.claro .dijitTreeRowHover {background-color: #abd6ff; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 3px 0 1px; border-color: #759dc0; border-width: 1px 0; color: #000000; -webkit-transition-duration: 0.25s; -moz-transition-duration: 0.25s; transition-duration: 0.25s;}.claro .dijitTreeRowActive {background-color: #7dbdfa; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 3px 0 1px; border-color: #759dc0; border-width: 1px 0; color: #000000;}.claro .dijitTreeRowFocused {background-repeat: repeat;}.claro .dijitTreeExpando {background-image: url("images/treeExpandImages.png"); width: 16px; height: 16px; background-position: -35px 0;}.dj_ie6 .claro .dijitTreeExpando {background-image: url("images/treeExpandImages8bit.png");}.claro .dijitTreeRowHover .dijitTreeExpandoOpened {background-position: -53px 0;}.claro .dijitTreeExpandoClosed {background-position: 1px 0;}.claro .dijitTreeRowHover .dijitTreeExpandoClosed {background-position: -17px 0;}.claro .dijitTreeExpandoLeaf,.dj_ie6 .claro .dijitTreeExpandoLeaf {background-image: none;}.claro .dijitTreeExpandoLoading {background-image: url("../../icons/images/loadingAnimation.gif"); background-position: 0 0;}.claro .dijitTreeNode .dojoDndItemBefore .dijitTreeContent {border-top: 2px solid #759dc0;}.claro .dijitTreeNode .dojoDndItemAfter .dijitTreeContent {border-bottom: 2px solid #759dc0;} .claro .dijitToolbar {border-bottom: 1px solid #b5bcc7; background-color: #efefef; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 2px 0 2px 4px; zoom: 1;}.claro .dijitToolbar label {padding: 0 3px 0 6px;}.claro .dijitToolbar .dijitButton .dijitButtonNode,.claro .dijitToolbar .dijitDropDownButton .dijitButtonNode,.claro .dijitToolbar .dijitComboButton .dijitButtonNode,.claro .dijitToolbar .dijitToggleButton .dijitButtonNode,.claro .dijitToolbar .dijitComboBox .dijitButtonNode {border-width: 0; padding: 2px; -moz-border-radius: 2px; border-radius: 2px; -webkit-box-shadow: none; -moz-box-shadow: none; box-shadow: none; -webkit-transition-property: background-color; -moz-transition-property: background-color; transition-property: background-color; -webkit-transition-duration: 0.3s; -moz-transition-duration: 0.3s; transition-duration: 0.3s; background-color: rgba(171, 214, 255, 0); background-image: none;}.dj_ie .claro .dijitToolbar .dijitButton .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitDropDownButton .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitComboButton .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitToggleButton .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitComboBox .dijitButtonNode {background-color: transparent;}.dj_ie .claro .dijitToolbar .dijitButtonHover .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitDropDownButtonHover .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitComboButton .dijitButtonNodeHover,.dj_ie .claro .dijitToolbar .dijitComboButton .dijitDownArrowButtonHover,.dj_ie .claro .dijitToolbar .dijitToggleButtonHover .dijitButtonNode {background-color: #abd6ff;}.dj_ie .claro .dijitToolbar .dijitButtonActive .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitDropDownButtonActive .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitComboButtonActive .dijitButtonNode,.dj_ie .claro .dijitToolbar .dijitToggleButtonActive .dijitButtonNode {background-color: #abd6ff;}.claro .dijitToolbar .dijitComboButton .dijitStretch {-moz-border-radius: 2px 0 0 2px; border-radius: 2px 0 0 2px;}.claro .dijitToolbar .dijitComboButton .dijitArrowButton {-moz-border-radius: 0 2px 2px 0; border-radius: 0 2px 2px 0;}.claro .dijitToolbar .dijitComboBox .dijitButtonNode {padding: 0;}.claro .dijitToolbar .dijitButtonHover .dijitButtonNode,.claro .dijitToolbar .dijitDropDownButtonHover .dijitButtonNode,.claro .dijitToolbar .dijitToggleButtonHover .dijitButtonNode,.claro .dijitToolbar .dijitComboButtonHover .dijitButtonNode {border-width: 1px; background-color: #abd6ff; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 1px;}.claro .dijitToolbar .dijitComboButtonHover .dijitButtonNode,.claro .dijitToolbar .dijitComboButtonHover .dijitDownArrowButton {background-color: #f3ffff;}.claro .dijitToolbar .dijitComboButtonHover .dijitButtonNodeHover,.claro .dijitToolbar .dijitComboButtonHover .dijitDownArrowButtonHover {background-color: #abd6ff;}.claro .dijitToolbar .dijitButtonActive .dijitButtonNode,.claro .dijitToolbar .dijitDropDownButtonActive .dijitButtonNode,.claro .dijitToolbar .dijitToggleButtonActive .dijitButtonNode {border-width: 1px; background-color: #7dbdfa; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none; padding: 1px;}.claro .dijitToolbar .dijitComboButtonActive {-webkit-transition-duration: 0.2s; -moz-transition-duration: 0.2s; transition-duration: 0.2s; border-width: 1px; padding: 0;}.claro .dijitToolbar .dijitComboButtonActive .dijitButtonNode,.claro .dijitToolbar .dijitComboButtonActive .dijitDownArrowButton {background-color: #f3ffff; padding: 2px;}.claro .dijitToolbar .dijitComboButtonActive .dijitButtonNodeActive {background-color: #7dbdfa; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitToolbar .dijitComboButtonActive .dijitDownArrowButtonActive {background-color: #7dbdfa; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitToolbar .dijitComboButtonHover .dijitDownArrowButton,.claro .dijitToolbar .dijitComboButtonActive .dijitDownArrowButton {border-left-width: 0;}.claro .dijitToolbar .dijitComboButtonHover .dijitDownArrowButton {padding-left: 2px;}.claro .dijitToolbar .dijitToggleButtonChecked .dijitButtonNode {margin: 0; border-width: 1px; border-style: solid; background-image: none; border-color: #759dc0; background-color: #ffffff; padding: 1px;}.claro .dijitToolbarSeparator {background: url("../../icons/images/editorIconsEnabled.png");}.claro .dijitDisabled .dijitToolbar {background: none; background-color: #efefef; border-bottom: 1px solid #d3d3d3;}.claro .dijitToolbar .dijitComboBoxDisabled .dijitArrowButtonInner {background-position: 0 50%;}.claro .dijitEditorIFrameContainer {padding: 3px 3px 1px 10px;}.claro .dijitEditorIFrame {background-color: #ffffff;}.claro .dijitEditor {border: 1px solid #b5bcc7;}.claro .dijitEditor .dijitEditorIFrameContainer {background-color: #ffffff; background-repeat: repeat-x;}.claro .dijitEditorHover .dijitEditorIFrameContainer,.claro .dijitEditorHover .dijitEditorIFrameContainer .dijitEditorIFrame {background-color: #e5f2fe;}.claro .dijitEditorFocused .dijitEditorIFrameContainer,.claro .dijitEditorFocused .dijitEditorIFrameContainer .dijitEditorIFrame {background-color: #ffffff;}.claro .dijitEditorHover .dijitEditorIFrameContainer,.claro .dijitEditorFocused .dijitEditorIFrameContainer {background-image: -moz-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -webkit-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: -o-linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px); background-image: linear-gradient(rgba(127, 127, 127, 0.2) 0%, rgba(127, 127, 127, 0) 2px);}.claro .dijitEditorDisabled {border: 1px solid #d3d3d3; color: #818181;}.claro .dijitDisabled .dijitEditorIFrame,.claro .dijitDisabled .dijitEditorIFrameContainer,.claro .dijitDisabled .dijitEditorIFrameContainer .dijitEditorIFrame {background-color: #efefef; background-image: none;}.dijitEditorIcon {background-image: url("../../icons/images/editorIconsEnabled.png"); background-repeat: no-repeat; width: 18px; height: 18px; text-align: center;}.dijitDisabled .dijitEditorIcon {background-image: url("../../icons/images/editorIconsDisabled.png");}.dijitEditorIconSep {background-position: 0;}.dijitEditorIconSave {background-position: -18px;}.dijitEditorIconPrint {background-position: -36px;}.dijitEditorIconCut {background-position: -54px;}.dijitEditorIconCopy {background-position: -72px;}.dijitEditorIconPaste {background-position: -90px;}.dijitEditorIconDelete {background-position: -108px;}.dijitEditorIconCancel {background-position: -126px;}.dijitEditorIconUndo {background-position: -144px;}.dijitEditorIconRedo {background-position: -162px;}.dijitEditorIconSelectAll {background-position: -180px;}.dijitEditorIconBold {background-position: -198px;}.dijitEditorIconItalic {background-position: -216px;}.dijitEditorIconUnderline {background-position: -234px;}.dijitEditorIconStrikethrough {background-position: -252px;}.dijitEditorIconSuperscript {background-position: -270px;}.dijitEditorIconSubscript {background-position: -288px;}.dijitEditorIconJustifyCenter {background-position: -306px;}.dijitEditorIconJustifyFull {background-position: -324px;}.dijitEditorIconJustifyLeft {background-position: -342px;}.dijitEditorIconJustifyRight {background-position: -360px;}.dijitEditorIconIndent {background-position: -378px;}.dijitEditorIconOutdent {background-position: -396px;}.dijitEditorIconListBulletIndent {background-position: -414px;}.dijitEditorIconListBulletOutdent {background-position: -432px;}.dijitEditorIconListNumIndent {background-position: -450px;}.dijitEditorIconListNumOutdent {background-position: -468px;}.dijitEditorIconTabIndent {background-position: -486px;}.dijitEditorIconLeftToRight {background-position: -504px;}.dijitEditorIconRightToLeft, .dijitEditorIconToggleDir {background-position: -522px;}.dijitEditorIconBackColor {background-position: -540px;}.dijitEditorIconForeColor {background-position: -558px;}.dijitEditorIconHiliteColor {background-position: -576px;}.dijitEditorIconNewPage {background-position: -594px;}.dijitEditorIconInsertImage {background-position: -612px;}.dijitEditorIconInsertTable {background-position: -630px;}.dijitEditorIconSpace {background-position: -648px;}.dijitEditorIconInsertHorizontalRule {background-position: -666px;}.dijitEditorIconInsertOrderedList {background-position: -684px;}.dijitEditorIconInsertUnorderedList {background-position: -702px;}.dijitEditorIconCreateLink {background-position: -720px;}.dijitEditorIconUnlink {background-position: -738px;}.dijitEditorIconViewSource {background-position: -756px;}.dijitEditorIconRemoveFormat {background-position: -774px;}.dijitEditorIconFullScreen {background-position: -792px;}.dijitEditorIconWikiword {background-position: -810px;} .claro .dijitTitlePaneTitle {background-color: #efefef; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; border: 1px solid #b5bcc7; padding: 0 7px 3px 7px; min-height: 17px; color: #494949;}.claro .dijitFieldset {-moz-border-radius: 4px; border-radius: 4px;}.claro .dijitTitlePaneTitleOpen,.claro .dijitTitlePaneTitleFixedOpen {background-color: #cfe5fa; color: #000000;}.claro .dijitTitlePaneTitleHover {background-color: #abd6ff; border-color: #759dc0;}.claro .dijitTitlePaneTitleActive {background-color: #7dbdfa; border-color: #759dc0; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitTitlePaneTitleFocus {margin-top: 3px; padding-bottom: 2px;}.claro .dijitTitlePane .dijitArrowNode,.claro .dijitFieldset .dijitArrowNode {background-image: url("images/spriteArrows.png"); background-repeat: no-repeat; height: 8px; width: 7px;}.claro .dijitTitlePaneTitleOpen .dijitArrowNode,.claro .dijitFieldsetTitleOpen .dijitArrowNode {background-position: 0 0;}.claro .dijitTitlePaneTitleClosed .dijitArrowNode,.claro .dijitFieldsetTitleClosed .dijitArrowNode {background-position: -14px 0;}.claro .dijitTitlePaneContentOuter {background: #ffffff; border: 1px solid #b5bcc7; border-top: none;}.claro .dijitTitlePaneContentInner {padding: 10px;}.claro .dijitFieldsetContentInner {padding: 4px;}.claro .dijitTitlePaneTextNode,.claro .dijitFieldsetLegendNode {margin-left: 4px; margin-right: 4px; vertical-align: text-top;}.claro .dijitSpinnerButtonContainer {overflow: hidden; position: relative; width: auto; padding: 0 2px;}.claro .dijitSpinnerButtonContainer .dijitSpinnerButtonInner {border-width: 1px 0; border-style: solid none;}.claro .dijitSpinner .dijitArrowButton {width: auto; background-color: #efefef; background-image: url("images/standardGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(255, 255, 255, 0.7) 0%, rgba(255, 255, 255, 0) 100%); _background-image: none; overflow: hidden;}.dj_iequirks .claro .dijitSpinner .dijitArrowButton {overflow: visible;}.claro .dijitSpinner .dijitSpinnerButtonInner {width: 15px;}.claro .dijitSpinner .dijitArrowButtonInner {border: solid 1px #ffffff; border-bottom-width: 0; background-image: url("form/images/commonFormArrows.png"); background-repeat: no-repeat; height: 100%; width: 15px; padding-left: 1px; padding-right: 1px; background-position: -139px center; display: block; margin: -1px 0 -1px 0;}.dj_iequirks .claro .dijitSpinner .dijitArrowButtonInner,.dj_ie6 .claro .dijitSpinner .dijitArrowButtonInner,.dj_ie7 .claro .dijitSpinner .dijitArrowButtonInner,.dj_ie8 .claro .dijitSpinner .dijitArrowButtonInner {margin-top: 0;}.dj_iequirks .claro .dijitSpinner .dijitArrowButtonInner {width: 19px;}.claro .dijitSpinner .dijitDownArrowButton .dijitArrowButtonInner {background-position: -34px;}.claro .dijitSpinner .dijitArrowButtonInner .dijitInputField {padding: 0;}.claro .dijitUpArrowButtonActive,.claro .dijitDownArrowButtonActive {background-color: #abd6ff;}.claro .dijitSpinner .dijitUpArrowButtonHover,.claro .dijitSpinner .dijitDownArrowButtonHover,.claro .dijitSpinnerFocused .dijitArrowButton {background-color: #abd6ff;}.claro .dijitSpinner .dijitUpArrowButtonHover .dijitArrowButtonInner {background-position: -174px;}.claro .dijitSpinner .dijitDownArrowButtonHover .dijitArrowButtonInner {background-position: -69px;}.claro .dijitSpinnerFocused {background-color: #ffffff; background-image: none;}.claro .dijitSpinner .dijitDownArrowButtonActive,.claro .dijitSpinner .dijitUpArrowButtonActive {background-color: #7dbefa; background-image: url("images/activeGradient.png"); background-repeat: repeat-x; background-image: -moz-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -webkit-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: -o-linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); background-image: linear-gradient(rgba(190, 190, 190, 0.98) 0px, rgba(255, 255, 255, 0.65) 3px, rgba(255, 255, 255, 0) 100%); _background-image: none;}.claro .dijitSpinner .dijitUpArrowButtonActive .dijitArrowButtonInner,.claro .dijitSpinner .dijitDownArrowButtonActive .dijitArrowButtonInner {border: 0; padding: 1px; margin-right: 2px; margin-bottom: 1px;}.claro .dijitSpinner .dijitUpArrowButtonActive .dijitArrowButtonInner {background-position: -173px;}.claro .dijitSpinner .dijitDownArrowButtonActive .dijitArrowButtonInner {background-position: -68px;}.claro .dijitSpinnerDisabled .dijitArrowButtonInner {background-color: #efefef;}.claro .dijitSpinnerDisabled .dijitUpArrowButton .dijitArrowButtonInner {background-position: -104px;}.claro .dijitSpinnerDisabled .dijitDownArrowButton .dijitArrowButtonInner {background-position: 1px;}.dj_ie7 .claro .dijitSpinner {overflow: visible;}.dijitRtl .dijitOffScreen {left: auto !important; right: -10000px !important;}.dijitRtl .dijitPlaceHolder {left: auto; right: 0;}.dijitMenuItemRtl {text-align: right;}.dj_iequirks .dijitComboButtonRtl button {float:left;}.dj_ie .dijitTextBoxRtl .dijitInputContainer {clear: right;}.dijitTextBoxRtl .dijitValidationContainer,.dijitTextBoxRtl .dijitSpinnerButtonContainer,.dijitComboBoxRtl .dijitArrowButtonContainer {border-right-width: 1px !important; border-left-width: 0 !important;}.dijitSpinnerRtl .dijitSpinnerButtonContainer .dijitArrowButton {right: 0; left: auto;}.dijitSelectRtl .dijitButtonText {float: right;}.dijitTextBoxRtl .dijitSpinnerButtonContainer,.dijitValidationTextBoxRtl .dijitValidationContainer,.dijitTextBoxRtl .dijitArrowButtonContainer {float: left;}div.dijitNumberTextBoxRtl {text-align: right;}.dijitCalendarRtl .dijitCalendarDecrementArrow {float: right;}.dijitCalendarRtl .dijitCalendarIncrementArrow {float: left;}.dijitCalendarRtl .dijitCalendarNextYear {margin:0 0.55em 0 0;}.dijitCalendarRtl .dijitCalendarPreviousYear {margin:0 0 0 0.55em;}.dijitSliderRtl .dijitSliderImageHandleV {left:auto;}.dijitSliderRtl .dijitSliderImageHandleH {left:-50%;}.dijitSliderRtl .dijitSliderMoveableH {right:auto; left:0;}.dijitSliderRtl .dijitRuleContainerV {float:right;}.dj_ie .dijitSliderRtl .dijitRuleContainerV {text-align:right;}.dj_ie .dijitSliderRtl .dijitRuleLabelV {text-align:left;}.dj_ie .dijitSliderRtl .dijitRuleLabelH {zoom:1;}.dijitSliderRtl .dijitSliderProgressBarH {float:right; right:0; left:auto;}.dijitRtl .dijitContentPaneLoading .dijitIconLoading,.dijitRtl .dijitContentPaneError .dijitIconError {margin-right: 0; margin-left: 9px;}.dijitTabControllerRtl .nowrapTabStrip {text-align: right;}.dijitTabRtl .dijitTabCloseButton {margin-left: 0; margin-right: 1em;}.dj_ie6 .dijitTabRtl .tabLabel,.dj_ie6 .dijitTabContainerRight-tabs .dijitTabRtl,.dj_ie6 .dijitTabContainerLeft-tabs .dijitTabRtl,.dj_ie7 .dijitTabContainerRight-tabs .dijitTabRtl,.dj_ie7 .dijitTabContainerLeft-tabs .dijitTabRtl {zoom: 1;}.dj_ie6 .dijitTabContainerRight-tabs .dijitTabRtl,.dj_ie7 .dijitTabContainerRight-tabs .dijitTabRtl {left: 0;}.dj_ie6 .dijitTabContainerRightRtl .dijitTabContainerRight-tabs,.dj_ie6 .dijitTabContainerLeftRtl .dijitTabContainerLeft-tabs {width: 1%;}.dj_ie .dijitTimePickerRtl .dijitTimePickerItem {width:100%;}.dijitColorPaletteRtl .dijitColorPaletteUnder {left: auto; right: 0;}.dijitSelectRtl .dijitButtonContents {border-style: none none none solid; text-align: right;}.dijitTreeRtl .dijitTreeContainer {float: right;}.dijitRtl .dojoDndHorizontal .dojoDndItemBefore {border-width: 0 2px 0 0; padding: 2px 0 2px 2px;}.dijitRtl .dojoDndHorizontal .dojoDndItemAfter {border-width: 0 0 0 2px; padding: 2px 2px 2px 0;}.claro .dijitTextBoxRtlError .dijitValidationContainer {border-left-width: 0; border-right-width: 1px;}.claro .dijitComboButtonRtl .dijitStretch {-moz-border-radius: 0 4px 4px 0; border-radius: 0 4px 4px 0;}.claro .dijitComboButtonRtl .dijitArrowButton {-moz-border-radius: 4px 0 0 4px; border-radius: 4px 0 0 4px; padding: 3px 0 4px; border-left-width: 1px; border-right-width: 0;}.claro .dijitTabContainerTop-tabs .dijitTabRtl,.claro .dijitTabContainerBottom-tabs .dijitTabRtl {margin-right: 0; margin-left: 1px;}.claro .dijitSliderRtl .dijitSliderProgressBarH,.claro .dijitSliderRtl .dijitSliderRemainingBarH,.claro .dijitSliderRtl .dijitSliderLeftBumper,.claro .dijitSliderRtl .dijitSliderRightBumper,.claro .dijitSliderRtl .dijitSliderTopBumper {background-position: top right;}.claro .dijitSliderRtl .dijitSliderProgressBarV,.claro .dijitSliderRtl .dijitSliderRemainingBarV,.claro .dijitSliderRtl .dijitSliderBottomBumper {background-position: bottom right;}.claro .dijitSliderRtl .dijitSliderLeftBumper {border-left-width: 0; border-right-width: 1px;}.claro .dijitSliderRtl .dijitSliderRightBumper {border-left-width: 1px; border-right-width: 0;}.claro .dijitSliderRtl .dijitSliderIncrementIconH {background-position: -357px 50%;}.claro .dijitSliderRtl .dijitSliderDecrementIconH {background-position: -251px 50%;}.claro .dijitDialogRtl .dijitDialogCloseIcon {right: auto; left: 5px;}.claro .dijitDialogRtl .dijitDialogPaneActionBar {text-align: left; padding: 3px 7px 2px 5px;}.claro .dijitEditorRtl .dijitEditorIFrameContainer {padding: 3px 10px 1px 3px;}.dj_ie6 .claro .dijitEditorRtl .dijitEditorIFrameContainer,.dj_ie7 .claro .dijitEditorRtl .dijitEditorIFrameContainer,.dj_ie8 .claro .dijitEditorRtl .dijitEditorIFrameContainer {padding: 3px 0px 1px 10px; margin-right: 0px; border: 0px solid #d3d3d3;}.dijitEditorRtl .dijitEditorIcon {background-image: url("../../icons/images/editorIconsEnabled_rtl.png");}.dijitEditorRtlDisabled .dijitEditorIcon {background-image: url("../../icons/images/editorIconsDisabled_rtl.png");}.dijitToolbarRtl .dijitToolbarSeparator {background-image: url("../../icons/images/editorIconsEnabled_rtl.png");}.dijitRtl .dijitIconSave,.dijitRtl .dijitIconPrint,.dijitRtl .dijitIconCut,.dijitRtl .dijitIconCopy,.dijitRtl .dijitIconClear,.dijitRtl .dijitIconDelete,.dijitRtl .dijitIconUndo,.dijitRtl .dijitIconEdit,.dijitRtl .dijitIconNewTask,.dijitRtl .dijitIconEditTask,.dijitRtl .dijitIconEditProperty,.dijitRtl .dijitIconTask,.dijitRtl .dijitIconFilter,.dijitRtl .dijitIconConfigure,.dijitRtl .dijitIconSearch,.dijitRtl .dijitIconApplication,.dijitRtl .dijitIconBookmark,.dijitRtl .dijitIconChart,.dijitRtl .dijitIconConnector,.dijitRtl .dijitIconDatabase,.dijitRtl .dijitIconDocuments,.dijitRtl .dijitIconMail,.dijitRtl .dijitLeaf,.dijitRtl .dijitIconFile,.dijitRtl .dijitIconFunction,.dijitRtl .dijitIconKey,.dijitRtl .dijitIconPackage,.dijitRtl .dijitIconSample,.dijitRtl .dijitIconTable,.dijitRtl .dijitIconUsers,.dijitRtl .dijitFolderClosed,.dijitRtl .dijitIconFolderClosed,.dijitRtl .dijitFolderOpened,.dijitRtl .dijitIconFolderOpen,.dijitRtl .dijitIconError {background-image: url("../../icons/images/commonIconsObjActEnabled_rtl.png"); width: 16px; height: 16px;}.dj_ie6 .dijitRtl .dijitIconSave,.dj_ie6 .dijitRtl .dijitIconPrint,.dj_ie6 .dijitRtl .dijitIconCut,.dj_ie6 .dijitRtl .dijitIconCopy,.dj_ie6 .dijitRtl .dijitIconClear,.dj_ie6 .dijitRtl .dijitIconDelete,.dj_ie6 .dijitRtl .dijitIconUndo,.dj_ie6 .dijitRtl .dijitIconEdit,.dj_ie6 .dijitRtl .dijitIconNewTask,.dj_ie6 .dijitRtl .dijitIconEditTask,.dj_ie6 .dijitRtl .dijitIconEditProperty,.dj_ie6 .dijitRtl .dijitIconTask,.dj_ie6 .dijitRtl .dijitIconFilter,.dj_ie6 .dijitRtl .dijitIconConfigure,.dj_ie6 .dijitRtl .dijitIconSearch,.dj_ie6 .dijitRtl .dijitIconApplication,.dj_ie6 .dijitRtl .dijitIconBookmark,.dj_ie6 .dijitRtl .dijitIconChart,.dj_ie6 .dijitRtl .dijitIconConnector,.dj_ie6 .dijitRtl .dijitIconDatabase,.dj_ie6 .dijitRtl .dijitIconDocuments,.dj_ie6 .dijitRtl .dijitIconMail,.dj_ie6 .dijitRtl .dijitLeaf,.dj_ie6 .dijitRtl .dijitIconFile,.dj_ie6 .dijitRtl .dijitIconFunction,.dj_ie6 .dijitRtl .dijitIconKey,.dj_ie6 .dijitRtl .dijitIconPackage,.dj_ie6 .dijitRtl .dijitIconSample,.dj_ie6 .dijitRtl .dijitIconTable,.dj_ie6 .dijitRtl .dijitIconUsers,.dj_ie6 .dijitRtl .dijitFolderClosed,.dj_ie6 .dijitRtl .dijitIconFolderClosed,.dj_ie6 .dijitRtl .dijitFolderOpened,.dj_ie6 .dijitRtl .dijitIconFolderOpen,.dj_ie6 .dijitRtl .dijitIconError {background-image: url("../../icons/images/commonIconsObjActEnabled8bit_rtl.png");}.dijitRtl .dijitDisabled .dijitIconSave,.dijitRtl .dijitDisabled .dijitIconPrint,.dijitRtl .dijitDisabled .dijitIconCut,.dijitRtl .dijitDisabled .dijitIconCopy,.dijitRtl .dijitDisabled .dijitIconClear,.dijitRtl .dijitDisabled .dijitIconDelete,.dijitRtl .dijitDisabled .dijitIconUndo,.dijitRtl .dijitDisabled .dijitIconEdit,.dijitRtl .dijitDisabled .dijitIconNewTask,.dijitRtl .dijitDisabled .dijitIconEditTask,.dijitRtl .dijitDisabled .dijitIconEditProperty,.dijitRtl .dijitDisabled .dijitIconTask,.dijitRtl .dijitDisabled .dijitIconFilter,.dijitRtl .dijitDisabled .dijitIconConfigure,.dijitRtl .dijitDisabled .dijitIconSearch,.dijitRtl .dijitDisabled .dijitIconApplication,.dijitRtl .dijitDisabled .dijitIconBookmark,.dijitRtl .dijitDisabled .dijitIconChart,.dijitRtl .dijitDisabled .dijitIconConnector,.dijitRtl .dijitDisabled .dijitIconDatabase,.dijitRtl .dijitDisabled .dijitIconDocuments,.dijitRtl .dijitDisabled .dijitIconMail,.dijitRtl .dijitDisabled .dijitLeaf,.dijitRtl .dijitDisabled .dijitIconFile,.dijitRtl .dijitDisabled .dijitIconFunction,.dijitRtl .dijitDisabled .dijitIconKey,.dijitRtl .dijitDisabled .dijitIconPackage,.dijitRtl .dijitDisabled .dijitIconSample,.dijitRtl .dijitDisabled .dijitIconTable,.dijitRtl .dijitDisabled .dijitIconUsers,.dijitRtl .dijitDisabled .dijitFolderClosed,.dijitRtl .dijitDisabled .dijitIconFolderClosed,.dijitRtl .dijitDisabled .dijitFolderOpened,.dijitRtl .dijitDisabled .dijitIconFolderOpen,.dijitRtl .dijitDisabled .dijitIconError {background-image: url("../../icons/images/commonIconsObjActDisabled_rtl.png");}.dijitRtl .dijitIconLoading {background-image: url("../../icons/images/loadingAnimation_rtl.gif");}.claro .dijitTitlePaneRtl .dijitClosed .dijitArrowNode,.claro .dijitFieldsetRtl .dijitFieldsetTitleClosed .dijitArrowNode {background-position: -7px 0;}.claro .dijitMenuItemRtl .dijitMenuExpand {background-position: -7px 0; margin-right: 0; margin-left: 3px;}.claro .dijitMenuItemRtl .dijitMenuItemIcon {margin: 0 4px 0 0;}.claro .dijitCalendarRtl .dijitCalendarIncrease {background-position: 0 0;}.claro .dijitCalendarRtl .dijitCalendarDecrease {background-position: -18px 0;}.claro .dijitCalendarRtl .dijitCalendarArrowHover .dijitCalendarIncrease {background-position: -36px 0;}.claro .dijitCalendarRtl .dijitCalendarArrowHover .dijitCalendarDecrease {background-position: -55px 0;}.claro .dijitCalendarRtl .dijitCalendarArrowActive .dijitCalendarIncrease {background-position: -72px 0;}.claro .dijitCalendarRtl .dijitCalendarArrowActive .dijitCalendarDecrease {background-position: -91px 0;}.claro .dijitToolbar .dijitComboButtonRtl .dijitButtonNode {border-width: 0; padding: 2px;}.claro .dijitToolbar .dijitComboButtonRtlHover .dijitButtonNode,.claro .dijitToolbar .dijitComboButtonRtlActive .dijitButtonNode {border-width: 1px; padding: 1px;}.claro .dijitToolbar .dijitComboButtonRtl .dijitStretch {-moz-border-radius: 0 2px 2px 0; border-radius: 0 2px 2px 0;}.claro .dijitToolbar .dijitComboButtonRtl .dijitArrowButton {-moz-border-radius: 2px 0 0 2px; border-radius: 2px 0 0 2px;}.claro .dijitToolbar .dijitComboButtonRtlHover .dijitArrowButton,.claro .dijitToolbar .dijitComboButtonRtlActive .dijitArrowButton {border-left-width: 1px; border-right-width: 0; padding-left: 1px; padding-right: 2px;}.claro .dijitTreeRtl .dijitTreeExpandoLoading {background-image: url("../../icons/images/loadingAnimation_rtl.gif"); background-position: 100% 0;}.claro .dijitProgressBarRtl .dijitProgressBarFull {border-left-width: 1px; border-right-width: 0px;}.claro .dijitProgressBarIndeterminateRtl .dijitProgressBarTile {-moz-transform: scaleX(-1); -o-transform: scaleX(-1); -webkit-transform: scaleX(-1); transform: scaleX(-1); filter: FlipH; -ms-filter: "FlipH";} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonArrows.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonArrows.png new file mode 100644 index 00000000..642eff39 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonArrows.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonDisabled.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonDisabled.png new file mode 100644 index 00000000..faf57ba1 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonDisabled.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonDisabled.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonDisabled.svg new file mode 100644 index 00000000..72a51a01 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonDisabled.svg @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonEnabled.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonEnabled.png new file mode 100644 index 00000000..0932a994 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonEnabled.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonEnabled.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonEnabled.svg new file mode 100644 index 00000000..d9e564ab --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/buttonEnabled.svg @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/checkboxAndRadioButtons_IE6.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/checkboxAndRadioButtons_IE6.png new file mode 100644 index 00000000..92d22217 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/checkboxAndRadioButtons_IE6.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/checkboxRadioButtonStates.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/checkboxRadioButtonStates.png new file mode 100644 index 00000000..2d06a828 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/checkboxRadioButtonStates.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/commonFormArrows.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/commonFormArrows.png new file mode 100644 index 00000000..6d04742e Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/commonFormArrows.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/error.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/error.png new file mode 100644 index 00000000..46de1cd8 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/error.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/sliderThumbs.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/sliderThumbs.png new file mode 100644 index 00000000..70ab2fe2 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/form/images/sliderThumbs.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/activeGradient.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/activeGradient.png new file mode 100644 index 00000000..e70daaa8 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/activeGradient.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/activeGradient.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/activeGradient.svg new file mode 100644 index 00000000..8ab6ce9c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/activeGradient.svg @@ -0,0 +1,19 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendar.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendar.png new file mode 100644 index 00000000..d892e495 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendar.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendarArrows.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendarArrows.png new file mode 100644 index 00000000..73333ada Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendarArrows.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendarArrows8bit.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendarArrows8bit.png new file mode 100644 index 00000000..c8652600 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/calendarArrows8bit.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/checkmarkNoBorder.gif b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/checkmarkNoBorder.gif new file mode 100644 index 00000000..324bfb3c Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/checkmarkNoBorder.gif differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/checkmarkNoBorder.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/checkmarkNoBorder.png new file mode 100644 index 00000000..ae3271a1 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/checkmarkNoBorder.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dialogCloseIcon.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dialogCloseIcon.png new file mode 100644 index 00000000..f69a1e7d Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dialogCloseIcon.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dialogCloseIcon8bit.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dialogCloseIcon8bit.png new file mode 100644 index 00000000..200c0afb Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dialogCloseIcon8bit.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dnd.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dnd.png new file mode 100644 index 00000000..6e1d8990 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/dnd.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/loadingAnimation.gif b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/loadingAnimation.gif new file mode 100644 index 00000000..694e2cb3 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/loadingAnimation.gif differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/progressBarAnim.gif b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/progressBarAnim.gif new file mode 100644 index 00000000..30c0d9d8 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/progressBarAnim.gif differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/progressBarFull.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/progressBarFull.png new file mode 100644 index 00000000..90c9eaa2 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/progressBarFull.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/spriteArrows.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/spriteArrows.png new file mode 100644 index 00000000..e9d99ab1 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/spriteArrows.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/standardGradient.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/standardGradient.png new file mode 100644 index 00000000..72241f1f Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/standardGradient.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/standardGradient.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/standardGradient.svg new file mode 100644 index 00000000..807c3c70 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/standardGradient.svg @@ -0,0 +1,18 @@ + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/tooltip.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/tooltip.png new file mode 100644 index 00000000..9d279cde Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/tooltip.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/tooltip8bit.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/tooltip8bit.png new file mode 100644 index 00000000..00350722 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/tooltip8bit.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/treeExpandImages.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/treeExpandImages.png new file mode 100644 index 00000000..350a1dde Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/treeExpandImages.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/treeExpandImages8bit.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/treeExpandImages8bit.png new file mode 100644 index 00000000..294ce7a8 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/images/treeExpandImages8bit.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomSelected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomSelected.png new file mode 100644 index 00000000..f92b05f4 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomSelected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomSelected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomSelected.svg new file mode 100644 index 00000000..4e6ff6d4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomSelected.svg @@ -0,0 +1,18 @@ + + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomUnselected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomUnselected.png new file mode 100644 index 00000000..7815d9cf Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomUnselected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomUnselected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomUnselected.svg new file mode 100644 index 00000000..4193238e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabBottomUnselected.svg @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabClose.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabClose.png new file mode 100644 index 00000000..f3b23639 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabClose.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftSelected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftSelected.png new file mode 100644 index 00000000..9700afb3 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftSelected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftSelected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftSelected.svg new file mode 100644 index 00000000..12e7d8a6 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftSelected.svg @@ -0,0 +1,17 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftUnselected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftUnselected.png new file mode 100644 index 00000000..412390e0 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftUnselected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftUnselected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftUnselected.svg new file mode 100644 index 00000000..e31c211b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabLeftUnselected.svg @@ -0,0 +1,16 @@ + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabNested.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabNested.png new file mode 100644 index 00000000..0140cf45 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabNested.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightSelected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightSelected.png new file mode 100644 index 00000000..1a284349 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightSelected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightSelected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightSelected.svg new file mode 100644 index 00000000..d8d3d674 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightSelected.svg @@ -0,0 +1,17 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightUnselected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightUnselected.png new file mode 100644 index 00000000..2bdd00e4 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightUnselected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightUnselected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightUnselected.svg new file mode 100644 index 00000000..d1379a71 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabRightUnselected.svg @@ -0,0 +1,16 @@ + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopSelected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopSelected.png new file mode 100644 index 00000000..f4d57725 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopSelected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopSelected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopSelected.svg new file mode 100644 index 00000000..d06e646e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopSelected.svg @@ -0,0 +1,18 @@ + + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopUnselected.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopUnselected.png new file mode 100644 index 00000000..8c34545f Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopUnselected.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopUnselected.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopUnselected.svg new file mode 100644 index 00000000..c55e9253 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dijit/themes/claro/layout/images/tabTopUnselected.svg @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/LICENSE b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/LICENSE new file mode 100644 index 00000000..139ec624 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/LICENSE @@ -0,0 +1,195 @@ +Dojo is available under *either* the terms of the modified BSD license *or* the +Academic Free License version 2.1. As a recipient of Dojo, you may choose which +license to receive this code under (except as noted in per-module LICENSE +files). Some modules may not be the copyright of the Dojo Foundation. These +modules contain explicit declarations of copyright in both the LICENSE files in +the directories in which they reside and in the code itself. No external +contributions are allowed under licenses which are fundamentally incompatible +with the AFL or BSD licenses that Dojo is distributed under. + +The text of the AFL and BSD licenses is reproduced below. + +------------------------------------------------------------------------------- +The "New" BSD License: +********************** + +Copyright (c) 2005-2016, The Dojo Foundation +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of the Dojo Foundation nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +------------------------------------------------------------------------------- +The Academic Free License, v. 2.1: +********************************** + +This Academic Free License (the "License") applies to any original work of +authorship (the "Original Work") whose owner (the "Licensor") has placed the +following notice immediately following the copyright notice for the Original +Work: + +Licensed under the Academic Free License version 2.1 + +1) Grant of Copyright License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license to do the +following: + +a) to reproduce the Original Work in copies; + +b) to prepare derivative works ("Derivative Works") based upon the Original +Work; + +c) to distribute copies of the Original Work and Derivative Works to the +public; + +d) to perform the Original Work publicly; and + +e) to display the Original Work publicly. + +2) Grant of Patent License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license, under patent +claims owned or controlled by the Licensor that are embodied in the Original +Work as furnished by the Licensor, to make, use, sell and offer for sale the +Original Work and Derivative Works. + +3) Grant of Source Code License. The term "Source Code" means the preferred +form of the Original Work for making modifications to it and all available +documentation describing how to modify the Original Work. Licensor hereby +agrees to provide a machine-readable copy of the Source Code of the Original +Work along with each copy of the Original Work that Licensor distributes. +Licensor reserves the right to satisfy this obligation by placing a +machine-readable copy of the Source Code in an information repository +reasonably calculated to permit inexpensive and convenient access by You for as +long as Licensor continues to distribute the Original Work, and by publishing +the address of that information repository in a notice immediately following +the copyright notice that applies to the Original Work. + +4) Exclusions From License Grant. Neither the names of Licensor, nor the names +of any contributors to the Original Work, nor any of their trademarks or +service marks, may be used to endorse or promote products derived from this +Original Work without express prior written permission of the Licensor. Nothing +in this License shall be deemed to grant any rights to trademarks, copyrights, +patents, trade secrets or any other intellectual property of Licensor except as +expressly stated herein. No patent license is granted to make, use, sell or +offer to sell embodiments of any patent claims other than the licensed claims +defined in Section 2. No right is granted to the trademarks of Licensor even if +such marks are included in the Original Work. Nothing in this License shall be +interpreted to prohibit Licensor from licensing under different terms from this +License any Original Work that Licensor otherwise would have a right to +license. + +5) This section intentionally omitted. + +6) Attribution Rights. You must retain, in the Source Code of any Derivative +Works that You create, all copyright, patent or trademark notices from the +Source Code of the Original Work, as well as any notices of licensing and any +descriptive text identified therein as an "Attribution Notice." You must cause +the Source Code for any Derivative Works that You create to carry a prominent +Attribution Notice reasonably calculated to inform recipients that You have +modified the Original Work. + +7) Warranty of Provenance and Disclaimer of Warranty. Licensor warrants that +the copyright in and to the Original Work and the patent rights granted herein +by Licensor are owned by the Licensor or are sublicensed to You under the terms +of this License with the permission of the contributor(s) of those copyrights +and patent rights. Except as expressly stated in the immediately proceeding +sentence, the Original Work is provided under this License on an "AS IS" BASIS +and WITHOUT WARRANTY, either express or implied, including, without limitation, +the warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY OF THE ORIGINAL WORK IS WITH YOU. +This DISCLAIMER OF WARRANTY constitutes an essential part of this License. No +license to Original Work is granted hereunder except under this disclaimer. + +8) Limitation of Liability. Under no circumstances and under no legal theory, +whether in tort (including negligence), contract, or otherwise, shall the +Licensor be liable to any person for any direct, indirect, special, incidental, +or consequential damages of any character arising as a result of this License +or the use of the Original Work including, without limitation, damages for loss +of goodwill, work stoppage, computer failure or malfunction, or any and all +other commercial damages or losses. This limitation of liability shall not +apply to liability for death or personal injury resulting from Licensor's +negligence to the extent applicable law prohibits such limitation. Some +jurisdictions do not allow the exclusion or limitation of incidental or +consequential damages, so this exclusion and limitation may not apply to You. + +9) Acceptance and Termination. If You distribute copies of the Original Work or +a Derivative Work, You must make a reasonable effort under the circumstances to +obtain the express assent of recipients to the terms of this License. Nothing +else but this License (or another written agreement between Licensor and You) +grants You permission to create Derivative Works based upon the Original Work +or to exercise any of the rights granted in Section 1 herein, and any attempt +to do so except under the terms of this License (or another written agreement +between Licensor and You) is expressly prohibited by U.S. copyright law, the +equivalent laws of other countries, and by international treaty. Therefore, by +exercising any of the rights granted to You in Section 1 herein, You indicate +Your acceptance of this License and all of its terms and conditions. + +10) Termination for Patent Action. This License shall terminate automatically +and You may no longer exercise any of the rights granted to You by this License +as of the date You commence an action, including a cross-claim or counterclaim, +against Licensor or any licensee alleging that the Original Work infringes a +patent. This termination provision shall not apply for an action alleging +patent infringement by combinations of the Original Work with other software or +hardware. + +11) Jurisdiction, Venue and Governing Law. Any action or suit relating to this +License may be brought only in the courts of a jurisdiction wherein the +Licensor resides or in which Licensor conducts its primary business, and under +the laws of that jurisdiction excluding its conflict-of-law provisions. The +application of the United Nations Convention on Contracts for the International +Sale of Goods is expressly excluded. Any use of the Original Work outside the +scope of this License or after its termination shall be subject to the +requirements and penalties of the U.S. Copyright Act, 17 U.S.C. § 101 et +seq., the equivalent laws of other countries, and international treaty. This +section shall survive the termination of this License. + +12) Attorneys Fees. In any action to enforce the terms of this License or +seeking damages relating thereto, the prevailing party shall be entitled to +recover its costs and expenses, including, without limitation, reasonable +attorneys' fees and costs incurred in connection with such action, including +any appeal of such action. This section shall survive the termination of this +License. + +13) Miscellaneous. This License represents the complete agreement concerning +the subject matter hereof. If any provision of this License is held to be +unenforceable, such provision shall be reformed only to the extent necessary to +make it enforceable. + +14) Definition of "You" in This License. "You" throughout this License, whether +in upper or lower case, means an individual or a legal entity exercising rights +under, and complying with all of the terms of, this License. For legal +entities, "You" includes any entity that controls, is controlled by, or is +under common control with you. For purposes of this definition, "control" means +(i) the power, direct or indirect, to cause the direction or management of such +entity, whether by contract or otherwise, or (ii) ownership of fifty percent +(50%) or more of the outstanding shares, or (iii) beneficial ownership of such +entity. + +15) Right to Use. You may use the Original Work in all ways not otherwise +restricted or conditioned by this License or by law, and Licensor promises not +to interfere with or be responsible for such uses by You. + +This license is Copyright (C) 2003-2004 Lawrence E. Rosen. All rights reserved. +Permission is hereby granted to copy and distribute this license without +modification. This license may not be modified without the express written +permission of its copyright owner. diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/LICENSE b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/LICENSE new file mode 100644 index 00000000..eb28b7e4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/LICENSE @@ -0,0 +1,30 @@ +License Disclaimer: + +All contents of this directory are Copyright (c) the Dojo Foundation, with the +following exceptions: +------------------------------------------------------------------------------- + +dojo.css: + * parts Copyright (c) 2007, Yahoo! Inc. All rights reserved. + Distributed under the terms of the BSD License + +The Program includes all or portions of the following software which was obtained under the terms and conditions of the BSD License. + +http://developer.yahoo.com/yui/license.html + +Copyright (c) 2007, Yahoo! Inc. + All rights reserved. + Redistribution and use of this software in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the +documentation and/or other materials provided with the distribution. + * Neither the name of Yahoo! Inc. nor the names of its contributors may be used to endorse or promote products derived from this software without +specific prior written permission of Yahoo! Inc. +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF +MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, +OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/blank.gif b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/blank.gif new file mode 100644 index 00000000..e565824a Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/blank.gif differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/blank.html b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/blank.html new file mode 100644 index 00000000..40fe7705 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/blank.html @@ -0,0 +1 @@ + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/dnd.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/dnd.css new file mode 100644 index 00000000..2080f7fb --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/dnd.css @@ -0,0 +1 @@ +.dojoDndAvatar {font-size: 75%; color: black;}.dojoDndAvatarHeader td {padding-left: 20px; padding-right: 4px; height: 16px;}.dojoDndAvatarHeader {background: #ccc;}.dojoDndAvatarItem {background: #eee;}.dojoDndMove .dojoDndAvatarHeader {background-image: url(images/dndNoMove.png); background-repeat: no-repeat;}.dojoDndCopy .dojoDndAvatarHeader {background-image: url(images/dndNoCopy.png); background-repeat: no-repeat;}.dojoDndMove .dojoDndAvatarCanDrop .dojoDndAvatarHeader {background-image: url(images/dndMove.png); background-repeat: no-repeat;}.dojoDndCopy .dojoDndAvatarCanDrop .dojoDndAvatarHeader {background-image: url(images/dndCopy.png); background-repeat: no-repeat;}.dojoDndHandle {cursor: move;}.dojoDndIgnore {cursor: default;}.dj_a11y .dojoDndAvatar {font-size: 1em; font-weight:bold;}.dj_a11y .dojoDndAvatarHeader td {padding-left:2px !important;}.dj_a11y .dojoDndAvatarHeader td span {padding-right: 5px;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/dojo.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/dojo.css new file mode 100644 index 00000000..ac90e0ca --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/dojo.css @@ -0,0 +1 @@ +body, div, dl, dt, dd, li, h1, h2, h3, h4, h5, h6, pre, form, fieldset, input, textarea, p, blockquote, th, td {margin: 0; padding: 0;}fieldset, img {border: 0 none;}address, caption, cite, code, dfn, th, var {font-style: normal; font-weight: normal;}caption, th {text-align: left;}q:before, q:after {content:"";}abbr, acronym {border:0;}body {font: 12px Myriad,Helvetica,Tahoma,Arial,clean,sans-serif; *font-size: 75%;}h1 {font-size: 1.5em; font-weight: normal; line-height: 1em; margin-top: 1em; margin-bottom:0;}h2 {font-size: 1.1667em; font-weight: bold; line-height: 1.286em; margin-top: 1.929em; margin-bottom:0.643em;}h3, h4, h5, h6 {font-size: 1em; font-weight: bold; line-height: 1.5em; margin-top: 1.5em; margin-bottom: 0;}p {font-size: 1em; margin-top: 1.5em; margin-bottom: 1.5em; line-height: 1.5em;}blockquote {font-size: 0.916em; margin-top: 3.272em; margin-bottom: 3.272em; line-height: 1.636em; padding: 1.636em; border-top: 1px solid #ccc; border-bottom: 1px solid #ccc;}ol li, ul li {font-size: 1em; line-height: 1.5em; margin: 0;}pre, code {font-size:115%; *font-size:100%; font-family: Courier, "Courier New"; background-color: #efefef; border: 1px solid #ccc;}pre {border-width: 1px 0; padding: 1.5em;}table {font-size:100%;}.dojoTabular {border-collapse: collapse; border-spacing: 0; border: 1px solid #ccc; margin: 0 1.5em;}.dojoTabular th {text-align: center; font-weight: bold;}.dojoTabular thead,.dojoTabular tfoot {background-color: #efefef; border: 1px solid #ccc; border-width: 1px 0;}.dojoTabular th,.dojoTabular td {padding: 0.25em 0.5em;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/iframe_history.html b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/iframe_history.html new file mode 100644 index 00000000..2c5acce2 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/iframe_history.html @@ -0,0 +1,44 @@ + + + + + + + + + +

The Dojo Toolkit -- iframe_history.html

+ +

This file is used in Dojo's back/fwd button management.

+ + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndCopy.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndCopy.png new file mode 100644 index 00000000..660ca4fb Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndCopy.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndMove.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndMove.png new file mode 100644 index 00000000..74af29c0 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndMove.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndNoCopy.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndNoCopy.png new file mode 100644 index 00000000..998c2f26 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndNoCopy.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndNoMove.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndNoMove.png new file mode 100644 index 00000000..e909173e Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/dojo/resources/images/dndNoMove.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/put-selector/LICENSE b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/put-selector/LICENSE new file mode 100644 index 00000000..c17fa742 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/put-selector/LICENSE @@ -0,0 +1,190 @@ +put-selector is available under *either* the terms of the modified BSD license *or* the +Academic Free License version 2.1. As a recipient of put-selector, you may choose which +license to receive this code under. + +The text of the AFL and BSD licenses is reproduced below. + +------------------------------------------------------------------------------- +The "New" BSD License: +********************** + +Copyright (c) 2010-2011, The Dojo Foundation +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of the Dojo Foundation nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +------------------------------------------------------------------------------- +The Academic Free License, v. 2.1: +********************************** + +This Academic Free License (the "License") applies to any original work of +authorship (the "Original Work") whose owner (the "Licensor") has placed the +following notice immediately following the copyright notice for the Original +Work: + +Licensed under the Academic Free License version 2.1 + +1) Grant of Copyright License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license to do the +following: + +a) to reproduce the Original Work in copies; + +b) to prepare derivative works ("Derivative Works") based upon the Original +Work; + +c) to distribute copies of the Original Work and Derivative Works to the +public; + +d) to perform the Original Work publicly; and + +e) to display the Original Work publicly. + +2) Grant of Patent License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license, under patent +claims owned or controlled by the Licensor that are embodied in the Original +Work as furnished by the Licensor, to make, use, sell and offer for sale the +Original Work and Derivative Works. + +3) Grant of Source Code License. The term "Source Code" means the preferred +form of the Original Work for making modifications to it and all available +documentation describing how to modify the Original Work. Licensor hereby +agrees to provide a machine-readable copy of the Source Code of the Original +Work along with each copy of the Original Work that Licensor distributes. +Licensor reserves the right to satisfy this obligation by placing a +machine-readable copy of the Source Code in an information repository +reasonably calculated to permit inexpensive and convenient access by You for as +long as Licensor continues to distribute the Original Work, and by publishing +the address of that information repository in a notice immediately following +the copyright notice that applies to the Original Work. + +4) Exclusions From License Grant. Neither the names of Licensor, nor the names +of any contributors to the Original Work, nor any of their trademarks or +service marks, may be used to endorse or promote products derived from this +Original Work without express prior written permission of the Licensor. Nothing +in this License shall be deemed to grant any rights to trademarks, copyrights, +patents, trade secrets or any other intellectual property of Licensor except as +expressly stated herein. No patent license is granted to make, use, sell or +offer to sell embodiments of any patent claims other than the licensed claims +defined in Section 2. No right is granted to the trademarks of Licensor even if +such marks are included in the Original Work. Nothing in this License shall be +interpreted to prohibit Licensor from licensing under different terms from this +License any Original Work that Licensor otherwise would have a right to +license. + +5) This section intentionally omitted. + +6) Attribution Rights. You must retain, in the Source Code of any Derivative +Works that You create, all copyright, patent or trademark notices from the +Source Code of the Original Work, as well as any notices of licensing and any +descriptive text identified therein as an "Attribution Notice." You must cause +the Source Code for any Derivative Works that You create to carry a prominent +Attribution Notice reasonably calculated to inform recipients that You have +modified the Original Work. + +7) Warranty of Provenance and Disclaimer of Warranty. Licensor warrants that +the copyright in and to the Original Work and the patent rights granted herein +by Licensor are owned by the Licensor or are sublicensed to You under the terms +of this License with the permission of the contributor(s) of those copyrights +and patent rights. Except as expressly stated in the immediately proceeding +sentence, the Original Work is provided under this License on an "AS IS" BASIS +and WITHOUT WARRANTY, either express or implied, including, without limitation, +the warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY OF THE ORIGINAL WORK IS WITH YOU. +This DISCLAIMER OF WARRANTY constitutes an essential part of this License. No +license to Original Work is granted hereunder except under this disclaimer. + +8) Limitation of Liability. Under no circumstances and under no legal theory, +whether in tort (including negligence), contract, or otherwise, shall the +Licensor be liable to any person for any direct, indirect, special, incidental, +or consequential damages of any character arising as a result of this License +or the use of the Original Work including, without limitation, damages for loss +of goodwill, work stoppage, computer failure or malfunction, or any and all +other commercial damages or losses. This limitation of liability shall not +apply to liability for death or personal injury resulting from Licensor's +negligence to the extent applicable law prohibits such limitation. Some +jurisdictions do not allow the exclusion or limitation of incidental or +consequential damages, so this exclusion and limitation may not apply to You. + +9) Acceptance and Termination. If You distribute copies of the Original Work or +a Derivative Work, You must make a reasonable effort under the circumstances to +obtain the express assent of recipients to the terms of this License. Nothing +else but this License (or another written agreement between Licensor and You) +grants You permission to create Derivative Works based upon the Original Work +or to exercise any of the rights granted in Section 1 herein, and any attempt +to do so except under the terms of this License (or another written agreement +between Licensor and You) is expressly prohibited by U.S. copyright law, the +equivalent laws of other countries, and by international treaty. Therefore, by +exercising any of the rights granted to You in Section 1 herein, You indicate +Your acceptance of this License and all of its terms and conditions. + +10) Termination for Patent Action. This License shall terminate automatically +and You may no longer exercise any of the rights granted to You by this License +as of the date You commence an action, including a cross-claim or counterclaim, +against Licensor or any licensee alleging that the Original Work infringes a +patent. This termination provision shall not apply for an action alleging +patent infringement by combinations of the Original Work with other software or +hardware. + +11) Jurisdiction, Venue and Governing Law. Any action or suit relating to this +License may be brought only in the courts of a jurisdiction wherein the +Licensor resides or in which Licensor conducts its primary business, and under +the laws of that jurisdiction excluding its conflict-of-law provisions. The +application of the United Nations Convention on Contracts for the International +Sale of Goods is expressly excluded. Any use of the Original Work outside the +scope of this License or after its termination shall be subject to the +requirements and penalties of the U.S. Copyright Act, 17 U.S.C. § 101 et +seq., the equivalent laws of other countries, and international treaty. This +section shall survive the termination of this License. + +12) Attorneys Fees. In any action to enforce the terms of this License or +seeking damages relating thereto, the prevailing party shall be entitled to +recover its costs and expenses, including, without limitation, reasonable +attorneys' fees and costs incurred in connection with such action, including +any appeal of such action. This section shall survive the termination of this +License. + +13) Miscellaneous. This License represents the complete agreement concerning +the subject matter hereof. If any provision of this License is held to be +unenforceable, such provision shall be reformed only to the extent necessary to +make it enforceable. + +14) Definition of "You" in This License. "You" throughout this License, whether +in upper or lower case, means an individual or a legal entity exercising rights +under, and complying with all of the terms of, this License. For legal +entities, "You" includes any entity that controls, is controlled by, or is +under common control with you. For purposes of this definition, "control" means +(i) the power, direct or indirect, to cause the direction or management of such +entity, whether by contract or otherwise, or (ii) ownership of fifty percent +(50%) or more of the outstanding shares, or (iii) beneficial ownership of such +entity. + +15) Right to Use. You may use the Original Work in all ways not otherwise +restricted or conditioned by this License or by law, and Licensor promises not +to interfere with or be responsible for such uses by You. + +This license is Copyright (C) 2003-2004 Lawrence E. Rosen. All rights reserved. +Permission is hereby granted to copy and distribute this license without +modification. This license may not be modified without the express written +permission of its copyright owner. diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/config.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/config.js new file mode 100644 index 00000000..3118c68c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/config.js @@ -0,0 +1,2 @@ +var dojoConfig=function(){var a=window&&"file:"===window.location.protocol&&(0Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ar.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ar.js new file mode 100644 index 00000000..ff5688fe --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ar.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_ar',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"حسنا","buttonCancel":"الغاء","buttonSave":"حفظ","itemClose":"اغلاق","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"جاري التحميل...","errorState":"عفوا، حدث خطأ","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ca.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ca.js new file mode 100644 index 00000000..7ba6be37 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ca.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_ca',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"D'acord","buttonCancel":"Cancel·la","buttonSave":"Desa","itemClose":"Tanca","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"S'està carregant...","errorState":"Ens sap greu. S'ha produït un error.","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_cs.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_cs.js new file mode 100644 index 00000000..1ce1b26c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_cs.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_cs',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Storno","buttonSave":"Uložit","itemClose":"Zavřít","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Probíhá načítání...","errorState":"Omlouváme se, došlo k chybě","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_da.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_da.js new file mode 100644 index 00000000..e1e487be --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_da.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_da',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Annullér","buttonSave":"Gem","itemClose":"Luk","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Indlæser...","errorState":"Der er opstået en fejl","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_de.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_de.js new file mode 100644 index 00000000..5628ef09 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_de.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_de',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Abbrechen","buttonSave":"Speichern","itemClose":"Schließen","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Wird geladen...","errorState":"Es ist ein Fehler aufgetreten.","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_el.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_el.js new file mode 100644 index 00000000..d4cbaf8a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_el.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_el',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"ΟΚ","buttonCancel":"Ακύρωση","buttonSave":"Αποθήκευση","itemClose":"Κλείσιμο","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Φόρτωση...","errorState":"Σας ζητούμε συγνώμη, παρουσιάστηκε σφάλμα","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_en-gb.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_en-gb.js new file mode 100644 index 00000000..043d4de4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_en-gb.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_en-gb',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Cancel","buttonSave":"Save","itemClose":"Close","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Loading...","errorState":"Sorry, an error occurred","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_en-us.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_en-us.js new file mode 100644 index 00000000..36c5913c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_en-us.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_en-us',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Cancel","buttonSave":"Save","itemClose":"Close","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Loading...","errorState":"Sorry, an error occurred","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_es-es.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_es-es.js new file mode 100644 index 00000000..ec77d51b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_es-es.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_es-es',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"Aceptar","buttonCancel":"Cancelar","buttonSave":"Guardar","itemClose":"Cerrar","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Cargando...","errorState":"Lo siento, se ha producido un error","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_fi-fi.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_fi-fi.js new file mode 100644 index 00000000..a2bd5b0b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_fi-fi.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_fi-fi',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Peruuta","buttonSave":"Tallenna","itemClose":"Sulje","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Lataus on meneillään...","errorState":"On ilmennyt virhe.","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_fr-fr.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_fr-fr.js new file mode 100644 index 00000000..defa4d5d --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_fr-fr.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_fr-fr',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Annuler","buttonSave":"Enregistrer","itemClose":"Fermer","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Chargement...","errorState":"Une erreur est survenue","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_he-il.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_he-il.js new file mode 100644 index 00000000..5881a668 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_he-il.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_he-il',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"אישור","buttonCancel":"ביטול","buttonSave":"שמירה","itemClose":"סגירה","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"טעינה...‏","errorState":"אירעה שגיאה","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_hu.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_hu.js new file mode 100644 index 00000000..6bca46bc --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_hu.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_hu',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Mégse","buttonSave":"Mentés","itemClose":"Bezárás","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Betöltés...","errorState":"Sajnálom, hiba történt","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_it-it.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_it-it.js new file mode 100644 index 00000000..745c9a08 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_it-it.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_it-it',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"Ok","buttonCancel":"Annulla","buttonSave":"Salva","itemClose":"Chiudi","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Caricamento in corso...","errorState":"Si è verificato un errore","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ja-jp.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ja-jp.js new file mode 100644 index 00000000..a620682e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ja-jp.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_ja-jp',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"新しいタブで開く","Open":"開く","NoExport":"このシステムはエクスポートされませんでした。","ModelBrowserButtonLabel":"モデル ブラウザーの非表示/表示","searchResults":"検索結果:","propertyName":"プロパティ名","ExplorerBarButtonLabel":"エクスプローラー バーの非表示/表示","advancedSearch":"詳細検索","ViewAll":"すべて表示","parent":"親","name":"名前","searchCurrentAndBelow":"現在の階層以下を検索...","propertyValue":"プロパティ値","FitToViewButtonLabel":"ビューに合わせる","maskType":"マスク タイプ","MarqueeZoomButtonLabel":"ズーム","blockType":"ブロック タイプ","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"新しいタブで開く","Open":"開く","Title":"モデル ブラウザー","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"キャンセル","buttonSave":"保存","itemClose":"閉じる","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"ロード中...","errorState":"エラーが発生しました。","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"コード生成","ParameterAttributes":"パラメーター属性","Documentation":"ドキュメンテーション","LoggingAndAccessibility":"ログとユーザー補助機能","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink の Web ビューは、ローカル ファイルのセキュリティ制限のため Google Chrome では表示できません。ローカル ファイルへのアクセスを可能にするには、以下を試してください。

Microsoft Windows

  1. [スタート] ボタンをクリックして、\"Chrome\" などのブラウザーの実行可能ファイルを検索します。
  2. 一致したブラウザー検索結果を右クリックして空白の領域にドラッグします。[ショートカットをここに作成] を選択します。
  3. 新しく作成されたショートカットを右クリックして [プロパティ] を選択します。
  4. [ショートカット] タブをクリックします。
  5. ターゲットのエディット ボックスで、\"--allow-file-access-from-files\" を引用符なしで追加します。
  6. [OK] をクリックしてプロパティ ダイアログ ボックスを閉じます。
  7. ブラウザーが実行されていないことを確認します。
  8. 新しく作成されたショートカットをダブルクリックしてブラウザーを起動します。

Mac

  1. Terminal.app を実行します。
  2. \"open /Applications Google Chrome.app --allow-file-access-from-files\" を引用符なしで入力します。

Linux

  1. ターミナルを起動します。
  2. \"./chromium-browser --allow-file-access-from-files\" を引用符なしで入力します。
","UnsupportedBrowser":"サポートされていないブラウザー","SvgSupport":"

SVG サポートが必要

ブラウザーが Scalable Vector Graphics をサポートしていません。次のいずれかのブラウザーを使用してみてください。

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ko-kr.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ko-kr.js new file mode 100644 index 00000000..bdbfadb1 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ko-kr.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_ko-kr',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"확인","buttonCancel":"취소","buttonSave":"저장","itemClose":"닫기","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"로드 중...","errorState":"죄송합니다. 오류가 발생했습니다.","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_nb.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_nb.js new file mode 100644 index 00000000..7db54635 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_nb.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_nb',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Avbryt","buttonSave":"Lagre","itemClose":"Lukk","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Laster inn...","errorState":"Det oppsto en feil","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_nl-nl.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_nl-nl.js new file mode 100644 index 00000000..879fecaf --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_nl-nl.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_nl-nl',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Annuleren","buttonSave":"Opslaan","itemClose":"Sluiten","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Bezig met laden...","errorState":"Er is een fout opgetreden","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pl.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pl.js new file mode 100644 index 00000000..06fc4674 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pl.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_pl',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Anuluj","buttonSave":"Zapisz","itemClose":"Zamknij","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Ładowanie...","errorState":"Niestety, wystąpił błąd","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pt-br.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pt-br.js new file mode 100644 index 00000000..57004b37 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pt-br.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_pt-br',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Cancelar","buttonSave":"Salvar","itemClose":"Fechar","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Carregando...","errorState":"Desculpe, ocorreu um erro","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pt-pt.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pt-pt.js new file mode 100644 index 00000000..41f87c59 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_pt-pt.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_pt-pt',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Cancelar","buttonSave":"Guardar","itemClose":"Fechar","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"A carregar...","errorState":"Lamentamos, mas ocorreu um erro","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ru.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ru.js new file mode 100644 index 00000000..93c849dc --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_ru.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_ru',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Отмена","buttonSave":"Сохранить","itemClose":"Закрыть","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Загрузка...","errorState":"Извините, возникла ошибка","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sk.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sk.js new file mode 100644 index 00000000..8c906e41 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sk.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_sk',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Zrušiť","buttonSave":"Uložiť","itemClose":"Zatvoriť","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Zavádza sa...","errorState":"Ľutujeme, ale vyskytla sa chyba","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sl.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sl.js new file mode 100644 index 00000000..b0fbadda --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sl.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_sl',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"V redu","buttonCancel":"Prekliči","buttonSave":"Shrani","itemClose":"Zapri","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Nalaganje ...","errorState":"Oprostite, prišlo je do napake.","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sv.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sv.js new file mode 100644 index 00000000..df8e4da7 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_sv.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_sv',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"OK","buttonCancel":"Avbryt","buttonSave":"Spara","itemClose":"Stäng","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Läser in...","errorState":"Det har inträffat ett fel.","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_th.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_th.js new file mode 100644 index 00000000..c0250183 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_th.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_th',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"ตกลง","buttonCancel":"ยกเลิก","buttonSave":"บันทึก","itemClose":"ปิด","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"กำลังโหลด...","errorState":"ขออภัย เกิดข้อผิดพลาด","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_tr.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_tr.js new file mode 100644 index 00000000..97284545 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_tr.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_tr',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"Tamam","buttonCancel":"İptal","buttonSave":"Kaydet","itemClose":"Kapat","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"Yükleniyor...","errorState":"Üzgünüz, bir hata oluştu","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_zh-cn.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_zh-cn.js new file mode 100644 index 00000000..9459264b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_zh-cn.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_zh-cn',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"确定","buttonCancel":"取消","buttonSave":"保存","itemClose":"关闭","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"正在加载...","errorState":"对不起,发生了错误","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_zh-tw.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_zh-tw.js new file mode 100644 index 00000000..0f8fa9bf --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/nls/webview_zh-tw.js @@ -0,0 +1,13 @@ +define('webview/nls/webview_zh-tw',{ +'webview/resources/slreportgen_webview/nls/modelviewer':{"OpenInNewTab":"Open In New Tab","Open":"Open","NoExport":"This system was not exported.","ModelBrowserButtonLabel":"Hide/Show Model Browser","searchResults":"Search Results:","propertyName":"Property Name","ExplorerBarButtonLabel":"Hide/Show Explorer Bar","advancedSearch":"Advanced Search","ViewAll":"View All","parent":"Parent","name":"Name","searchCurrentAndBelow":"Search current and below...","propertyValue":"Property Value","FitToViewButtonLabel":"Fit to View","maskType":"Mask Type","MarqueeZoomButtonLabel":"Zoom","blockType":"Block Type","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelbrowser':{"OpenInNewTab":"Open In New Tab","Open":"Open","Title":"Model Browser","_localized":{}} +, +'dijit/nls/common':{"buttonOk":"確定","buttonCancel":"取消","buttonSave":"儲存","itemClose":"關閉","_localized":{}} +, +'dijit/nls/loading':{"loadingState":"載入中...","errorState":"抱歉,發生錯誤","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/modelinspector':{"CodeGeneration":"Code Generation","ParameterAttributes":"Parameter Attributes","Documentation":"Documentation","LoggingAndAccessibility":"Logging and Accessibility","_localized":{}} +, +'webview/resources/slreportgen_webview/nls/utils':{"ChromeLocalFileSupport":"

Simulink Web View cannot be viewed in Google Chrome because of local file security restrictions. To allow local file access, try the following:

Microsoft Windows

  1. Click the Start button and search for the browser executable, such as \"Chrome\".
  2. Right-click and drag the matched browser search result to an open area. Select Create shortcuts here.
  3. Right-click the newly created shortcut and select Properties.
  4. Click the Shortcut tab.
  5. In the target edit box, append \"--allow-file-access-from-files\", with no quotes.
  6. Click OK to dismiss property dialog box.
  7. Verify that the browser is no longer running.
  8. Double-click on the newly created shortcut to start the browser.

Mac

  1. Run Terminal.app.
  2. Type \"open /Applications Google Chrome.app --allow-file-access-from-files\", with no quotes.

Linux

  1. Start terminal.
  2. Type \"./chromium-browser --allow-file-access-from-files\", with no quotes.
","UnsupportedBrowser":"Unsupported Browser","SvgSupport":"

SVG Support Required

Your browser does not support Scalable Vector Graphics. Try to use one of the following browser:

","_localized":{}} +}); \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/palette/images/PaletteIcons.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/palette/images/PaletteIcons.png new file mode 100644 index 00000000..bf1dcd15 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/palette/images/PaletteIcons.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/palette/images/PaletteSeparator.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/palette/images/PaletteSeparator.png new file mode 100644 index 00000000..e0615053 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/palette/images/PaletteSeparator.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/search/images/SearchIcons.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/search/images/SearchIcons.png new file mode 100644 index 00000000..548f272a Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/search/images/SearchIcons.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/webview.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/webview.css new file mode 100644 index 00000000..f633e35a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/webview.css @@ -0,0 +1 @@ + .wvApp {width: 100%; height: 100%; font-family: sans-serif; background-color: #e0e2e2; padding: 0px; margin: 0px; overflow: hidden;}.wvApp .dijitSplitterVHover {background-color: #e0e2e2; background-image: none;}.wvApp .dijitSplitterVActive {background-color: #e0e2e2; background-image: none;}.wvApp .dijitSplitterHHover {background-color: #e0e2e2; background-image: none;}.wvApp .dijitSplitterHActive {background-color: #e0e2e2; background-image: none;}*:focus {outline: none;} .wvModelBrowser {background-color: #dee4eb; margin:0; padding:0;}.wvModelBrowserTitleBar {padding: 5px 7px 4px 7px;}.wvModelBrowserTitleText {display: none; padding: 0 1px; font-size: 1.1em; color: #000000; font-weight: bold;}.dijitMenu.wvModelBrowser {border-color: #afafaf;}.dijitMenu.wvModelBrowser .dijitMenuItem {font-family: sans-serif;}.dijitMenu.wvModelBrowser .dijitMenuItemSelected td{background-color: #ecf5fc; background-image: none; border-color: #ecf5fc;}.wvModelBrowser .dijitTreeRowHover {background-color: #ecf5fc; background-image: none; border-color: #ecf5fc; cursor: pointer;}.wvModelBrowser .dijitTreeRowSelected {background-color: #c6defe; background-image: none; border-color: #c6defe; cursor: pointer;}.wvModelBrowser .dijitTreeContent {cursor: pointer;}.wvModelBrowser .wvModelBrowserTreeRowHover {background-color: #ecf5fc; background-image: none; border-color: #ecf5fc; cursor: pointer;}.dgrid {position: relative; overflow: hidden; border: 1px solid #ddd; height: 30em; display: block;}.dgrid-header {background-color: #eee;}.dgrid-header-row {position: absolute; right: 17px; left: 0;}.dgrid-header-scroll {position: absolute; top: 0; right: 0;}.dgrid-footer {position: absolute; bottom: 0; width: 100%;}.dgrid-header-hidden,html.has-quirks .dgrid-header-hidden .dgrid-cell {font-size: 0; height: 0 !important; border-top: none !important; border-bottom: none !important; margin-top: 0 !important; margin-bottom: 0 !important; padding-top: 0 !important; padding-bottom: 0 !important;}.dgrid-footer-hidden {display: none;}.dgrid-sortable {cursor: pointer;}.dgrid-header, .dgrid-header-row, .dgrid-footer {overflow: hidden; background-color: #eee;}.dgrid-row-table {border-collapse: collapse; border: none; table-layout: fixed; empty-cells: show; width: 100%; height: 100%;}.dgrid-cell {padding: 0px; text-align: left; overflow: hidden; vertical-align: top; border: 1px solid #ddd; border-top-style: none; box-sizing: border-box; -moz-box-sizing: border-box; -ms-box-sizing: border-box; -webkit-box-sizing: border-box;}.dgrid-cell-padding {padding: 3px;}.dgrid-content {position: relative; height: 99%;}.dgrid-scroller {overflow-x: auto; overflow-y: scroll; position: absolute; top: 0px; margin-top: 25px; bottom: 0px; width: 100%;}.dgrid-preload {font-size: 0; line-height: 0;}.dgrid-loading {position: relative; height: 100%;}.dgrid-above {position: absolute; bottom: 0;}.ui-icon {width: 16px; height: 16px; background-image: url("../dgrid/css/images/ui-icons_222222_256x240.png");}.ui-icon-triangle-1-e {background-position: -32px -16px;}.ui-icon-triangle-1-se {background-position: -48px -16px;}.dgrid-expando-icon {width: 16px; height: 16px;}.dgrid-tree-container {-webkit-transition-duration: 0.3s; -moz-transition-duration: 0.3s; -ms-transition-duration: 0.3s; -o-transition-duration: 0.3s; transition-duration: 0.3s; overflow: hidden;}.dgrid-tree-container.dgrid-tree-resetting {-webkit-transition-duration: 0; -moz-transition-duration: 0; -ms-transition-duration: 0; -o-transition-duration: 0; transition-duration: 0;}.dgrid-sort-arrow {background-position: -64px -16px; display: block; float: right; margin: 0 4px 0 5px; height: 12px;}.dgrid-sort-up .dgrid-sort-arrow {background-position: 0px -16px;}.dgrid-selected {background-color: #bfd6eb;}.dgrid-input {width: 99%;}html.has-mozilla .dgrid *:focus, html.has-opera .dgrid *:focus {outline: 1px dotted;}html.has-ie-6-7.has-no-quirks .dgrid-row-table {width: auto;}html.has-quirks .dgrid-row-table, html.has-ie-6 .dgrid-row-table {height: auto;}html.has-quirks .dgrid-header-scroll,html.has-ie-6 .dgrid-header-scroll {font-size: 0;}html.has-mozilla .dgrid-focus {outline-offset: -1px;}.dgrid-scrollbar-measure {width: 100px; height: 100px; overflow: scroll; position: absolute; top: -9999px;}.dgrid-autoheight {height: auto;}.dgrid-autoheight .dgrid-scroller {position: relative; overflow-y: hidden;}.dgrid-autoheight .dgrid-header-scroll {display: none;}.dgrid-autoheight .dgrid-header {right: 0;}#dgrid-css-dgrid-loaded {display: none;}.touchscroll-x, .touchscroll-y {display: none; overflow: hidden; position: absolute; opacity: 0.7;}.touchscroll-fadeout .touchscroll-x, .touchscroll-fadeout .touchscroll-y {opacity: 0; -webkit-transition: opacity 0.3s ease-out 0.1s; -moz-transition: opacity 0.3s ease-out 0.1s; -o-transition: opacity 0.3s ease-out 0.1s; transition: opacity 0.3s ease-out 0.1s;}.touchscroll-bar {background-color: rgba(88,88,88,0.97); border: 1px solid rgba(88,88,88,1); border-radius: 3px; -webkit-box-shadow: 0 0 1px rgba(88,88,88,0.4);}.touchscroll-x {left: 1px; right: 3px; bottom: 1px; height: 5px;}.touchscroll-y {top: 1px; bottom: 3px; right: 1px; width: 5px;}.touchscroll-scrollable-x .touchscroll-x, .touchscroll-scrollable-y .touchscroll-y {display: block;}.touchscroll-bar {-webkit-transition: transform cubic-bezier(0.33, 0.66, 0.66, 1); -moz-transition: transform cubic-bezier(0.33, 0.66, 0.66, 1); -o-transition: transform cubic-bezier(0.33, 0.66, 0.66, 1); transition: transform cubic-bezier(0.33, 0.66, 0.66, 1);}#dgrid-css-TouchScroll-loaded {display: none;}.wvModelInspector {background-color: #e1e2e2;}.wvModelInspectorTitleBar {padding: 5px 7px 4px 7px;}.wvModelInspectorTitleText {padding: 0 1px; font-size: 1.1em; font-weight: bold; color: #000000;}.wvModelInspectorContainer {width:100%; margin:0; padding:0; border:0; overflow:auto;}.wvModelInspector .wvModelInspectorTitlePane {margin:0; padding:0; border:0;}.wvModelInspector .dijitTitlePaneContentOuter {border: 0;}.wvModelInspector .dijitTitlePaneTitleOpen {background-color: #afafaf; border-color: #afafaf; background-image: none;}.wvModelInspector .dijitTitlePaneTitleClosed {background-color: #afafaf; border-color: #afafaf; background-image: none;}.wvModelInspector .dijitTitlePaneTitleHover {background-color: #afafaf; border-color: #afafaf; background-image: none;}.wvModelInspector .dijitTitlePaneTitleFocus {margin-top: 2px; padding-bottom: 2px;}.wvModelInspector .dijitTitlePaneTitle {padding: 0 7px 0 7px;}.wvModelInspector .dijitTitlePaneTextNode {font-weight: bold; font-size: 1.1em;}.wvModelInspector .dgrid {height: auto; border: 0px; width: 100%;}.wvModelInspector .dgrid .dgrid-scroller {position: relative; overflow-y: hidden;}.wvModelInspector .dgrid-header-scroll {display: none;}.wvModelInspector .dgrid-row-table{margin: 0;}.wvModelInspector .dgrid-header {background-color: #eee; position: absolute; right: 0px; left: 0px; width: 100%;}.wvModelInspector .field-name {background-color: #e1e2e2;}.wvModelInspector .dgrid-cell {border-color: #e1e2e2;}.wvModelInspectorFieldName {height: auto; width: auto; text-overflow: ellipsis; white-space: nowrap; overflow: hidden; display: block;}.wvModelInspectorFieldValue {white-space: pre-wrap;}.palette-widget {width:28px; height:100%; background-color:#d0d3d3; overflow:hidden; border: none;}.palette-separator {padding: 2px 6px 2px 6px; width: 16px; height: 1px;}.palette-separator-icon {background-image: url("palette/images/PaletteSeparator.png"); background-repeat: no-repeat; width: 16px; height: 1px;}.palette-widget .dijitButton {margin: 0px;}.palette-widget .dijitButton .dijitButtonNode {border: none; border-radius: 0px; padding: 6px 6px 6px 6px; color: #000000; box-shadow: none; background-color: transparent; background-image: none !important;}.palette-widget .dijitButtonHover .dijitButtonNode {background-color: #d7d9d9; -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.palette-widget .dijitButtonChecked .dijitButtonNode {background-color: white; -webkit-transition-duration: 0.1s; -moz-transition-duration: 0.1s; transition-duration: 0.1s;}.Palette_Collapse,.Palette_CollapseHover,.Palette_Expand,.Palette_ExpandHover,.Palette_Hide,.Palette_HideHover,.Palette_Show,.Palette_ShowHover,.Palette_ZoomFitView,.Palette_ZoomFitViewHover,.Palette_ZoomMarquee,.Palette_ZoomMarqueeHover {background-image: url("palette/images/PaletteIcons.png"); width: 16px; height: 16px;}.Palette_Collapse {background-position: -0px;}.Palette_CollapseHover {background-position: -16px;}.Palette_Expand {background-position: -32px;}.Palette_ExpandHover {background-position: -48px;}.Palette_Hide {background-position: -64px;}.Palette_HideHover {background-position: -80px;}.Palette_Show {background-position: -96px;}.Palette_ShowHover {background-position: -112px;}.Palette_ZoomFitView {background-position: -128px;}.Palette_ZoomFitViewHover {background-position: -144px;}.Palette_ZoomMarquee {background-position: -160px;}.Palette_ZoomMarqueeHover {background-position: -176px;}.system-button-widget {padding: 0; margin: 0;}.system-button-widget .dijitButton .dijitButtonNode {background-color: transparent; box-shadow: none; border: none; background-image: none; padding: 0;}.system-button-widget .dijitButton .dijitButtonNode .dijitButtonText {padding: 0 0 0 0.3em;}.system-button-widget .dijitDropDownButton {margin: 0;}.dijitPopup {box-shadow: none !important;}.dijitMenu.system-button-widget{border-color: #afafaf;}.dijitMenu.system-button-widget .dijitMenuItem {font-family: sans-serif;}.dijitMenu.system-button-widget .dijitMenuItemSelected td{background-color: #ecf5fc; background-image: none; border-color: #ecf5fc;}.system-button-widget .dijitDropDownButton .dijitButtonNode {background-color: transparent; box-shadow: none; border: none; background-image: none; padding: 0;}.system-button-widget .dijitDropDownButton .dijitButtonNode .dijitButtonText {display: none;}.system-button-widgetHover {background-color: #ecf5fc;}.system-button-widget .dijitDropDownButton .dijitArrowButtonInner {background-position: -26px 53%;}.system-button-widget .dijitDropDownButtonOpened .dijitArrowButtonInner {background-position: -51px 53%;}.wvViewAllTab {}.dijitMenu.wvViewAllTab {border-color: #afafaf;}.dijitMenu.wvViewAllTab .dijitMenuItem {font-family: sans-serif;}.dijitMenu.wvViewAllTab .dijitMenuItemSelected td{background-color: #ecf5fc; background-image: none; border-color: #ecf5fc;}.wvViewAllTabImg {cursor: pointer; padding: 5px; margin: 5px;}.wvViewAllTabImgHover {background-color: #ecf5fc;}.wvViewAllTabImgSelected {background-color: #c6defe;}.model-graphics-widget {width: 100%; height: 100%;}.model-graphics-canvas {width: 100%; height: 100%;}.wvInlineSearch.dijitBorderContainer-child {border: 0;}.wvInlineSearch > form {display: inline-block; background-color: rgb(240,240,240);}.wvInlineSearch .dijitTextBox {height: 22px; border: 1px solid rgb(165,165,165); margin: 3px 0px 3px 0px; padding: 0; background-color: white;}.wvInlineSearch .dijitTextBoxFocused {border: 1px solid rgb(0,153,255); background-color: white;}.wvInlineSearch .dijitTextBoxHover {border: 1px solid rgb(0,153,255); background-color: white;}.wvInlineSearch .dijitTextBox .dijitInputContainer {padding: 0px 0px 0px 8px; line-height: 22px; height: 22px;}.wvInlineSearch .dijitTextBox .dijitPlaceHolder {font-size: 12px; padding: 0px 0px 0px 8px; line-height: 22px; height: 22px;}.wvInlineSearch .dijitTextBox .dijitInputInner {font-size: 12px; padding: 0px 0px 0px 8px; line-height: 22px; height: 22px;} .wvInlineSearch > .dijitDropDownButton {border: none; height: 30px; width: 30px; padding: 0; margin: 0px 0px 0px 0px; background-color: rgb(240,240,240);}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode {background-color: transparent; box-shadow: none; border: 1px solid transparent; border-radius: 5px; background-image: none; padding: 3px; margin: 3px;}.wvInlineSearch > .dijitDropDownButtonHover > .dijitButtonNode {background-color: rgb(250,250,250); border: 1px solid rgb(178,178,178); box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9); -webkit-box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9); -moz-box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9);}.wvInlineSearch > .dijitDropDownButtonActive > .dijitButtonNode {background-color: rgb(223,223,223); border: 1px solid rgb(165,165,165); box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15); -webkit-box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15); -moz-box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15);}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitButtonText {display: none;}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitArrowButtonInner {display: none;}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitArrowButtonChar {display: none;}.wvInlineSearch > .dijitTooltipContainer {border: 1px solid rgb(166,166,166); border-radius: 0px; padding: 2px;}.wvInlineSearch > .dijitTooltipConnector{display: none;}.wvInlineSearch.dijitTooltipBelow {padding-top: 1px; padding-left: 0px;} .wvInlineSearch label {font-family: sans-serif;}.wvExplorerBar {height: 30px; width: 100% !important; overflow:hidden; border-bottom: 1px #b5bcc7 solid;}.wvExplorerBar > .wvExplorerBarBreadCrumbs{padding: 0px; margin: 0px 0px 0px 5px; white-space: nowrap; overflow:hidden; line-height:30px; border: none;}.wvExplorerBarOverflowButton {padding: 0; margin: 0; line-height:30px;}.wvExplorerBarOverflowButton.dijitBorderContainer-child {border: none;} .wvExplorerBarOverflowButton.dijitDropDownButton > .dijitButtonNode {background-color: transparent; box-shadow: none; border: none; background-image: none; padding: 0;}.wvExplorerBarOverflowButton.dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitArrowButtonInner {background-image: url("palette/images/PaletteIcons.png"); width: 16px; height: 16px; background-position: -64px;}.wvExplorerBarOverflowButton.dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitButtonText {display: none;}.wvExplorerBarOverflowButton.dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitArrowButtonChar {display: none;}.dijitMenu.wvExplorerBarOverflowMenu {border-color: #afafaf;}.dijitMenu.wvExplorerBarOverflowMenu .dijitMenuItem {font-family: sans-serif;}.dijitMenu.wvExplorerBarOverflowMenu .dijitMenuItemSelected td{background-color: #ecf5fc; background-image: none; border-color: #ecf5fc;}.wvExplorerBarExpandButton {padding: 0; margin: 0; line-height:30px;}.wvExplorerBarExpandButton.dijitBorderContainer-child {border: none;}.wvExplorerBarExpandButton.dijitDropDownButton > .dijitButtonNode {background-color: transparent; box-shadow: none; border: none; background-image: none; padding: 0;}.wvExplorerBarExpandButton.dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitButtonText {display: none;}.wvExplorerBarExpandButton.dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitArrowButtonChar {display: none;}.wvExplorerBarExpandButton.dijitDropDownButtonHover {background-color: #ecf5fc;}.dijitMenu.wvExplorerBarExpandMenu {border-color: #afafaf;}.dijitMenu.wvExplorerBarExpandMenu .dijitMenuItem {font-family: sans-serif;}.dijitMenu.wvExplorerBarExpandMenu .dijitMenuItemSelected td{background-color: #ecf5fc; background-image: none; border-color: #ecf5fc;}.dijitMenu.wvExplorerBarExpandMenu .dijitMenuItemIconCell {width: 20px;}.wvExplorerBar .dijitSplitterThumb {top:0;}.wvExplorerBar .dijitSplitterV .dijitSplitterThumb {height:100%;}.wvExplorerBarToggleButton.dijitButton {border: none; height: 30px; width: 30px; padding: 0; margin: 0; background-color: rgb(240,240,240);}.wvExplorerBarToggleButton.dijitButton > .dijitButtonNode {background-color: transparent; box-shadow: none; border: 1px solid transparent; border-radius: 5px; background-image: none; padding: 3px; margin: 3px;}.wvExplorerBarToggleButton.dijitButtonHover > .dijitButtonNode {background-color: rgb(250,250,250); border: 1px solid rgb(178,178,178); box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9); -webkit-box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9); -moz-box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9);}.wvExplorerBarToggleButton.dijitButtonActive > .dijitButtonNode {background-color: rgb(223,223,223); border: 1px solid rgb(165,165,165); box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15); -webkit-box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15); -moz-box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15);}.wvExplorerBarToggleButton.dijitButton > .dijitButtonNode > .dijitButtonContents > .dijitButtonChar {display: none;}.wvExplorerBarToggleButton.dijitButton > .dijitButtonNode > .dijitButtonContents > .dijitButtonText {display: none;}.wvExplorerBar > .wvExplorerBarToggleButtonSplitter {cursor: default;}.system-button-widget {padding: 0; margin: 0;}.system-button-widget .dijitButton .dijitButtonNode {background-color: transparent; box-shadow: none; border: none; background-image: none; padding: 0;}.system-button-widget .dijitButton .dijitButtonNode .dijitButtonText {padding: 0 0 0 0.3em;}.system-button-widget .dijitDropDownButton {margin: 0;}.dijitPopup {box-shadow: none !important;}.dijitMenu.system-button-widget{border-color: #afafaf;}.dijitMenu.system-button-widget .dijitMenuItem {font-family: sans-serif;}.dijitMenu.system-button-widget .dijitMenuItemSelected td{background-color: #ecf5fc; background-image: none; border-color: #ecf5fc;}.system-button-widget .dijitDropDownButton .dijitButtonNode {background-color: transparent; box-shadow: none; border: none; background-image: none; padding: 0;}.system-button-widget .dijitDropDownButton .dijitButtonNode .dijitButtonText {display: none;}.system-button-widgetHover {background-color: #ecf5fc;}.system-button-widget .dijitDropDownButton .dijitArrowButtonInner {background-position: -26px 53%;}.system-button-widget .dijitDropDownButtonOpened .dijitArrowButtonInner {background-position: -51px 53%;}.wvInlineSearch.dijitBorderContainer-child {border: 0;}.wvInlineSearch > form {display: inline-block; background-color: rgb(240,240,240);}.wvInlineSearch .dijitTextBox {height: 22px; border: 1px solid rgb(165,165,165); margin: 3px 0px 3px 0px; padding: 0; background-color: white;}.wvInlineSearch .dijitTextBoxFocused {border: 1px solid rgb(0,153,255); background-color: white;}.wvInlineSearch .dijitTextBoxHover {border: 1px solid rgb(0,153,255); background-color: white;}.wvInlineSearch .dijitTextBox .dijitInputContainer {padding: 0px 0px 0px 8px; line-height: 22px; height: 22px;}.wvInlineSearch .dijitTextBox .dijitPlaceHolder {font-size: 12px; padding: 0px 0px 0px 8px; line-height: 22px; height: 22px;}.wvInlineSearch .dijitTextBox .dijitInputInner {font-size: 12px; padding: 0px 0px 0px 8px; line-height: 22px; height: 22px;} .wvInlineSearch > .dijitDropDownButton {border: none; height: 30px; width: 30px; padding: 0; margin: 0px 0px 0px 0px; background-color: rgb(240,240,240);}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode {background-color: transparent; box-shadow: none; border: 1px solid transparent; border-radius: 5px; background-image: none; padding: 3px; margin: 3px;}.wvInlineSearch > .dijitDropDownButtonHover > .dijitButtonNode {background-color: rgb(250,250,250); border: 1px solid rgb(178,178,178); box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9); -webkit-box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9); -moz-box-shadow: inset 0px 1px 2px 0px rgba(255,255,255,0.9);}.wvInlineSearch > .dijitDropDownButtonActive > .dijitButtonNode {background-color: rgb(223,223,223); border: 1px solid rgb(165,165,165); box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15); -webkit-box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15); -moz-box-shadow: inset 0px 1px 2px 0px rgba(0,0,0,0.15);}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitButtonText {display: none;}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitArrowButtonInner {display: none;}.wvInlineSearch > .dijitDropDownButton > .dijitButtonNode > .dijitButtonContents > .dijitArrowButtonChar {display: none;}.wvInlineSearch > .dijitTooltipContainer {border: 1px solid rgb(166,166,166); border-radius: 0px; padding: 2px;}.wvInlineSearch > .dijitTooltipConnector{display: none;}.wvInlineSearch.dijitTooltipBelow {padding-top: 1px; padding-left: 0px;} .wvInlineSearch label {font-family: sans-serif;}.wvDiagramTab {}.wvDiagramTabViewPane {margin:0; padding:0 !important; overflow:hidden;}.wvDiagramTab .wvDiagramTabViewPane .no-export {text-align: center; display: table-cell; vertical-align: middle; font-weight: bold; font-size: 2em;}.lightbox-widget {border:none !important;}.lightbox-widget .dijitDialog {border: 1px solid #afafaf;}.lightbox-widget .dijitDialogUnderlay {width: 100%; height: 100%; background-color: rgba(48,48,48,0.7); opacity: 1;}.lightbox-widget .dijitDialogTitleBar {width: 100%; height: 100%; border: none; background-color: #afafaf; background-image: none;}.lightbox-widget .dijitDialogTitleBar .dijitDialogTitle {font-size: 1.1em; font-weight: bold;}.lightbox-widget-line {white-space: pre; padding: 0.25em 0 0 0.25em;}.lightbox-line-number-col {text-align: right; background-color: rgb(240,240,240); padding: 0.25em 0.5em 0 1em;}.lightbox-code-col {padding: 0.25em 1em 0 0.25em;}.lightbox-code-tablebody {font-family: monospace;}.lightbox-code-table {border: 0; border-spacing: 0;} .lightbox-line-tablerow {padding: 0 0 0.25em 0;}.wvModelViewer {}.wvModelViewer .dijitTabContainerTop-tabs .dijitTab{padding: 3px 8px 2px 8px; background-image: none; font-size: 1.1em; background-color: #d0d3d3; border-radius: 0px; margin-right: 4px; min-width: 30px; box-shadow: none;}.wvModelViewer .dijitTabContainerTop-tabs .dijitTabChecked {padding: 3px 8px 3px 8px; background-color: #ffffff; font-weight: bold; border-color: #000000;}.wvModelViewer .dijitTab {border-color: #000000;}.wvModelViewer .dijitTabPaneWrapper {border-color: #000000;}.wvModelViewer .dijitTabContainerTop-tabs {border-color: #000000;}.wvModelViewer .dijitTabContainerTop-tabs .dijitTabHover{border-color: #000000;}.wvInformer {background-color: #e1e2e2; margin:0; padding:0;}.wvInformerTitleBar {padding: 5px 7px 7px 7px;}.wvInformerTitleText {padding: 0 1px; font-size: 1.1em; font-weight: bold; color: #000000;}.wvInformerContent {background-color: white;}.dgrid {position: relative; overflow: hidden; border: 1px solid #ddd; height: 30em; display: block;}.dgrid-header {background-color: #eee;}.dgrid-header-row {position: absolute; right: 17px; left: 0;}.dgrid-header-scroll {position: absolute; top: 0; right: 0;}.dgrid-footer {position: absolute; bottom: 0; width: 100%;}.dgrid-header-hidden,html.has-quirks .dgrid-header-hidden .dgrid-cell {font-size: 0; height: 0 !important; border-top: none !important; border-bottom: none !important; margin-top: 0 !important; margin-bottom: 0 !important; padding-top: 0 !important; padding-bottom: 0 !important;}.dgrid-footer-hidden {display: none;}.dgrid-sortable {cursor: pointer;}.dgrid-header, .dgrid-header-row, .dgrid-footer {overflow: hidden; background-color: #eee;}.dgrid-row-table {border-collapse: collapse; border: none; table-layout: fixed; empty-cells: show; width: 100%; height: 100%;}.dgrid-cell {padding: 0px; text-align: left; overflow: hidden; vertical-align: top; border: 1px solid #ddd; border-top-style: none; box-sizing: border-box; -moz-box-sizing: border-box; -ms-box-sizing: border-box; -webkit-box-sizing: border-box;}.dgrid-cell-padding {padding: 3px;}.dgrid-content {position: relative; height: 99%;}.dgrid-scroller {overflow-x: auto; overflow-y: scroll; position: absolute; top: 0px; margin-top: 25px; bottom: 0px; width: 100%;}.dgrid-preload {font-size: 0; line-height: 0;}.dgrid-loading {position: relative; height: 100%;}.dgrid-above {position: absolute; bottom: 0;}.ui-icon {width: 16px; height: 16px; background-image: url("../dgrid/css/images/ui-icons_222222_256x240.png");}.ui-icon-triangle-1-e {background-position: -32px -16px;}.ui-icon-triangle-1-se {background-position: -48px -16px;}.dgrid-expando-icon {width: 16px; height: 16px;}.dgrid-tree-container {-webkit-transition-duration: 0.3s; -moz-transition-duration: 0.3s; -ms-transition-duration: 0.3s; -o-transition-duration: 0.3s; transition-duration: 0.3s; overflow: hidden;}.dgrid-tree-container.dgrid-tree-resetting {-webkit-transition-duration: 0; -moz-transition-duration: 0; -ms-transition-duration: 0; -o-transition-duration: 0; transition-duration: 0;}.dgrid-sort-arrow {background-position: -64px -16px; display: block; float: right; margin: 0 4px 0 5px; height: 12px;}.dgrid-sort-up .dgrid-sort-arrow {background-position: 0px -16px;}.dgrid-selected {background-color: #bfd6eb;}.dgrid-input {width: 99%;}html.has-mozilla .dgrid *:focus, html.has-opera .dgrid *:focus {outline: 1px dotted;}html.has-ie-6-7.has-no-quirks .dgrid-row-table {width: auto;}html.has-quirks .dgrid-row-table, html.has-ie-6 .dgrid-row-table {height: auto;}html.has-quirks .dgrid-header-scroll,html.has-ie-6 .dgrid-header-scroll {font-size: 0;}html.has-mozilla .dgrid-focus {outline-offset: -1px;}.dgrid-scrollbar-measure {width: 100px; height: 100px; overflow: scroll; position: absolute; top: -9999px;}.dgrid-autoheight {height: auto;}.dgrid-autoheight .dgrid-scroller {position: relative; overflow-y: hidden;}.dgrid-autoheight .dgrid-header-scroll {display: none;}.dgrid-autoheight .dgrid-header {right: 0;}#dgrid-css-dgrid-loaded {display: none;}.dgrid-column-resizer {cursor: col-resize; position: absolute; width: 2px; background-color: #666; z-index: 1000;}.dgrid-resize-guard {cursor: col-resize; position: absolute; bottom: 0; left: 0; right: 0; top: 0;}.dgrid-resize-handle {height: 100px; width: 0; position: absolute; right: -4px; top:-4px; cursor: col-resize; z-index: 999; border-left: 5px solid transparent; outline: none;}html.has-ie-6 .dgrid-resize-handle {border-color: pink; filter: chroma(color=pink);}html.has-mozilla .dgrid .dgrid-resize-handle:focus,html.has-opera .dgrid .dgrid-resize-handle:focus {outline: none;}.dgrid-resize-header-container {height:100%;}html.has-touch .dgrid-resize-handle {border-left: 20px solid transparent;}html.has-touch .dgrid-column-resizer {width: 2px;}html.has-no-quirks .dgrid-resize-header-container {position: relative;}html.has-ie-6 .dgrid-resize-header-container {position: static;}.dgrid-header .dgrid-cell-padding {overflow: hidden;}html.has-ie-6 .dgrid-header .dgrid-cell-padding {margin-right: 4px;}html.has-ie-6 .dgrid-header .dgrid-sort-arrow {margin-right: 0;}html.has-quirks .dgrid-header .dgrid-cell-padding, html.has-ie-6 .dgrid-header .dgrid-cell {position:relative;}#dgrid-css-extensions-ColumnResizer-loaded {display: none;} .wvSearchResultsPane {background-color: #e1e2e2; margin:0; padding:0;}.wvSearchResultsPaneTitleBar {padding: 5px 7px 7px 7px;}.wvSearchResultsPaneTitleText {padding: 0 1px; font-size: 1.1em; font-weight: bold; color: #000000;}.wvSearchResultsPane .wvSearchResultsPaneContent {background-color: white; margin:0; padding:0; border:0;}.wvSearchResultsPane .dgrid {height: auto; border: 0px; width: 100%;}.wvSearchResultsPane .dgrid-header {background-color: #eee;}.wvSearchResultsPane .field-icon {width: 24px;}.wvSearchResultsPane .field-name {width: 30%;}.wvSearchResultsPane .dgrid-cell {border-color: #e1e2e2;}.Search_Search_16,.Search_Adv_Search_16,.Search_Collapse_16,.Search_Close_16 {background-image: url("search/images/SearchIcons.png"); width: 16px; height: 16px;}.Search_Search_16 {background-position: -0px;}.Search_Adv_Search_16 {background-position: -16px;}.Search_Collapse_16 {background-position: -32px;}.Search_Close_16 {background-position: -48px;}.slwebview-link {cursor: pointer;}.slwebview-link:hover {color: blue;}.slwebview-link:active {color: red;}.slwebview-anchor-highlight {background: rgba(255,255,0,0); animation-name: yellowFade; animation-duration: 2s; animation-iteration-count: 1;}@keyframes yellowFade {from {background-color: rgba(255,255,0,0.8); fill: rgba(255,255,0,0.8);} to {background-color: rgba(255,255,0,0); fill: rgba(255,255,0,0);}} .webview-MarqueeZoomTool {stroke: #99ccff; fill: #ffdbb7; fill-opacity: 0.3;}html {padding: 0;}html, body {height: 100%; -ms-box-sizing: border-box; -webkit-box-sizing: border-box; -moz-box-sizing: border-box; box-sizing: border-box;}body {margin: 0;} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/webview.js b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/webview.js new file mode 100644 index 00000000..7268330c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/webview/webview.js @@ -0,0 +1,1142 @@ +//>>built +/* + Copyright 2015 The MathWorks, Inc. + @exports MW/utils/deprecation +*/ +(function(e,k){var h,l=function(){},b=function(a){for(var f in a)return 0;return 1},m={}.toString,d=function(a){return"[object Function]"==m.call(a)},g=function(a){return"[object String]"==m.call(a)},c=function(a){return"[object Array]"==m.call(a)},a=function(a,f){if(a)for(var c=0;ch;)try{if(P=T[h++],new ActiveXObject(P))break}catch(Q){}I=function(){return new ActiveXObject(P)}}q.getXhr=I;w.add("dojo-gettext-api", +1);q.getText=function(a,f,c){var b=I();b.open("GET",Ua(a),!1);b.send(null);if(200==b.status||!location.host&&!b.status)c&&c(b.responseText,f);else throw u("xhrFailed",b.status);return b.responseText};var L=w("csp-restrictions")?function(){}:new Function("return eval(arguments[0]);");q.eval=function(a,f){return L(a+"\r\n//# sourceURL\x3d"+f)};var J={},H=q.signal=function(f,b){var p=J[f];a(p&&p.slice(0),function(a){a.apply(null,c(b)?b:[b])})},V=q.on=function(a,f){var c=J[a]||(J[a]=[]);c.push(f);return{remove:function(){for(var a= +0;al.attributes.length);h.clearElement=function(b){b.innerHTML="";return b};h.normalize=function(b,m){var d=b.match(/[\?:]|[^:\?]*/g),g=0,c=function(a){var f=d[g++];if(":"==f)return 0;if("?"==d[g++]){if(!a&&h(f))return c();c(!0);return c(a)}return f||0};return(b=c())&&m(b)};h.load=function(b,m, +d){b?m([b],d):d()};return h})},"dojo/_base/config":function(){define(["../has","require"],function(e,k){var h={},l=k.rawConfig,b;for(b in l)h[b]=l[b];h.updateLocale=function(b,d){var g,c;if(0<=b.indexOf(d)&&"zh"!==d)h.locale=d;else if(g=d.split("-")[0],"zh"===g)h.locale="en-us".toLocaleLowerCase();else{for(var a=0;ar?(r=s+r,0>r&&(r=b)):r=r>=s?s+d:r;for(s&&"string"==typeof n&&(n=n.split(""));r!=m;r+=f)if(n[r]==q)return r;return-1}}var d={},g,c={every:b(!1),some:b(!0),indexOf:m(!0),lastIndexOf:m(!1),forEach:function(a,c,b){var p=0,n=a&&a.length||0;n&&"string"== +typeof a&&(a=a.split(""));"string"==typeof c&&(c=d[c]||l(c));if(b)for(;p=d[g].priority;g++);d.splice(g,0,n);c()},f=e.config.addOnLoad;if(f)a[b.isArray(f)?"apply":"call"](e,f);e.config.parseOnLoad&&!e.isAsync&&a(99,function(){e.parser||(e.deprecated("Add explicit require(['dojo/parser']);","","2.0"),h(["dojo/parser"]))});l? +l(k):k();return a})},"dojo/domReady":function(){define(["./has"],function(e){function k(a){c.push(a);g&&h()}function h(){if(!a){for(a=!0;c.length;)try{c.shift()(b)}catch(f){console.error(f,"in domReady callback",f.stack)}a=!1;k._onQEmpty()}}var l=function(){return this}(),b=document,m={loaded:1,complete:1},d="string"!=typeof b.readyState,g=!!m[b.readyState],c=[],a;k.load=function(a,c,f){k(f)};k._Q=c;k._onQEmpty=function(){};d&&(b.readyState="loading");if(!g){var f=[],u=function(a){a=a||l.event;g|| +"readystatechange"==a.type&&!m[b.readyState]||(d&&(b.readyState="complete"),g=1,h())},p=function(a,f){a.addEventListener(f,u,!1);c.push(function(){a.removeEventListener(f,u,!1)})};if(!e("dom-addeventlistener")){var p=function(a,f){f="on"+f;a.attachEvent(f,u);c.push(function(){a.detachEvent(f,u)})},n=b.createElement("div");try{n.doScroll&&null===l.frameElement&&f.push(function(){try{return n.doScroll("left"),1}catch(a){}})}catch(q){}}p(b,"DOMContentLoaded");p(l,"load");"onreadystatechange"in b?p(b, +"readystatechange"):d||f.push(function(){return m[b.readyState]});if(f.length){var r=function(){if(!g){for(var a=f.length;a--;)if(f[a]()){u("poller");return}setTimeout(r,30)}};r()}}return k})},"dojo/_base/declare":function(){define(["./kernel","../has","./lang"],function(e,k,h){function l(a,c){throw Error("declare"+(c?" "+c:"")+": "+a);}function b(a,c,f){var b,d,n,p,g,q,r,s=this._inherited=this._inherited||{};"string"==typeof a&&(b=a,a=c,c=f);f=0;p=a.callee;(b=b||p.nom)||l("can't deduce a name to call inherited()", +this.declaredClass);g=this.constructor._meta;n=g.bases;r=s.p;if(b!=F){if(s.c!==p&&(r=0,q=n[0],g=q._meta,g.hidden[b]!==p)){(d=g.chains)&&"string"==typeof d[b]&&l("calling chained method with inherited: "+b,this.declaredClass);do if(g=q._meta,d=q.prototype,g&&(d[b]===p&&d.hasOwnProperty(b)||g.hidden[b]===p))break;while(q=n[++r]);r=q?r:-1}if(q=n[++r])if(d=q.prototype,q._meta&&d.hasOwnProperty(b))f=d[b];else{p=y[b];do if(d=q.prototype,(f=d[b])&&(q._meta?d.hasOwnProperty(b):f!==p))break;while(q=n[++r])}f= +q&&f||y[b]}else{if(s.c!==p&&(r=0,(g=n[0]._meta)&&g.ctor!==p)){d=g.chains;for((!d||"manual"!==d.constructor)&&l("calling chained constructor with inherited",this.declaredClass);(q=n[++r])&&!((g=q._meta)&&g.ctor===p););r=q?r:-1}for(;(q=n[++r])&&!(f=(g=q._meta)?g.ctor:q););f=q&&f}s.c=f;s.p=r;if(f)return!0===c?f:f.apply(this,c||a)}function m(a,c){return"string"==typeof a?this.__inherited(a,c,!0):this.__inherited(a,!0)}function d(a,c,f){var b=this.getInherited(a,c);if(b)return b.apply(this,f||c||a)}function g(a){for(var c= +this.constructor._meta.bases,f=0,b=c.length;fb||90b||111b||192b||222g?g-48:!a.shiftKey&&65<=g&&90>=g?g+32:f[g]||g}b=p(a,{type:"keypress",faux:!0,charCode:g});c.call(a.currentTarget,b);if(d("ie"))try{a.keyCode=b.keyCode}catch(n){}}}),g=k(a,"keypress",function(a){var f=a.charCode;a=p(a,{charCode:32<=f?f:0,faux:!0});return c.call(this,a)});return{remove:function(){b.remove();g.remove()}}}:d("opera")?function(a,c){return k(a,"keypress",function(a){var f=a.which;3==f&&(f=99);f=32>f&&!a.shiftKey?0:f;a.ctrlKey&&(!a.shiftKey&&65<=f&&90>=f)&&(f+=32);return c.call(this, +p(a,{charCode:f}))})}:function(c,f){return k(c,"keypress",function(c){a(c);return f.call(this,c)})};var q={_keypress:n,connect:function(a,f,b,d,g){var n=arguments,p=[],q=0;p.push("string"==typeof n[0]?null:n[q++],n[q++]);var u=n[q+1];p.push("string"==typeof u||"function"==typeof u?n[q++]:null,n[q++]);for(u=n.length;qh("jscript"))&&!h("config-_allow_leaks")){"undefined"==typeof _dojoIEListeners_&&(_dojoIEListeners_=[]);var b=a[c];if(!b||!b.listeners){var d=b,b=Function("event","var callee \x3d arguments.callee; for(var i \x3d 0; i\x3ccallee.listeners.length; i++){var listener \x3d _dojoIEListeners_[callee.listeners[i]]; if(listener){listener.call(this,event);}}"); +b.listeners=[];a[c]=b;b.global=this;d&&b.listeners.push(_dojoIEListeners_.push(d)-1)}b.listeners.push(a=b.global._dojoIEListeners_.push(f)-1);return new r(a)}return e.after(a,c,f,!0)},w=function(){this.cancelBubble=!0},y=g._preventDefault=function(){this.bubbledKeyCode=this.keyCode;if(this.ctrlKey)try{this.keyCode=0}catch(a){}this.defaultPrevented=!0;this.returnValue=!1;this.modified=!0}}if(h("touch"))var A=function(){},B=window.orientation,C=function(a){return function(c){var f=c.corrected;if(!f){var b= +c.type;try{delete c.type}catch(d){}if(c.type){if(h("touch-can-modify-event-delegate"))A.prototype=c,f=new A;else{var f={},g;for(g in c)f[g]=c[g]}f.preventDefault=function(){c.preventDefault()};f.stopPropagation=function(){c.stopPropagation()}}else f=c,f.type=b;c.corrected=f;if("resize"==b){if(B==window.orientation)return null;B=window.orientation;f.type="orientationchange";return a.call(this,f)}"rotation"in f||(f.rotation=0,f.scale=1);var b=f.changedTouches[0],n;for(n in b)delete f[n],f[n]=b[n]}return a.call(this, +f)}};return g})},"dojo/topic":function(){define(["./Evented"],function(e){var k=new e;return{publish:function(e,l){return k.emit.apply(k,arguments)},subscribe:function(e,l){return k.on.apply(k,arguments)}}})},"dojo/Evented":function(){define(["./aspect","./on"],function(e,k){function h(){}var l=e.after;h.prototype={on:function(b,m){return k.parse(this,b,m,function(b,g){return l(b,"on"+g,m,!0)})},emit:function(b,m){var d=[this];d.push.apply(d,arguments);return k.emit.apply(k,d)}};return h})},"dojo/aspect":function(){define([], +function(){function e(b,g,c,a){var f=b[g],u="around"==g,p;if(u){var n=c(function(){return f.advice(this,arguments)});p={remove:function(){n&&(n=b=c=null)},advice:function(a,c){return n?n.apply(a,c):f.advice(a,c)}}}else p={remove:function(){if(p.advice){var a=p.previous,f=p.next;!f&&!a?delete b[g]:(a?a.next=f:b[g]=f,f&&(f.previous=a));b=c=p.advice=null}},id:b.nextId++,advice:c,receiveArguments:a};if(f&&!u)if("after"==g){for(;f.next&&(f=f.next););f.next=p;p.previous=f}else"before"==g&&(b[g]=p,p.next= +f,f.previous=p);else b[g]=p;return p}function k(b){return function(g,c,a,f){var u=g[c],p;if(!u||u.target!=g)g[c]=p=function(){for(var a=p.nextId,c=arguments,f=p.before;f;)f.advice&&(c=f.advice.apply(this,c)||c),f=f.next;if(p.around)var b=p.around.advice(this,c);for(f=p.after;f&&f.idn.clientHeight)&&(a+=n.clientLeft);return 8>b||d?a+n.clientWidth-n.scrollWidth:-a}return a};g.position=function(a,c){a=h.byId(a);var b=k.body(a.ownerDocument),d=a.getBoundingClientRect(),d={x:d.left,y:d.top,w:d.right-d.left,h:d.bottom-d.top};9>e("ie")&&(d.x-=e("quirks")?b.clientLeft+b.offsetLeft:0,d.y-=e("quirks")?b.clientTop+b.offsetTop:0);c&&(b= +g.docScroll(a.ownerDocument),d.x+=b.x,d.y+=b.y);return d};g.getMarginSize=function(a,c){a=h.byId(a);var b=g.getMarginExtents(a,c||l.getComputedStyle(a)),d=a.getBoundingClientRect();return{w:d.right-d.left+b.w,h:d.bottom-d.top+b.h}};g.normalizeEvent=function(a){"layerX"in a||(a.layerX=a.offsetX,a.layerY=a.offsetY);if(!("pageX"in a)){var c=a.target,c=c&&c.ownerDocument||document,b=e("quirks")?c.body:c.documentElement;a.pageX=a.clientX+g.fixIeBiDiScrollLeft(b.scrollLeft||0,c);a.pageY=a.clientY+(b.scrollTop|| +0)}};return g})},"dojo/_base/window":function(){define(["./kernel","./lang","../sniff"],function(e,k,h){var l={global:e.global,doc:e.global.document||null,body:function(b){b=b||e.doc;return b.body||b.getElementsByTagName("body")[0]},setContext:function(b,m){e.global=l.global=b;e.doc=l.doc=m},withGlobal:function(b,m,d,g){var c=e.global;try{return e.global=l.global=b,l.withDoc.call(null,b.document,m,d,g)}finally{e.global=l.global=c}},withDoc:function(b,m,d,g){var c=l.doc,a=h("quirks"),f=h("ie"),u,p, +n;try{e.doc=l.doc=b;e.isQuirks=h.add("quirks","BackCompat"==e.doc.compatMode,!0,!0);if(h("ie")&&(n=b.parentWindow)&&n.navigator)u=parseFloat(n.navigator.appVersion.split("MSIE ")[1])||void 0,(p=b.documentMode)&&(5!=p&&Math.floor(u)!=p)&&(u=p),e.isIE=h.add("ie",u,!0,!0);d&&"string"==typeof m&&(m=d[m]);return m.apply(d,g||[])}finally{e.doc=l.doc=c,e.isQuirks=h.add("quirks",a,!0,!0),e.isIE=h.add("ie",f,!0,!0)}}};k.mixin(e,l);return l})},"dojo/dom":function(){define(["./sniff","./_base/window"],function(e, +k){if(7>=e("ie"))try{document.execCommand("BackgroundImageCache",!1,!0)}catch(h){}var l={};e("ie")?l.byId=function(b,d){if("string"!=typeof b)return b;var g=d||k.doc,c=b&&g.getElementById(b);if(c&&(c.attributes.id.value==b||c.id==b))return c;g=g.all[b];if(!g||g.nodeName)g=[g];for(var a=0;c=g[a++];)if(c.attributes&&c.attributes.id&&c.attributes.id.value==b||c.id==b)return c}:l.byId=function(b,d){return("string"==typeof b?(d||k.doc).getElementById(b):b)||null};l.isDescendant=function(b,d){try{b=l.byId(b); +for(d=l.byId(d);b;){if(b==d)return!0;b=b.parentNode}}catch(g){}return!1};e.add("css-user-select",function(b,d,g){if(!g)return!1;b=g.style;d=["Khtml","O","Moz","Webkit"];g=d.length;var c="userSelect";do if("undefined"!==typeof b[c])return c;while(g--&&(c=d[g]+"UserSelect"));return!1});var b=e("css-user-select");l.setSelectable=b?function(m,d){l.byId(m).style[b]=d?"":"none"}:function(b,d){b=l.byId(b);var g=b.getElementsByTagName("*"),c=g.length;if(d)for(b.removeAttribute("unselectable");c--;)g[c].removeAttribute("unselectable"); +else for(b.setAttribute("unselectable","on");c--;)g[c].setAttribute("unselectable","on")};return l})},"dojo/dom-style":function(){define(["./sniff","./dom","./_base/window"],function(e,k,h){function l(a,c,b){c=c.toLowerCase();if("auto"==b){if("height"==c)return a.offsetHeight;if("width"==c)return a.offsetWidth}if("fontweight"==c)switch(b){case 700:return"bold";default:return"normal"}c in f||(f[c]=u.test(c));return f[c]?d(a,b):b}var b,m={};b=e("webkit")?function(a){var c;if(1==a.nodeType){var b=a.ownerDocument.defaultView; +c=b.getComputedStyle(a,null);!c&&a.style&&(a.style.display="",c=b.getComputedStyle(a,null))}return c||{}}:e("ie")&&(9>e("ie")||e("quirks"))?function(a){return 1==a.nodeType&&a.currentStyle?a.currentStyle:{}}:function(a){if(1===a.nodeType){var c=a.ownerDocument.defaultView;return(c.opener?c:h.global.window).getComputedStyle(a,null)||{}}return{}};m.getComputedStyle=b;var d;d=e("ie")?function(a,c){if(!c)return 0;if("medium"==c)return 4;if(c.slice&&"px"==c.slice(-2))return parseFloat(c);var b=a.style, +f=a.runtimeStyle,d=b.left,g=f.left;f.left=a.currentStyle.left;try{b.left=c,c=b.pixelLeft}catch(p){c=0}b.left=d;f.left=g;return c}:function(a,c){return parseFloat(c)||0};m.toPixelValue=d;var g=function(a,c){try{return a.filters.item("DXImageTransform.Microsoft.Alpha")}catch(b){return c?{}:null}},c=9>e("ie")||10>e("ie")&&e("quirks")?function(a){try{return g(a).Opacity/100}catch(c){return 1}}:function(a){return b(a).opacity},a=9>e("ie")||10>e("ie")&&e("quirks")?function(c,b){""===b&&(b=1);var f=100* +b;1===b?(c.style.zoom="",g(c)&&(c.style.filter=c.style.filter.replace(/\s*progid:DXImageTransform.Microsoft.Alpha\([^\)]+?\)/i,""))):(c.style.zoom=1,g(c)?g(c,1).Opacity=f:c.style.filter+=" progid:DXImageTransform.Microsoft.Alpha(Opacity\x3d"+f+")",g(c,1).Enabled=!0);if("tr"==c.tagName.toLowerCase())for(f=c.firstChild;f;f=f.nextSibling)"td"==f.tagName.toLowerCase()&&a(f,b);return b}:function(a,c){return a.style.opacity=c},f={left:!0,top:!0},u=/margin|padding|width|height|max|min|offset/,p={cssFloat:1, +styleFloat:1,"float":1};m.get=function(a,b){var f=k.byId(a),d=arguments.length;if(2==d&&"opacity"==b)return c(f);b=p[b]?"cssFloat"in f.style?"cssFloat":"styleFloat":b;var g=m.getComputedStyle(f);return 1==d?g:l(f,b,g[b]||f.style[b])};m.set=function(c,b,f){var d=k.byId(c),g=arguments.length,u="opacity"==b;b=p[b]?"cssFloat"in d.style?"cssFloat":"styleFloat":b;if(3==g)return u?a(d,f):d.style[b]=f;for(var e in b)m.set(c,e,b[e]);return m.getComputedStyle(d)};return m})},"dojo/mouse":function(){define(["./_base/kernel", +"./on","./has","./dom","./_base/window"],function(e,k,h,l,b){function m(b,g){var c=function(a,c){return k(a,b,function(b){if(g)return g(b,c);if(!l.isDescendant(b.relatedTarget,a))return c.call(this,b)})};c.bubble=function(a){return m(b,function(c,b){var d=a(c.target),g=c.relatedTarget;if(d&&d!=(g&&1==g.nodeType&&a(g)))return b.call(d,c)})};return c}h.add("dom-quirks",b.doc&&"BackCompat"==b.doc.compatMode);h.add("events-mouseenter",b.doc&&"onmouseenter"in b.doc.createElement("div"));h.add("events-mousewheel", +b.doc&&"onmousewheel"in b.doc);b=h("dom-quirks")&&h("ie")||!h("dom-addeventlistener")?{LEFT:1,MIDDLE:4,RIGHT:2,isButton:function(b,g){return b.button&g},isLeft:function(b){return b.button&1},isMiddle:function(b){return b.button&4},isRight:function(b){return b.button&2}}:{LEFT:0,MIDDLE:1,RIGHT:2,isButton:function(b,g){return b.button==g},isLeft:function(b){return 0==b.button},isMiddle:function(b){return 1==b.button},isRight:function(b){return 2==b.button}};e.mouseButtons=b;e=h("events-mousewheel")? +"mousewheel":function(b,g){return k(b,"DOMMouseScroll",function(c){c.wheelDelta=-c.detail;g.call(this,c)})};return{_eventHandler:m,enter:m("mouseover"),leave:m("mouseout"),wheel:e,isLeft:b.isLeft,isMiddle:b.isMiddle,isRight:b.isRight}})},"dojo/_base/sniff":function(){define(["./kernel","./lang","../sniff"],function(e,k,h){e._name="browser";k.mixin(e,{isBrowser:!0,isFF:h("ff"),isIE:h("ie"),isKhtml:h("khtml"),isWebKit:h("webkit"),isMozilla:h("mozilla"),isMoz:h("mozilla"),isOpera:h("opera"),isSafari:h("safari"), +isChrome:h("chrome"),isMac:h("mac"),isIos:h("ios"),isAndroid:h("android"),isWii:h("wii"),isQuirks:h("quirks"),isAir:h("air")});return h})},"dojo/keys":function(){define(["./_base/kernel","./sniff"],function(e,k){return e.keys={BACKSPACE:8,TAB:9,CLEAR:12,ENTER:13,SHIFT:16,CTRL:17,ALT:18,META:k("webkit")?91:224,PAUSE:19,CAPS_LOCK:20,ESCAPE:27,SPACE:32,PAGE_UP:33,PAGE_DOWN:34,END:35,HOME:36,LEFT_ARROW:37,UP_ARROW:38,RIGHT_ARROW:39,DOWN_ARROW:40,INSERT:45,DELETE:46,HELP:47,LEFT_WINDOW:91,RIGHT_WINDOW:92, +SELECT:93,NUMPAD_0:96,NUMPAD_1:97,NUMPAD_2:98,NUMPAD_3:99,NUMPAD_4:100,NUMPAD_5:101,NUMPAD_6:102,NUMPAD_7:103,NUMPAD_8:104,NUMPAD_9:105,NUMPAD_MULTIPLY:106,NUMPAD_PLUS:107,NUMPAD_ENTER:108,NUMPAD_MINUS:109,NUMPAD_PERIOD:110,NUMPAD_DIVIDE:111,F1:112,F2:113,F3:114,F4:115,F5:116,F6:117,F7:118,F8:119,F9:120,F10:121,F11:122,F12:123,F13:124,F14:125,F15:126,NUM_LOCK:144,SCROLL_LOCK:145,UP_DPAD:175,DOWN_DPAD:176,LEFT_DPAD:177,RIGHT_DPAD:178,copyKey:k("mac")&&!k("air")?k("safari")?91:224:17}})},"dojo/_base/Deferred":function(){define("./kernel ../Deferred ../promise/Promise ../errors/CancelError ../has ./lang ../when".split(" "), +function(e,k,h,l,b,m,d){var g=function(){},c=Object.freeze||function(){},a=e.Deferred=function(f){function d(a){if(q)throw Error("This deferred has already been resolved");n=a;q=!0;p()}function p(){for(var a;!a&&y;){var c=y;y=y.next;if(a=c.progress==g)q=!1;var f=e?c.error:c.resolved;b("config-useDeferredInstrumentation")&&e&&k.instrumentRejected&&k.instrumentRejected(n,!!f);if(f)try{var d=f(n);d&&"function"===typeof d.then?d.then(m.hitch(c.deferred,"resolve"),m.hitch(c.deferred,"reject"),m.hitch(c.deferred, +"progress")):(f=a&&void 0===d,a&&!f&&(e=d instanceof Error),c.deferred[f&&e?"reject":"resolve"](f?n:d))}catch(p){c.deferred.reject(p)}else e?c.deferred.reject(n):c.deferred.resolve(n)}}var n,q,r,s,e,w,y,A=this.promise=new h;this.isResolved=A.isResolved=function(){return 0==s};this.isRejected=A.isRejected=function(){return 1==s};this.isFulfilled=A.isFulfilled=function(){return 0<=s};this.isCanceled=A.isCanceled=function(){return r};this.resolve=this.callback=function(a){this.fired=s=0;this.results= +[a,null];d(a)};this.reject=this.errback=function(a){e=!0;this.fired=s=1;b("config-useDeferredInstrumentation")&&k.instrumentRejected&&k.instrumentRejected(a,!!y);d(a);this.results=[null,a]};this.progress=function(a){for(var c=y;c;){var b=c.progress;b&&b(a);c=c.next}};this.addCallbacks=function(a,c){this.then(a,c,g);return this};A.then=this.then=function(c,b,f){var d=f==g?this:new a(A.cancel);c={resolved:c,error:b,progress:f,deferred:d};y?w=w.next=c:y=w=c;q&&p();return d.promise};var B=this;A.cancel= +this.cancel=function(){if(!q){var a=f&&f(B);q||(a instanceof Error||(a=new l(a)),a.log=!1,B.reject(a))}r=!0};c(A)};m.extend(a,{addCallback:function(a){return this.addCallbacks(m.hitch.apply(e,arguments))},addErrback:function(a){return this.addCallbacks(null,m.hitch.apply(e,arguments))},addBoth:function(a){var c=m.hitch.apply(e,arguments);return this.addCallbacks(c,c)},fired:-1});a.when=e.when=d;return a})},"dojo/Deferred":function(){define(["./has","./_base/lang","./errors/CancelError","./promise/Promise", +"./promise/instrumentation"],function(e,k,h,l,b){var m=Object.freeze||function(){},d=function(a,c,b,d,r){2===c&&(f.instrumentRejected&&0===a.length)&&f.instrumentRejected(b,!1,d,r);for(r=0;ra?"0"+a:a});if(c.valueOf()!==c)return d(c.valueOf(),a,f);var p=m?a+m:"",n=m?" ":"",q=m?"\n":"";if(c instanceof Array){var n=c.length,r=[];for(f=0;fb.length?"0"+b:b},this).join("")},toCss:function(b){var d=this.r+", "+this.g+", "+this.b;return(b?"rgba("+d+", "+this.a:"rgb("+d)+")"},toString:function(){return this.toCss(!0)}});b.blendColors=e.blendColors=function(m,d,g,c){var a=c||new b;h.forEach(["r","g","b","a"],function(c){a[c]=m[c]+(d[c]-m[c])*g;"a"!= +c&&(a[c]=Math.round(a[c]))});return a.sanitize()};b.fromRgb=e.colorFromRgb=function(m,d){var g=m.toLowerCase().match(/^rgba?\(([\s\.,0-9]+)\)/);return g&&b.fromArray(g[1].split(/\s*,\s*/),d)};b.fromHex=e.colorFromHex=function(m,d){var g=d||new b,c=4==m.length?4:8,a=(1<>=c;g[b]=4==c?17*d:d});g.a=1;return g};b.fromArray=e.colorFromArray=function(m,d){var g=d||new b;g._set(Number(m[0]),Number(m[1]), +Number(m[2]),Number(m[3]));isNaN(g.a)&&(g.a=1);return g.sanitize()};b.fromString=e.colorFromString=function(m,d){var g=b.named[m];return g&&b.fromArray(g,d)||b.fromRgb(m,d)||b.fromHex(m,d)};return b})},"dojo/_base/browser":function(){require.has&&require.has.add("config-selectorEngine","acme");define("../ready ./kernel ./connect ./unload ./window ./event ./html ./NodeList ../query ./xhr ./fx".split(" "),function(e){return e})},"dojo/_base/unload":function(){define(["./kernel","./lang","../on"],function(e, +k,h){var l=window,b={addOnWindowUnload:function(b,d){e.windowUnloaded||h(l,"unload",e.windowUnloaded=function(){});h(l,"unload",k.hitch(b,d))},addOnUnload:function(b,d){h(l,"beforeunload",k.hitch(b,d))}};e.addOnWindowUnload=b.addOnWindowUnload;e.addOnUnload=b.addOnUnload;return b})},"dojo/_base/html":function(){define("./kernel ../dom ../dom-style ../dom-attr ../dom-prop ../dom-class ../dom-construct ../dom-geometry".split(" "),function(e,k,h,l,b,m,d,g){e.byId=k.byId;e.isDescendant=k.isDescendant; +e.setSelectable=k.setSelectable;e.getAttr=l.get;e.setAttr=l.set;e.hasAttr=l.has;e.removeAttr=l.remove;e.getNodeProp=l.getNodeProp;e.attr=function(c,a,b){return 2==arguments.length?l["string"==typeof a?"get":"set"](c,a):l.set(c,a,b)};e.hasClass=m.contains;e.addClass=m.add;e.removeClass=m.remove;e.toggleClass=m.toggle;e.replaceClass=m.replace;e._toDom=e.toDom=d.toDom;e.place=d.place;e.create=d.create;e.empty=function(c){d.empty(c)};e._destroyElement=e.destroy=function(c){d.destroy(c)};e._getPadExtents= +e.getPadExtents=g.getPadExtents;e._getBorderExtents=e.getBorderExtents=g.getBorderExtents;e._getPadBorderExtents=e.getPadBorderExtents=g.getPadBorderExtents;e._getMarginExtents=e.getMarginExtents=g.getMarginExtents;e._getMarginSize=e.getMarginSize=g.getMarginSize;e._getMarginBox=e.getMarginBox=g.getMarginBox;e.setMarginBox=g.setMarginBox;e._getContentBox=e.getContentBox=g.getContentBox;e.setContentSize=g.setContentSize;e._isBodyLtr=e.isBodyLtr=g.isBodyLtr;e._docScroll=e.docScroll=g.docScroll;e._getIeDocumentElementOffset= +e.getIeDocumentElementOffset=g.getIeDocumentElementOffset;e._fixIeBiDiScrollLeft=e.fixIeBiDiScrollLeft=g.fixIeBiDiScrollLeft;e.position=g.position;e.marginBox=function(c,a){return a?g.setMarginBox(c,a):g.getMarginBox(c)};e.contentBox=function(c,a){return a?g.setContentSize(c,a):g.getContentBox(c)};e.coords=function(c,a){e.deprecated("dojo.coords()","Use dojo.position() or dojo.marginBox().");c=k.byId(c);var b=h.getComputedStyle(c),b=g.getMarginBox(c,b),d=g.position(c,a);b.x=d.x;b.y=d.y;return b}; +e.getProp=b.get;e.setProp=b.set;e.prop=function(c,a,f){return 2==arguments.length?b["string"==typeof a?"get":"set"](c,a):b.set(c,a,f)};e.getStyle=h.get;e.setStyle=h.set;e.getComputedStyle=h.getComputedStyle;e.__toPixelValue=e.toPixelValue=h.toPixelValue;e.style=function(c,a,b){switch(arguments.length){case 1:return h.get(c);case 2:return h["string"==typeof a?"get":"set"](c,a)}return h.set(c,a,b)};return e})},"dojo/dom-attr":function(){define("exports ./sniff ./_base/lang ./dom ./dom-style ./dom-prop".split(" "), +function(e,k,h,l,b,m){function d(a,c){var b=a.getAttributeNode&&a.getAttributeNode(c);return!!b&&b.specified}var g={innerHTML:1,textContent:1,className:1,htmlFor:k("ie"),value:1},c={classname:"class",htmlfor:"for",tabindex:"tabIndex",readonly:"readOnly"};e.has=function(a,b){var e=b.toLowerCase();return g[m.names[e]||b]||d(l.byId(a),c[e]||b)};e.get=function(a,b){a=l.byId(a);var e=b.toLowerCase(),p=m.names[e]||b,n=a[p];if(g[p]&&"undefined"!=typeof n)return n;if("textContent"==p)return m.get(a,p);if("href"!= +p&&("boolean"==typeof n||h.isFunction(n)))return n;e=c[e]||b;return d(a,e)?a.getAttribute(e):null};e.set=function(a,f,d){a=l.byId(a);if(2==arguments.length){for(var p in f)e.set(a,p,f[p]);return a}p=f.toLowerCase();var n=m.names[p]||f,q=g[n];if("style"==n&&"string"!=typeof d)return b.set(a,d),a;if(q||"boolean"==typeof d||h.isFunction(d))return m.set(a,f,d);a.setAttribute(c[p]||f,d);return a};e.remove=function(a,b){l.byId(a).removeAttribute(c[b.toLowerCase()]||b)};e.getNodeProp=function(a,b){a=l.byId(a); +var g=b.toLowerCase(),p=m.names[g]||b;if(p in a&&"href"!=p)return a[p];g=c[g]||b;return d(a,g)?a.getAttribute(g):null}})},"dojo/dom-prop":function(){define("exports ./_base/kernel ./sniff ./_base/lang ./dom ./dom-style ./dom-construct ./_base/connect".split(" "),function(e,k,h,l,b,m,d,g){function c(a){var b="";a=a.childNodes;for(var f=0,d;d=a[f];f++)8!=d.nodeType&&(b=1==d.nodeType?b+c(d):b+d.nodeValue);return b}var a={},f=1,u=k._scopeName+"attrid";h.add("dom-textContent",function(a,c,b){return"textContent"in +b});e.names={"class":"className","for":"htmlFor",tabindex:"tabIndex",readonly:"readOnly",colspan:"colSpan",frameborder:"frameBorder",rowspan:"rowSpan",textcontent:"textContent",valuetype:"valueType"};e.get=function(a,f){a=b.byId(a);var d=f.toLowerCase(),d=e.names[d]||f;return"textContent"==d&&!h("dom-textContent")?c(a):a[d]};e.set=function(c,n,q){c=b.byId(c);if(2==arguments.length&&"string"!=typeof n){for(var r in n)e.set(c,r,n[r]);return c}r=n.toLowerCase();r=e.names[r]||n;if("style"==r&&"string"!= +typeof q)return m.set(c,q),c;if("innerHTML"==r)return h("ie")&&c.tagName.toLowerCase()in{col:1,colgroup:1,table:1,tbody:1,tfoot:1,thead:1,tr:1,title:1}?(d.empty(c),c.appendChild(d.toDom(q,c.ownerDocument))):c[r]=q,c;if("textContent"==r&&!h("dom-textContent"))return d.empty(c),c.appendChild(c.ownerDocument.createTextNode(q)),c;if(l.isFunction(q)){var s=c[u];s||(s=f++,c[u]=s);a[s]||(a[s]={});var x=a[s][r];if(x)g.disconnect(x);else try{delete c[r]}catch(w){}q?a[s][r]=g.connect(c,r,q):c[r]=null;return c}c[r]= +q;return c}})},"dojo/dom-construct":function(){define("exports ./_base/kernel ./sniff ./_base/window ./dom ./dom-attr".split(" "),function(e,k,h,l,b,m){function d(a,c){var b=c.parentNode;b&&b.insertBefore(a,c)}function g(a){if("innerHTML"in a)try{a.innerHTML="";return}catch(c){}for(var b;b=a.lastChild;)a.removeChild(b)}var c={option:["select"],tbody:["table"],thead:["table"],tfoot:["table"],tr:["table","tbody"],td:["table","tbody","tr"],th:["table","thead","tr"],legend:["fieldset"],caption:["table"], +colgroup:["table"],col:["table","colgroup"],li:["ul"]},a=/<\s*([\w\:]+)/,f={},u=0,p="__"+k._scopeName+"ToDomId",n;for(n in c)c.hasOwnProperty(n)&&(k=c[n],k.pre="option"==n?'\x3cselect multiple\x3d"multiple"\x3e':"\x3c"+k.join("\x3e\x3c")+"\x3e",k.post="\x3c/"+k.reverse().join("\x3e\x3c/")+"\x3e");var q;8>=h("ie")&&(q=function(a){a.__dojo_html5_tested="yes";var c=r("div",{innerHTML:"\x3cnav\x3ea\x3c/nav\x3e",style:{visibility:"hidden"}},a.body);1!==c.childNodes.length&&"abbr article aside audio canvas details figcaption figure footer header hgroup mark meter nav output progress section summary time video".replace(/\b\w+\b/g, +function(c){a.createElement(c)});s(c)});e.toDom=function(b,d){d=d||l.doc;var g=d[p];g||(d[p]=g=++u+"",f[g]=d.createElement("div"));8>=h("ie")&&!d.__dojo_html5_tested&&d.body&&q(d);b+="";var n=b.match(a),s=n?n[1].toLowerCase():"",g=f[g];if(n&&c[s]){n=c[s];g.innerHTML=n.pre+b+n.post;for(n=n.length;n;--n)g=g.firstChild}else g.innerHTML=b;if(1==g.childNodes.length)return g.removeChild(g.firstChild);for(s=d.createDocumentFragment();n=g.firstChild;)s.appendChild(n);return s};e.place=function(a,c,f){c=b.byId(c); +"string"==typeof a&&(a=/^\s*f?0:f])}else switch(f){case "before":d(a,c);break;case "after":f=a;(g=c.parentNode)&&(g.lastChild==c?g.appendChild(f):g.insertBefore(f,c.nextSibling));break;case "replace":c.parentNode.replaceChild(a,c);break;case "only":e.empty(c);c.appendChild(a);break;case "first":if(c.firstChild){d(a,c.firstChild);break}default:c.appendChild(a)}return a}; +var r=e.create=function(a,c,f,d){var g=l.doc;f&&(f=b.byId(f),g=f.ownerDocument);"string"==typeof a&&(a=g.createElement(a));c&&m.set(a,c);f&&e.place(a,f,d);return a};e.empty=function(a){g(b.byId(a))};var s=e.destroy=function(a){if(a=b.byId(a)){var c=a;a=a.parentNode;c.firstChild&&g(c);a&&(h("ie")&&a.canHaveChildren&&"removeNode"in c?c.removeNode(!1):a.removeChild(c))}}})},"dojo/dom-class":function(){define(["./_base/lang","./_base/array","./dom"],function(e,k,h){function l(c){if("string"==typeof c|| +c instanceof String){if(c&&!m.test(c))return d[0]=c,d;c=c.split(m);c.length&&!c[0]&&c.shift();c.length&&!c[c.length-1]&&c.pop();return c}return!c?[]:k.filter(c,function(a){return a})}var b,m=/\s+/,d=[""],g={};return b={contains:function(c,a){return 0<=(" "+h.byId(c).className+" ").indexOf(" "+a+" ")},add:function(c,a){c=h.byId(c);a=l(a);var b=c.className,d,b=b?" "+b+" ":" ";d=b.length;for(var g=0,n=a.length,q;gb.indexOf(" "+q+" ")&&(b+=q+" ");dc&&(c=this.length+c);this[c]&&a.push(this[c])},this);return a._stash(this)}}); +var x=c(g,q);e.query=c(g,function(a){return q(a)});x.load=function(a,b,f){d.load(a,b,function(a){f(c(a,q))})};e._filterQueryResult=x._filterResult=function(a,c,b){return new q(x.filter(a,c,b))};e.NodeList=x.NodeList=q;return x})},"dojo/selector/_loader":function(){define(["../has","require"],function(e,k){if("undefined"!==typeof document){var h=document.createElement("div");e.add("dom-qsa2.1",!!h.querySelectorAll);e.add("dom-qsa3",function(){try{return h.innerHTML="\x3cp class\x3d'TEST'\x3e\x3c/p\x3e", +1==h.querySelectorAll(".TEST:empty").length}catch(b){}})}var l;return{load:function(b,m,d,g){if(g&&g.isBuild)d();else{g=k;b="default"==b?e("config-selectorEngine")||"css3":b;b="css2"==b||"lite"==b?"./lite":"css2.1"==b?e("dom-qsa2.1")?"./lite":"./acme":"css3"==b?e("dom-qsa3")?"./lite":"./acme":"acme"==b?"./acme":(g=m)&&b;if("?"==b.charAt(b.length-1)){b=b.substring(0,b.length-1);var c=!0}if(c&&(e("dom-compliant-qsa")||l))return d(l);g([b],function(a){"./lite"!=b&&(l=a);d(a)})}}}})},"dojo/selector/acme":function(){define(["../dom", +"../sniff","../_base/array","../_base/lang","../_base/window"],function(e,k,h,l,b){var m=l.trim,d=h.forEach,g="BackCompat"==b.doc.compatMode,c=!1,a=function(){return!0},f=function(a){a=0<="\x3e~+".indexOf(a.slice(-1))?a+" * ":a+" ";for(var b=function(c,b){return m(a.slice(c,b))},f=[],d=-1,g=-1,n=-1,q=-1,p=-1,s=-1,r=-1,e,l="",h="",u,x=0,y=a.length,w=null,B=null,k=function(){0<=s&&(w.id=b(s,x).replace(/\\/g,""),s=-1);if(0<=r){var a=r==x?null:b(r,x);w[0>"\x3e~+".indexOf(a)?"tag":"oper"]=a;r=-1}0<=p&& +(w.classes.push(b(p+1,x).replace(/\\/g,"")),p=-1)};l=h,h=a.charAt(x),xg?g=g%d&&d+g%d:0=d&&(n=g-g%d),g%=d):0>d&&(d*=-1,0=n&&(0>q||a<=q)&&a%d==g};c=g}var p=b(c);return function(a){return C(a)==p}}},I=9>k("ie")||9==k("ie")&&k("quirks")?function(a){var b=a.toLowerCase();"class"==b&&(a="className");return function(f){return c?f.getAttribute(a): +f[a]||f[b]}}:function(a){return function(c){return c&&c.getAttribute&&c.hasAttribute(a)}},O=function(b,f){if(!b)return a;f=f||{};var g=null;"el"in f||(g=u(g,n));"tag"in f||"*"!=b.tag&&(g=u(g,function(a){return a&&(c?a.tagName:a.tagName.toUpperCase())==b.getTag()}));"classes"in f||d(b.classes,function(a,c,b){var f=RegExp("(?:^|\\s)"+a+"(?:\\s|$)");g=u(g,function(a){return f.test(a.className)});g.count=c});"pseudos"in f||d(b.pseudos,function(a){var c=a.name;G[c]&&(g=u(g,G[c](c,a.value)))});"attrs"in +f||d(b.attrs,function(a){var c,b=a.attr;a.type&&r[a.type]?c=r[a.type](b,a.matchFor):b.length&&(c=I(b));c&&(g=u(g,c))});"id"in f||b.id&&(g=u(g,function(a){return!!a&&a.id==b.id}));g||"default"in f||(g=a);return g},N=function(a){return function(c,b,f){for(;c=c[x];)if(!s||n(c)){(!f||ia(c,f))&&a(c)&&b.push(c);break}return b}},T=function(a){return function(c,b,f){for(c=c[x];c;){if(y(c)){if(f&&!ia(c,f))break;a(c)&&b.push(c)}c=c[x]}return b}},P=function(c,b){var f=function(a){var c=[];try{c=Array.prototype.slice.call(a)}catch(b){for(var f= +0,d=a.length;f~+]|n\+\d|([^ \\])?([>~+])([^ =])?/g,U=function(a,c,b,f){return b?(c?c+" ":"")+b+(f?" "+f:""):a},ka=/([^[]*)([^\]]*])?/g,S=function(a,c,b){return c.replace(ba,U)+(b||"")}, +aa=function(a,c){a=a.replace(ka,S);if(Z){var b=V[a];if(b&&!c)return b}if(b=H[a])return b;var b=a.charAt(0),f=-1==a.indexOf(" ");0<=a.indexOf("#")&&f&&(c=!0);if(Z&&!c&&-1=="\x3e~+".indexOf(b)&&(!k("ie")||-1==a.indexOf(":"))&&!(g&&0<=a.indexOf("."))&&-1==a.indexOf(":contains")&&-1==a.indexOf(":checked")&&-1==a.indexOf("|\x3d")){var d=0<="\x3e~+".indexOf(a.charAt(a.length-1))?a+" *":a;return V[a]=function(c){if(9==c.nodeType||f)try{var b=c.querySelectorAll(d);b[R]=!0;return b}catch(g){}return aa(a,!0)(c)}}var n= +a.match(/([^\s,](?:"(?:\\.|[^"])+"|'(?:\\.|[^'])+'|[^,])*)/g);return H[a]=2>n.length?W(a):function(a){for(var c=0,b=[],f;f=n[c++];)b=b.concat(W(f)(a));return b}},ha=0,Aa=k("ie")?function(a){return c?a.getAttribute("_uid")||a.setAttribute("_uid",++ha)||ha:a.uniqueID}:function(a){return a._uid||(a._uid=++ha)},ia=function(a,c){if(!c)return 1;var b=Aa(a);return!c[b]?c[b]=1:0},qa=function(a){if(a&&a.nozip)return a;if(!a||!a.length)return[];if(2>a.length)return[a[0]];var b=[];ha++;var f,d;if(k("ie")&&c){var g= +ha+"";for(f=0;f= +B&&(B=0,s.ioPublish&&(e.publish&&(!a||a&&!1!==a.ioArgs.args.ioPublish))&&e.publish("/dojo/io/stop"))},B=0;p.after(n,"_onAction",function(){B-=1});p.after(n,"_onInFlight",A);e._ioCancelAll=n.cancelAll;e._ioNotifyStart=function(a){s.ioPublish&&(e.publish&&!1!==a.ioArgs.args.ioPublish)&&(B||e.publish("/dojo/io/start"),B+=1,e.publish("/dojo/io/send",[a]))};e._ioWatch=function(c,b,f,d){c.ioArgs.options=c.ioArgs.args;a.mixin(c,{response:c.ioArgs,isValid:function(a){return b(c)},isReady:function(a){return f(c)}, +handleResponse:function(a){return d(c)}});n(c);A(c)};e._ioAddQueryToUrl=function(a){a.query.length&&(a.url+=(-1==a.url.indexOf("?")?"?":"\x26")+a.query,a.query=null)};e.xhr=function(a,c,b){var f,d=e._ioSetArgs(c,function(a){f&&f.cancel()},w,y),g=d.ioArgs;"postData"in c?g.query=c.postData:"putData"in c?g.query=c.putData:"rawBody"in c?g.query=c.rawBody:(2a?(m=l(d),d=""):(m=l(d.slice(0,a)),d=l(d.slice(a+1)));"string"==typeof b[m]&&(b[m]=[b[m]]);e.isArray(b[m])?b[m].push(d):b[m]=d}return b}}})},"dojo/dom-form":function(){define(["./_base/lang","./dom","./io-query", +"./json"],function(e,k,h,l){var b={fieldToObject:function(b){var d=null;if(b=k.byId(b)){var g=b.name,c=(b.type||"").toLowerCase();if(g&&c&&!b.disabled)if("radio"==c||"checkbox"==c)b.checked&&(d=b.value);else if(b.multiple){d=[];for(b=[b.firstChild];b.length;)for(g=b.pop();g;g=g.nextSibling)if(1==g.nodeType&&"option"==g.tagName.toLowerCase())g.selected&&d.push(g.value);else{g.nextSibling&&b.push(g.nextSibling);g.firstChild&&b.push(g.firstChild);break}}else d=b.value}return d},toObject:function(m){var d= +{};m=k.byId(m).elements;for(var g=0,c=m.length;g"file|submit|image|reset|button".indexOf(h)&&!a.disabled){var p=d,n=f,a=b.fieldToObject(a);if(null!==a){var q=p[n];"string"==typeof q?p[n]=[q,a]:e.isArray(q)?q.push(a):p[n]=a}"image"==h&&(d[f+".x"]=d[f+".y"]=d[f].x=d[f].y=0)}}return d},toQuery:function(e){return h.objectToQuery(b.toObject(e))},toJson:function(e,d){return l.stringify(b.toObject(e),null,d?4:0)}};return b})},"dojo/request/watch":function(){define("./util ../errors/RequestTimeoutError ../errors/CancelError ../_base/array ../_base/window ../has!host-browser?dom-addeventlistener?:../on:".split(" "), +function(e,k,h,l,b,m){function d(){for(var b=+new Date,d=0,p;da||304===a||1223===a||!a}})},"dojo/errors/RequestError":function(){define(["./create"],function(e){return e("RequestError",function(e,h){this.response=h})})},"dojo/errors/RequestTimeoutError":function(){define(["./create","./RequestError"],function(e,k){return e("RequestTimeoutError",null,k,{dojoType:"timeout"})})},"dojo/request/xhr":function(){define(["../errors/RequestError", +"./watch","./handlers","./util","../has"],function(e,k,h,l,b){function m(a,c){var b=a.xhr;a.status=a.xhr.status;try{a.text=b.responseText}catch(f){}"xml"===a.options.handleAs&&(a.data=b.responseXML);if(!c)try{h(a)}catch(d){c=d}var g;if(c)this.reject(c);else{try{h(a)}catch(n){g=n}l.checkStatus(b.status)?g?this.reject(g):this.resolve(a):(c=g?new e("Unable to load "+a.url+" status: "+b.status+" and an error in handleAs: transformation of response",a):new e("Unable to load "+a.url+" status: "+b.status, +a),this.reject(c))}}function d(a){return this.xhr.getResponseHeader(a)}function g(r,s,h){var A=b("native-formdata")&&s&&s.data&&s.data instanceof FormData,B=l.parseArgs(r,l.deepCreate(q,s),A);r=B.url;s=B.options;var C,F=l.deferred(B,p,a,f,m,function(){C&&C()}),K=B.xhr=g._create();if(!K)return F.cancel(new e("XHR was not created")),h?F:F.promise;B.getHeader=d;u&&(C=u(K,F,B));var G=s.data,I=!s.sync,O=s.method;try{K.open(O,r,I,s.user||n,s.password||n);s.withCredentials&&(K.withCredentials=s.withCredentials); +b("native-response-type")&&s.handleAs in c&&(K.responseType=c[s.handleAs]);var N=s.headers;r=A?!1:"application/x-www-form-urlencoded";if(N)for(var T in N)"content-type"===T.toLowerCase()?r=N[T]:N[T]&&K.setRequestHeader(T,N[T]);r&&!1!==r&&K.setRequestHeader("Content-Type",r);(!N||!("X-Requested-With"in N))&&K.setRequestHeader("X-Requested-With","XMLHttpRequest");l.notify&&l.notify.emit("send",B,F.promise.cancel);K.send(G)}catch(P){F.reject(P)}k(F);K=null;return h?F:F.promise}b.add("native-xhr",function(){return"undefined"!== +typeof XMLHttpRequest});b.add("dojo-force-activex-xhr",function(){return b("activex")&&"file:"===window.location.protocol});b.add("native-xhr2",function(){if(b("native-xhr")&&!b("dojo-force-activex-xhr")){var a=new XMLHttpRequest;return"undefined"!==typeof a.addEventListener&&("undefined"===typeof opera||"undefined"!==typeof a.upload)}});b.add("native-formdata",function(){return"undefined"!==typeof FormData});b.add("native-response-type",function(){return b("native-xhr")&&"undefined"!==typeof(new XMLHttpRequest).responseType}); +b.add("native-xhr2-blob",function(){if(b("native-response-type")){var a=new XMLHttpRequest;a.open("GET","/",!0);a.responseType="blob";var c=a.responseType;a.abort();return"blob"===c}});var c={blob:b("native-xhr2-blob")?"blob":"arraybuffer",document:"document",arraybuffer:"arraybuffer"},a,f,u,p;b("native-xhr2")?(a=function(a){return!this.isFulfilled()},p=function(a,c){c.xhr.abort()},u=function(a,c,b){function f(a){c.handleResponse(b)}function d(a){a=new e("Unable to load "+b.url+" status: "+a.target.status, +b);c.handleResponse(b,a)}function g(a){a.lengthComputable?(b.loaded=a.loaded,b.total=a.total,c.progress(b)):3===b.xhr.readyState&&(b.loaded="loaded"in a?a.loaded:a.position,c.progress(b))}a.addEventListener("load",f,!1);a.addEventListener("error",d,!1);a.addEventListener("progress",g,!1);return function(){a.removeEventListener("load",f,!1);a.removeEventListener("error",d,!1);a.removeEventListener("progress",g,!1);a=null}}):(a=function(a){return a.xhr.readyState},f=function(a){return 4===a.xhr.readyState}, +p=function(a,c){var b=c.xhr,f=typeof b.abort;("function"===f||"object"===f||"unknown"===f)&&b.abort()});var n,q={data:null,query:null,sync:!1,method:"GET"};g._create=function(){throw Error("XMLHTTP not available");};if(b("native-xhr")&&!b("dojo-force-activex-xhr"))g._create=function(){return new XMLHttpRequest};else if(b("activex"))try{new ActiveXObject("Msxml2.XMLHTTP"),g._create=function(){return new ActiveXObject("Msxml2.XMLHTTP")}}catch(r){try{new ActiveXObject("Microsoft.XMLHTTP"),g._create= +function(){return new ActiveXObject("Microsoft.XMLHTTP")}}catch(s){}}l.addCommonMethods(g);return g})},"dojo/request/handlers":function(){define(["../json","../_base/kernel","../_base/array","../has","../selector/_loader"],function(e,k,h,l){function b(c){var b=a[c.options.handleAs];c.data=b?b(c):c.data||c.text;return c}l.add("activex","undefined"!==typeof ActiveXObject);l.add("dom-parser",function(a){return"DOMParser"in a});var m;if(l("activex")){var d=["Msxml2.DOMDocument.6.0","Msxml2.DOMDocument.4.0", +"MSXML2.DOMDocument.3.0","MSXML.DOMDocument"],g;m=function(a){function c(a){try{var f=new ActiveXObject(a);f.async=!1;f.loadXML(n);b=f;g=a}catch(d){return!1}return!0}var b=a.data,n=a.text;b&&(l("dom-qsa2.1")&&!b.querySelectorAll&&l("dom-parser"))&&(b=(new DOMParser).parseFromString(n,"application/xml"));if(!b||!b.documentElement)(!g||!c(g))&&h.some(d,c);return b}}var c=function(a){return!l("native-xhr2-blob")&&"blob"===a.options.handleAs&&"undefined"!==typeof Blob?new Blob([a.xhr.response],{type:a.xhr.getResponseHeader("Content-Type")}): +a.xhr.response},a={javascript:function(a){return k.eval(a.text||"")},json:function(a){return e.parse(a.text||null)},xml:m,blob:c,arraybuffer:c,document:c};b.register=function(c,b){a[c]=b};return b})},"dojo/_base/fx":function(){define("./kernel ./config ./lang ../Evented ./Color ../aspect ../sniff ../dom ../dom-style".split(" "),function(e,k,h,l,b,m,d,g,c){var a=h.mixin,f={},u=f._Line=function(a,c){this.start=a;this.end=c};u.prototype.getValue=function(a){return(this.end-this.start)*a+this.start}; +var p=f.Animation=function(c){a(this,c);h.isArray(this.curve)&&(this.curve=new u(this.curve[0],this.curve[1]))};p.prototype=new l;h.extend(p,{duration:350,repeat:0,rate:20,_percent:0,_startRepeatCount:0,_getStep:function(){var a=this._percent,c=this.easing;return c?c(a):a},_fire:function(a,c){var b=c||[];if(this[a])if(k.debugAtAllCosts)this[a].apply(this,b);else try{this[a].apply(this,b)}catch(f){console.error("exception in animation handler for:",a),console.error(f)}return this},play:function(a, +c){this._delayTimer&&this._clearTimer();if(c)this._stopTimer(),this._active=this._paused=!1,this._percent=0;else if(this._active&&!this._paused)return this;this._fire("beforeBegin",[this.node]);var b=a||this.delay,f=h.hitch(this,"_play",c);if(0this._percent?this._startTimer():(this._active=!1,0=n&&(clearInterval(q),q=null,n=0)}});var s=d("ie")?function(a){var b=a.style;!b.width.length&&"auto"==c.get(a,"width")&&(b.width="auto")}:function(){};f._fade=function(b){b.node=g.byId(b.node);var d=a({properties:{}},b);b=d.properties.opacity={};b.start=!("start"in d)?function(){return+c.get(d.node,"opacity")||0}:d.start;b.end=d.end; +b=f.animateProperty(d);m.after(b,"beforeBegin",h.partial(s,d.node),!0);return b};f.fadeIn=function(c){return f._fade(a({end:1},c))};f.fadeOut=function(c){return f._fade(a({end:0},c))};f._defaultEasing=function(a){return 0.5+Math.sin((a+1.5)*Math.PI)/2};var x=function(a){this._properties=a;for(var c in a){var f=a[c];f.start instanceof b&&(f.tempColor=new b)}};x.prototype.getValue=function(a){var c={},f;for(f in this._properties){var d=this._properties[f],g=d.start;g instanceof b?c[f]=b.blendColors(g, +d.end,a,d.tempColor).toCss():h.isArray(g)||(c[f]=(d.end-g)*a+g+("opacity"!=f?d.units||"px":0))}return c};f.animateProperty=function(f){var d=f.node=g.byId(f.node);f.easing||(f.easing=e._defaultEasing);f=new p(f);m.after(f,"beforeBegin",h.hitch(f,function(){var f={},g;for(g in this.properties){if("width"==g||"height"==g)this.node.display="block";var n=this.properties[g];h.isFunction(n)&&(n=n(d));n=f[g]=a({},h.isObject(n)?n:{end:n});h.isFunction(n.start)&&(n.start=n.start(d));h.isFunction(n.end)&&(n.end= +n.end(d));var q=0<=g.toLowerCase().indexOf("color"),p=function(a,b){var f={height:a.offsetHeight,width:a.offsetWidth}[b];if(void 0!==f)return f;f=c.get(a,b);return"opacity"==b?+f:q?f:parseFloat(f)};"end"in n?"start"in n||(n.start=p(d,g)):n.end=p(d,g);q?(n.start=new b(n.start),n.end=new b(n.end)):n.start="opacity"==g?+n.start:parseFloat(n.start)}this.curve=new x(f)}),!0);m.after(f,"onAnimate",h.hitch(c,"set",f.node),!0);return f};f.anim=function(a,c,b,d,g,n){return f.animateProperty({node:a,duration:b|| +p.prototype.duration,properties:c,easing:d,onEnd:g}).play(n||0)};a(e,f);e._Animation=p;return f})},"dojo/_base/loader":function(){define("./kernel ../has require module ../json ./lang ./array".split(" "),function(e,k,h,l,b,m,d){var g=function(a){return a.replace(/\./g,"/")},c=/\/\/>>built/,a=[],f=[],u=function(c,b,g){a.push(g);d.forEach(c.split(","),function(a){a=N(a,b.module);f.push(a);T(a)});p()},p=function(){var c,b;for(b in I)if(c=I[b],void 0===c.noReqPluginCheck&&(c.noReqPluginCheck=/loadInit\!/.test(b)|| +/require\!/.test(b)?1:0),!c.executed&&!c.noReqPluginCheck&&c.injected==A)return;V(function(){var c=a;a=[];d.forEach(c,function(a){a(1)})})},n=function(a,c,b){var f=/\(|\)/g,d=1;for(f.lastIndex=c;(c=f.exec(a))&&!(d=")"==c[0]?d-1:d+1,0==d););if(0!=d)throw"unmatched paren around character "+f.lastIndex+" in: "+a;return[e.trim(a.substring(b,f.lastIndex))+";\n",f.lastIndex]},q=/(\/\*([\s\S]*?)\*\/|\/\/(.*)$)/mg,r=/(^|\s)dojo\.(loadInit|require|provide|requireLocalization|requireIf|requireAfterIf|platformRequire)\s*\(/mg, +s=/(^|\s)(require|define)\s*\(/m,x=function(a,c){var b,f,d,g=[],p=[];b=[];for(c=c||a.replace(q,function(a){r.lastIndex=s.lastIndex=0;return r.test(a)||s.test(a)?"":a});b=r.exec(c);)f=r.lastIndex,d=f-b[0].length,f=n(c,f,d),"loadInit"==b[2]?g.push(f[0]):p.push(f[0]),r.lastIndex=f[1];b=g.concat(p);return b.length||!s.test(c)?[a.replace(/(^|\s)dojo\.loadInit\s*\(/g,"\n0 \x26\x26 dojo.loadInit("),b.join(""),b]:0},w=h.initSyncLoader(u,p,function(a,f){var d,g,n=[],q=[];if(c.test(f)||!(d=x(f)))return 0;g= +a.mid+"-*loadInit";for(var p in N("dojo",a).result.scopeMap)n.push(p),q.push('"'+p+'"');return"// xdomain rewrite of "+a.mid+"\ndefine('"+g+"',{\n\tnames:"+b.stringify(n)+",\n\tdef:function("+n.join(",")+"){"+d[1]+"}});\n\ndefine("+b.stringify(n.concat(["dojo/loadInit!"+g]))+", function("+n.join(",")+"){\n"+d[0]+"});"}),y=w.sync,A=w.requested,B=w.arrived,C=w.nonmodule,F=w.executing,K=w.executed,G=w.syncExecStack,I=w.modules,O=w.execQ,N=w.getModule,T=w.injectModule,P=w.setArrived,Q=w.signal,L=w.finishExec, +J=w.execModule,H=w.getLegacyMode,V=w.guardCheckComplete,u=w.dojoRequirePlugin;e.provide=function(a){var c=G[0],b=m.mixin(N(g(a),h.module),{executed:F,result:m.getObject(a,!0)});P(b);c&&(c.provides||(c.provides=[])).push(function(){b.result=m.getObject(a);delete b.provides;b.executed!==K&&L(b)});return b.result};k.add("config-publishRequireResult",1,0,0);e.require=function(a,c){var b=function(a,c){var b=N(g(a),h.module);if(G.length&&G[0].finish)G[0].finish.push(a);else{if(b.executed)return b.result; +c&&(b.result=C);var f=H();T(b);f=H();b.executed!==K&&b.injected===B&&w.guardCheckComplete(function(){J(b)});if(b.executed)return b.result;f==y?b.cjs?O.unshift(b):G.length&&(G[0].finish=[a]):O.push(b)}}(a,c);k("config-publishRequireResult")&&(!m.exists(a)&&void 0!==b)&&m.setObject(a,b);return b};e.loadInit=function(a){a()};e.registerModulePath=function(a,c){var b={};b[a.replace(/\./g,"/")]=c;h({paths:b})};e.platformRequire=function(a){a=(a.common||[]).concat(a[e._name]||a["default"]||[]);for(var c;a.length;)m.isArray(c= +a.shift())?e.require.apply(e,c):e.require(c)};e.requireIf=e.requireAfterIf=function(a,c,b){a&&e.require(c,b)};e.requireLocalization=function(a,c,b){h(["../i18n"],function(f){f.getLocalization(a,c,b)})};return{extractLegacyApiApplications:x,require:u,loadInit:function(a,c,b){c([a],function(a){c(a.names,function(){for(var f="",d=[],n=0;np&&(g.l+=g.w-p,g.w=p,f.resize(g));a=a.w-q-g.w-c.minSize;n.w>a&&(n.w=p,d.resize(n));f.set("maxSize",p);d.set("maxSize",a);this.inherited(arguments)},showModelBrowser:!1,_setShowModelBrowserAttr:function(a){var c=this.modelBrowser;this._started&& +this.showModelBrowser!==a&&(a?this.addChild(c):this.removeChild(c),this._set("showModelBrowser",a),this.resize())},showInformer:!1,_setShowInformerAttr:function(a){var c=this.informer;this._started&&(this.showInformer!==a&&(a?this.addChild(c):this.removeChild(c),this.resize()),this._set("showInformer",a))},getElementViewer:function(){return this.modelViewer.selectedDiagramTab.lightBox},getDiagram:function(a){return this.data.getDiagram(a)},getElement:function(a){return this.data.getElement(a)},isElement:function(a){return this.data.isElement(a)}, +isDiagram:function(a){return this.data.isDiagram(a)},getSelectedDiagram:function(){return this.modelViewer.selectedDiagram},getSelectedElement:function(){return this.modelViewer.selectedDiagramTab.modelGraphicsPane.selectedElement},isDiagramInView:function(a){return a===this.getSelectedDiagram()&&"ViewAllTab"!==this.modelViewer.selectedTab.role},open:function(a,c){var b=this,f=b.id,g=b._deferred,q,p;p=c&&c.nohash;if(g)g.then(function(){b.open(a,c)});else{g=new k;g.id=Math.round(1E3*Math.random()); +b._deferred=g;q=d.subscribe(f+"/postOpen",function(c){c===a&&(b._deferred=void 0,q.remove(),g.resolve())});setTimeout(function(){g.isFulfilled()||(b._deferred=void 0,g.reject("timed out"))},5E3);if(!p&&(p=b.isDiagram(a)?f+":"+a.hid.toString():b.getElementViewer().hasContentToShow(a)?f+":"+a.eid:null)&&p!==n())b._ignoreHashChange=!0,n(p);b.emit("open",a);d.publish(f+"/open",a,c)}return g},close:function(a){var c=this.id,b=new k,f,g;if(this.isDiagram(a)){f=this.isDiagramInView(a)?c+"/postOpen":c+"/postClose"; +g=d.subscribe(f,function(){g.remove();b.resolve()});try{d.publish(c+"/close",a)}catch(n){g.remove(),b.reject(n)}}else d.publish(c+"/close",a),b.resolve();return b},highlightAndFade:function(c){var b=this.userHighlighter,f,d;if(this.isElement(c))if(b.unhighlightAll(),b.highlight(c,"foo: foo"),f=b.getStylingLayer(c.diagram),d=f.styleElements.get(c.backing.sid).node,a("trident"))var g=new Date,n=setInterval(function(){var a=(new Date-g)/1E3;1I+1E3)&&f.call(this,a)});return{remove:function(){d.remove();g.remove()}}}:function(c,b){return m(c,a,b)}}function u(a){do if(void 0!==a.dojoClick)return a;while(a=a.parentNode)}function p(c,b,f){if(!g.isRight(c)){var d=u(c.target);if(w=!c.target.disabled&&d&&d.dojoClick)if(A=(y="useTarget"==w)?d:c.target,y&&c.preventDefault(),B=c.changedTouches?c.changedTouches[0].pageX-a.global.pageXOffset: +c.clientX,C=c.changedTouches?c.changedTouches[0].pageY-a.global.pageYOffset:c.clientY,F=("object"==typeof w?w.x:"number"==typeof w?w:0)||4,K=("object"==typeof w?w.y:"number"==typeof w?w:0)||4,!x){x=!0;var n=function(c){w=y?h.isDescendant(a.doc.elementFromPoint(c.changedTouches?c.changedTouches[0].pageX-a.global.pageXOffset:c.clientX,c.changedTouches?c.changedTouches[0].pageY-a.global.pageYOffset:c.clientY),A):w&&(c.changedTouches?c.changedTouches[0].target:c.target)==A&&Math.abs((c.changedTouches? +c.changedTouches[0].pageX-a.global.pageXOffset:c.clientX)-B)<=F&&Math.abs((c.changedTouches?c.changedTouches[0].pageY-a.global.pageYOffset:c.clientY)-C)<=K};a.doc.addEventListener(b,function(a){g.isRight(a)||(n(a),y&&a.preventDefault())},!0);a.doc.addEventListener(f,function(a){if(!g.isRight(a)&&(n(a),w)){G=(new Date).getTime();var c=y?A:a.target;"LABEL"===c.tagName&&(c=h.byId(c.getAttribute("for"))||c);var b=a.changedTouches?a.changedTouches[0]:a,f=function(c){var f=document.createEvent("MouseEvents"); +f._dojo_click=!0;f.initMouseEvent(c,!0,!0,a.view,a.detail,b.screenX,b.screenY,b.clientX,b.clientY,a.ctrlKey,a.altKey,a.shiftKey,a.metaKey,0,null);return f},d=f("mousedown"),q=f("mouseup"),p=f("click");setTimeout(function(){m.emit(c,"mousedown",d);m.emit(c,"mouseup",q);m.emit(c,"click",p);G=(new Date).getTime()},0)}},!0);c=function(c){a.doc.addEventListener(c,function(a){var b=a.target;w&&(!a._dojo_click&&(new Date).getTime()<=G+1E3&&!("INPUT"==b.tagName&&l.contains(b,"dijitOffScreen")))&&(a.stopPropagation(), +a.stopImmediatePropagation&&a.stopImmediatePropagation(),"click"==c&&(("INPUT"!=b.tagName||"radio"==b.type&&(l.contains(b,"dijitCheckBoxInput")||l.contains(b,"mblRadioButton"))||"checkbox"==b.type&&(l.contains(b,"dijitCheckBoxInput")||l.contains(b,"mblCheckBox")))&&"TEXTAREA"!=b.tagName&&"AUDIO"!=b.tagName&&"VIDEO"!=b.tagName)&&a.preventDefault())},!0)};c("click");c("mousedown");c("mouseup")}}}var n=5>d("ios"),q=d("pointer-events")||d("MSPointer"),r=function(){var a={},c;for(c in{down:1,move:1,up:1, +cancel:1,over:1,out:1})a[c]=d("MSPointer")?"MSPointer"+c.charAt(0).toUpperCase()+c.slice(1):"pointer"+c;return a}(),s=d("touch-events"),x,w,y=!1,A,B,C,F,K,G,I,O;d("touch")&&(q?c(function(){a.doc.addEventListener(r.down,function(a){p(a,r.move,r.up)},!0)}):c(function(){function c(a){var f=b.delegate(a,{bubbles:!0});6<=d("ios")&&(f.touches=a.touches,f.altKey=a.altKey,f.changedTouches=a.changedTouches,f.ctrlKey=a.ctrlKey,f.metaKey=a.metaKey,f.shiftKey=a.shiftKey,f.targetTouches=a.targetTouches);return f} +O=a.body();a.doc.addEventListener("touchstart",function(a){I=(new Date).getTime();var c=O;O=a.target;m.emit(c,"dojotouchout",{relatedTarget:O,bubbles:!0});m.emit(O,"dojotouchover",{relatedTarget:c,bubbles:!0});p(a,"touchmove","touchend")},!0);m(a.doc,"touchmove",function(b){I=(new Date).getTime();var f=a.doc.elementFromPoint(b.pageX-(n?0:a.global.pageXOffset),b.pageY-(n?0:a.global.pageYOffset));f&&(O!==f&&(m.emit(O,"dojotouchout",{relatedTarget:f,bubbles:!0}),m.emit(f,"dojotouchover",{relatedTarget:O, +bubbles:!0}),O=f),m.emit(f,"dojotouchmove",c(b))||b.preventDefault())});m(a.doc,"touchend",function(b){I=(new Date).getTime();var f=a.doc.elementFromPoint(b.pageX-(n?0:a.global.pageXOffset),b.pageY-(n?0:a.global.pageYOffset))||a.body();m.emit(f,"dojotouchend",c(b))})}));k={press:f("mousedown","touchstart",r.down),move:f("mousemove","dojotouchmove",r.move),release:f("mouseup","dojotouchend",r.up),cancel:f(g.leave,"touchcancel",q?r.cancel:null),over:f("mouseover","dojotouchover",r.over),out:f("mouseout", +"dojotouchout",r.out),enter:g._eventHandler(f("mouseover","dojotouchover",r.over)),leave:g._eventHandler(f("mouseout","dojotouchout",r.out))};return e.touch=k})},"dijit/_WidgetBase":function(){define("require dojo/_base/array dojo/aspect dojo/_base/config dojo/_base/connect dojo/_base/declare dojo/dom dojo/dom-attr dojo/dom-class dojo/dom-construct dojo/dom-geometry dojo/dom-style dojo/has dojo/_base/kernel dojo/_base/lang dojo/on dojo/ready dojo/Stateful dojo/topic dojo/_base/window ./Destroyable require ./registry".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q,r,s,x,w,y,A,B,C){function F(a){return function(c){g[c?"set":"remove"](this.domNode,a,c);this._set(a,c)}}p.add("dijit-legacy-requires",!n.isAsync);p("dijit-legacy-requires")&&s(0,function(){e(["dijit/_base/manager"])});var K={};return m("dijit._WidgetBase",[x,A],{id:"",_setIdAttr:"domNode",lang:"",_setLangAttr:F("lang"),dir:"",_setDirAttr:F("dir"),"class":"",_setClassAttr:{node:"domNode",type:"class"},_setTypeAttr:null,style:"",title:"",tooltip:"",baseClass:"", +srcNodeRef:null,domNode:null,containerNode:null,ownerDocument:null,_setOwnerDocumentAttr:function(a){this._set("ownerDocument",a)},attributeMap:{},_blankGif:l.blankGif||e.toUrl("dojo/resources/blank.gif"),textDir:"",_introspect:function(){var a=this.constructor;if(!a._setterAttrs){var c=a.prototype,b=a._setterAttrs=[],a=a._onMap={},f;for(f in c.attributeMap)b.push(f);for(f in c)/^on/.test(f)&&(a[f.substring(2).toLowerCase()]=f),/^_set[A-Z](.*)Attr$/.test(f)&&(f=f.charAt(4).toLowerCase()+f.substr(5, +f.length-9),(!c.attributeMap||!(f in c.attributeMap))&&b.push(f))}},postscript:function(a,c){this.create(a,c)},create:function(a,c){this._introspect();this.srcNodeRef=d.byId(c);this._connects=[];this._supportingWidgets=[];this.srcNodeRef&&(this.srcNodeRef.id&&"string"==typeof this.srcNodeRef.id)&&(this.id=this.srcNodeRef.id);a&&(this.params=a,q.mixin(this,a));this.postMixInProperties();this.id||(this.id=C.getUniqueId(this.declaredClass.replace(/\./g,"_")),this.params&&delete this.params.id);this.ownerDocument= +this.ownerDocument||(this.srcNodeRef?this.srcNodeRef.ownerDocument:document);this.ownerDocumentBody=y.body(this.ownerDocument);C.add(this);this.buildRendering();var b;if(this.domNode){this._applyAttributes();var f=this.srcNodeRef;f&&(f.parentNode&&this.domNode!==f)&&(f.parentNode.replaceChild(this.domNode,f),b=!0);this.domNode.setAttribute("widgetId",this.id)}this.postCreate();b&&delete this.srcNodeRef;this._created=!0},_applyAttributes:function(){var a={},c;for(c in this.params||{})a[c]=this._get(c); +k.forEach(this.constructor._setterAttrs,function(c){if(!(c in a)){var b=this._get(c);b&&this.set(c,b)}},this);for(c in a)this.set(c,a[c])},postMixInProperties:function(){},buildRendering:function(){this.domNode||(this.domNode=this.srcNodeRef||this.ownerDocument.createElement("div"));if(this.baseClass){var a=this.baseClass.split(" ");this.isLeftToRight()||(a=a.concat(k.map(a,function(a){return a+"Rtl"})));c.add(this.domNode,a)}},postCreate:function(){},startup:function(){this._started||(this._started= +!0,k.forEach(this.getChildren(),function(a){!a._started&&(!a._destroyed&&q.isFunction(a.startup))&&(a.startup(),a._started=!0)}))},destroyRecursive:function(a){this._beingDestroyed=!0;this.destroyDescendants(a);this.destroy(a)},destroy:function(a){function c(b){b.destroyRecursive?b.destroyRecursive(a):b.destroy&&b.destroy(a)}this._beingDestroyed=!0;this.uninitialize();k.forEach(this._connects,q.hitch(this,"disconnect"));k.forEach(this._supportingWidgets,c);this.domNode&&k.forEach(C.findWidgets(this.domNode, +this.containerNode),c);this.destroyRendering(a);C.remove(this.id);this._destroyed=!0},destroyRendering:function(c){this.bgIframe&&(this.bgIframe.destroy(c),delete this.bgIframe);this.domNode&&(c?g.remove(this.domNode,"widgetId"):a.destroy(this.domNode),delete this.domNode);this.srcNodeRef&&(c||a.destroy(this.srcNodeRef),delete this.srcNodeRef)},destroyDescendants:function(a){k.forEach(this.getChildren(),function(c){c.destroyRecursive&&c.destroyRecursive(a)})},uninitialize:function(){return!1},_setStyleAttr:function(a){var c= +this.domNode;q.isObject(a)?u.set(c,a):c.style.cssText=c.style.cssText?c.style.cssText+("; "+a):a;this._set("style",a)},_attrToDom:function(a,b,f){f=3<=arguments.length?f:this.attributeMap[a];k.forEach(q.isArray(f)?f:[f],function(f){var d=this[f.node||f||"domNode"];switch(f.type||"attribute"){case "attribute":q.isFunction(b)&&(b=q.hitch(this,b));f=f.attribute?f.attribute:/^on[A-Z][a-zA-Z]*$/.test(a)?a.toLowerCase():a;d.tagName?g.set(d,f,b):d.set(f,b);break;case "innerText":d.innerHTML="";d.appendChild(this.ownerDocument.createTextNode(b)); +break;case "textContent":d.textContent=b;break;case "innerHTML":d.innerHTML=b;break;case "class":c.replace(d,b,this[a]);break;case "toggleClass":c.toggle(d,f.className||a,b)}},this)},get:function(a){var c=this._getAttrNames(a);return this[c.g]?this[c.g]():this._get(a)},set:function(a,c){if("object"===typeof a){for(var b in a)this.set(b,a[b]);return this}b=this._getAttrNames(a);var f=this[b.s];if(q.isFunction(f))var d=f.apply(this,Array.prototype.slice.call(arguments,1));else{var f=this.focusNode&& +!q.isFunction(this.focusNode)?"focusNode":"domNode",g=this[f]&&this[f].tagName,n;if(n=g)if(!(n=K[g])){n=this[f];var p={},s;for(s in n)p[s.toLowerCase()]=!0;n=K[g]=p}s=n;b=a in this.attributeMap?this.attributeMap[a]:b.s in this?this[b.s]:s&&b.l in s&&"function"!=typeof c||/^aria-|^data-|^role$/.test(a)?f:null;null!=b&&this._attrToDom(a,c,b);this._set(a,c)}return d||this},_attrPairNames:{},_getAttrNames:function(a){var c=this._attrPairNames;if(c[a])return c[a];var b=a.replace(/^[a-z]|-[a-zA-Z]/g,function(a){return a.charAt(a.length- +1).toUpperCase()});return c[a]={n:a+"Node",s:"_set"+b+"Attr",g:"_get"+b+"Attr",l:b.toLowerCase()}},_set:function(a,c){var b=this[a];this[a]=c;if(this._created&&!(b===c||b!==b&&c!==c))this._watchCallbacks&&this._watchCallbacks(a,b,c),this.emit("attrmodified-"+a,{detail:{prevValue:b,newValue:c}})},_get:function(a){return this[a]},emit:function(a,c,b){c=c||{};void 0===c.bubbles&&(c.bubbles=!0);void 0===c.cancelable&&(c.cancelable=!0);c.detail||(c.detail={});c.detail.widget=this;var f,d=this["on"+a]; +d&&(f=d.apply(this,b?b:[c]));this._started&&!this._beingDestroyed&&r.emit(this.domNode,a.toLowerCase(),c);return f},on:function(a,c){var b=this._onMap(a);return b?h.after(this,b,c,!0):this.own(r(this.domNode,a,c))[0]},_onMap:function(a){var c=this.constructor,b=c._onMap;if(!b){var b=c._onMap={},f;for(f in c.prototype)/^on/.test(f)&&(b[f.replace(/^on/,"").toLowerCase()]=f)}return b["string"==typeof a&&a.toLowerCase()]},toString:function(){return"[Widget "+this.declaredClass+", "+(this.id||"NO ID")+ +"]"},getChildren:function(){return this.containerNode?C.findWidgets(this.containerNode):[]},getParent:function(){return C.getEnclosingWidget(this.domNode.parentNode)},connect:function(a,c,f){return this.own(b.connect(a,c,this,f))[0]},disconnect:function(a){a.remove()},subscribe:function(a,c){return this.own(w.subscribe(a,q.hitch(this,c)))[0]},unsubscribe:function(a){a.remove()},isLeftToRight:function(){return this.dir?"ltr"==this.dir.toLowerCase():f.isBodyLtr(this.ownerDocument)},isFocusable:function(){return this.focus&& +"none"!=u.get(this.domNode,"display")},placeAt:function(c,b){var f=!c.tagName&&C.byId(c);f&&f.addChild&&(!b||"number"===typeof b)?f.addChild(this,b):(f=f&&"domNode"in f?f.containerNode&&!/after|before|replace/.test(b||"")?f.containerNode:f.domNode:d.byId(c,this.ownerDocument),a.place(this.domNode,f,b),!this._started&&(this.getParent()||{})._started&&this.startup());return this},defer:function(a,c){var b=setTimeout(q.hitch(this,function(){b&&(b=null,this._destroyed||q.hitch(this,a)())}),c||0);return{remove:function(){b&& +(clearTimeout(b),b=null);return null}}}})})},"dojo/Stateful":function(){define(["./_base/declare","./_base/lang","./_base/array","./when"],function(e,k,h,l){return e("dojo.Stateful",null,{_attrPairNames:{},_getAttrNames:function(b){var e=this._attrPairNames;return e[b]?e[b]:e[b]={s:"_"+b+"Setter",g:"_"+b+"Getter"}},postscript:function(b){b&&this.set(b)},_get:function(b,e){return"function"===typeof this[e.g]?this[e.g]():this[b]},get:function(b){return this._get(b,this._getAttrNames(b))},set:function(b, +e){if("object"===typeof b){for(var d in b)b.hasOwnProperty(d)&&"_watchCallbacks"!=d&&this.set(d,b[d]);return this}d=this._getAttrNames(b);var g=this._get(b,d);d=this[d.s];var c;"function"===typeof d?c=d.apply(this,Array.prototype.slice.call(arguments,1)):this[b]=e;if(this._watchCallbacks){var a=this;l(c,function(){a._watchCallbacks(b,g,e)})}return this},_changeAttrValue:function(b,e){var d=this.get(b);this[b]=e;this._watchCallbacks&&this._watchCallbacks(b,d,e);return this},watch:function(b,e){var d= +this._watchCallbacks;if(!d)var g=this,d=this._watchCallbacks=function(a,c,b,n){var q=function(d){if(d){d=d.slice();for(var n=0,q=d.length;n=n||7==n&&e?!1:k("position-fixed-support")&&"fixed"==m.get(a,"position").toLowerCase()},A=this,B=function(a,c,b){"BODY"==a.tagName||"HTML"==a.tagName?A.get(a.ownerDocument).scrollBy(c,b):(c&&(a.scrollLeft+=c),b&&(a.scrollTop+=b))};if(!q(c))for(;y;){y==d&&(y=f);var C=b.position(y),F=q(y),K="rtl"==m.getComputedStyle(y).direction.toLowerCase();if(y==f){C.w=s;C.h=x;if(f==g&&(n||k("trident"))&& +K)C.x+=f.offsetWidth-C.w;C.x=0;C.y=0}else{var G=b.getPadBorderExtents(y);C.w-=G.w;C.h-=G.h;C.x+=G.l;C.y+=G.t;var I=y.clientWidth,O=C.w-I;0C.y&&(C.h+=C.y,C.y=0),0>C.x&&(C.w+=C.x,C.x=0),C.y+C.h>x&&(C.h=x-C.y),C.x+C.w>s&&(C.w=s-C.x));var N=w.x-C.x,T=w.y-C.y,P=N+w.w-C.w,Q=T+w.h-C.h,L,J;if(0y.offsetHeight)){L=Math[0>N?"max":"min"](N,P);if(K&& +(8==n&&!e||5<=k("trident")))L=-L;J=y.scrollLeft;B(y,L,0);L=y.scrollLeft-J;w.x-=L}if(0y.offsetHeight))L=Math.ceil(Math[0>T?"max":"min"](T,Q)),J=y.scrollTop,B(y,0,L),L=y.scrollTop-J,w.y-=L;y=y!=f&&!F&&y.parentNode}}}catch(H){console.error("scrollIntoView: "+H),c.scrollIntoView(!1)}}};e.setObject("dojo.window",g);return g})},"dijit/a11y":function(){define("dojo/_base/array dojo/dom dojo/dom-attr dojo/dom-style dojo/_base/lang dojo/sniff ./main".split(" "),function(e, +k,h,l,b,m,d){var g={_isElementShown:function(c){var a=l.get(c);return"hidden"!=a.visibility&&"collapsed"!=a.visibility&&"none"!=a.display&&"hidden"!=h.get(c,"type")},hasDefaultTabStop:function(c){switch(c.nodeName.toLowerCase()){case "a":return h.has(c,"href");case "area":case "button":case "input":case "object":case "select":case "textarea":return!0;case "iframe":var a;try{var b=c.contentDocument;if("designMode"in b&&"on"==b.designMode)return!0;a=b.body}catch(d){try{a=c.contentWindow.document.body}catch(g){return!1}}return a&& +("true"==a.contentEditable||a.firstChild&&"true"==a.firstChild.contentEditable);default:return"true"==c.contentEditable}},effectiveTabIndex:function(c){return h.get(c,"disabled")?void 0:h.has(c,"tabIndex")?+h.get(c,"tabIndex"):g.hasDefaultTabStop(c)?0:void 0},isTabNavigable:function(c){return 0<=g.effectiveTabIndex(c)},isFocusable:function(c){return-1<=g.effectiveTabIndex(c)},_getTabNavigable:function(c){function a(a){return a&&"input"==a.tagName.toLowerCase()&&a.type&&"radio"==a.type.toLowerCase()&& +a.name&&a.name.toLowerCase()}var b,d,p,n,q,e,s={},l=g._isElementShown,k=g.effectiveTabIndex,y=function(c){for(c=c.firstChild;c;c=c.nextSibling)if(!(1!=c.nodeType||9>=m("ie")&&"HTML"!==c.scopeName||!l(c))){var g=k(c);if(0<=g){if(0==g)b||(b=c),d=c;else if(0=e)e=g,q=c}g=a(c);h.get(c,"checked")&&g&&(s[g]=c)}"SELECT"!=c.nodeName.toUpperCase()&&y(c)}};l(c)&&y(c);return{first:s[a(b)]||b,last:s[a(d)]||d,lowest:s[a(p)]||p,highest:s[a(q)]||q}},getFirstInTabbingOrder:function(c, +a){var b=g._getTabNavigable(k.byId(c,a));return b.lowest?b.lowest:b.first},getLastInTabbingOrder:function(c,a){var b=g._getTabNavigable(k.byId(c,a));return b.last?b.last:b.highest}};b.mixin(d,g);return g})},"dojo/uacss":function(){define(["./dom-geometry","./_base/lang","./domReady","./sniff","./_base/window"],function(e,k,h,l,b){var m=b.doc.documentElement;b=l("ie");var d=l("trident"),g=l("opera"),c=Math.floor,a=l("ff"),f=e.boxModel.replace(/-/,""),g={dj_quirks:l("quirks"),dj_opera:g,dj_khtml:l("khtml"), +dj_webkit:l("webkit"),dj_safari:l("safari"),dj_chrome:l("chrome"),dj_edge:l("edge"),dj_gecko:l("mozilla"),dj_ios:l("ios"),dj_android:l("android")};b&&(g.dj_ie=!0,g["dj_ie"+c(b)]=!0,g.dj_iequirks=l("quirks"));d&&(g.dj_trident=!0,g["dj_trident"+c(d)]=!0);a&&(g["dj_ff"+c(a)]=!0);g["dj_"+f]=!0;var u="",p;for(p in g)g[p]&&(u+=p+" ");m.className=k.trim(m.className+" "+u);h(function(){if(!e.isBodyLtr()){var a="dj_rtl dijitRtl "+u.replace(/ /g,"-rtl ");m.className=k.trim(m.className+" "+a+"dj_rtl dijitRtl "+ +u.replace(/ /g,"-rtl "))}});return l})},"dijit/hccss":function(){define(["dojo/dom-class","dojo/hccss","dojo/domReady","dojo/_base/window"],function(e,k,h,l){h(function(){k("highcontrast")&&e.add(l.body(),"dijit_a11y")});return k})},"dojo/hccss":function(){define("require ./_base/config ./dom-class ./dom-style ./has ./domReady ./_base/window".split(" "),function(e,k,h,l,b,m,d){b.add("highcontrast",function(){var g=d.doc.createElement("div");try{g.style.cssText='border: 1px solid; border-color:red green; position: absolute; height: 5px; top: -999px;background-image: url("'+ +(k.blankGif||e.toUrl("./resources/blank.gif"))+'");';d.body().appendChild(g);var c=l.getComputedStyle(g),a=c.backgroundImage;return c.borderTopColor==c.borderRightColor||a&&("none"==a||"url(invalid-url:)"==a)}catch(f){return console.warn("hccss: exception detecting high-contrast mode, document is likely hidden: "+f.toString()),!1}finally{8>=b("ie")?g.outerHTML="":d.body().removeChild(g)}});m(function(){b("highcontrast")&&h.add(d.body(),"dj_a11y")});return b})},"dijit/_TemplatedMixin":function(){define("dojo/cache dojo/_base/declare dojo/dom-construct dojo/_base/lang dojo/on dojo/sniff dojo/string ./_AttachMixin".split(" "), +function(e,k,h,l,b,m,d,g){var c=k("dijit._TemplatedMixin",g,{templateString:null,templatePath:null,_skipNodeCache:!1,searchContainerNode:!0,_stringRepl:function(a){var c=this.declaredClass,b=this;return d.substitute(a,this,function(a,d){"!"==d.charAt(0)&&(a=l.getObject(d.substr(1),!1,b));if("undefined"==typeof a)throw Error(c+" template:"+d);return null==a?"":"!"==d.charAt(0)?a:this._escapeValue(""+a)},this)},_escapeValue:function(a){return a.replace(/["'<>&]/g,function(a){return{"\x26":"\x26amp;", +"\x3c":"\x26lt;","\x3e":"\x26gt;",'"':"\x26quot;","'":"\x26#x27;"}[a]})},buildRendering:function(){if(!this._rendered){this.templateString||(this.templateString=e(this.templatePath,{sanitize:!0}));var a=c.getCachedTemplate(this.templateString,this._skipNodeCache,this.ownerDocument),b;if(l.isString(a)){if(b=h.toDom(this._stringRepl(a),this.ownerDocument),1!=b.nodeType)throw Error("Invalid template: "+a);}else b=a.cloneNode(!0);this.domNode=b}this.inherited(arguments);this._rendered||this._fillContent(this.srcNodeRef); +this._rendered=!0},_fillContent:function(a){var c=this.containerNode;if(a&&c)for(;a.hasChildNodes();)c.appendChild(a.firstChild)}});c._templateCache={};c.getCachedTemplate=function(a,b,g){var p=c._templateCache,n=a,q=p[n];if(q){try{if(!q.ownerDocument||q.ownerDocument==(g||document))return q}catch(e){}h.destroy(q)}a=d.trim(a);if(b||a.match(/\$\{([^\}]+)\}/g))return p[n]=a;b=h.toDom(a,g);if(1!=b.nodeType)throw Error("Invalid template: "+a);return p[n]=b};m("ie")&&b(window,"unload",function(){var a= +c._templateCache,b;for(b in a){var d=a[b];"object"==typeof d&&h.destroy(d);delete a[b]}});return c})},"dojo/cache":function(){define(["./_base/kernel","./text"],function(e){return e.cache})},"dojo/text":function(){define(["./_base/kernel","require","./has","./request"],function(e,k,h,l){var b;b=function(a,c,b){l(a,{sync:!!c,headers:{"X-Requested-With":null}}).then(b)};var m={},d=function(a){if(a){a=a.replace(/^\s*<\?xml(\s)+version=[\'\"](\d)*.(\d)*[\'\"](\s)*\?>/im,"");var c=a.match(/]*>\s*([\s\S]+)\s*<\/body>/im); +c&&(a=c[1])}else a="";return a},g={},c={};e.cache=function(a,c,g){var p;"string"==typeof a?/\//.test(a)?(p=a,g=c):p=k.toUrl(a.replace(/\./g,"/")+(c?"/"+c:"")):(p=a+"",g=c);a=void 0!=g&&"string"!=typeof g?g.value:g;g=g&&g.sanitize;if("string"==typeof a)return m[p]=a,g?d(a):a;if(null===a)return delete m[p],null;p in m||b(p,!0,function(a){m[p]=a});return g?d(m[p]):m[p]};return{dynamic:!0,normalize:function(a,c){var b=a.split("!"),d=b[0];return(/^\./.test(d)?c(d):d)+(b[1]?"!"+b[1]:"")},load:function(a, +f,e){a=a.split("!");var p=1'"\/]/g,l={"\x26":"\x26amp;","\x3c":"\x26lt;","\x3e":"\x26gt;",'"':"\x26quot;","'":"\x26#x27;","/":"\x26#x2F;"},b={};k.setObject("dojo.string",b);b.escape=function(b){return!b?"":b.replace(h,function(b){return l[b]})};b.rep=function(b,d){if(0>=d||!b)return"";for(var g=[];;){d& +1&&g.push(b);if(!(d>>=1))break;b+=b}return g.join("")};b.pad=function(e,d,g,c){g||(g="0");e=String(e);d=b.rep(g,Math.ceil((d-e.length)/g.length));return c?e+d:d+e};b.substitute=function(b,d,g,c){c=c||e.global;g=g?k.hitch(c,g):function(a){return a};return b.replace(/\$\{([^\s\:\}]*)(?:\:([^\s\:\}]+))?\}/g,function(a,b,e){if(""==b)return"$";a=k.getObject(b,!1,d);e&&(a=k.getObject(e,!1,c).call(c,a,b));return g(a,b).toString()})};b.trim=String.prototype.trim?k.trim:function(b){b=b.replace(/^\s+/,""); +for(var d=b.length-1;0<=d;d--)if(/\S/.test(b.charAt(d))){b=b.substring(0,d+1);break}return b};return b})},"dijit/_AttachMixin":function(){define("require dojo/_base/array dojo/_base/connect dojo/_base/declare dojo/_base/lang dojo/mouse dojo/on dojo/touch ./_WidgetBase".split(" "),function(e,k,h,l,b,m,d,g,c){var a=b.delegate(g,{mouseenter:m.enter,mouseleave:m.leave,keypress:h._keypress}),f;h=l("dijit._AttachMixin",null,{constructor:function(){this._attachPoints=[];this._attachEvents=[]},buildRendering:function(){this.inherited(arguments); +this._attachTemplateNodes(this.domNode);this._beforeFillContent()},_beforeFillContent:function(){},_attachTemplateNodes:function(a){for(var c=a;;)if(1==c.nodeType&&(this._processTemplateNode(c,function(a,c){return a.getAttribute(c)},this._attach)||this.searchContainerNode)&&c.firstChild)c=c.firstChild;else{if(c==a)break;for(;!c.nextSibling;)if(c=c.parentNode,c==a)return;c=c.nextSibling}},_processTemplateNode:function(a,c,f){var d=!0,g=this.attachScope||this,e=c(a,"dojoAttachPoint")||c(a,"data-dojo-attach-point"); +if(e)for(var m=e.split(/\s*,\s*/);e=m.shift();)b.isArray(g[e])?g[e].push(a):g[e]=a,d="containerNode"!=e,this._attachPoints.push(e);if(c=c(a,"dojoAttachEvent")||c(a,"data-dojo-attach-event")){e=c.split(/\s*,\s*/);for(m=b.trim;c=e.shift();)if(c){var h=null;-1!=c.indexOf(":")?(h=c.split(":"),c=m(h[0]),h=m(h[1])):c=m(c);h||(h=c);this._attachEvents.push(f(a,c,b.hitch(g,h)))}}return d},_attach:function(c,b,g){b=b.replace(/^on/,"").toLowerCase();b="dijitclick"==b?f||(f=e("./a11yclick")):a[b]||b;return d(c, +b,g)},_detachTemplateNodes:function(){var a=this.attachScope||this;k.forEach(this._attachPoints,function(c){delete a[c]});this._attachPoints=[];k.forEach(this._attachEvents,function(a){a.remove()});this._attachEvents=[]},destroyRendering:function(){this._detachTemplateNodes();this.inherited(arguments)}});b.extend(c,{dojoAttachEvent:"",dojoAttachPoint:""});return h})},"dijit/layout/LayoutContainer":function(){define("dojo/_base/array dojo/_base/declare dojo/dom-class dojo/dom-style dojo/_base/lang ../_WidgetBase ./_LayoutWidget ./utils".split(" "), +function(e,k,h,l,b,m,d,g){k=k("dijit.layout.LayoutContainer",d,{design:"headline",baseClass:"dijitLayoutContainer",startup:function(){this._started||(e.forEach(this.getChildren(),this._setupChild,this),this.inherited(arguments))},_setupChild:function(c){this.inherited(arguments);c.region&&h.add(c.domNode,this.baseClass+"Pane")},_getOrderedChildren:function(){var c=e.map(this.getChildren(),function(a,c){return{pane:a,weight:["center"==a.region?Infinity:0,a.layoutPriority,("sidebar"==this.design?1: +-1)*(/top|bottom/.test(a.region)?1:-1),c]}},this);c.sort(function(a,c){for(var b=a.weight,d=c.weight,g=0;gn)?-1:1}return 0});if(h&&(h.start||h.count)){var g=b.length;b=b.slice(h.start||0,(h.start||0)+(h.count||Infinity));b.total=g}return b}switch(typeof k){default:throw Error("Can not query with a "+typeof k);case "object":case "undefined":var b=k;k=function(e){for(var d in b){var g=b[d];if(g&&g.test){if(!g.test(e[d],e))return!1}else if(g!=e[d])return!1}return!0};break;case "string":if(!this[k])throw Error("No filter function "+k+" was found in store");k=this[k];case "function":}l.matches=k;return l}})}, +"webview/utils/pathParts":function(){define([],function(){return function(e){var k,h,l;for(l=e.length-1;0A.indexOf(w))){m=w;k=p;(q||!a)&&d.splice(p,1);break}}}if(q){if(a&&(q.matches?q.matches(a):q([a]).length))p=-1=b.zOrder){e.insertBefore(b.node,g.node);d.splice(c,0,b);return}e.appendChild(b.node);d.push(b)},_removeStylingLayer:function(b){var e=this.stylingLayers,d=k.indexOf(e,b);-1this.elementStrokeWidth?(d=e.stroke,h.forEach(this.noStrokeFillNodes,function(a){b.setAttribute(a,"stroke",d);b.setAttribute(a,"stroke-width",g-1);b.setAttribute(a,"stroke-opacity",e["stroke-opacity"]);b.setAttribute(a,"fill",d);b.setAttribute(a,"fill-opacity",e["stroke-opacity"])})):h.forEach(this.noStrokeFillNodes,function(a){b.setAttribute(a,"stroke","none")})},removeStyle:function(){var c=this.node,a,f=this.appliedStyleMap; +if(f){for(a in f)f.hasOwnProperty(a)&&b.setAttribute(c,a,f[a]);h.forEach(this.noStrokeFillNodes,function(a){b.setAttribute(a,"stroke","none");b.removeAttribute(a,"fill");b.removeAttribute(a,"fill-opacity")})}this.appliedStyleMap={}},showStyle:function(){b.setAttribute(this.node,"display","inline")},hideStyle:function(){b.setAttribute(this.node,"display","none")}}),g=e(null,{constructor:function(c){var a=c.svgDocument,f=c.node,d=c.id+"-mask",g=b.createSvgElement(a,"mask",{id:d,x:"-100%",y:"-100%", +width:"300%",height:"300%"},f);c._isLine()&&(b.setAttribute(g,"x","-300%"),b.setAttribute(g,"y","-300%"),b.setAttribute(g,"width","700%"),b.setAttribute(g,"height","700%"));this.styleElement=c;this.maskNode=g;b.createSvgElement(a,"use",{"xlink:href":"#"+c.styler.maskBackgroundNode.id},g);this.maskObj=c._createUnstyledObj(g);this.styleObj=c._createUnstyledObj(f);b.setAttribute(this.styleObj.node,"mask","url(#"+d+")")},destroy:function(){this.maskObj.destroy();this.styleObj.destroy();this.styleElement.node.removeChild(this.maskNode)}, +update:function(){this.setStyle(this.styleMap)},setStyle:function(b){var a=this.styleElement,f=a.stylingLayer,d=a.elementId,g=k.mixin({},b),e=a.styleObj.appliedStyleMap["stroke-width"]||a._getElementStrokeWidth(),e=parseFloat(e);this.styleMap=b;h.forEach(a.styler.stylingLayers,function(a){var b;if(a!==f&&a.show&&a.zOrdera.zOrder&&(f=f.getStyle(b))&&f.show&&f.outerStroke?(f.outerStroke.update(),!0):!1})},_isLine:function(){var c=b.getParent(this.elementNode),c=b.getAttribute(c,"data-tags");return!this._getFrameNode()&&(!c||-1!==c.indexOf("line"))},_getBackgroundColor:function(){var c=this._backgroundColor, +a,f;c||(b.someElement(this.elementNode.childNodes,function(d){return"text"!==d.nodeName&&(f=(a=b.getAttribute(d,"data-tags"))?a.split(" "):[],-1===f.indexOf("line")&&-1===f.indexOf("frame")&&(c=b.getAttribute(d,"fill")||"none","none"!==c))?!0:!1}),this._backgroundColor=c||"none");return this._backgroundColor},_removeBackgroundColor:function(){var c=this._getBackgroundColor(),a=this.backgroundNodes;"none"!==c&&(a||(a=b.getDescendentNodes(this.elementNode,{filter:function(a){return a.nodeType===b.ELEMENT_NODE&& +!/defs|image|text/.test(a.tagName)}}),this.backgroundNodes=a=h.filter(a,function(a){return b.getAttribute(a,"fill")===c})),h.forEach(this.backgroundNodes,function(a){var c=b.getAttribute(a,"fill");if(c&&(b.hasAttribute(a,"data-orig-fill")||b.setAttribute(a,"data-orig-fill",c),b.setAttribute(a,"fill","#ffffff"),c=b.getAttribute(a,"fill-opacity")))b.hasAttribute(a,"data-orig-fill-opacity")||b.setAttribute(a,"data-orig-fill-opacity",c),b.setAttribute(a,"fill-opacity","1")}))},_restoreBackgroundColor:function(){this.backgroundNodes&& +h.forEach(this.backgroundNodes,function(c){var a=b.getAttribute(c,"data-orig-fill"),f=b.getAttribute(c,"data-orig-fill-opacity");a&&b.setAttribute(c,"fill",a);f&&b.setAttribute(c,"fill-opacity",f)})}})})},"dojo/i18n":function(){define("./_base/kernel require ./has ./_base/array ./_base/config ./_base/lang ./_base/xhr ./json module".split(" "),function(e,k,h,l,b,m,d,g,c){h.add("dojo-preload-i18n-Api",1);var a=e.i18n={},f=/(^.*(^|\/)nls)(\/|$)([^\/]*)\/?([^\/]*)/,u=function(a,b,c,f){var d=[c+f];b=b.split("-"); +for(var g="",e=0;e=this._outstandingPaintOperations&&(!this._adjustWidthsTimer&&this._started)&&(this._adjustWidthsTimer=this.defer("_adjustWidths"))});y(a,b,b)},_adjustWidths:function(){this._adjustWidthsTimer&&(this._adjustWidthsTimer.remove(),delete this._adjustWidthsTimer); +this.containerNode.style.width="auto";this.containerNode.style.width=this.domNode.scrollWidth>this.domNode.offsetWidth?"auto":"100%"},_createTreeNode:function(a){return new W(a)},focus:function(){this.lastFocusedChild?this.focusNode(this.lastFocusedChild):this.focusFirstChild()}});R.PathError=f("TreePathError");R._TreeNode=W;return R})},"dojo/fx":function(){define("./_base/lang ./Evented ./_base/kernel ./_base/array ./aspect ./_base/fx ./dom ./dom-style ./dom-geometry ./ready require".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f){h.isAsync||a(0,function(){f(["./fx/Toggler"])});h=h.fx={};a={_fire:function(a,b){this[a]&&this[a].apply(this,b||[]);return this}};var u=function(a){this._index=-1;this._animations=a||[];this._current=this._onAnimateCtx=this._onEndCtx=null;this.duration=0;l.forEach(this._animations,function(a){a&&("undefined"!=typeof a.duration&&(this.duration+=a.duration),a.delay&&(this.duration+=a.delay))},this)};u.prototype=new k;e.extend(u,{_onAnimate:function(){this._fire("onAnimate", +arguments)},_onEnd:function(){this._onAnimateCtx.remove();this._onEndCtx.remove();this._onAnimateCtx=this._onEndCtx=null;this._index+1==this._animations.length?this._fire("onEnd"):(this._current=this._animations[++this._index],this._onAnimateCtx=b.after(this._current,"onAnimate",e.hitch(this,"_onAnimate"),!0),this._onEndCtx=b.after(this._current,"onEnd",e.hitch(this,"_onEnd"),!0),this._current.play(0,!0))},play:function(a,c){this._current||(this._current=this._animations[this._index=0]);if(!c&&"playing"== +this._current.status())return this;var f=b.after(this._current,"beforeBegin",e.hitch(this,function(){this._fire("beforeBegin")}),!0),d=b.after(this._current,"onBegin",e.hitch(this,function(a){this._fire("onBegin",arguments)}),!0),g=b.after(this._current,"onPlay",e.hitch(this,function(a){this._fire("onPlay",arguments);f.remove();d.remove();g.remove()}));this._onAnimateCtx&&this._onAnimateCtx.remove();this._onAnimateCtx=b.after(this._current,"onAnimate",e.hitch(this,"_onAnimate"),!0);this._onEndCtx&& +this._onEndCtx.remove();this._onEndCtx=b.after(this._current,"onEnd",e.hitch(this,"_onEnd"),!0);this._current.play.apply(this._current,arguments);return this},pause:function(){if(this._current){var a=b.after(this._current,"onPause",e.hitch(this,function(b){this._fire("onPause",arguments);a.remove()}),!0);this._current.pause()}return this},gotoPercent:function(a,b){this.pause();var c=this.duration*a;this._current=null;l.some(this._animations,function(a,b){if(c<=a.duration)return this._current=a,this._index= +b,!0;c-=a.duration;return!1},this);this._current&&this._current.gotoPercent(c/this._current.duration);b&&this.play();return this},stop:function(a){if(this._current){if(a){for(;this._index+1this._animations.length&&this._fire("onEnd")},_call:function(a,b){var c=this._pseudoAnimation;c[a].apply(c,b)},play:function(a, +b){this._finished=0;this._doAction("play",arguments);this._call("play",arguments);return this},pause:function(){this._doAction("pause",arguments);this._call("pause",arguments);return this},gotoPercent:function(a,b){var c=this.duration*a;l.forEach(this._animations,function(a){a.gotoPercent(a.durationa?"previousSibling":"nextSibling"])&&"getAttribute"in b){var f=d.byNode(b);if(f)return f}return null}})})}, +"dijit/tree/TreeStoreModel":function(){define(["dojo/_base/array","dojo/aspect","dojo/_base/declare","dojo/_base/lang"],function(e,k,h,l){return h("dijit.tree.TreeStoreModel",null,{store:null,childrenAttrs:["children"],newItemIdAttr:"id",labelAttr:"",root:null,query:null,deferItemLoadingUntilExpand:!1,constructor:function(b){l.mixin(this,b);this.connects=[];b=this.store;if(!b.getFeatures()["dojo.data.api.Identity"])throw Error("dijit.tree.TreeStoreModel: store must support dojo.data.Identity");b.getFeatures()["dojo.data.api.Notification"]&& +(this.connects=this.connects.concat([k.after(b,"onNew",l.hitch(this,"onNewItem"),!0),k.after(b,"onDelete",l.hitch(this,"onDeleteItem"),!0),k.after(b,"onSet",l.hitch(this,"onSetItem"),!0)]))},destroy:function(){for(var b;b=this.connects.pop();)b.remove()},getRoot:function(b,e){this.root?b(this.root):this.store.fetch({query:this.query,onComplete:l.hitch(this,function(d){if(1!=d.length)throw Error("dijit.tree.TreeStoreModel: root query returned "+d.length+" items, but must return exactly one");this.root= +d[0];b(this.root)}),onError:e})},mayHaveChildren:function(b){return e.some(this.childrenAttrs,function(e){return this.store.hasAttribute(b,e)},this)},getChildren:function(b,h,d){var g=this.store;if(g.isItemLoaded(b)){for(var c=[],a=0;ab?b=c:(b=a,a=c);for(c=[];b!=a;)c.push(b),b=this.tree._getNext(b);c.push(a);this.setSelection(c)}else this.selection[a.id]&&b?this.removeTreeNode(a):b?this.addTreeNode(a,!0):(this.setSelection([a]),this.anchor=a)},getItem:function(a){return{data:this.selection[a],type:["treeNode"]}},forInSelectedItems:function(a, +b){b=b||h.global;for(var c in this.selection)a.call(b,this.getItem(c),c,this)}})})},"dojo/dnd/common":function(){define(["../sniff","../_base/kernel","../_base/lang","../dom"],function(e,k,h,l){var b=h.getObject("dojo.dnd",!0);b.getCopyKeyState=function(b){return b[e("mac")?"metaKey":"ctrlKey"]};b._uniqueId=0;b.getUniqueId=function(){var e;do e=k._scopeName+"Unique"+ ++b._uniqueId;while(l.byId(e));return e};b._empty={};b.isFormElement=function(b){b=b.target;3==b.nodeType&&(b=b.parentNode);return 0<= +" a button textarea input select option ".indexOf(" "+b.tagName.toLowerCase()+" ")};return b})},"dijit/tree/_dndContainer":function(){define("dojo/aspect dojo/_base/declare dojo/dom-class dojo/_base/lang dojo/on dojo/touch".split(" "),function(e,k,h,l,b,m){return k("dijit.tree._dndContainer",null,{constructor:function(d,g){this.tree=d;this.node=d.domNode;l.mixin(this,g);this.containerState="";h.add(this.node,"dojoDndContainer");this.events=[b(this.node,m.enter,l.hitch(this,"onOverEvent")),b(this.node, +m.leave,l.hitch(this,"onOutEvent")),e.after(this.tree,"_onNodeMouseEnter",l.hitch(this,"onMouseOver"),!0),e.after(this.tree,"_onNodeMouseLeave",l.hitch(this,"onMouseOut"),!0),b(this.node,"dragstart, selectstart",function(b){b.preventDefault()})]},destroy:function(){for(var b;b=this.events.pop();)b.remove();this.node=this.parent=null},onMouseOver:function(b){this.current=b},onMouseOut:function(){this.current=null},_changeState:function(b,g){var c="dojoDnd"+b,a=b.toLowerCase()+"State";h.replace(this.node, +c+g,c+this[a]);this[a]=g},_addItemClass:function(b,g){h.add(b,"dojoDndItem"+g)},_removeItemClass:function(b,g){h.remove(b,"dojoDndItem"+g)},onOverEvent:function(){this._changeState("Container","Over")},onOutEvent:function(){this._changeState("Container","")}})})},"dijit/Menu":function(){define("require dojo/_base/array dojo/_base/declare dojo/dom dojo/dom-attr dojo/dom-geometry dojo/dom-style dojo/keys dojo/_base/lang dojo/on dojo/sniff dojo/_base/window dojo/window ./popup ./DropDownMenu dojo/ready".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q,r){f("dijit-legacy-requires")&&r(0,function(){e(["dijit/MenuItem","dijit/PopupMenuItem","dijit/CheckedMenuItem","dijit/MenuSeparator"])});return h("dijit.Menu",q,{constructor:function(){this._bindings=[]},targetNodeIds:[],selector:"",contextMenuForWindow:!1,leftClickToOpen:!1,refocus:!0,postCreate:function(){this.contextMenuForWindow?this.bindDomNode(this.ownerDocumentBody):k.forEach(this.targetNodeIds,this.bindDomNode,this);this.inherited(arguments)},_iframeContentWindow:function(a){return p.get(this._iframeContentDocument(a))|| +this._iframeContentDocument(a).__parent__||a.name&&document.frames[a.name]||null},_iframeContentDocument:function(a){return a.contentDocument||a.contentWindow&&a.contentWindow.document||a.name&&document.frames[a.name]&&document.frames[a.name].document||null},bindDomNode:function(f){f=l.byId(f,this.ownerDocument);var d;if("iframe"==f.tagName.toLowerCase()){var e=f;d=this._iframeContentWindow(e);d=u.body(d.document)}else d=f==u.body(this.ownerDocument)?this.ownerDocument.documentElement:f;var h={node:f, +iframe:e};b.set(f,"_dijitMenu"+this.id,this._bindings.push(h));var n=c.hitch(this,function(b){var c=this.selector,f=c?function(b){return a.selector(c,b)}:function(a){return a},d=this;return[a(b,f(this.leftClickToOpen?"click":"contextmenu"),function(a){a.stopPropagation();a.preventDefault();(new Date).getTime()I&&(O=g.getComputedStyle(r),g.set(G,{overflowY:"scroll",height:I+"px",border:O.borderLeftWidth+" "+O.borderLeftStyle+" "+O.borderLeftColor}),r._originalStyle=r.style.cssText,r.style.border="none"); +b.set(G,{id:K,style:{zIndex:this._beginZIndex+h.length},"class":"dijitPopup "+(s.baseClass||s["class"]||"").split(" ")[0]+"Popup",dijitPopupParent:e.parent?e.parent.id:""});0==h.length&&F&&(this._firstAroundNode=F,this._firstAroundPosition=d.position(F,!0),this._aroundMoveListener=setTimeout(f.hitch(this,"_repositionAll"),50));c("config-bgIframe")&&!s.bgIframe&&(s.bgIframe=new n(G));K=s.orient?f.hitch(s,"orient"):null;m=F?p.around(G,F,m,k,K):p.at(G,e,"R"==m?["TR","BR","TL","BL"]:["TL","BL","TR","BR"], +e.padding,K);G.style.visibility="visible";r.style.visibility="visible";r=[];r.push(u(G,"keydown",f.hitch(this,function(b){if(b.keyCode==a.ESCAPE&&e.onCancel)b.stopPropagation(),b.preventDefault(),e.onCancel();else if(b.keyCode==a.TAB&&(b.stopPropagation(),b.preventDefault(),(b=this.getTopPopup())&&b.onCancel))b.onCancel()})));s.onCancel&&e.onCancel&&r.push(s.on("cancel",e.onCancel));r.push(s.on(s.onExecute?"execute":"change",f.hitch(this,function(){var a=this.getTopPopup();if(a&&a.onExecute)a.onExecute()}))); +h.push({widget:s,wrapper:G,parent:e.parent,onExecute:e.onExecute,onCancel:e.onCancel,onClose:e.onClose,handlers:r});if(s.onOpen)s.onOpen(m);return m},close:function(a){for(var b=this._stack;a&&e.some(b,function(b){return b.widget==a})||!a&&b.length;){var c=b.pop(),f=c.widget,d=c.onClose;f.bgIframe&&(f.bgIframe.destroy(),delete f.bgIframe);if(f.onClose)f.onClose();for(var g;g=c.handlers.pop();)g.remove();f&&f.domNode&&this.hide(f);d&&d()}0==b.length&&this._aroundMoveListener&&(clearTimeout(this._aroundMoveListener), +this._firstAroundNode=this._firstAroundPosition=this._aroundMoveListener=null)}});return r.popup=new h})},"dijit/place":function(){define("dojo/_base/array dojo/dom-geometry dojo/dom-style dojo/_base/kernel dojo/_base/window ./Viewport ./main".split(" "),function(e,k,h,l,b,m,d){function g(a,c,d,g){var n=m.getEffectiveBox(a.ownerDocument);(!a.parentNode||"body"!=String(a.parentNode.tagName).toLowerCase())&&b.body(a.ownerDocument).appendChild(a);var q=null;e.some(c,function(b){var c=b.corner,f=b.pos, +e=0,h={w:{L:n.l+n.w-f.x,R:f.x-n.l,M:n.w}[c.charAt(1)],h:{T:n.t+n.h-f.y,B:f.y-n.t,M:n.h}[c.charAt(0)]},l=a.style;l.left=l.right="auto";d&&(e=d(a,b.aroundCorner,c,h,g),e="undefined"==typeof e?0:e);var s=a.style,r=s.display,m=s.visibility;"none"==s.display&&(s.visibility="hidden",s.display="");l=k.position(a);s.display=r;s.visibility=m;r={L:f.x,R:f.x-l.w,M:Math.max(n.l,Math.min(n.l+n.w,f.x+(l.w>>1))-l.w)}[c.charAt(1)];m={T:f.y,B:f.y-l.h,M:Math.max(n.t,Math.min(n.t+n.h,f.y+(l.h>>1))-l.h)}[c.charAt(0)]; +f=Math.max(n.l,r);s=Math.max(n.t,m);r=Math.min(n.l+n.w,r+l.w);m=Math.min(n.t+n.h,m+l.h);r-=f;m-=s;e+=l.w-r+(l.h-m);if(null==q||e>1)}[a.charAt(1)],y:{T:C,B:C+K,M:C+(K>>1)}[a.charAt(0)]}})}var r;if("string"==typeof b||"offsetWidth"in b||"ownerSVGElement"in b){if(r=k.position(b,!0), +/^(above|below)/.test(c[0])){var s=k.getBorderExtents(b),m=b.firstChild?k.getBorderExtents(b.firstChild):{t:0,l:0,b:0,r:0},w=k.getBorderExtents(a),y=a.firstChild?k.getBorderExtents(a.firstChild):{t:0,l:0,b:0,r:0};r.y+=Math.min(s.t+m.t,w.t+y.t);r.h-=Math.min(s.t+m.t,w.t+y.t)+Math.min(s.b+m.b,w.b+y.b)}}else r=b;if(b.parentNode){s="absolute"==h.getComputedStyle(b).position;for(b=b.parentNode;b&&1==b.nodeType&&"BODY"!=b.nodeName;){m=k.position(b,!0);w=h.getComputedStyle(b);/relative|absolute/.test(w.position)&& +(s=!1);if(!s&&/hidden|auto|scroll/.test(w.overflow)){var y=Math.min(r.y+r.h,m.y+m.h),A=Math.min(r.x+r.w,m.x+m.w);r.x=Math.max(r.x,m.x);r.y=Math.max(r.y,m.y);r.h=y-r.y;r.w=A-r.x}"absolute"==w.position&&(s=!0);b=b.parentNode}}var B=r.x,C=r.y,F="w"in r?r.w:r.w=r.width,K="h"in r?r.h:(l.deprecated("place.around: dijit/place.__Rectangle: { x:"+B+", y:"+C+", height:"+r.height+", width:"+F+" } has been deprecated. Please use { x:"+B+", y:"+C+", h:"+r.height+", w:"+F+" }","","2.0"),r.h=r.height),G=[];e.forEach(c, +function(a){var b=d;switch(a){case "above-centered":q("TM","BM");break;case "below-centered":q("BM","TM");break;case "after-centered":b=!b;case "before-centered":q(b?"ML":"MR",b?"MR":"ML");break;case "after":b=!b;case "before":q(b?"TL":"TR",b?"TR":"TL");q(b?"BL":"BR",b?"BR":"BL");break;case "below-alt":b=!b;case "below":q(b?"BL":"BR",b?"TL":"TR");q(b?"BR":"BL",b?"TR":"TL");break;case "above-alt":b=!b;case "above":q(b?"TL":"TR",b?"BL":"BR");q(b?"TR":"TL",b?"BR":"BL");break;default:q(a.aroundCorner, +a.corner)}});a=g(a,G,n,{w:F,h:K});a.aroundNodePos=r;return a}}})},"dijit/BackgroundIframe":function(){define("require ./main dojo/_base/config dojo/dom-construct dojo/dom-style dojo/_base/lang dojo/on dojo/sniff".split(" "),function(e,k,h,l,b,m,d,g){g.add("config-bgIframe",g("ie")&&!/IEMobile\/10\.0/.test(navigator.userAgent)||g("trident")&&/Windows NT 6.[01]/.test(navigator.userAgent));var c=new function(){var a=[];this.pop=function(){var c;a.length?(c=a.pop(),c.style.display=""):(9>g("ie")?(c="\x3ciframe src\x3d'"+ +(h.dojoBlankHtmlUrl||e.toUrl("dojo/resources/blank.html")||'javascript:""')+"' role\x3d'presentation' style\x3d'position: absolute; left: 0px; top: 0px;z-index: -1; filter:Alpha(Opacity\x3d\"0\");'\x3e",c=document.createElement(c)):(c=l.create("iframe"),c.src='javascript:""',c.className="dijitBackgroundIframe",c.setAttribute("role","presentation"),b.set(c,"opacity",0.1)),c.tabIndex=-1);return c};this.push=function(b){b.style.display="none";a.push(b)}};k.BackgroundIframe=function(a){if(!a.id)throw Error("no id"); +if(g("config-bgIframe")){var f=this.iframe=c.pop();a.appendChild(f);7>g("ie")||g("quirks")?(this.resize(a),this._conn=d(a,"resize",m.hitch(this,"resize",a))):b.set(f,{width:"100%",height:"100%"})}};m.extend(k.BackgroundIframe,{resize:function(a){this.iframe&&b.set(this.iframe,{width:a.offsetWidth+"px",height:a.offsetHeight+"px"})},destroy:function(){this._conn&&(this._conn.remove(),this._conn=null);this.iframe&&(this.iframe.parentNode.removeChild(this.iframe),c.push(this.iframe),delete this.iframe)}}); +return k.BackgroundIframe})},"dijit/DropDownMenu":function(){define(["dojo/_base/declare","dojo/keys","dojo/text!./templates/Menu.html","./_MenuBase"],function(e,k,h,l){return e("dijit.DropDownMenu",l,{templateString:h,baseClass:"dijitMenu",_onUpArrow:function(){this.focusPrev()},_onDownArrow:function(){this.focusNext()},_onRightArrow:function(b){this._moveToPopup(b);b.stopPropagation();b.preventDefault()},_onLeftArrow:function(b){if(this.parentMenu)if(this.parentMenu._isMenuBar)this.parentMenu.focusPrev(); +else this.onCancel(!1);else b.stopPropagation(),b.preventDefault()}})})},"dijit/_MenuBase":function(){define("dojo/_base/array dojo/_base/declare dojo/dom dojo/dom-attr dojo/dom-class dojo/_base/lang dojo/mouse dojo/on dojo/window ./a11yclick ./registry ./_Widget ./_CssStateMixin ./_KeyNavContainer ./_TemplatedMixin".split(" "),function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q){return k("dijit._MenuBase",[u,q,n,p],{selected:null,_setSelectedAttr:function(a){this.selected!=a&&(this.selected&&(this.selected._setSelected(!1), +this._onChildDeselect(this.selected)),a&&a._setSelected(!0),this._set("selected",a))},activated:!1,_setActivatedAttr:function(a){b.toggle(this.domNode,"dijitMenuActive",a);b.toggle(this.domNode,"dijitMenuPassive",!a);this._set("activated",a)},parentMenu:null,popupDelay:500,passivePopupDelay:Infinity,autoFocus:!1,childSelector:function(a){var b=f.byNode(a);return a.parentNode==this.containerNode&&b&&b.focus},postCreate:function(){var b=this,c="string"==typeof this.childSelector?this.childSelector: +m.hitch(this,"childSelector");this.own(g(this.containerNode,g.selector(c,d.enter),function(){b.onItemHover(f.byNode(this))}),g(this.containerNode,g.selector(c,d.leave),function(){b.onItemUnhover(f.byNode(this))}),g(this.containerNode,g.selector(c,a),function(a){b.onItemClick(f.byNode(this),a);a.stopPropagation()}),g(this.containerNode,g.selector(c,"focusin"),function(){b._onItemFocus(f.byNode(this))}));this.inherited(arguments)},onKeyboardSearch:function(a,b,c,f){this.inherited(arguments);if(a&&(-1== +f||a.popup&&1==f))this.onItemClick(a,b)},_keyboardSearchCompare:function(a,b){return a.shortcutKey?b==a.shortcutKey.toLowerCase()?-1:0:this.inherited(arguments)?1:0},onExecute:function(){},onCancel:function(){},_moveToPopup:function(a){if(this.focusedChild&&this.focusedChild.popup&&!this.focusedChild.disabled)this.onItemClick(this.focusedChild,a);else(a=this._getTopMenu())&&a._isMenuBar&&a.focusNext()},_onPopupHover:function(){this.set("selected",this.currentPopupItem);this._stopPendingCloseTimer()}, +onItemHover:function(a){this.activated?(this.set("selected",a),a.popup&&(!a.disabled&&!this.hover_timer)&&(this.hover_timer=this.defer(function(){this._openItemPopup(a)},this.popupDelay))):Infinity>this.passivePopupDelay&&(this.passive_hover_timer&&this.passive_hover_timer.remove(),this.passive_hover_timer=this.defer(function(){this.onItemClick(a,{type:"click"})},this.passivePopupDelay));this._hoveredChild=a;a._set("hovering",!0)},_onChildDeselect:function(a){this._stopPopupTimer();this.currentPopupItem== +a&&(this._stopPendingCloseTimer(),this._pendingClose_timer=this.defer(function(){this.currentPopupItem=this._pendingClose_timer=null;a._closePopup()},this.popupDelay))},onItemUnhover:function(a){this._hoveredChild==a&&(this._hoveredChild=null);this.passive_hover_timer&&(this.passive_hover_timer.remove(),this.passive_hover_timer=null);a._set("hovering",!1)},_stopPopupTimer:function(){this.hover_timer&&(this.hover_timer=this.hover_timer.remove())},_stopPendingCloseTimer:function(){this._pendingClose_timer&& +(this._pendingClose_timer=this._pendingClose_timer.remove())},_getTopMenu:function(){for(var a=this;a.parentMenu;a=a.parentMenu);return a},onItemClick:function(a,b){this.passive_hover_timer&&this.passive_hover_timer.remove();this.focusChild(a);if(a.disabled)return!1;if(a.popup){this.set("selected",a);this.set("activated",!0);var c=/^key/.test(b._origType||b.type)||0==b.clientX&&0==b.clientY;this._openItemPopup(a,c)}else this.onExecute(),a._onClick?a._onClick(b):a.onClick(b)},_openItemPopup:function(a, +b){if(a!=this.currentPopupItem){this.currentPopupItem&&(this._stopPendingCloseTimer(),this.currentPopupItem._closePopup());this._stopPopupTimer();var c=a.popup;c.parentMenu=this;this.own(this._mouseoverHandle=g.once(c.domNode,"mouseover",m.hitch(this,"_onPopupHover")));var f=this;a._openPopup({parent:this,orient:this._orient||["after","before"],onCancel:function(){b&&f.focusChild(a);f._cleanUp()},onExecute:m.hitch(this,"_cleanUp",!0),onClose:function(){f._mouseoverHandle&&(f._mouseoverHandle.remove(), +delete f._mouseoverHandle)}},b);this.currentPopupItem=a}},onOpen:function(){this.isShowingNow=!0;this.set("activated",!0)},onClose:function(){this.set("activated",!1);this.set("selected",null);this.isShowingNow=!1;this.parentMenu=null},_closeChild:function(){this._stopPopupTimer();this.currentPopupItem&&(this.focused&&(l.set(this.selected.focusNode,"tabIndex",this.tabIndex),this.selected.focusNode.focus()),this.currentPopupItem._closePopup(),this.currentPopupItem=null)},_onItemFocus:function(a){if(this._hoveredChild&& +this._hoveredChild!=a)this.onItemUnhover(this._hoveredChild);this.set("selected",a)},_onBlur:function(){this._cleanUp(!0);this.inherited(arguments)},_cleanUp:function(a){this._closeChild();"undefined"==typeof this.isShowingNow&&this.set("activated",!1);a&&this.set("selected",null)}})})},"dijit/_KeyNavContainer":function(){define("dojo/_base/array dojo/_base/declare dojo/dom-attr dojo/_base/kernel dojo/keys dojo/_base/lang ./registry ./_Container ./_FocusMixin ./_KeyNavMixin".split(" "),function(e, +k,h,l,b,m,d,g,c,a){return k("dijit._KeyNavContainer",[c,a,g],{connectKeyNavHandlers:function(a,c){var d=this._keyNavCodes={},g=m.hitch(this,"focusPrev"),h=m.hitch(this,"focusNext");e.forEach(a,function(a){d[a]=g});e.forEach(c,function(a){d[a]=h});d[b.HOME]=m.hitch(this,"focusFirstChild");d[b.END]=m.hitch(this,"focusLastChild")},startupKeyNavChildren:function(){l.deprecated("startupKeyNavChildren() call no longer needed","","2.0")},startup:function(){this.inherited(arguments);e.forEach(this.getChildren(), +m.hitch(this,"_startupChild"))},addChild:function(a,b){this.inherited(arguments);this._startupChild(a)},_startupChild:function(a){a.set("tabIndex","-1")},_getFirst:function(){var a=this.getChildren();return a.length?a[0]:null},_getLast:function(){var a=this.getChildren();return a.length?a[a.length-1]:null},focusNext:function(){this.focusChild(this._getNextFocusableChild(this.focusedChild,1))},focusPrev:function(){this.focusChild(this._getNextFocusableChild(this.focusedChild,-1),!0)},childSelector:function(a){return(a= +d.byNode(a))&&a.getParent()==this}})})},"dijit/MenuItem":function(){define("dojo/_base/declare dojo/dom dojo/dom-attr dojo/dom-class dojo/_base/kernel dojo/sniff dojo/_base/lang ./_Widget ./_TemplatedMixin ./_Contained ./_CssStateMixin dojo/text!./templates/MenuItem.html".split(" "),function(e,k,h,l,b,m,d,g,c,a,f,u){return e("dijit.MenuItem",[g,c,a,f],{templateString:u,baseClass:"dijitMenuItem",label:"",_setLabelAttr:function(a){this._set("label",a);var b="",c,f=a;"object"===typeof f&&(f=f.label|| +f.value);"string"===typeof f&&(c=f.search(/{\S}/),0<=c?(b=f.charAt(c+1),a=f.substr(0,c),f=f.substr(c+3),c=a+b+f,a=a+'\x3cspan class\x3d"dijitMenuItemShortcutKey"\x3e'+b+"\x3c/span\x3e"+f):c=f,this.domNode.setAttribute("aria-label",c+" "+this.accelKey));this.containerNode.innerHTML=a;this._set("shortcutKey",b)},iconClass:"dijitNoIcon",_setIconClassAttr:{node:"iconNode",type:"class"},accelKey:"",disabled:!1,_fillContent:function(a){a&&!("label"in this.params)&&this._set("label",a.innerHTML)},buildRendering:function(){this.inherited(arguments); +h.set(this.containerNode,"id",this.id+"_text");this.accelKeyNode&&h.set(this.accelKeyNode,"id",this.id+"_accel");k.setSelectable(this.domNode,!1)},onClick:function(){},focus:function(){try{8==m("ie")&&this.containerNode.focus(),this.focusNode.focus()}catch(a){}},_setSelected:function(a){l.toggle(this.domNode,"dijitMenuItemSelected",a)},setLabel:function(a){b.deprecated("dijit.MenuItem.setLabel() is deprecated. Use set('label', ...) instead.","","2.0");this.set("label",a)},setDisabled:function(a){b.deprecated("dijit.Menu.setDisabled() is deprecated. Use set('disabled', bool) instead.", +"","2.0");this.set("disabled",a)},_setDisabledAttr:function(a){this.focusNode.setAttribute("aria-disabled",a?"true":"false");this._set("disabled",a)},_setAccelKeyAttr:function(a){this.accelKeyNode&&(this.accelKeyNode.style.display=a?"":"none",this.accelKeyNode.innerHTML=a,h.set(this.containerNode,"colSpan",a?"1":"2"));this._set("accelKey",a)}})})},"webview/widgets/ModelViewer":function(){define("dojo/_base/declare dojo/_base/lang dojo/dom-class dojo/dom-style dojo/topic dijit/layout/BorderContainer dijit/layout/TabContainer ./ViewAllTab ./DiagramTab ../palette/Palette ../palette/ModelBrowserButton ../palette/ExplorerBarButton ../palette/PaletteSeparator ../palette/PaletteSpacer ../palette/FitToViewButton ../palette/MarqueeZoomButton ../palette/OptionalViewButton ../search/SearchResultsPane ./ExplorerBar".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q,r,s,x,w){var y=e([d],{selectChild:function(a,b){var c=this.modelViewer,f=c.explorerBar,d=this.selectedChildWidget;if(d&&d!==a&&d.onPreHide)d.onPreHide();this.inherited(arguments);this._started&&(c.get("showExplorerBar")?(a.addChild(f),f.update(a.diagram)):a.removeChild(f),c.set("showPaletteNavButtons",a.showPaletteNavButtons),"SystemTab"===a.role&&(c.selectedDiagramTab=a,c.selectedDiagram=a.diagram),c.selectedTab=a,c.resize(),(!b||!1!==b.doFocus)&&c.focus())}, +addChild:function(){this.inherited(arguments);this._started&&this._updateTabCloseButtons()},removeChild:function(a){this.inherited(arguments);this._started&&(this.selectedChildWidget===a&&a.removeChild(this.modelViewer.explorerBar),this._updateTabCloseButtons())},_hideChild:function(a){this.inherited(arguments);this._started&&a.removeChild(this.modelViewer.explorerBar)},_updateTabCloseButtons:function(){var a,b,c,f,d;d=0;a=this.getChildren();f=a.length;for(c=0;cb?1:aa("ie")||a("trident")&&a("quirks")||a("webkit")?this.scrollNode.scrollLeft:b.get(this.containerNode,"width")-b.get(this.scrollNode,"width")+(a("trident")||a("edge")?-1:1)*this.scrollNode.scrollLeft},_convertToScrollLeft:function(c){if(this.isLeftToRight()||8>a("ie")||a("trident")&&a("quirks")||a("webkit"))return c;var f=b.get(this.containerNode,"width")-b.get(this.scrollNode,"width");return(a("trident")|| +a("edge")?-1:1)*(c-f)},onSelectChild:function(a,c){var f=this.pane2button(a.id);if(f){var d=f.domNode;if(d!=this._selectedTab&&(this._selectedTab=d,this._postResize)){var g=this._getScroll();g>d.offsetLeft||g+b.get(this.scrollNode,"width")c)return{min:this.isLeftToRight()?0:a[a.length-1].domNode.offsetLeft,max:this.isLeftToRight()?a[a.length-1].domNode.offsetLeft+a[a.length-1].domNode.offsetWidth-c:f};a=this.isLeftToRight()?0:f;return{min:a,max:a}},_getScrollForSelectedTab:function(){var a=this._selectedTab,c=b.get(this.scrollNode,"width"),f=this._getScrollBounds(),a=a.offsetLeft+b.get(a,"width")/2-c/2;return a=Math.min(Math.max(a,f.min),f.max)},createSmoothScroll:function(a){if(0=b.max)}});p=k("dijit.layout._ScrollingTabControllerButtonMixin", +null,{baseClass:"dijitTab tabStripButton",templateString:p,tabIndex:"",isFocusable:function(){return!1}});k("dijit.layout._ScrollingTabControllerButton",[w,p]);k("dijit.layout._ScrollingTabControllerMenuButton",[w,y,p],{containerId:"",tabIndex:"-1",isLoaded:function(){return!1},loadDropDown:function(a){this.dropDown=new s({id:this.containerId+"_menu",ownerDocument:this.ownerDocument,dir:this.dir,lang:this.lang,textDir:this.textDir});var b=f.byId(this.containerId);e.forEach(b.getChildren(),function(a){var c= +new x({id:a.id+"_stcMi",label:a.title,iconClass:a.iconClass,disabled:a.disabled,ownerDocument:this.ownerDocument,dir:a.dir,lang:a.lang,textDir:a.textDir||b.textDir,onClick:function(){b.selectChild(a)}});this.dropDown.addChild(c)},this);a()},closeDropDown:function(a){this.inherited(arguments);this.dropDown&&(this._popupStateNode.removeAttribute("aria-owns"),this.dropDown.destroyRecursive(),delete this.dropDown)}});return u})},"dijit/_WidgetsInTemplateMixin":function(){define(["dojo/_base/array","dojo/aspect", +"dojo/_base/declare","dojo/_base/lang","dojo/parser"],function(e,k,h,l,b){return h("dijit._WidgetsInTemplateMixin",null,{_earlyTemplatedStartup:!1,contextRequire:null,_beforeFillContent:function(){if(/dojoType|data-dojo-type/i.test(this.domNode.innerHTML)){var e=this.domNode;this.containerNode&&!this.searchContainerNode&&(this.containerNode.stopParser=!0);b.parse(e,{noStart:!this._earlyTemplatedStartup,template:!0,inherited:{dir:this.dir,lang:this.lang,textDir:this.textDir},propsThis:this,contextRequire:this.contextRequire, +scope:"dojo"}).then(l.hitch(this,function(b){this._startupWidgets=b;for(var g=0;g.*$/,""),A=l.map(r.split(/\s+/),function(a){var c=a.toLowerCase();return{name:a,value:"LI"==b.nodeName&&"value"==a||"enctype"==c?b.getAttribute(c):b.getAttributeNode(c).value}}));var Q=e.scope||k._scopeName; +r="data-"+Q+"-";var L={};"dojo"!==Q&&(L[r+"props"]="data-dojo-props",L[r+"type"]="data-dojo-type",L[r+"mixins"]="data-dojo-mixins",L[Q+"type"]="dojotype",L[r+"id"]="data-dojo-id");for(var J=0,H,Q=[],V,W;H=A[J++];){var R=H.name,Z=R.toLowerCase();H=H.value;switch(L[Z]||Z){case "data-dojo-type":case "dojotype":case "data-dojo-mixins":break;case "data-dojo-props":W=H;break;case "data-dojo-id":case "jsid":V=H;break;case "data-dojo-attach-point":case "dojoattachpoint":w.dojoAttachPoint=H;break;case "data-dojo-attach-event":case "dojoattachevent":w.dojoAttachEvent= +H;break;case "class":w["class"]=b.className;break;case "style":w.style=b.style&&b.style.cssText;break;default:if(R in y||(R=x(a)[Z]||R),R in y)switch(typeof y[R]){case "string":w[R]=H;break;case "number":w[R]=H.length?Number(H):NaN;break;case "boolean":w[R]="false"!=H.toLowerCase();break;case "function":""===H||-1!=H.search(/[^\w\.]+/i)?w[R]=new Function(H):w[R]=h.getObject(H,!1)||new Function(H);Q.push(R);break;default:Z=y[R],w[R]=Z&&"length"in Z?H?H.split(/\s*,\s*/):[]:Z instanceof Date?""==H?new Date(""): +"now"==H?new Date:f.fromISOString(H):Z instanceof g?k.baseUrl+H:s(H)}else w[R]=H}}for(A=0;Am[0]&&d.setFullYear(m[0]||1970);var g=0,c=m[7]&&m[7].charAt(0);"Z"!=c&&(g=60*(m[8]||0)+(Number(m[9])||0),"-"!=c&&(g*=-1));c&&(g-=d.getTimezoneOffset());g&&d.setTime(d.getTime()+6E4*g)}return d};h.toISOString=function(e,b){var h=function(a){return 10>a?"0"+a:a};b=b||{};var d=[],g=b.zulu?"getUTC":"get",c="";"time"!=b.selector&&(c=e[g+"FullYear"](),c=["0000".substr((c+"").length)+c,h(e[g+"Month"]()+ +1),h(e[g+"Date"]())].join("-"));d.push(c);if("date"!=b.selector){c=[h(e[g+"Hours"]()),h(e[g+"Minutes"]()),h(e[g+"Seconds"]())].join(":");g=e[g+"Milliseconds"]();b.milliseconds&&(c+="."+(100>g?"0":"")+h(g));if(b.zulu)c+="Z";else if("time"!=b.selector)var g=e.getTimezoneOffset(),a=Math.abs(g),c=c+((0=d.x&&a.pageX<=d.x+d.w)||!(a.pageY>=d.y&&a.pageY<=d.y+d.h)){for(d=a.target;d&&!f;)b.contains(d,"dijitPopup")?f=!0:d=d.parentNode;if(f){d=a.target;if(c.onItemClick){for(var g;d&&!(g=p.byNode(d));)d=d.parentNode;if(g&&g.onClick&&g.getParent)g.getParent().onItemClick(g,a)}return}}}if(this._opened){if(c.focus&&(!1!==c.autoFocus||"mouseup"==a.type&&!this.hovering))this._focusDropDownTimer= +this.defer(function(){c.focus();delete this._focusDropDownTimer})}else this.focus&&this.defer("focus")},_onDropDownClick:function(a){this._stopClickEvents&&(a.stopPropagation(),a.preventDefault())},buildRendering:function(){this.inherited(arguments);this._buttonNode=this._buttonNode||this.focusNode||this.domNode;this._popupStateNode=this._popupStateNode||this.focusNode||this._buttonNode;var a={after:this.isLeftToRight()?"Right":"Left",before:this.isLeftToRight()?"Left":"Right",above:"Up",below:"Down", +left:"Left",right:"Right"}[this.dropDownPosition[0]]||this.dropDownPosition[0]||"Down";b.add(this._arrowWrapperNode||this._buttonNode,"dijit"+a+"ArrowButton")},postCreate:function(){this.inherited(arguments);var b=this.focusNode||this.domNode;this.own(f(this._buttonNode,u.press,a.hitch(this,"_onDropDownMouseDown")),f(this._buttonNode,"click",a.hitch(this,"_onDropDownClick")),f(b,"keydown",a.hitch(this,"_onKey")),f(b,"keyup",a.hitch(this,"_onKeyUp")))},destroy:function(){this._opened&&this.closeDropDown(!0); +this.dropDown&&(this.dropDown._destroyed||this.dropDown.destroyRecursive(),delete this.dropDown);this.inherited(arguments)},_onKey:function(a){if(!this.disabled&&!this.readOnly){var b=this.dropDown,f=a.target;if(b&&(this._opened&&b.handleKey)&&!1===b.handleKey(a))a.stopPropagation(),a.preventDefault();else if(b&&this._opened&&a.keyCode==c.ESCAPE)this.closeDropDown(),a.stopPropagation(),a.preventDefault();else if(!this._opened&&(a.keyCode==c.DOWN_ARROW||(a.keyCode==c.ENTER||a.keyCode==c.SPACE&&(!this._searchTimer|| +a.ctrlKey||a.altKey||a.metaKey))&&("input"!==(f.tagName||"").toLowerCase()||f.type&&"text"!==f.type.toLowerCase())))this._toggleOnKeyUp=!0,a.stopPropagation(),a.preventDefault()}},_onKeyUp:function(){if(this._toggleOnKeyUp){delete this._toggleOnKeyUp;this.toggleDropDown();var b=this.dropDown;b&&b.focus&&this.defer(a.hitch(b,"focus"),1)}},_onBlur:function(){this.closeDropDown(!1);this.inherited(arguments)},isLoaded:function(){return!0},loadDropDown:function(a){a()},loadAndOpenDropDown:function(){var b= +new k,c=a.hitch(this,function(){this.openDropDown();b.resolve(this.dropDown)});this.isLoaded()?c():this.loadDropDown(c);return b},toggleDropDown:function(){!this.disabled&&!this.readOnly&&(this._opened?this.closeDropDown(!0):this.loadAndOpenDropDown())},openDropDown:function(){var c=this.dropDown,f=c.domNode,d=this._aroundNode||this.domNode,g=this,e=q.open({parent:this,popup:c,around:d,orient:this.dropDownPosition,maxHeight:this.maxHeight,onExecute:function(){g.closeDropDown(!0)},onCancel:function(){g.closeDropDown(!0)}, +onClose:function(){l.set(g._popupStateNode,"popupActive",!1);b.remove(g._popupStateNode,"dijitHasDropDownOpen");g._set("_opened",!1)}});if(this.forceWidth||this.autoWidth&&d.offsetWidth>c._popupWrapper.offsetWidth){var d=d.offsetWidth-c._popupWrapper.offsetWidth,h={w:c.domNode.offsetWidth+d};this._origStyle=f.style.cssText;a.isFunction(c.resize)?c.resize(h):m.setMarginBox(f,h);"R"==e.corner[1]&&(c._popupWrapper.style.left=c._popupWrapper.style.left.replace("px","")-d+"px")}l.set(this._popupStateNode, +"popupActive","true");b.add(this._popupStateNode,"dijitHasDropDownOpen");this._set("_opened",!0);this._popupStateNode.setAttribute("aria-expanded","true");this._popupStateNode.setAttribute("aria-owns",c.id);"presentation"!==f.getAttribute("role")&&!f.getAttribute("aria-labelledby")&&f.setAttribute("aria-labelledby",this.id);return e},closeDropDown:function(a){this._focusDropDownTimer&&(this._focusDropDownTimer.remove(),delete this._focusDropDownTimer);this._opened&&(this._popupStateNode.setAttribute("aria-expanded", +"false"),a&&this.focus&&this.focus(),q.close(this.dropDown),this._opened=!1);this._origStyle&&(this.dropDown.domNode.style.cssText=this._origStyle,delete this._origStyle)}})})},"webview/widgets/ViewAllTab":function(){define("dojo/_base/declare dojo/_base/lang dojo/promise/all dojo/store/Memory dojo/window dojo/dom-construct dojo/dom-class dojo/on dojo/mouse dojo/topic dojo/Deferred dijit/layout/BorderContainer dijit/layout/ContentPane dijit/Menu dijit/MenuItem dijit/popup dojo/i18n!../resources/slreportgen_webview/nls/modelviewer".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q,r,s){return e([u],{title:s.ViewAll,postMixInProperties:function(){this.gutters=!1;this.inherited(arguments)},postCreate:function(){var b=this.app,c=b.id,f=new p({region:"center",style:"overflow: auto;"}),g=new n({targetNodeIds:[f.containerNode],"class":"wvViewAllTab",selector:".wvViewAllTabImg",onMouseEnter:function(){var f=parseFloat(g.currentTarget.getAttribute("data-hid"));f&&a.publish(c+"/hover",b.getDiagram(f))},onMouseLeave:function(){a.publish(c+"/unhover")}}); +d.add(this.domNode,"wvViewAllTab");g.addChild(new q({label:s.Open,onClick:function(){var a=parseFloat(g.currentTarget.getAttribute("data-hid"));a&&b.open(b.getDiagram(a),{tab:"reuse"}).then(function(){b.modelViewer.focus()})}}));g.addChild(new q({label:s.OpenInNewTab,onClick:function(){var a=parseFloat(g.currentTarget.getAttribute("data-hid"));a&&b.open(b.getDiagram(a),{tab:"new"}).then(function(){b.modelViewer.focus()})}}));this.own(f,g);this.addChild(f);this.thumbnailsPane=f;this.contextMenu=g; +this.imgStore=new l;this._unloadedSectionStore=new l({idProperty:"hid",data:this.app.data.diagramStore.sectionStore.query().reverse()});this.inherited(arguments)},startup:function(){var a=this.thumbnailsPane.domNode,b=this;this.own(g(this.thumbnailsPane.domNode,"scroll",function(c){c=(a.scrollTop+a.clientHeight)/a.scrollHeight;0.75b._lastScroll-c&&b._addNextSection();b._lastScroll=c}))},destroy:function(){this._hoverHandle&&this._hoverHandle.remove();this._unhoverHandle&&this._unhoverHandle.remove(); +this.inherited(arguments)},onShow:function(){var b=this.app,c=b.id;this.update(b.modelViewer.selectedDiagram);this._hoverHandle=a.subscribe(c+"/hover",k.hitch(this,"_hover"));this._unhoverHandle=a.subscribe(c+"/unhover",k.hitch(this,"_unhover"));this._fillThumbnailsPane()},onHide:function(){this._hoverHandle&&this._hoverHandle.remove();this._unhoverHandle&&this._unhoverHandle.remove()},update:function(a){if(a&&(this.diagram=a,this._unhover(),this._selectedImgNode&&(d.remove(this._selectedImgNode, +"wvViewAllTabImgSelected"),this._selectedImgNode=null),a=this._getImgNode(a)))this._selectedImgNode=a,d.add(a,"wvViewAllTabImgSelected"),b.scrollIntoView(a)},_fillThumbnailsPane:function(){var a=this,b=this.thumbnailsPane.domNode,c,f,d,g;if(0b.scrollHeight-b.clientHeight&&(a._addNextSection(),a._fillThumbnailsPane())})}},_addNextSection:function(){var a= +this._unloadedSectionStore.data;(a=a[a.length-1])&&this._addSection(a)},_addSection:function(a){var b=this.app,c=a.descendants,f,d,g;if(this._unloadedSectionStore.get(a.hid)){(g=b.getDiagram(a.hid))&&g.thumbnail&&this._createImgNode(g);d=a.descendants.length;for(f=0;f]+>|]*>[\s\S]*?<\/title>)/ig,"")},_emptyNode:m.empty,_setNodeContent:function(a,b){m.empty(a);if(b)if("number"==typeof b&&(b=b.toString()),"string"==typeof b&&(b=m.toDom(b,a.ownerDocument)),!b.nodeType&&k.isArrayLike(b))for(var c=b.length,d=0;d]*>\s*([\s\S]+)\s*<\/body>/im);b&&(a=b[1])}this.empty();this.content=a;return this.node},onEnd:function(){this.parseContent&&this._parse();return this.node},tearDown:function(){delete this.parseResults;delete this.parseDeferred;delete this.node;delete this.content},onContentError:function(a){return"Error occurred setting content: "+a},onExecError:function(a){return"Error occurred executing scripts: "+ +a},_mixin:function(a){var b={},c;for(c in a)c in b||(this[c]=a[c])},_parse:function(){var a=this.node;try{var b={};h.forEach(["dir","lang","textDir"],function(a){this[a]&&(b[a]=this[a])},this);var c=this;this.parseDeferred=d.parse({rootNode:a,noStart:!this.startup,inherited:b,scope:this.parserScope}).then(function(a){return c.parseResults=a},function(a){c._onError("Content",a,"Error parsing in _ContentSetter#"+this.id)})}catch(g){this._onError("Content",g,"Error parsing in _ContentSetter#"+this.id)}}, +_onError:function(a,b,d){a=this["on"+a+"Error"].call(this,b);d?console.error(d,b):a&&c._setNodeContent(this.node,a,!0)}}),set:function(a,b,d){void 0==b&&(console.warn("dojo.html.set: no cont argument provided, using empty string"),b="");"number"==typeof b&&(b=b.toString());return d?(new c._ContentSetter(k.mixin(d,{content:b,node:a}))).set():c._setNodeContent(a,b,!0)}};k.setObject("dojo.html",c);return c})},"webview/widgets/DiagramTab":function(){define("dojo/_base/declare dojo/dom-class dojo/topic dijit/layout/BorderContainer dijit/layout/ContentPane ./ModelGraphicsPane ./EmptyModelGraphicsPane ./LightBox".split(" "), +function(e,k,h,l,b,m,d,g){return e([l],{postMixInProperties:function(){this.gutters=!1;this.inherited(arguments)},postCreate:function(){var c=this,a=this.app,d=new g({id:this.id+"_lightbox",app:a}),e=new b({region:"center","class":"wvDiagramTabViewPane"});e.addChild(d);this.addChild(e);this.viewPane=e;this.lightBox=d;k.add(this.domNode,"wvDiagramTab");this.own(e,d,h.subscribe(a.id+"/postOpen",function(a){c.diagram===a&&(c._opening=!1)}));this.inherited(arguments)},onShow:function(){this.update(this.diagram)}, +onPreHide:function(){var b=this.modelGraphicsPane;b&&(this.diagram.state=b.getState(),this.viewPane.removeChild(b),b.destroy(),this.modelGraphicsPane=null,this.lightBox.close())},update:function(b,a){var f=this.app,g=this.viewPane,e=this.emptyPane,n=b||f.modelViewer.selectedDiagram,l=this.modelGraphicsPane;n&&!this._opening&&(this.lightBox.close(a),!l||this.diagram!==n?(this._opening=!0,this.diagram&&l&&(this.diagram.state=l.getState()),this.diagram=n,this.set("title",n.name),e&&(g.removeChild(e), +e.destroy(),this.emptyPane=null),l&&(g.removeChild(l),l.destroy(),this.modelGraphicsPane=null),n.svg?(l=new m({app:f,diagram:n}),g.addChild(l),this.modelGraphicsPane=l):(e=new d({app:f,diagram:n}),g.addChild(e),this.emptyPane=e),this.resize()):h.publish(f.id+"/postOpen",n))}})})},"webview/widgets/ModelGraphicsPane":function(){define("dojo/_base/declare dojo/_base/lang dojo/_base/array dojo/topic dijit/_WidgetBase dijit/_TemplatedMixin ../base/Rect ../mg/Canvas ../tools/PanTool ../tools/ScrollWheelTool ../tools/FitToViewTool ../tools/KeyboardZoomTool ../tools/KeyboardESCBackTool ../tools/TextSelectionTool ../tools/DelegateToHandlerTool dojo/text!./templates/ModelGraphicsPane.html".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q,r){function s(a){return 0a?-1:0}return e([b,m],{templateString:r,_selectionStyle:"fill: none; outer-stroke: #c6defe; outer-stroke-linecap: butt; outer-stroke-opacity: 0.80; outer-stroke-width: 4; outer-stroke-linejoin: miter; outer-stroke-dasharray: none; outer-stroke-miterlimit: 4",startup:function(){var b=this.app,d=b.id,e=this.diagram,m=new g(e.svg,this.id),r=this;m.focusNode=this.domNode;this.canvas=m;this.own(m,l.subscribe(d+"/cancel",k.hitch(this, +"cancel")),l.subscribe(d+"/select",k.hitch(this,"_select")));m=m.load(this.CanvasNode,"100%","100%").then(function(d){var g=d.sceneServer.svgDocument,l=d.toolStack,k=d.styler,m=k.createStylingLayer({id:"selection",zOrder:90,displayMode:k.COMBINE_DISPLAY}),s=k.createStylingLayer({id:"default-view"});l.addTool(new q({app:b,diagram:e}));l.addTool(new p({app:b}));l.addTool(new u);l.addTool(new f);l.addTool(new c);l.addTool(new a);l.addTool(new n);r.defaultViewStylingLayer=s;r.selectionStylingLayer=m; +h.forEach(b.data.optViewsStore.query(),function(a){k.createStylingLayer({id:a.id,zOrder:3})});k.updateMaskBackground();m.set("show",!0);g=g.createElementNS("http://www.w3.org/1999/xhtml","link");g.setAttribute("type","text/css");g.setAttribute("rel","stylesheet");l=document.styleSheets;m=l.length;for(s=0;s=e.left()&&e.right()>=this.left()&&this.bottom()>=e.top()&&e.bottom()>=this.top()},extend:function(h,l){var b=new e(h,l),k=Math.max(this.right(),b.x),d=Math.max(this.bottom(),b.y);this.x=Math.min(this.x,b.x);this.y=Math.min(this.y,b.y);this.width=k-this.x; +this.height=d-this.y;return this},expand:function(e){this.x-=e;this.y-=e;this.width+=2*e;this.height+=2*e;return this}};return k})},"webview/base/Point":function(){define([],function(){var e=function(k,h){var l;this.y=this.x=0;"number"===typeof k&&"number"===typeof h?(this.x=k,this.y=h):"string"===typeof k?(l=k.split(" "),2!==l.length&&(l=k.split(",")),2===l.length&&(this.x=parseFloat(l[0]),this.y=parseFloat(l[1]))):k instanceof Array&&"number"===typeof k[0]&&"number"===typeof k[1]?(this.x=k[0],this.y= +k[1]):k instanceof e&&(this.x=k.x,this.y=k.y)};return e})},"webview/mg/Canvas":function(){define("dojo/_base/declare dojo/_base/array dojo/on dojo/topic dojo/Deferred ../utils/svg ../utils/dom ../base/Point ../base/Rect ./registry ./SceneServer ./Styler ./TextSelection ./Cursor ../tools/ToolStack".split(" "),function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q){e=function(b,c){c||alert('You must specify an id for Canvas construction for svg file "'+b+'"');this.id=c;this.toolStack=this.htmlElement=this.sceneServer= +null;m.hasSvgSupport?(this.htmlElement=m.createHtmlElement(b,"0px","0px"),this.htmlElement.setAttribute("id",c),a.addCanvas(this)):l.publish("webview:mg:Canvas:noSvgSupport")};e.prototype={load:function(a,c,d){var g=this,e,l=g.htmlElement,k=new b;m.hasNativeSvgSupport&&!m.hasMatlabWebKitSupport?(e=function(){g.sceneServer=new f(g.htmlElement,c,d);g.toolStack=new q(g);g.styler=new u(g);g._doTextLOD();g.selection=new p(g);g.cursor=new n(g);k.resolve(g)},h.once(l,"load",e)):(e=function(){g.isLoaded()? +(g.sceneServer=new f(g.htmlElement,c,d),g.toolStack=new q(g),g.styler=new u(g),g._doTextLOD(),g.selection=new p(g),g.cursor=new n(g),k.resolve(g)):setTimeout(e,250)},setTimeout(e,250));a.appendChild(l);return k.promise},destroy:function(){a.removeCanvas(this.id);this.focusNode=this._textNodes=this.htmlElement=this.id=null;this.sceneServer&&this.sceneServer.destroy();this.toolStack&&this.toolStack.destroy();this.cursor&&this.cursor.destroy();this.styler&&this.styler.destroy()},width:function(){return this.htmlElement.getAttribute("width")}, +setWidth:function(a){this.htmlElement.setAttribute("width",a)},height:function(){return this.htmlElement.getAttribute("height")},setHeight:function(a){this.htmlElement.setAttribute("height",a)},isLoaded:function(){return m.isSvgLoaded(this.htmlElement)},position:function(){return d.position(this.htmlElement)},viewOffset:function(){return this.position().topLeft()},viewExtents:function(){var a=this.position();return[a.width(),a.height()]},sceneRectInView:function(){return this.sceneServer.sceneRectInView()}, +sceneRect:function(){return this.sceneServer.sceneRect()},scale:function(){var a=this.sceneRectInView();return this.position().width/a.width},nextZoomScale:function(a){var b=this.scale();return 0c&&0Math.abs(e*n)?"none"!==m.getAttribute(b,"display")&&(m.setAttribute(b,"display","none"),l+=1):m.hasAttribute(b,"display")&&(b.removeAttribute("display"),l-=1))}this._nHiddenText=l}this._lastScale=a}};return e})},"webview/utils/dom":function(){define(["../base/Rect"], +function(e){return{position:function(k){var h=new e;h.width=k.offsetWidth;for(h.height=k.offsetHeight;k&&!isNaN(k.offsetLeft)&&!isNaN(k.offsetTop);)h.x+=k.offsetLeft-k.scrollLeft,h.y+=k.offsetTop-k.scrollTop,k=k.offsetParent;return h}}})},"webview/mg/registry":function(){define(["dojo/_base/unload","dojo/store/Memory"],function(e,k){var h=new k,l={getCanvas:function(b){return h.get(b)},addCanvas:function(b){h.get(b.id)&&console.error("Canvas's id must be unique! Id, "+b.id+", is already in use!"); +h.put(b)},removeCanvas:function(b){h.remove(b)},destroyAllCanvases:function(){h.query().forEach(function(b){h.remove(b.id);b.destroy()})}};e.addOnWindowUnload(l.destroyAllCanvases);return l})},"webview/mg/SceneServer":function(){define("dojo/_base/declare ../utils/svg ../utils/units ../utils/dom ../base/Rect ./Scene".split(" "),function(e,k,h,l,b,m){return e(null,{constructor:function(b,g,c){this.htmlElement=b;this.heightAttrib=c||"100%";this.widthAttrib=g||"100%";this._initSvgSceneHierarchy();this._initHtmlViewportSize(); +this._initBaseSceneViewbox()},svgDocument:null,documentElement:null,backgroundScene:null,baseScene:null,foregroundScene:null,htmlElement:null,heightAttrib:null,widthAttrib:null,widthPixels:null,heightPixels:null,destroy:function(){this.documentElement=this.svgDocument=void 0;this.backgroundScene.destroy();this.baseScene.destroy();this.foregroundScene.destroy()},_cacheSceneRect:null,MIN_SCALE:0.25,MAX_SCALE:10,showSceneRect:function(d,g,c,a){d=new b(d,g,c,a);this.sceneRect();g=d.width/d.height;c=d.center(); +a=this.sceneRectInView();a=a.width/a.height;g>a?d.height=d.height*g/a:d.width=d.width*a/g;d.setCenter(c);this.baseScene.setViewBox(d)},sceneRectInView:function(){return this.baseScene.viewBox()},sceneRect:function(){var d,g,c,a;d=this._cacheSceneRect;if(!d||1>d.width)k.hasAdobePluginSvgSupport?(d=this.documentElement.getBBox(),d=new b(d.x,d.y,d.width,d.height),g=this.sceneRectInView(),c=g.width/this.widthPixels,a=g.height/this.heightPixels,d.x=g.x+d.x*c,d.y=g.y+d.y*a,d.width*=c,d.height*=a):(d=this.baseScene.getBoundingBox(), +d=new b(d.x,d.y,d.width,d.height)),this._cacheSceneRect=d;return new b(this._cacheSceneRect)},_handlePercentageResize:function(){var b=this.htmlElement,g=this.documentElement,c=l.position(b.parentElement),a=this.baseScene,f=a.viewBox(),e,h;0<=this.heightAttrib.indexOf("%")&&(e=c.height,b.setAttribute("height",e+"px"),f.height*=e/this.heightPixels,this.heightPixels=e);0<=this.widthAttrib.indexOf("%")&&(h=c.width,b.setAttribute("width",h+"px"),f.width*=h/this.widthPixels,this.widthPixels=h);g.setAttribute("height", +e+"px");g.setAttribute("width",h+"px");a.setViewBox(f)},_initBaseSceneViewbox:function(){var b=this.baseScene,g=b.rootElement,c=b.viewBox(),a=c.width/c.height,f=c.center(),e=this.widthPixels/this.heightPixels;a>e?c.height=c.height*a/e:c.width=c.width*e/a;c.setCenter(f);b.setViewBox(c);g.setAttribute("height","100%");g.setAttribute("width","100%")},_initSvgSceneHierarchy:function(){var b=k.XMLNS,g=k.getSvgDocument(this.htmlElement),c=g.createElementNS(b,"svg"),a=g.createElementNS(b,"svg"),f=g.documentElement, +b=g.createElementNS(b,"svg"),e=g.createDocumentFragment();this.svgDocument=g;this.documentElement=c;this.backgroundScene=new m(a);this.baseScene=new m(f);this.foregroundScene=new m(b);g.removeChild(g.documentElement);e.appendChild(c);c.appendChild(a);c.appendChild(f);c.appendChild(b);c.setAttribute("zoomAndPan","disable");g.appendChild(e);this._initBackgroundHierarchy()},_initBackgroundHierarchy:function(){var d=this.documentElement.getElementById("background"),g=this.backgroundScene,c=g.rootElement, +a;c.setAttribute("width","100%");c.setAttribute("height","100%");c.setAttribute("preserveAspectRatio","none");d&&(a=new b(d.getBBox()),k.getParent(d).removeChild(d),c.appendChild(d),g.setViewBox(a.toString()))},_initHtmlViewportSize:function(){var b=this.baseScene.rootElement,g=l.position(this.htmlElement.parentElement),c=!1,a=!1;this.heightAttrib||(this.heightAttrib=b.getAttribute("height"));c=0<=this.heightAttrib.indexOf("%");this.widthAttrib||(this.widthAttrib=b.getAttribute("width"));a=0<=this.widthAttrib.indexOf("%"); +this.heightPixels=c?g.height:h.getPixelValue(this.heightAttrib);this.widthPixels=a?g.width:h.getPixelValue(this.widthAttrib);this.resize=c||a?this._handlePercentageResize:function(){};(0===this.widthPixels||0===this.heightPixels)&&console.error("SceneServer: Invalid width or height");this.htmlElement.setAttribute("width",this.widthPixels+"px");this.htmlElement.setAttribute("height",this.heightPixels+"px");this.documentElement.setAttribute("height",this.heightPixels+"px");this.documentElement.setAttribute("width", +this.widthPixels+"px")}})})},"webview/utils/units":function(){define([],function(){var e=function(){var e=document.createElement("div"),b;e.setAttribute("style","height: 1in; left: -100%; position: absolute; top: -100%; width: 1in;");document.documentElement.appendChild(e);b=e.offsetWidth;document.documentElement.removeChild(e);return b}(),k=function(){var e=document.createElement("div"),b;e.setAttribute("style","font-size:1em; position:absolute; line-height:1; padding:0; visibility:hidden");e.appendChild(document.createTextNode("M")); +document.documentElement.appendChild(e);b=e.offsetHeight;document.documentElement.removeChild(e);return b}(),h=/(\d+\.*\d*)\s*(\w*)/;return{getPixelValue:function(l){var b;if(l)if(b=h.exec(l),3===b.length)switch(l=parseFloat(b[1]),b=b[2].toLowerCase(),b){case "in":b=e*l;break;case "mm":b=e/25.4*l;break;case "cm":b=e/2.54*l;break;case "em":b=k*l;break;case "ex":b=2*k*l;break;case "pt":b=e/72*l;break;case "pc":b=e/6*l;break;default:b=l}else b=parseFloat(l);return b}}})},"webview/mg/Scene":function(){define(["dojo/_base/declare", +"../base/Rect","../utils/svg"],function(e,k,h){return e(null,{constructor:function(e){var b=e.ownerDocument,k;h.hasAdobePluginSvgSupport||(k=[b.createElementNS(h.XMLNS,"rect"),b.createElementNS(h.XMLNS,"rect")],k[0].setAttribute("width",100),k[0].setAttribute("height",100),k[1].setAttribute("width",1),k[1].setAttribute("height",1),k[0].setAttribute("stroke","none"),k[0].setAttribute("fill","none"),k[1].setAttribute("stroke","none"),k[1].setAttribute("fill","none"),e.appendChild(k[0]),e.appendChild(k[1])); +this.rootElement=e;this._cornerElements=k},destroy:function(){this.rootElement=void 0},viewBox:function(){var e,b;this._viewBox||(e=this.rootElement,this._viewBox=e=(b=e.getAttribute("viewBox"))?new k(e.getAttribute("viewBox")):new k(0,0,0,0));return this._viewBox},setViewBox:function(e){e=new k(e);var b=this._cornerElements;this.rootElement.setAttribute("viewBox",e.toString());b&&(b[0].setAttribute("x",e.x-5),b[0].setAttribute("y",e.y-5),b[1].setAttribute("x",e.right()+5),b[1].setAttribute("y",e.bottom()+ +5));this._viewBox=e},getBoundingBox:function(){var e=this._cornerElements,b=this.rootElement,m;h.hasAdobePluginSvgSupport&&alert("Adobe SVG plugin does not return correct bounding box!");e&&(b.removeChild(e[0]),b.removeChild(e[1]));m=b.getBBox();m=new k(m.x,m.y,m.width,m.height);e&&(b.appendChild(e[0]),b.appendChild(e[1]));return m}})})},"webview/mg/TextSelection":function(){define(["dojo/_base/declare","../utils/svg"],function(e,k){return e(null,{constructor:function(e){var l=e.sceneServer,b=l.svgDocument; +this.documentElement=l.documentElement;if(b.getSelection)this._selection=b.getSelection();else if(e=e.htmlElement.contentWindow)this._selection=e.getSelection()},enable:function(){var e=this.documentElement,l,b;l=k.getAttribute(e,"style")||"";-1===l.indexOf("-webkit-touch-callout: text; -webkit-user-select: text; -khtml-user-select: text; -moz-user-select: text; -ms-user-select: text; user-select: text;")&&(b=l.replace("-webkit-touch-callout: none; -webkit-user-select: none; -khtml-user-select: none; -moz-user-select: none; -ms-user-select: none; user-select: none;", +"-webkit-touch-callout: text; -webkit-user-select: text; -khtml-user-select: text; -moz-user-select: text; -ms-user-select: text; user-select: text;"),b===l?k.setAttribute(e,"style",l+"-webkit-touch-callout: text; -webkit-user-select: text; -khtml-user-select: text; -moz-user-select: text; -ms-user-select: text; user-select: text;"):k.setAttribute(e,"style",b))},disable:function(){var e=this.documentElement,l,b;l=k.getAttribute(e,"style")||"";-1===l.indexOf("-webkit-touch-callout: none; -webkit-user-select: none; -khtml-user-select: none; -moz-user-select: none; -ms-user-select: none; user-select: none;")&& +(b=l.replace("-webkit-touch-callout: text; -webkit-user-select: text; -khtml-user-select: text; -moz-user-select: text; -ms-user-select: text; user-select: text;","-webkit-touch-callout: none; -webkit-user-select: none; -khtml-user-select: none; -moz-user-select: none; -ms-user-select: none; user-select: none;"),b===l?k.setAttribute(e,"style",l+"-webkit-touch-callout: none; -webkit-user-select: none; -khtml-user-select: none; -moz-user-select: none; -ms-user-select: none; user-select: none;"):k.setAttribute(e, +"style",b))},toString:function(){var e=this._selection;return e?e.toString():""},clear:function(){try{this._selection.removeAllRanges()}catch(e){}},_getSvgSelection:function(e){var l,b=e.sceneServer.svgDocument;b.getSelection?l=b.getSelection():(e=e.htmlElement.contentWindow)&&(l=e.getSelection());return l}})})},"webview/mg/Cursor":function(){define("require dojo/_base/declare dojo/_base/window dojo/Stateful dijit/Destroyable ../utils/svg".split(" "),function(e,k,h,l,b,m){h=document.URL;h=h.substring(0, +Math.max(h.lastIndexOf("/"),h.lastIndexOf("\\"))+1);var d={Default:{name:"Default",curName:"default"},Wait:{name:"Wait",curName:"wait"},ClosedHand:{name:"ClosedHand",curFile:h+e.toUrl("./images/closed_hand.cur"),imgFile:h+e.toUrl("./images/closed_hand.png"),imgWidth:16,imgHeight:16},OpenHand:{name:"OpenHand",curFile:h+e.toUrl("./images/open_hand.cur"),imgFile:h+e.toUrl("./images/open_hand.png"),imgWidth:16,imgHeight:16},ZoomIn:{name:"ZoomIn",curFile:h+e.toUrl("./images/zoom_in.cur"),imgFile:h+e.toUrl("./images/zoom_in.png"), +imgWidth:16,imgHeight:16}},g=k(b,{constructor:function(b){function a(a){k.setAttribute("x",a.clientX-d.imgWidth/2);k.setAttribute("y",a.clientY-d.imgHeight/2)}var d=b.cursor,g=b.x,e=b.y;b=b.canvas.sceneServer;var h=b.documentElement,l=b.foregroundScene.rootElement,k=b.svgDocument.createElementNS(m.XMLNS,"image");k.setAttributeNS("http://www.w3.org/1999/xlink","href",d.imgFile);k.setAttribute("width",d.imgWidth);k.setAttribute("height",d.imgHeight);g&&k.setAttribute("x",g-d.imgWidth/2);e&&k.setAttribute("y", +e-d.imgHeight/2);k.setAttribute("visiblity","visible");h.addEventListener("mousemove",a,!1);this.own({remove:function(){h.removeEventListener("mousemove",a,!1);l.removeChild(k)}});l.appendChild(k)}});return k(null,{constructor:function(b){this.canvas=b;this._name="Default"},destroy:function(){this._asvCursor&&this._asvCursor.destroy()},toString:function(){return this._name},set:function(b){var a=b.name?d[b.name]:d[b],f=this.canvas.sceneServer.documentElement;a.curName?f.style.cursor=a.curName:a&& +(f.style.cursor="url("+a.curFile+"),default");this._asvCursor&&this._asvCursor.destroy();m.hasAdobePluginSvgSupport&&a.imgFile&&(this._asvCursor=new g({canvas:this.canvas,cursor:a,x:b.x,y:b.y}));this._name=a.name}})})},"webview/tools/ToolStack":function(){define("dojo/_base/declare dojo/_base/lang dojo/_base/array dojo/_base/window dojo/store/Memory dojo/on dojo/keys dijit/Destroyable ../utils/svg ../base/Event".split(" "),function(e,k,h,l,b,m,d,g,c,a){var f,u;return e(g,{constructor:function(a){a.isLoaded()|| +console.error("Canvas must be loaded.");this.canvas=a;this._stack=new b({idProperty:"role"});this._registerEvents()},destroy:function(){this.clearToolStack();this.inherited(arguments)},addTool:function(a){var b=this._stack;this.removeTool(a.role);b.put(a);a.onAddToStack(this)},removeTool:function(a){var b=this._stack,c=b.get(a);c&&(c.onRemoveFromStack(),b.remove(a))},getTool:function(a){return this._stack.get(a)},clearToolStack:function(){var a=this._stack,b=a.query();h.forEach(b,function(b){b.onRemoveFromStack(); +a.remove(b.id)})},cancelAllTools:function(){var a=this._stack.query();h.forEach(a,function(a){a.cancel()})},moveToolAbove:function(a,b){var c=this._stack,d,f=this.getTool(a);d=this.getTool(b);var g=[];f&&d&&(c.remove(a),d=c.query(),h.forEach(d,function(a){g.push(a);a.role===b&&g.push(f)}),c.setData(g))},moveToolBelow:function(a,b){var c=this._stack,d,f=this.getTool(a);d=this.getTool(b);var g=[];f&&d&&(c.remove(a),d=c.query(),h.forEach(d,function(a){a.role===b&&g.push(f);g.push(a)}),c.setData(g))}, +addToolAbove:function(a,b){this.addTool(a);this.moveToolAbove(a.role,b)},addToolBelow:function(a,b){this.addTool(a);this.moveToolBelow(a.role,b)},cancelAllToolsExcept:function(a){var b=this._stack.query();h.forEach(b,function(b){b.role!==a&&b.cancel()})},_registerEvents:function(){var a=this,b=this.canvas,d=b.focusNode,f=b.sceneServer.svgDocument.documentElement,g=[{evtName:"mouseup",handler:"handleMouseUpEvent"},{evtName:"mousedown",handler:"handleMouseDownEvent"},{evtName:"mouseover",handler:"handleMouseOverEvent"}, +{evtName:"mousemove",handler:"handleMouseMoveEvent"},{evtName:"mouseout",handler:"handleMouseOutEvent"},{evtName:"keyup",handler:"handleKeyUpEvent"},{evtName:"keydown",handler:"handleKeyDownEvent"}];c.hasAdobePluginSvgSupport?(h.forEach(g,function(b){var c=function(c){a.handleGenericEvent(b.handler,c)};f.addEventListener(b.evtName,c,!1);this.own({remove:function(){f.removeEventListener(b.evtName,c,!1)}})}),f.addEventListener("click",a.handleClick,!1),this.own({remove:function(){f.removeEventListener("click", +a.handleClick,!1)}},m(b.htmlElement,"mousewheel",function(c){var d=b.position();c=k.mixin({},c);var f=l.doc;c.clientX=c.clientX-d.x+f.documentElement.scrollLeft;c.clientY=c.clientY-d.y+f.documentElement.scrollTop;a.handleGenericEvent("handleMouseWheelEvent",c)}))):(g.push({evtName:"DOMMouseScroll",handler:"handleMouseWheelEvent"}),g.push({evtName:"mousewheel",handler:"handleMouseWheelEvent"}),h.forEach(g,function(b){a.own(m(f,b.evtName,function(c){a.handleGenericEvent(b.handler,c)}))}),this.own(m(f, +"click",function(b){a.handleClick(b)})));this.own(m(d,"keydown",function(b){a.handleGenericEvent("handleKeyDownEvent",b)}),m(d,"keyup",function(b){a.handleGenericEvent("handleKeyUpEvent",b)}))},handleGenericEvent:function(b,c){var f=this.activeTool,g,e,l,k=c instanceof a?c:new a(c);"handleKeyUpEvent"===b&&k.getKeyCharOrCode()===d.ESCAPE&&(e=this._stack.query(),h.forEach(e,function(a){if(a.isActive()||a.isAlert())k.consume(),a.cancel()}));f&&f.handleGenericEvent(b,k);e=this._stack.query().reverse(); +l=0;for(g=e[l];!k.isConsumed()&&g;)g!==f&&g.handleGenericEvent(b,k),g=e[l+=1]},handleClick:function(b){b=new a(b);this.handleGenericEvent("handleClickEvent",b);b.isConsumed()?u=null:(u===b.domEvent.target&&this.handleGenericEvent("handleDoubleClickEvent",b),u=b.domEvent.target,f&&clearTimeout(f),f=setTimeout(function(){f=u=null},500))}})})},"webview/base/Event":function(){define(["dojo/_base/declare","./Point"],function(e,k){return e(null,{constructor:function(e){var l=!1;this.domEvent=e;this.isConsumed= +function(){return l};this.consume=function(){var b=this.domEvent;if("mousedown"!==b.type||!this.isLeftMouse(b))b.preventDefault&&b.preventDefault(),b.preventDefault&&b.stopPropagation(),b.returnValue=!1;if(b=window.event)b.returnValue=!1;l=!0}},getKeyCharOrCode:function(){var e=this.domEvent;return e.charCode||e.keyCode},shiftKey:function(){return this.domEvent.shiftKey},ctrlKey:function(){return this.domEvent.ctrlKey},altKey:function(){return this.domEvent.altKey},getMousePosition:function(){var e= +this.domEvent;return new k(e.clientX,e.clientY)},isLeftMouse:function(){var e=this.domEvent;return"number"===typeof e.button&&0===e.button},isMiddleMouse:function(){var e=this.domEvent;return"number"===typeof e.button&&1===e.button},isRightMouse:function(){var e=this.domEvent;return"number"===typeof e.button&&2===e.button},mouseWheelDir:function(){var e=this.domEvent;return e.wheelDelta?0e.detail?1:-1}})})},"webview/tools/PanTool":function(){define(["dojo/_base/declare","dojo/keys", +"../base/Point","./Tool"],function(e,k,h,l){return e(l,{postMixInProperties:function(){this.role="PanTool";this.panState={mousePosition:null,isPanning:!1,spaceKeyInitiated:!1}},becomeIdle:function(){var b=this.canvas,e=this.panState;this.inherited(arguments);e.spaceKeyInitiated=!1;e.isPanning=!1;e.mousePosition=null;b&&b.cursor.set("Default")},becomeAlert:function(b){this.inherited(arguments);this.canvas.cursor.set({name:"OpenHand",x:b.domEvent.clientX,y:b.domEvent.clientY})},becomeActive:function(b){this.inherited(arguments); +this.canvas.cursor.set({name:"ClosedHand",x:b.domEvent.clientX,y:b.domEvent.clientY});this.panState.mousePosition=null},handleMouseDownEvent:function(b){this.isIdle()&&b.isMiddleMouse()?this.becomeAlert(b):this.isAlert()&&b.isLeftMouse()&&this.becomeActive(b)},handleMouseMoveEvent:function(b){var e=this.canvas,d=e.scale(),g=this.panState,c;this.isAlert()&&!g.spaceKeyInitiated&&this.becomeActive(b);this.isActive()&&(b=b.getMousePosition(),g.mousePosition?(c=new h(g.mousePosition.x-b.x,g.mousePosition.y- +b.y),e.translate(-c.x/d,-c.y/d),g.mousePosition=b,g.isPanning=!0):g.mousePosition=b)},handleClickEvent:function(b){this.isActive()&&(this.panState.spaceKeyInitiated?this.becomeAlert(b):this.becomeIdle(),b.consume())},keyPanPercent:0.05,handleKeyDownEvent:function(b){function e(b,a,d,h){var l=a.sceneRectInView();a.translate(g*d*l.width,g*h*l.height);b.consume()}var d=this.canvas,g=this.keyPanPercent;if(this.isIdle())if(b.getKeyCharOrCode()===k.SPACE)this.panState.spaceKeyInitiated=!0,this.becomeAlert(b); +else if(!b.altKey()&&!b.ctrlKey())switch(b.getKeyCharOrCode()){case k.UP_ARROW:case k.NUMPAD_8:e(b,d,0,1);break;case k.DOWN_ARROW:case k.NUMPAD_2:e(b,d,0,-1);break;case k.LEFT_ARROW:case k.NUMPAD_4:e(b,d,1,0);break;case k.RIGHT_ARROW:case k.NUMPAD_6:e(b,d,-1,0)}},handleKeyUpEvent:function(b){if(b.getKeyCharOrCode()===k.SPACE&&(this.isAlert()||this.isActive()))this.panState.isPanning&&b.consume(),this.becomeIdle()}})})},"webview/tools/Tool":function(){define(["dojo/_base/declare","dojo/Evented","../base/EventHandler"], +function(e,k,h){return e([k,h],{constructor:function(h){this.role="";this.state=this.IDLE;this.consumeEventWhenActive=!0;e.safeMixin(this,h);this.postMixInProperties()},postMixInProperties:function(){},destroy:function(){},IDLE:0,ACTIVE:1,ALERT:2,DONE:3,isIdle:function(){return this.state===this.IDLE},isAlert:function(){return this.state===this.ALERT},isActive:function(){return this.state===this.ACTIVE},isDone:function(){return this.state===this.DONE},becomeIdle:function(){this._becomeNewState(this.IDLE); +this.emit("idle")},becomeAlert:function(){this._becomeNewState(this.ALERT);this.emit("alert")},becomeActive:function(){var e=this.toolStack;this._becomeNewState(this.ACTIVE);e.cancelAllToolsExcept(this.role);e.activeTool=this;this.emit("active")},becomeDone:function(){this._becomeNewState(this.DONE);this.toolStack.removeTool(this.role);this.emit("done")},cancel:function(){this.isIdle()||this.becomeIdle()},onAddToStack:function(e){this.toolStack=e;this.canvas=e.canvas},onRemoveFromStack:function(){this.canvas= +this.toolStack=null},handleGenericEvent:function(e,b){this[e](b);this.isActive()&&this.consumeEventWhenActive&&b.consume()},_becomeNewState:function(e){var b=this.toolStack,h,d;this.state===e&&console.error("Tool state did not change");this.isActive()&&(h=b.activeTool.role,d=this.role,h!==d&&console.error("Unexpected active tool: "+h+"expected: "+d),b.activeTool=void 0);this.state=e}})})},"webview/base/EventHandler":function(){define(["dojo/_base/declare"],function(e){return e(null,{constructor:function(){}, +handleMouseWheelEvent:function(e){},handleMouseMoveEvent:function(e){},handleMouseDownEvent:function(e){},handleMouseUpEvent:function(e){},handleMouseOverEvent:function(e){},handleMouseOutEvent:function(e){},handleClickEvent:function(e){},handleDoubleClickEvent:function(e){},handleKeyDownEvent:function(e){},handleKeyUpEvent:function(e){}})})},"webview/tools/ScrollWheelTool":function(){define(["dojo/_base/declare","./Tool"],function(e,k){return e(k,{postMixInProperties:function(){this.role="ScrollWheelTool"}, +handleMouseWheelEvent:function(e){var l=this.canvas,b=e.mouseWheelDir();e.shiftKey()?l.translate(-0.05*l.sceneRectInView().width*b,0):e.ctrlKey()?l.translate(0,-0.05*l.sceneRectInView().height*b):l.setScaleAroundScenePoint(l.nextZoomScale(b),l.viewPointToScenePoint(e.getMousePosition()));e.consume()}})})},"webview/tools/FitToViewTool":function(){define(["dojo/_base/declare","dojo/keys","./Tool"],function(e,k,h){return e(h,{postMixInProperties:function(){this.role="FitToViewTool"},handleKeyUpEvent:function(e){e.getKeyCharOrCode()=== +k.SPACE&&(this.becomeActive(),this.canvas.zoomToSceneRect(),this.becomeIdle(),e.consume())}})})},"webview/tools/KeyboardZoomTool":function(){define(["dojo/_base/declare","dojo/keys","./Tool"],function(e,k,h){var l="+".charCodeAt(),b="-".charCodeAt(),m="1".charCodeAt();return e(h,{postMixInProperties:function(){this.role="KeyboardZoomTool"},handleKeyUpEvent:function(d){var g=this.canvas,c=g.scale();switch(d.getKeyCharOrCode()){case k.NUMPAD_PLUS:case l:case 187:this.becomeActive();g.setScale(1.1*c); +this.becomeIdle();d.consume();break;case k.NUMPAD_MINUS:case b:case 189:this.becomeActive();g.setScale(0.9*c);this.becomeIdle();d.consume();break;case m:d.altKey()&&(this.becomeActive(),g.zoomToActualSize(),this.becomeIdle(),d.consume())}}})})},"webview/tools/KeyboardESCBackTool":function(){define(["dojo/_base/declare","dojo/keys","./Tool"],function(e,k,h){return e(h,{postMixInProperties:function(){this.role="KeyboardESCBackTool"},handleKeyUpEvent:function(e){switch(e.getKeyCharOrCode()){case k.ESCAPE:window.history.back(), +e.consume()}}})})},"webview/tools/TextSelectionTool":function(){define(["dojo/_base/declare","./Tool"],function(e,k){return e(k,{postMixInProperties:function(){this.role="TextSelection";this.consumeEventWhenActive=!1;this._disableInDBClick=/chrome/.test(navigator.userAgent.toLowerCase())},cancel:function(){this.inherited(arguments);this.canvas.selection.clear()},handleMouseDownEvent:function(e){var l=this.canvas;!this.isAlert()&&e.isLeftMouse()&&(this.becomeAlert(),l.selection.clear(),this._startMousePos= +e.getMousePosition(),this._disableInDBClick&&l.selection.disable())},handleMouseMoveEvent:function(e){this.isAlert()&&this._didMouseMove(e)&&(this.becomeActive(),this._disableInDBClick&&this.canvas.selection.enable())},handleClickEvent:function(e){var l=this.canvas,b;this.isActive()?(b=l.selection.toString(),""!==b&&e.consume(),this._disableInDBClick&&""===b&&l.selection.disable(),this.becomeIdle()):this.isAlert()&&this.becomeIdle()},_didMouseMove:function(e){e=e.getMousePosition();var l=this._startMousePos; +return l&&(l.x!==e.x||l.y!==e.y)}})})},"webview/tools/DelegateToHandlerTool":function(){define("dojo/_base/declare require dojo/store/Memory ../utils/svg ./Tool ../handlers/ElementHandler ../handlers/ContainerHandler".split(" "),function(e,k,h,l,b,m){return e(b,{postMixInProperties:function(){this.role="DelegateToHandlerTool";this._cache=new h;this.defaultHandler=new m},getHandler:function(b){b=b.domEvent.target;var g=this.app,c=this.diagram,a,f,e,h;for(h=this.defaultHandler;b;){if(e=l.getAttribute(b, +"id")){if(e===this._lastTargetId)return this._lastJsHandler;if(a=c.getElement(e))if(f=a.backing.viewer)if(f=f.jshandler,"string"===typeof f)return h=this._getJsHandlerFromCache(f),h||(h=new (k(f)),this._addJsHandlerToCache(f,h)),h.init({app:g,diagram:c,element:a,svgNode:b,canvas:this.canvas}),this._lastTargetId=e,this._lastJsHandler=h}b=l.getParent(b)}h.init({app:g,diagram:c,element:null,svgNode:null,canvas:this.canvas});return h},handleGenericEvent:function(b,e){var c=this.getHandler(e);c&&(c[b](e), +this.toolStack&&e.isConsumed()&&(this.becomeActive(),this.becomeIdle()))},_getJsHandlerFromCache:function(b){b=this._cache.get(b);var e;b&&b.jshandler&&(e=b.jshandler);return e},_addJsHandlerToCache:function(b,e){this._cache.put({id:b,jshandler:e})}})})},"webview/handlers/ElementHandler":function(){define(["dojo/_base/declare","dojo/_base/lang","../base/EventHandler"],function(e,k,h){return e(h,{init:function(e){this.reset();k.mixin(this,e)},reset:function(){this.canvas=this.svgNode=this.element= +this.diagram=this.app=null},handleClickEvent:function(e){e=this.app;var b=this.element||this.diagram;b&&e.select(b,{svgNode:this.svgNode})},handleDoubleClickEvent:function(e){var b=this.element||this.diagram;b&&(this.app.open(b),e.consume())}})})},"webview/handlers/ContainerHandler":function(){define(["dojo/_base/declare","./ElementHandler"],function(e,k){return e(k,{handleDoubleClickEvent:function(e){var l=this.app,b=l.data.diagramStore.getTargetDiagram(this.element);b&&l.open(b,{tab:e.ctrlKey()? +"new":"reuse"}).then(function(){l.modelViewer.focus()});e.consume()}})})},"webview/widgets/EmptyModelGraphicsPane":function(){define(["dojo/_base/declare","dojo/topic","dijit/layout/ContentPane","dojo/i18n!../resources/slreportgen_webview/nls/modelviewer"],function(e,k,h,l){return e([h],{postCreate:function(){this.inherited(arguments);this.set("class","no-export");this.set("innerHTML",l.NoExport)},startup:function(){k.publish(this.app.id+"/select",this.diagram);k.publish(this.app.id+"/postOpen",this.diagram)}})})}, +"webview/widgets/LightBox":function(){define("dojo/_base/declare dojo/_base/lang dojo/topic dojo/query dojo/Deferred dojo/dom-construct dojo/dom-geometry dojo/dom-style dojo/keys dojo/on dijit/_WidgetBase dijit/_TemplatedMixin dijit/_CssStateMixin dijit/layout/ContentPane dijit/focus ../base/Rect MW/rtc/plugins/language/matlab/tokenizer/TokenState MW/rtc/plugins/language/matlab/tokenizer/TokenConstants MW/syntaxhighlighting/ColorMapDefaults dojo/text!./templates/LightBox.html dojo/i18n!dijit/nls/common".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f,u,p,n,q,r,s,x,w,y,A){return e([f,u,p],{templateString:y,baseClass:"dijitDialog",cssStateNodes:{closeButtonNode:"dijitDialogCloseIcon"},title:"",_setTitleAttr:{node:"titleNode",type:"innerHTML"},content:null,_setContentAttr:function(a){this.contentPane.set("content",a);this.resize()},_hasContentToShow:!1,href:null,_setHrefAttr:function(a){this.contentPane.set("href",a);this.resize()},contentPane:null,isOpen:!1,_lastObjId:"",_lastViewId:"",_contentSize:null,_titleBarSize:null, +spacing:20,postMixInProperties:function(){k.mixin(this,A);this.inherited(arguments)},startup:function(){var b=this.app.id,c=this.app,d=this;this.own(a(this.dialogNode,"keyup",k.hitch(this,"_onKeyUp")),a(this.underlayNode,"click",k.hitch(this,"close")),h.subscribe(b+"/open",function(a,b){c.isElement(a)&&d.open(a,b)}),h.subscribe(b+"/close",k.hitch(this,"close")),h.subscribe(b+"/select",k.hitch(this,"_select")),h.subscribe(b+"/postClose",k.hitch(this,"close")));this.contentPane=new n({content:this.content, +style:"padding: 0"},this.contentNode);this.reset()},destroy:function(){this._tableSignal&&this._tableSignal.remove()},resize:function(){this.isOpen&&(this._sizeWidget(),this._sizeDialog(),this._positionDialog())},open:function(a,b){var c=this,d=this.app,f=a.backing.sid,e=a.backing,g=e.obj_viewer,n=0a&&(e=a);var h=c;a>f?(this._deleteTokenPlaceHolders(c,a,a-f,f),this._deleteLineHandles(e,c)):a=a&&(delete this._tokenMap[b],delete this._tokensOnLine[b])}))},_deleteLineHandles:function(b,e){for(var c=e-1;c>=b;c--)this._removeLineHandle(c)},_removeLineHandle:function(b){b+1=b;l--){for(var f=this._tokenMap[l],n=0;nc&&n&&(a=!0),e++,e===h&&(a=!0);-1===f&&(f=c);return f}},createStateHandle:function(b,e){var c=this.getLexStateForLine(e);return this._createStateHandle(b,e,c)},_createStateHandle:function(b,e,c){return this.tokenizeCode(b[e],e,c)},tokenizeCode:function(b, +e,c){var a=b.length+3,f=[],h=this._tokenizer.lex_line(f,a,c,b,b.length);this._notEnoughRoom(h)&&(h=this._tokenizer.lex_line(f,2*a,c,b,b.length));this._isLineExecutable[e]=h.isExecutable;this._parseTokens(f,b,e);this._tokensChanged=this._tokensOnLine[e]!==JSON.stringify(this._tokenMap[e]);this._tokensOnLine[e]=JSON.stringify(this._tokenMap[e]);return h.newState},_isLineUnchanged:function(b,e){return this.areStatesEqual(e,this.getLexStateForLine(b+1))&&!this._tokensChanged},_notEnoughRoom:function(b){return-1=== +b.numTokens},getLexStateForLine:function(b){return this._savedLexStates[b]},getExecutableLineData:function(){return this._isLineExecutable},isLineContinuation:function(b){return this._tokenizer.is_contin(b)},areStatesEqual:function(b,e){if(b&&e)return this._tokenizer.are_states_equal(b,e)},getNumberOfSavedStates:function(){return this._savedLexStates.length},getTokenMap:function(){return this._tokenMap},getLastToken:function(b){var e=null;if((b=this._tokenMap[b])&&0>this.SHIFT_FOR_LENGTH;return e},destroy:function(){this._tokenMap={};this._tokenizer={};this._lexState={};this._savedLexStates=[];this._isLineExecutable= +[]}})})},"MW/rtc/plugins/language/matlab/tokenizer/TokenConstants":function(){define([],function(){var e={FUNCTION:1,NESTED:2,IF:3,SWITCH:4,TRY:5,WHILE:6,FOR:7,END:8,ELSE:9,ELSEIF:10,BREAK:11,RETURN:12,PARFOR:13,GLOBAL:15,PERSISTENT:16,CATCH:20,CONTINUE:21,CASE:22,OTHERWISE:23,CLASSDEF:25,PROPERTIES:28,METHODS:30,EVENTS:31,ENUMERATION:32,SPMD:33,PARSECTION:34,SECTION:35,ID:40,EEND:41,INT:42,FLOAT:43,STRING:44,DUAL:45,BANG:46,QUEST:47,SEMI:50,COMMA:51,LP:52,RP:53,LB:54,RB:55,LC:56,RC:57,FEEND:58,TRANS:60, +DOTTRANS:61,NOT:62,AT:63,DOLLAR:64,BACKQUOTE:65,DOUBLEQUOTE:66,SHARP:67,PLUS:70,MINUS:71,MUL:72,DIV:73,LDIV:74,EXP:75,COLON:76,DOT:80,DOTMUL:81,DOTDIV:82,DOTLDIV:83,DOTEXP:84,AND:85,OR:86,ANDAND:87,OROR:88,LT:89,GT:90,LE:91,GE:92,EQ:93,NE:94,EQUALS:95,CNE:96,EOL:100,SEOL:101,CEOL:102,IEOL:103,COMMENT:105,BLKSTART:106,BLKCOM:107,BLKEND:108,SECTION_TITLE:109,PRAGMA:110,DOTDOTDOT:111,DOTDOT:112,DEEP_NEST:113,DEEP_STMT:114,WHITE:116,NEGERR:118,SEMERR:119,EOLERR:120,UNTERM:121,BADCHAR:122,DEEP_PAREN:123, +FP_ERR:124,RES_ERR:125,DEEP_COM:126,BEGIN_TYPE:127,END_TYPE:128,STRING_LITERAL:129,UNTERM_STRING_LITERAL:130},k={"0":"NA",1:"function",2:"nested",3:"if",4:"switch",5:"try",6:"while",7:"for",8:"end",9:"else",10:"elseif",11:"break",12:"return",13:"parfor",14:"NA",15:"global",16:"persistent",17:"NA",18:"NA",19:"NA",20:"catch",21:"continue",22:"case",23:"otherwise",24:"NA",25:"classdef",26:"NA",27:"NA",28:"properties",29:"NA",30:"methods",31:"events",32:"enumeration",33:"reserved_mcos_keyword_33",34:"spmd", +35:"reserved_mcos_keyword_35",36:"NA",37:"NA",38:"NA",39:"NA",40:"ID",41:"\x3cend\x3e",42:"\x3cint\x3e",43:"\x3cfloat.",44:"\x3cstring\x3e",45:"\x3cdual\x3e",46:"\x3cBANG\x3e",47:"?",48:"NA",49:"NA",50:";",51:",",52:"(",53:")",54:"[",55:"]",56:"{",57:"}",58:"NA",59:"NA",60:"'",61:".'",62:"~",63:"@",64:"$",65:"`",66:"\\",67:"#",68:"NA",69:"NA",70:"+",71:"-",72:"*",73:"/",74:"\\\\",75:"^",76:":",77:"::",78:"NA",79:"NA",80:".",81:".*",82:"./",83:".\\",84:".^",85:"\x26",86:"|",87:"\x26\x26",88:"||",89:"\x3c", +90:"\x3e",91:"\x3c\x3d",92:"\x3e\x3d",93:"\x3d\x3d",94:"~\x3d",95:"\x3d",96:"\x3cCNE\x3e",97:"NA",98:"NA",99:"NA",100:"\x3cEOL\x3e",101:"\x3cSEOL\x3e",102:"\x3cCEOL\x3e",103:"\x3cIEOL\x3e",104:"NA",105:"\x3ccomment\x3e",106:"\x3cbegin block comment\x3e",107:"\x3cblock comment\x3e",108:"\x3cend block comment\x3e",109:"%%",110:"PRAGMA",111:"...",112:"\x3cDOT DOT\x3e",113:"\x3cDEEP NEST\x3e",114:"\x3cDEEP STMT\x3e",115:"NA",116:"\x3cwhitespace\x3e",117:"NA",118:"\x3cNEG ERROR\x3e",119:"\x3cSEM ERROR\x3e", +120:"\x3cEOL ERROR\x3e",121:"\x3cunterm string\x3e",122:"\x3cbadchar\x3e",123:"\x3cDEEP PAREN\x3e",124:"NA",125:"\x3cRES ERROR\x3e",126:"\x3cDEEP COM\x3e",127:"NA",129:"\x3cstring literal\x3e",130:"\x3cunterm string literal\x3e"},h={"0":339,1:333,2:333,3:333,4:333,5:333,6:333,7:333,8:333,9:333,10:333,11:333,12:333,13:333,14:333,15:333,16:333,17:333,18:333,19:333,20:333,21:333,22:333,23:333,24:333,25:333,26:333,27:333,28:333,29:333,30:333,31:333,32:333,33:333,34:333,35:333,44:44,45:45,46:338,64:122, +65:122,66:122,67:122,105:105,106:106,107:107,108:108,109:109,110:110,111:333,121:337,122:122,125:122,129:44,130:337};e.getValueOfToken=function(e){return k[e]};e.getCategoryOfToken=function(e){return h[e]};return e})},"MW/rtc/plugins/language/matlab/tokenizer/Token":function(){define(["dojo/_base/declare"],function(e){return e(null,{constructor:function(e,h,l,b,m,d){this._index=e;this._type=h;this._line=l;this._column=b;this._length=m;this._value=d},getIndex:function(){return this._index},equals:function(e){return e&& +this._index===e._index&&this._type===e._type&&this._line===e._line&&this._column===e._column&&this._length===e._length&&this._value===e._value},getPositionInfo:function(){return{line:this._line,column:this._column}},setLine:function(e){this._line=e},getType:function(){return this._type},getValue:function(){return this._value}})})},"MW/rtc/plugins/language/matlab/tokenizer/Tokenizer":function(){define([],function(){var e,k,h,l,b,m,d,g,c;function a(a,b){a+=uc[b&127];a=a+" ("+(b>>8);return a+=") "}var f= +1,u=2,p=3,n=4,q=5,r=6,s=7,x=8,w=9,y=10,A=11,B=12,C=13,F=15,K=16,G=20,I=21,O=22,N=23,T=25,P=28,Q=30,L=31,J=32,H=33,V=34,W=35,R=40,Z=41,ba=42,U=43,ka=44,S=45,aa=46,ha=47,Aa=50,ia=51,qa=52,ra=53,Eb=54,lb=55,Fb=56,mb=57,Xa=58,Ya=60,nb=61,Ba=62,Fa=63,Za=64,Na=65,Oa=67,Qb=70,Db=71,oa=72,pb=73,pa=74,fc=75,Ma=76,Sb=80,qb=81,Tb=82,ob=83,Ub=84,Wa=85,Vb=86,Wb=87,xa=88,Gb=89,Rb=90,Xb=91,Hb=92,hc=93,ic=94,jc=95,sb=96,Ja=100,Pa=101,tb=102,ya=103,cb=105,za=106,Ga=107,Da=108,Ha=109,Ua=110,bb=111,Ia=112,db=113,Ib= +114,sa=116,Ea=118,vb=119,Jb=120,Qa=121,ab=122,$a=123,Ra=124,Yb=125,ub=126,eb=127,ja=128,Dc=129,rc=130,na=0,La=1,la=2,Va=3,ea=4,sc=5,dc=6,ec=7,tc=0,Ec=1,ta=2,gc=3,rb=4,uc=[null,"FUNCTION","NESTED","IF","SWITCH","TRY","WHILE","FOR","END","ELSE","ELSEIF","BREAK","RETURN","PARFOR",null,"GLOBAL","PERSISTENT",null,null,null,"CATCH","CONTINUE","CASE","OTHERWISE",null,"CLASSDEF",null,null,"PROPERTIES",null,"METHODS","EVENTS","ENUMERATION","SPMD","PARSECTION","SECTION",null,null,null,null,"ID","EEND","INT", +"FLOAT","STRING","DUAL","BANG","QUEST",null,null,"SEMI","COMMA","LP","RP","LB","RB","LC","RC","FEEND",null,"TRANS","DOTTRANS","NOT","AT","DOLLAR","BACKQUOTE","DOUBLEQUOTE",null,null,null,"PLUS","MINUS","MUL","DIV","LDIV","EXP","COLON",null,null,null,"DOT","DOTMUL","DOTDIV","DOTLDIV","DOTEXP","AND","OR","ANDAND","OROR","LT","GT","LE","GE","EQ","NE","EQUALS","CNE","ARROW",null,null,"EOL","SEOL","CEOL","IEOL",null,"COMMENT","BLKSTART","BLKCOM","BLKEND","CPAD","PRAGMA","DOTDOTDOT","DOTDOT","DEEP_NEST", +"DEEP_STMT",null,"WHITE",null,"NEGERR","SEMERR","EOLERR","UNTERM","BADCHAR","DEEP_PAREN","FP_ERR","RES_ERR","DEEP_COM","BEGIN_TYPE","END_TYPE","STRING_LITERAL","UNTERM_STRING_LITERAL","LAST_TOKEN"];e=0;k=1;h=2;l=3;b=4;m=5;d=6;g=7;c=8;return function(){function vc(){return{cstate:tc,lstate:na,indent:0,infun:0,npars:0,ncoms:0,ldsv:0,atlp:0,contin:0,elist:0,haveends:0,begin:1,spare:0,stack:0,propParseState:-1}}function kc(a,b){a.cstate=b.cstate;a.lstate=b.lstate;a.indent=b.indent;a.infun=b.infun;a.npars= +b.npars;a.ncoms=b.ncoms;a.ldsv=b.ldsv;a.atlp=b.atlp;a.contin=b.contin;a.elist=b.elist;a.haveends=b.haveends;a.begin=b.begin;a.spare=b.spare;a.stack=b.stack;a.propParseState=b.propParseState}function Fc(a){a.lstate=na;a.cstate=tc;a.atlp=a.contin=a.elist=a.haveends=0;a.indent=a.infun=0;a.npars=a.ncoms=a.stack=0;a.begin=1;a.ldsv=0;a.spare=0}function E(a){if(a>=X)return fa;a=ma.charCodeAt(a);return!(a&-128)?Tc[a]:z}function Zb(){for(;E(v)!==fa;++v);}function fb(){for(;E(v)!==fa;++v);if(v+1=X)return 0;switch(E(v)){case $b:case ac:return E(v+1)===da?0:1;case bc:return E(v+1)===ga?0:1;case Y:return E(v+1)===ca?1:0;case M:case ca:case ib:case Sa:case xb:case ua:case va:case Ta:case cc:case xc:return 1;default:return 0}} +function Kc(a){return a>>8}function yc(){for(;v=X)return lc&&!t.begin?(D=v=X,wb(a,b)):0;D=v;if(t.begin&&(c=Vc(a,b)))return c;if(t.cstate===rb){if(c=Uc(a,b),0=X||E(v+1)!==va)d=0;else{++v;continue}else d=1;continue;case Sa:case xb:case ua:d||++c;continue;case jb:case Kb:case kb:d||--c;continue;case da:if(d||c)continue;break;case gb:if(d)continue;break;case fa:break;case Ca:if(d)continue; +break;case Y:if(d)continue;if(E(v+1)===Y&&E(v+2)===Y)break;continue;case hb:if(d||c)continue;break;default:continue}break}if(d&&!c)a[b]=v-D<<8|Qa;else{if(t.ldsv===zc&&E(D)===M){for(c=D+1;cD)return a[b+0]=v-D<<8|sa,D=v,a[b+1]=v-D<<8|ia,2;a[b]=v-D<<8|ia;return 1}switch(E(v)){case Mc:return v=X,a[b]=v-D<<8|sa,1;case da:for(++v;E(v)== +da;++v);if(t.stack&1&&(t.lstate==Va||t.lstate==la)&&Jc())return a[b+0]=v-D<<8|sa,D=v,a[b+1]=v-D<<8|ia,2;a[b]=v-D<<8|sa;return 1;case fa:return fb(),wb(a,b);case M:for(c=v+1;c=X-1)return X=D,0;Zb();a[b]=v-D<<8|Hc();D=v;fb();return 1+wb(a,b+1);case bc:++v;if(E(v)==ga)return++v,a[b]=v-D<<8|ic,1;a[b]=v-D<<8|Ba;return 1;case ga:++v;if(E(v)==ga)return++v,a[b]=v-D<<8|hc,1;a[b]=v-D<<8|jc;return 1;case mc:++v;if(E(v)==ga)return++v,a[b]=v-D<<8|Xb,1;a[b]=v-D<<8|Gb;return 1;case nc:++v;if(E(v)==ga)return++v,a[b]=v-D<<8|Hb,1;a[b]=v-D<<8|Rb;return 1;case Lb:++v;if(E(v)==Lb)return++v,a[b]=v-D<<8|Wb,1;a[b]=v-D<<8| +Wa;return 1;case Mb:++v;if(E(v)==Mb)return++v,a[b]=v-D<<8|xa,1;a[b]=v-D<<8|Vb;return 1;case hb:return++v,a[b]=v-D<<8|ia,1;case gb:++v;if(t.npars&&!(t.stack&1))return a[b+0]=0|vb,a[b+1]=v-D<<8|Aa,2;a[b]=v-D<<8|Aa;return 1;case oc:return++v,a[b]=v-D<<8|Ma,1;case Sa:++v;if(t.npars==Nb)return a[b+0]=0|$a,a[b+1]=v-D<<8|qa,2;a[b]=v-D<<8|qa;return 1;case ua:++v;if(t.npars==Nb)return a[b+0]=0|$a,a[b+1]=v-D<<8|Fb,2;a[b]=v-D<<8|Fb;return 1;case xb:++v;if(t.npars==Nb)return a[b+0]=0|$a,a[b+1]=v-D<<8|Eb,2;a[b]= +v-D<<8|Eb;return 1;case jb:++v;if(0==t.npars)return a[b+0]=0|Ea,a[b+1]=v-D<<8|ra,2;a[b]=v-D<<8|ra;return 1;case Kb:++v;if(0==t.npars)return a[b+0]=0|Ea,a[b+1]=v-D<<8|lb,2;a[b]=v-D<<8|lb;return 1;case kb:++v;if(0==t.npars)return a[b+0]=0|Ea,a[b+1]=v-D<<8|mb,2;a[b]=v-D<<8|mb;return 1;case xc:return++v,a[b]=v-D<<8|ha,1;case wc:return++v,a[b]=v-D<<8|Oa,1;case Nc:return++v,a[b]=v-D<<8|Za,1;case Oc:return++v,a[b]=v-D<<8|Na,1;case cc:return++v,a[b]=v-D<<8|Fa,1;case $b:return++v,a[b]=v-D<<8|Qb,1;case ac:return++v, +a[b]=v-D<<8|Db,1;case yb:return++v,a[b]=v-D<<8|oa,1;case zb:return++v,a[b]=v-D<<8|pb,1;case Ab:return++v,a[b]=v-D<<8|pa,1;case Bb:return++v,a[b]=v-D<<8|fc,1;case va:if(0=X)return Ra;if(E(v)==$b||E(v)==ac)if(++v,v>=X)return Ra;if(E(v)!=ca)return Ra;for(;v=X)return la;if(Pc&&b&&($(ma,"load",4,a)||$(ma,"save",4,a)))f=!0;switch(E(c)){case Y:if(E(c+1)==Y&&E(c+2)==Y)return la;switch(E(c+1)){case ca:return La;case da:break;case Bb:case yb:case zb:case Ab:case va:case Sa:return Ka(c+2);case M:break;default:return La}break;case ga:if(E(c+1)==ga)return Ka(c+2);case Sa:case jb:return la;case fa:case gb:case hb:case Ca:case Ta:return la; +case ua:break;case Lb:return E(c+1)==Lb?Ka(c+2):Ka(c+1);case Mb:return E(c+1)==Mb?Ka(c+2):Ka(c+1);case bc:return E(c+1)==ga?Ka(c+2):La;case mc:case nc:case Bc:return E(c+1)==ga?Ka(c+2):Ka(c+1);case oc:case $b:case ac:case yb:case zb:case Ab:case Bb:case cc:return Ka(c+1);case xb:if(f||t.ldsv==pc)return ea;default:return La}for(e=d=f=0;c>8}function Qc(a){for(;a=X)return 0;for(;E(c)==da;)++c;if(0!==t.ncoms){var f=Ga;if(E(c)===Ca&&(E(c+1)===ua||E(c+1)===kb)&&Qc(c+2))f=E(c+1)===ua?t.ncoms>=Rc?ub:za:Da;fb();a[b]=v-D<<8|f;return 1}if(E(c)===fa)return 0;if(E(c)===Ca){if(E(c+1)===Ca&&(E(c+2)===fa||E(c+2)===da))return Zb(),a[b]=v-D<<8|Ha,1;if(E(c+ +1)===ua&&Qc(c+2))return fb(),a[b]=v-D<<8|za,1}return 0}function Cc(a,z){t.lstate===na&&wa===qc&&(wa=Sc);a:{var D,X=z>>8;t.begin=0;if(t.cstate===rb)switch(z&255){case Ja:case ya:t.propParseState===c&&(t.propParseState=e);break;case eb:t.propParseState=h;break;case ja:t.propParseState=c;break;case R:if(t.propParseState===e)t.propParseState=k;else if(t.propParseState===b||t.propParseState===h)t.propParseState=m;break;case ia:t.propParseState===c&&0===t.npars&&(t.propParseState=e);break;case Aa:if(t.propParseState=== +c&&(0===t.npars||!(t.stack&1)))t.propParseState=e;break;case ra:1===t.npars&&t.propParseState===l&&(t.propParseState=b);break;case qa:t.propParseState===h&&(t.propParseState=l);break;case Fb:if(t.propParseState===d||t.propParseState===b||t.propParseState===h)t.propParseState=g}switch(z&255){case cb:case bb:break;case za:case Ga:case Da:t.begin=1;break;case Ja:case ya:t.begin=1;t.contin=0;break;case Pa:case tb:t.contin=1;t.begin=1;break;case qa:t.lstate==sc&&(t.atlp=1);case R:case Z:case Xa:t.lstate== +sc&&(t.lstate=ea);default:t.contin=0}if(t.cstate==tc)switch(z&255){case sa:case cb:case za:case Ga:case Da:case bb:case Ja:case ya:case tb:break;case T:t.cstate=ta;break;default:t.cstate=Ec}switch(z&255){case R:case Z:case Xa:switch(t.lstate){case na:D=v-(z>>8);var Cb;b:{Cb=z>>8;var da=ma.slice(D),ha="pi eps nan NaN inf Inf i j ans".split(" "),fa=[2,3,3,3,3,3,1,1,3],ga;if(0===da.length)Cb=1;else{for(ga=0;ga>8);if(Pc&&4===z>>8&&t.lstate!==la&&($(a,"load",4,X)||$(a,"save",4,X)))t.ldsv=pc;break;case ec:case ea:case dc:t.lstate=la}break;case q:++t.indent;case w:case N:case G:case B:case A:case I:t.npars=0;t.stack=0;t.lstate=na;break;case f:t.npars=0;t.stack=0;t.indent=1;t.cstate===ta&&(t.cstate=gc,t.indent=3);t.infun=t.indent;t.lstate=ea;break;case u:t.npars=0;t.stack=0;t.indent>=1);t.ldsv===pc&&0===t.npars?(t.lstate=La,t.ldsv=zc):t.lstate=Va;break;case mb:0>=1);t.lstate=la;break;case ra:0< +t.npars&&(t.npars--,t.stack>>=1);t.lstate=la;t.atlp&&(t.lstate=ea,t.atlp=0);break;case qa:t.npars=b-3&&!t.begin)return{numTokens:-1,newState:f,isExecutable:wa===Ob};n&&(1>8<<8|Z)}return{isExecutable:wa=== +Ob,newState:t}},make_lex_state:vc,copy_lex_state:kc,dump_token:a,set_state:function(a){kc(t,a)},initialize:function(a,b,c){t=vc();Fc(t);Pb=ma=a;v=0;X=b;lc=c;wa=qc},initialize_state:Fc,in_block_comment:function(a){a||(a=t);return 0=d&&h<=g&&l>=d&&l<=g)return b=e,!0});return b}}})},"MW/syntaxhighlighting/ColorMapDefaults":function(){define(["dojo/_base/declare"],function(e){return{typeMapDefaults:{122:"error",105:"comment",106:"comment",107:"comment",108:"comment",109:"comment",110:"comment",44:"string",45:"string",127:"type sections", +333:"keyword",337:"invalid",338:"system",339:"plain"},colorMapDefaults:{122:{r:255,g:0,b:0},105:{r:34,g:139,b:34},106:{r:34,g:139,b:34},107:{r:34,g:139,b:34},108:{r:34,g:139,b:34},109:{r:34,g:139,b:34},110:{r:34,g:139,b:34},44:{r:160,g:32,b:240},45:{r:160,g:32,b:240},127:{r:162,g:82,b:45},333:{r:0,g:0,b:255},337:{r:179,g:0,b:0},338:{r:179,g:140,b:0},339:{r:0,g:0,b:0}},HTMLColorMapDefaults:{122:"#ff0000",105:"#228b22",106:"#228b22",107:"#228b22",108:"#228b22",109:"#228b22",110:"#228b22",44:"#a020f0", +45:"#a020f0",127:"#a2522d",333:"#0000ff",337:"#b30000",338:"#b38c00",339:"#000000"}}})},"webview/palette/Palette":function(){define("dojo/_base/declare dojo/store/Memory dojo/dom-geometry dojo/dom-style dijit/_WidgetBase dijit/_Container dijit/_TemplatedMixin dojo/text!./templates/Palette.html".split(" "),function(e,k,h,l,b,m,d,g){return e([b,m,d],{templateString:g,postCreate:function(){this.inherited(arguments);this.buttonStore=new k},startup:function(){this.inherited(arguments);this._computedStyle= +l.getComputedStyle(this.domNode)},resize:function(b){var a=this.getChildren(),f,d,e=a.length;b&&h.setMarginBox(this.domNode,b,this._computedStyle);for(d=0;d>1)-l.y+"px",this.connectorNode.style.left=""):"M"==l.corner.charAt(1)&& +"M"==l.aroundCorner.charAt(1)?this.connectorNode.style.left=k.x+(k.w-this.connectorNode.offsetWidth>>1)-l.x+"px":(this.connectorNode.style.left="",this.connectorNode.style.top="");d.set(this.domNode,"opacity",0);this.fadeIn.play();this.isShowingNow=!0;this.aroundNode=b;this.onMouseEnter=h||w;this.onMouseLeave=n||w}},orient:function(a,b,c,d,e){this.connectorNode.style.top="";var g=d.h;d=d.w;a.className="dijitTooltip "+{"MR-ML":"dijitTooltipRight","ML-MR":"dijitTooltipLeft","TM-BM":"dijitTooltipAbove", +"BM-TM":"dijitTooltipBelow","BL-TL":"dijitTooltipBelow dijitTooltipABLeft","TL-BL":"dijitTooltipAbove dijitTooltipABLeft","BR-TR":"dijitTooltipBelow dijitTooltipABRight","TR-BR":"dijitTooltipAbove dijitTooltipABRight","BR-BL":"dijitTooltipRight","BL-BR":"dijitTooltipLeft"}[b+"-"+c];this.domNode.style.width="auto";var h=m.position(this.domNode);if(f("ie")||f("trident"))h.w+=2;var n=Math.min(Math.max(d,1),h.w);m.setMarginBox(this.domNode,{w:n});"B"==c.charAt(0)&&"B"==b.charAt(0)?(a=m.position(a),b= +this.connectorNode.offsetHeight,a.h>g?(this.connectorNode.style.top=g-(e.h+b>>1)+"px",this.connectorNode.style.bottom=""):(this.connectorNode.style.bottom=Math.min(Math.max(e.h/2-b/2,0),a.h-b)+"px",this.connectorNode.style.top="")):(this.connectorNode.style.top="",this.connectorNode.style.bottom="");return Math.max(0,h.w-d)},_onShow:function(){f("ie")&&(this.domNode.style.filter="")},hide:function(a){this._onDeck&&this._onDeck[1]==a?this._onDeck=null:this.aroundNode===a&&(this.fadeIn.stop(),this.isShowingNow= +!1,this.aroundNode=null,this.fadeOut.play());this.onMouseEnter=this.onMouseLeave=w},_onHide:function(){this.domNode.style.cssText="";this.containerNode.innerHTML="";this._onDeck&&(this.show.apply(this,this._onDeck),this._onDeck=null)}});x.showTooltip=function(a,b,c,f,d,g,h){c&&(c=e.map(c,function(a){return{after:"after-centered",before:"before-centered"}[a]||a}));A._masterTT||(x._masterTT=A._masterTT=new y);return A._masterTT.show(a,b,c,f,d,g,h)};x.hideTooltip=function(a){return A._masterTT&&A._masterTT.hide(a)}; +var A=k("dijit.Tooltip",n,{label:"",showDelay:400,hideDelay:400,connectId:[],position:[],selector:"",_setConnectIdAttr:function(b){e.forEach(this._connections||[],function(a){e.forEach(a,function(a){a.remove()})},this);this._connectIds=e.filter(g.isArrayLike(b)?b:b?[b]:[],function(a){return l.byId(a,this.ownerDocument)},this);this._connections=e.map(this._connectIds,function(b){b=l.byId(b,this.ownerDocument);var f=this.selector,d=f?function(b){return a.selector(f,b)}:function(a){return a},e=this; +return[a(b,d(c.enter),function(){e._onHover(this)}),a(b,d("focusin"),function(){e._onHover(this)}),a(b,d(c.leave),g.hitch(e,"_onUnHover")),a(b,d("focusout"),g.hitch(e,"set","state","DORMANT"))]},this);this._set("connectId",b)},addTarget:function(a){a=a.id||a;-1==e.indexOf(this._connectIds,a)&&this.set("connectId",this._connectIds.concat(a))},removeTarget:function(a){a=e.indexOf(this._connectIds,a.id||a);0<=a&&(this._connectIds.splice(a,1),this.set("connectId",this._connectIds))},buildRendering:function(){this.inherited(arguments); +b.add(this.domNode,"dijitTooltipData")},startup:function(){this.inherited(arguments);var a=this.connectId;e.forEach(g.isArrayLike(a)?a:[a],this.addTarget,this)},getContent:function(a){return this.label||this.domNode.innerHTML},state:"DORMANT",_setStateAttr:function(a){if(!(this.state==a||"SHOW TIMER"==a&&"SHOWING"==this.state||"HIDE TIMER"==a&&"DORMANT"==this.state)){this._hideTimer&&(this._hideTimer.remove(),delete this._hideTimer);this._showTimer&&(this._showTimer.remove(),delete this._showTimer); +switch(a){case "DORMANT":this._connectNode&&(A.hide(this._connectNode),delete this._connectNode,this.onHide());break;case "SHOW TIMER":"SHOWING"!=this.state&&(this._showTimer=this.defer(function(){this.set("state","SHOWING")},this.showDelay));break;case "SHOWING":var b=this.getContent(this._connectNode);if(!b){this.set("state","DORMANT");return}A.show(b,this._connectNode,this.position,!this.isLeftToRight(),this.textDir,g.hitch(this,"set","state","SHOWING"),g.hitch(this,"set","state","HIDE TIMER")); +this.onShow(this._connectNode,this.position);break;case "HIDE TIMER":this._hideTimer=this.defer(function(){this.set("state","DORMANT")},this.hideDelay)}this._set("state",a)}},_onHover:function(a){this._connectNode&&a!=this._connectNode&&this.set("state","DORMANT");this._connectNode=a;this.set("state","SHOW TIMER")},_onUnHover:function(a){this.set("state","HIDE TIMER")},open:function(a){this.set("state","DORMANT");this._connectNode=a;this.set("state","SHOWING")},close:function(){this.set("state","DORMANT")}, +onShow:function(){},onHide:function(){},destroy:function(){this.set("state","DORMANT");e.forEach(this._connections||[],function(a){e.forEach(a,function(a){a.remove()})},this);this.inherited(arguments)}});A._MasterTooltip=y;A.show=x.showTooltip;A.hide=x.hideTooltip;A.defaultPosition=["after-centered","before-centered"];return A})},"webview/palette/ExplorerBarButton":function(){define(["dojo/_base/declare","./PaletteButton","dojo/i18n!../resources/slreportgen_webview/nls/modelviewer"],function(e,k, +h){return e([k],{role:"ExplorerBar",iconClass:"Palette_Collapse",label:h.ExplorerBarButtonLabel,startup:function(){var e=this,b=this.app.modelViewer;this.inherited(arguments);this.update();this.own(b.watch("showExplorerBar",function(){e.update()}))},onClick:function(){var e=this.app.modelViewer;e.set("showExplorerBar",!e.get("showExplorerBar"));e.focus()},update:function(){this.set("iconClass",this.app.modelViewer.get("showExplorerBar")?"Palette_Collapse":"Palette_Expand")}})})},"webview/palette/PaletteSeparator":function(){define(["dojo/_base/declare", +"dojo/dom","dijit/_WidgetBase","dijit/_TemplatedMixin","dojo/text!./templates/PaletteSeparator.html"],function(e,k,h,l,b){return e([h,l],{templateString:b,role:"Separator",buildRendering:function(){this.inherited(arguments);k.setSelectable(this.domNode,!1)},isFocusable:function(){return!1}})})},"webview/palette/PaletteSpacer":function(){define("dojo/_base/declare dojo/dom dojo/dom-geometry dojo/dom-style dijit/_WidgetBase dijit/_Contained dijit/_TemplatedMixin".split(" "),function(e,k,h,l,b,m,d){return e([b, +m,d],{templateString:'\x3cdiv class\x3d"PaletteSpacer" role\x3d"presentation"\x3e\x3c/div\x3e',role:"spacer",height:null,buildRendering:function(){this.inherited(arguments);k.setSelectable(this.domNode,!1)},isFocusable:function(){return!1},postCreate:function(){this.height&&(l.set(this.domNode,"height",this.height+"px"),this.resize=function(){})},resize:function(){var b=this.getParent(),c=this.getIndexInParent(),a=h.position(b.domNode).h,f=0,d,b=b.getChildren();b.splice(c,1);c=b.length;for(d=0;d< +c;d+=1)f+=h.position(b[d].domNode).h;l.set(this.domNode,"height",a-f-2+"px")}})})},"webview/palette/FitToViewButton":function(){define(["dojo/_base/declare","./PaletteButton","dojo/i18n!../resources/slreportgen_webview/nls/modelviewer"],function(e,k,h){return e([k],{role:"FitToView",iconClass:"Palette_ZoomFitView",label:h.FitToViewButtonLabel,onClick:function(){var e=this.app.modelViewer,b=e.selectedDiagramTab.modelGraphicsPane;b&&b.fitToView();e.focus()}})})},"webview/palette/MarqueeZoomButton":function(){define("dojo/_base/declare dojo/on dijit/form/_ToggleButtonMixin ../tools/MarqueeZoomTool ./PaletteButton dojo/i18n!../resources/slreportgen_webview/nls/modelviewer".split(" "), +function(e,k,h,l,b,m){return e([b,h],{role:"MarqueeZoom",iconClass:"Palette_ZoomMarquee",label:m.MarqueeZoomButtonLabel,startup:function(){var b=this,e=new l;this.inherited(arguments);this.set("checked",!1);this.marqueeZoomTool=e;this.own(k(e,"done",function(){b.done()}),k(e,"idle",function(){b.done()}))},onClick:function(){var b=this,e=this.marqueeZoomTool;this.get("checked")?this.marqueeZoom():setTimeout(function(){e.isPersistent||b.done()},500);this.app.modelViewer.focus()},onDblClick:function(){this.marqueeZoom(!0)}, +marqueeZoom:function(b){var e=this.app.modelViewer.selectedDiagramTab.modelGraphicsPane.canvas.toolStack,c=this.marqueeZoomTool;c.isPersistent=b||!1;e.getTool(c.role)||(e.addTool(c),c.becomeAlert());this.set("checked",!0)},done:function(){var b=this.marqueeZoomTool;b&&!b.isDone()&&(b.isPersistent=!1,b.becomeDone());this.set("checked",!1)}})})},"webview/tools/MarqueeZoomTool":function(){define(["dojo/_base/declare","../utils/svg","../base/Rect","./Tool"],function(e,k,h,l){var b=e(null,{constructor:function(b, +d){var e=b.sceneServer.svgDocument.createElementNS(k.XMLNS,"rect");e.setAttribute("style","stroke: #99ccff; fill: #ffdbb7; fill-opacity: 0.6");b.sceneServer.foregroundScene.rootElement.appendChild(e);this.canvas=b;this.startPoint=d;this.rect=new h;this.svgRect=e},update:function(b){var d=this.rect,e=this.svgRect;b.x<=this.startPoint.x?(d.x=b.x,d.setRight(this.startPoint.x)):(d.x=this.startPoint.x,d.setRight(b.x-1));b.y<=this.startPoint.y?(d.y=b.y,d.setBottom(this.startPoint.y)):(d.y=this.startPoint.y, +d.setBottom(b.y-1));e.setAttribute("x",d.x);e.setAttribute("y",d.y);e.setAttribute("width",d.width);e.setAttribute("height",d.height)},destroy:function(){this.canvas.sceneServer.foregroundScene.rootElement.removeChild(this.svgRect)}});return e(l,{postMixInProperties:function(){this.role="MarqueeZoomTool";this.marqueeRect=null},isPersistent:!1,becomeActive:function(){this.inherited(arguments);this.canvas.selection.disable()},becomeAlert:function(){var b=this.canvas.cursor;this.inherited(arguments); +b.set("ZoomIn");this.removeMarqueeRect()},becomeIdle:function(){this.reset();this.inherited(arguments)},becomeDone:function(){this.reset();this.inherited(arguments)},handleMouseDownEvent:function(e){this.isAlert()&&e.isLeftMouse()&&(this.marqueeRect=new b(this.canvas,e.getMousePosition()),this.becomeActive())},handleMouseMoveEvent:function(b){var d=this.marqueeRect;this.isActive()&&d&&this.marqueeRect.update(b.getMousePosition())},handleClickEvent:function(b){var d=this.canvas,e,c;this.isActive()&& +(e=parseFloat(d.width()),c=parseFloat(d.height()),0.05*el("ie")&&!l("quirks");k=k(m,{columns:null,cellNavigation:!0,tabableHeader:!0,showHeader:!0,column:function(a){return"object"!=typeof a?this.columns[a]:this.cell(a).column},listType:"grid",cell:function(a,b){if(a.column&& +a.element)return a;a.target&&a.target.nodeType&&(a=a.target);var c;if(a.nodeType){do{if(this._rowIdToObject[a.id])break;var d=a.columnId;if(d){b=d;c=a;break}a=a.parentNode}while(a&&a!=this.domNode)}if(!c&&"undefined"!=typeof b){var e=this.row(a);if(d=e&&e.element)for(var d=d.getElementsByTagName("td"),g=0;gl("ie")||l("quirks")?b(k,"tbody"):k,s,x,w,y,A,B,C,F,K,G;g=g||this.subRows;x=0;for(w=g.length;x ]/;e([],k=function(e,b){function m(b){function k(){s&&(r&&s!=r)&&(r==b&&(p||(p=h.test(A)&& +e.createDocumentFragment()))?p:r).insertBefore(s,q||null)}for(var p,n,q,r,s,x=arguments,w=x[0],y=0;yy&&(b=null);n=!0;if(w=A.replace(d,function(d,h,n,p,w,B){h&&(k(),"-"==h||"+"==h?(r=(q=s||r).parentNode,s=null,"+"==h&&(q=q.nextSibling)): +("\x3c"==h?r=s=(s||r).parentNode:(","==h?r=b:s&&(r=s),s=null),q=0),s&&(r=s));if((d=!n&&p)||!s&&(n||w))"$"==d?(d=x[++y],r.appendChild(e.createTextNode(d))):(d=d||m.defaultTag,(h=a&&x[y+1]&&x[y+1].name)&&(d="\x3c"+d+' name\x3d"'+h+'"\x3e'),s=c&&~(g=d.indexOf("|"))?e.createElementNS(c[d.slice(0,g)],d.slice(g+1)):e.createElement(d));if(n)if("$"==p&&(p=x[++y]),"#"==n)s.id=p;else if(h=(d=s.className)&&(" "+d+" ").replace(" "+p+" "," "),"."==n)s.className=d?(h+p).substring(1):p;else if("!"==A){var N;a?m("div", +s,"\x3c").innerHTML="":(N=s.parentNode)&&N.removeChild(s)}else h=h.substring(1,h.length-1),h!=d&&(s.className=h);w&&("$"==B&&(B=x[++y]),"style"==w?s.style.cssText=B:(n="!"==w.charAt(0)?(w=w.substring(1))&&"removeAttribute":"setAttribute",B=""===B?w:B,c&&~(g=w.indexOf("|"))?s[n+"NS"](c[w.slice(0,g)],w.slice(g+1),B):s[n](w,B)));return""}))throw new SyntaxError("Unexpected char "+w+" in "+A);k();r=w=s||r}}b&&p&&b.appendChild(p);return w}h=b||h;var d=/(?:\s*([-+ ,<>]))?\s*(\.|!\.?|#)?([-\w\u00A0-\uFFFF%$|]+)?(?:\[([^\]=]+)=?['"]?([^\]'"]*)['"]?\])?/g, +g,c=!1;e=e||document;var a="object"==typeof e.createElement;m.addNamespace=function(a,b){e.createElementNS?(c||(c={}))[a]=b:e.namespaces.add(a,b)};m.defaultTag="div";m.forDocument=k;return m})})(function(e,k,h){h=h||k;"function"===typeof define?define([],function(){return h()}):"undefined"==typeof window?require("./node-html")(module,h):put=h()})},"dgrid/List":function(){define("dojo/_base/kernel dojo/_base/declare dojo/dom dojo/on dojo/has ./util/misc ./TouchScroll xstyle/has-class put-selector/put dojo/_base/sniff xstyle/css!./css/dgrid.css".split(" "), +function(e,k,h,l,b,m,d,g,c){function a(a,b){c(document.body,a,".dgrid-scrollbar-measure");var d=a["offset"+b]-a["client"+b];a.className="";document.body.removeChild(a);return d}function f(a){var b=a?"."+a.replace(x,"."):"";this._class&&(b="!"+this._class.replace(x,"!")+b);c(this.domNode,b);this._class=a}function u(){return this._class}function p(){return{x:this.bodyNode.scrollLeft,y:this.bodyNode.scrollTop}}function n(a){"undefined"!==typeof a.x&&(this.bodyNode.scrollLeft=a.x);"undefined"!==typeof a.y&& +(this.bodyNode.scrollTop=a.y)}g("mozilla","opera","webkit","ie","ie-6","ie-6-7","quirks","no-quirks","touch");var q,r;b.add("dom-scrollbar-width",function(b,c,d){return a(d,"Width")});b.add("dom-scrollbar-height",function(b,c,d){return a(d,"Height")});b.add("dom-rtl-scrollbar-left",function(a,d,f){a=c("div");c(document.body,f,".dgrid-scrollbar-measure[dir\x3drtl]");c(f,a);d=!!b("ie")||!!b("trident")||a.offsetLeft>=b("dom-scrollbar-width");f.className="";document.body.removeChild(f);c(a,"!");f.removeAttribute("dir"); +return d});var s=0,x=/ +/g,w=7>b("ie")&&!b("quirks")?function(){var a,b,c;if(this._started&&(a=document.documentElement,b=a.clientWidth,a=a.clientHeight,c=this._prevWinDims||[],c[0]!==b||c[1]!==a))this.resize(),this._prevWinDims=[b,a]}:function(){this._started&&this.resize()};return k(b("touch")?d:null,{tabableHeader:!1,showHeader:!1,showFooter:!1,maintainOddEven:!0,cleanAddedRules:!0,useTouchScroll:null,addUiClasses:!0,cleanEmptyObservers:!0,highlightDuration:250,postscript:function(a,b){var c=this; +(this._Row=function(a,b,c){this.id=a;this.data=b;this.element=c}).prototype.remove=function(){c.removeRow(this.element)};b&&(this.srcNodeRef=b=b.nodeType?b:document.getElementById(b));this.create(a,b)},listType:"list",create:function(a,d){var e=this.domNode=d||c("div"),g;a?(this.params=a,k.safeMixin(this,a),g=a["class"]||a.className||e.className,this._sort=a.sort||[],delete this.sort):this._sort=[];this.observers=[];this._numObservers=0;this._listeners=[];this._rowIdToObject={};this.postMixInProperties&& +this.postMixInProperties();this.id=e.id=e.id||this.id||"dgrid_"+s++;null===this.useTouchScroll&&(this.useTouchScroll=!b("dom-scrollbar-width"));this.buildRendering();g&&f.call(this,g);this.postCreate();delete this.srcNodeRef;this.domNode.offsetHeight&&this.startup()},buildRendering:function(){var a=this.domNode,d=this.addUiClasses,f=this,e,g,h,n;n=this.isRTL="rtl"==(document.body.dir||document.documentElement.dir||document.body.style.direction).toLowerCase();a.className="";c(a,"[role\x3dgrid].dgrid.dgrid-"+ +this.listType+(d?".ui-widget":""));e=this.headerNode=c(a,"div.dgrid-header.dgrid-header-row"+(d?".ui-widget-header":"")+(this.showHeader?"":".dgrid-header-hidden"));(b("quirks")||8>b("ie"))&&c(a,"div.dgrid-spacer");g=this.bodyNode=c(a,"div.dgrid-scroller");b("ff")&&(g.tabIndex=-1);this.headerScrollNode=c(a,"div.dgrid-header.dgrid-header-scroll.dgrid-scrollbar-width"+(d?".ui-widget-header":""));h=this.footerNode=c("div.dgrid-footer"+(this.showFooter?"":".dgrid-footer-hidden"));c(a,h);n&&(a.className+= +" dgrid-rtl"+(b("dom-rtl-scrollbar-left")?" dgrid-rtl-swap":""));l(g,"scroll",function(b){f.showHeader&&(e.scrollLeft=b.scrollLeft||g.scrollLeft);b.stopPropagation();l.emit(a,"scroll",{scrollTarget:g})});this.configStructure();this.renderHeader();this.contentNode=this.touchNode=c(this.bodyNode,"div.dgrid-content"+(d?".ui-widget-content":""));this._listeners.push(this._resizeHandle=l(window,"resize",m.throttleDelayed(w,this)))},postCreate:b("touch")?function(){this.useTouchScroll&&this.inherited(arguments)}: +function(){},startup:function(){this._started||(this.inherited(arguments),this._started=!0,this.resize(),this.set("sort",this._sort))},configStructure:function(){},resize:function(){var a=this.bodyNode,c=this.headerNode,d=this.footerNode,f=c.offsetHeight,e=this.showFooter?d.offsetHeight:0,g=b("quirks")||7>b("ie");this.headerScrollNode.style.height=a.style.marginTop=f+"px";a.style.marginBottom=e+"px";g&&(a.style.height="",a.style.height=Math.max(this.domNode.offsetHeight-f-e,0)+"px",e&&(d.style.bottom= +"1px",setTimeout(function(){d.style.bottom=""},0)));q||(q=b("dom-scrollbar-width"),r=b("dom-scrollbar-height"),b("ie")&&(q++,r++),m.addCssRule(".dgrid-scrollbar-width","width: "+q+"px"),m.addCssRule(".dgrid-scrollbar-height","height: "+r+"px"),17!=q&&!g&&(m.addCssRule(".dgrid-header-row","right: "+q+"px"),m.addCssRule(".dgrid-rtl-swap .dgrid-header-row","left: "+q+"px")));g&&(c.style.width=a.clientWidth+"px",setTimeout(function(){c.scrollLeft=a.scrollLeft},0))},addCssRule:function(a,b){var c=m.addCssRule(a, +b);this.cleanAddedRules&&this._listeners.push(c);return c},on:function(a,c){var d=l(this.domNode,a,c);b("dom-addeventlistener")||this._listeners.push(d);return d},cleanup:function(){var a=this.observers,b;for(b in this._rowIdToObject)if(this._rowIdToObject[b]!=this.columns){var c=document.getElementById(b);c&&this.removeRow(c,!0)}for(b=0;bb?"previousSibling":"nextSibling"]){do if((f=a)&&-1<(f.className+" ").indexOf(c+" ")){e=f;b+=0>b?1:-1;break}while(a=(!d||!f.hidden)&&f[0>b?"lastChild":"firstChild"])}else if(f=f.parentNode, +!f||f===this.bodyNode||f===this.headerNode)break;while(b);return e},up:function(a,b,c){a.element||(a=this.row(a));return this.row(this._move(a,-(b||1),"dgrid-row",c))},down:function(a,b,c){a.element||(a=this.row(a));return this.row(this._move(a,b||1,"dgrid-row",c))},scrollTo:b("touch")?function(a){return this.useTouchScroll?this.inherited(arguments):n.call(this,a)}:n,getScrollPosition:b("touch")?function(){return this.useTouchScroll?this.inherited(arguments):p.call(this)}:p,get:function(a){var b= +"_get"+a.charAt(0).toUpperCase()+a.slice(1);return"function"===typeof this[b]?this[b].apply(this,[].slice.call(arguments,1)):this[a]},set:function(a,b){if("object"===typeof a)for(var c in a)this.set(c,a[c]);else c="_set"+a.charAt(0).toUpperCase()+a.slice(1),"function"===typeof this[c]?this[c].apply(this,[].slice.call(arguments,1)):this[a]=b;return this},_getClass:u,_setClass:f,_getClassName:u,_setClassName:f,_setSort:function(a,b){this._sort="string"!=typeof a?a:[{attribute:a,descending:b}];this.refresh(); +this._lastCollection&&(a.length&&("string"!=typeof a&&(b=a[0].descending,a=a[0].attribute),this._lastCollection.sort(function(c,d){var f=c[a],e=d[a];void 0===f&&(f="");void 0===e&&(e="");return f==e?0:f>e==!b?1:-1})),this.renderArray(this._lastCollection))},sort:function(a,b){e.deprecated("sort(...)",'use set("sort", ...) instead',"dgrid 0.4");this.set("sort",a,b)},_getSort:function(){return this._sort},_setShowHeader:function(a){var b=this.headerNode;this.showHeader=a;c(b,(a?"!":".")+"dgrid-header-hidden"); +this.renderHeader();this.resize();a&&(b.scrollLeft=this.getScrollPosition().x)},setShowHeader:function(a){e.deprecated("setShowHeader(...)",'use set("showHeader", ...) instead',"dgrid 0.4");this.set("showHeader",a)},_setShowFooter:function(a){this.showFooter=a;c(this.footerNode,(a?"!":".")+"dgrid-footer-hidden");this.resize()}})})},"dgrid/util/misc":function(){define(["dojo/has","put-selector/put"],function(e,k){e.add("dom-contains",function(b,a,d){return!!d.contains});var h=[],l,b,m,d=/([^A-Za-z0-9_\u00A0-\uFFFF-])/g, +g={defaultDelay:15,throttle:function(b,a,d){var e=!1;d=d||g.defaultDelay;return function(){e||(e=!0,b.apply(a,arguments),setTimeout(function(){e=!1},d))}},throttleDelayed:function(b,a,d){var e=!1;d=d||g.defaultDelay;return function(){if(!e){e=!0;var g=arguments;setTimeout(function(){e=!1;b.apply(a,g)},d)}}},debounce:function(b,a,d){var e;d=d||g.defaultDelay;return function(){e&&(clearTimeout(e),e=null);var g=arguments;e=setTimeout(function(){b.apply(a,g)},d)}},each:function(b,a,d){var e,g;if(b)if("number"=== +typeof b.length){e=0;for(g=b.length;ea&&h[c]--}}}},escapeCssIdentifier:function(b,a){return"string"===typeof b?b.replace(d,a||"\\$1"):b}};return g})},"dgrid/TouchScroll":function(){define("dojo/_base/declare dojo/on ./util/touch ./util/has-css3 put-selector/put xstyle/css!./css/TouchScroll.css".split(" "),function(e,k,h,l,b){function m(a,b,c,d){d=a.touchNode;var f= +r[a.id],e,g,h;if("object"!==typeof b)h=b,b=c,c=g=!0;else{c="x"in b;g="y"in b;if(!c||!g)e=a.getScrollPosition();h=c?b.x:e.x;b=g?b.y:e.y}d.style[I]=O+-h+"px,"+-b+"px"+N;f&&(c&&a._scrollbarXNode)&&(a._scrollbarXNode.style[I]=O+h*f.parentWidth/f.scrollWidth+"px,0"+N);f&&(g&&a._scrollbarYNode)&&(a._scrollbarYNode.style[I]=O+"0,"+b*f.parentHeight/f.scrollHeight+"px"+N);k.emit(a.touchNode.parentNode,"scroll",{scrollLeft:h,scrollTop:b})}function d(a){return r[a.id]?A.exec(window.getComputedStyle(a.touchNode)[I]): +y.exec(a.touchNode.style[I])}function g(a){var c=this.widget,c=[this.node,c._scrollbarXNode,c._scrollbarYNode],d=c.length;this.timer&&(clearTimeout(this.timer),this.timer=null);for(this.transitionHandler&&this.transitionHandler.remove();d--;)c[d]&&(c[d].style[G+"Duration"]="0");(!a||!a.preserveScrollbars)&&b(this.node.parentNode,".touchscroll-fadeout");delete this.resetEffects}function c(a){var b=a.widget,c=b.touchNode,f=b.id,e=0,g=0,l;if(h.countCurrentTouches(a,c)===b.touchesToScroll){if(l=d(b))e= ++l[1],g=+l[2];if(l=r[f])l.resetEffects&&l.resetEffects({preserveScrollbars:!0}),c.style[I]=O+e+"px,"+g+"px"+N,s[f]=l;a=a.targetTouches[0];l=r[f]={widget:b,node:c,startX:e-a.pageX,startY:g-a.pageY,lastX:e,lastY:g,pageX:a.pageX,pageY:a.pageY,tickFunc:function(){var a=r[f],b,c;a&&(b=a.node,(c=y.exec(b.style[I]))?(b=+c[1],c=+c[2],a.velX=b-a.lastX,a.velY=c-a.lastY,a.lastX=b,a.lastY=c):a.lastX=a.lastY=0,a.timer=setTimeout(a.tickFunc,n))}};l.timer=setTimeout(l.tickFunc,n)}}function a(a){var c=a.widget,d= +c.id,f=c.touchesToScroll,e=r[d],g,n;if(!e||(g=h.countCurrentTouches(a,c.touchNode))!==f)g>f&&c.cancelTouchScroll();else{g=a.targetTouches;f=g[0];if(!e.scrollbarsShown&&(s[d]||Math.abs(f.pageX-e.pageX)>c.scrollThreshold||Math.abs(f.pageY-e.pageY)>c.scrollThreshold)){var d=c.touchNode,l=d.parentNode,k=l.offsetWidth-w,p=l.offsetHeight-w,q=e.scrollWidth=d.scrollWidth,x=e.scrollHeight=d.scrollHeight,u=e.parentWidth=l.offsetWidth,y=e.parentHeight=l.offsetHeight;q>u?(c._scrollbarXNode||(n=b(l,"div.touchscroll-x")), +n=c._scrollbarXNode=c._scrollbarXNode||b(n,"div.touchscroll-bar"),n.style.width=k*k/q+"px",n.style.left=d.offsetLeft+"px",b(l,".touchscroll-scrollable-x"),e.scrollableX=!0):b(l,"!touchscroll-scrollable-x");x>y?(c._scrollbarYNode||(n=b(l,"div.touchscroll-y")),n=c._scrollbarYNode=c._scrollbarYNode||b(n,"div.touchscroll-bar"),n.style.height=p*p/x+"px",n.style.top=d.offsetTop+"px",b(l,".touchscroll-scrollable-y"),e.scrollableY=!0):b(l,"!touchscroll-scrollable-y");b(l,"!touchscroll-fadeout");e.scrollbarsShown= +!0;for(n=g.length;n--;)g[n].touchScrolled=!0}if(e.scrollbarsShown&&(e.scrollableX||e.scrollableY))a.preventDefault(),a=e.scrollableX?e.startX+f.pageX:0,f=e.scrollableY?e.startY+f.pageY:0,n=e.scrollableX?-(e.scrollWidth-e.parentWidth):0,e=e.scrollableY?-(e.scrollHeight-e.parentHeight):0,0h?O+"0,0"+N:O+(g.parentNode.offsetWidth-g.offsetWidth)+ +"px,0"+N),n!=c&&f.scrollableY&&(g=f.widget._scrollbarYNode,g.style[G+"Duration"]=e.bounceDuration+"ms",g.style[I]=c>n?O+"0,0"+N:O+"0,"+(g.parentNode.offsetHeight-g.offsetHeight)+"px"+N)):d()}function p(a){var b=r[a],c=s[a],d,f;delete s[a];b.timer&&clearTimeout(b.timer);b.resetEffects=g;(d=y.exec(b.node.style[I]))?(f=+d[1],d=+d[2]):f=d=0;if(!b.velX&&!b.velY||(0<=f||f<=-(b.scrollWidth-b.parentWidth))&&(0<=d||d<=-(b.scrollHeight-b.parentHeight)))u(a,f,d);else{if(c&&(c.velX||c.velY)&&(0>=b.velX&&0>=c.velX|| +0<=b.velX&&0<=c.velX)&&(0>=b.velY&&0>=c.velY||0<=b.velY&&0<=c.velY))b.velX=1.15*(b.velX+c.velX),b.velY=1.15*(b.velY+c.velY);b.lastX=f;b.lastY=d;b.calcFunc=function(){var b=r[a],c,d,f,e,g,h;if(b)if(c=b.widget,g=c.glideDecel(b.velX),h=c.glideDecel(b.velY),Math.abs(g)>=x||Math.abs(h)>=x){f=b.lastX+g;e=b.lastY+h;if(0=d:!!d)==!m[1])document.documentElement.className+=" has-"+h}}})},"dgrid/OnDemandList":function(){define("./List ./_StoreMixin dojo/_base/declare dojo/_base/lang dojo/_base/Deferred dojo/dom dojo/on ./util/misc put-selector/put".split(" "), +function(e,k,h,l,b,m,d,g,c){return h([e,k],{minRowsPerPage:25,maxRowsPerPage:250,maxEmptySpace:Infinity,bufferRows:10,farOffRemoval:2E3,queryRowsOverlap:0,pagingMethod:"debounce",pagingDelay:g.defaultDelay,keepScrollPosition:!1,rowHeight:22,postCreate:function(){this.inherited(arguments);var a=this;d(this.bodyNode,"scroll",g[this.pagingMethod](function(b){a._processScroll(b)},null,this.pagingDelay))},renderQuery:function(a,d){function e(a){c(y,"!");if(a)throw g._refreshDeferred&&(g._refreshDeferred.reject(a), +delete g._refreshDeferred),a;}var g=this,h=d&&d.container||this.contentNode,k={query:a,count:0,options:d},m,s=this.preload,x,w={node:c(h,"div.dgrid-preload",{rowIndex:0}),count:0,query:a,next:k,options:d};w.node.style.height="0";k.node=m=c(h,"div.dgrid-preload");k.previous=w;m.rowIndex=this.minRowsPerPage;s?((k.next=s.next)&&m.offsetTop>=s.node.offsetTop?k.previous=s:(k.next=s,k.previous=s.previous),k.previous.next=k,k.next.previous=k):this.preload=k;var y=c(m,"-div.dgrid-loading");c(y,"div.dgrid-below").innerHTML= +this.loadingMessage;d=l.mixin(this.get("queryOptions"),d,{start:0,count:this.minRowsPerPage},"level"in a?{queryLevel:a.level}:null);this._trackError(function(){return x=a(d)});if("undefined"===typeof x)e();else return b.when(g.renderArray(x,m,d),function(a){return b.when("undefined"===typeof x.total?x.length:x.total,function(b){var e=a.length,h=m.parentNode,n=g.noDataNode;c(y,"!");"queryLevel"in d||(g._total=b);0===b&&(n&&(c(n,"!"),delete g.noDataNode),g.noDataNode=n=c("div.dgrid-no-data"),h.insertBefore(n, +g._getFirstRowSibling(h)),n.innerHTML=g.noDataMessage);for(n=h=0;n2*l){for(var m,p=k[f],q=0,s=0,r=[];m=p;){var x=h._calcRowHeight(m);if(q+x+l>b||0>p.className.indexOf("dgrid-row")&&0>p.className.indexOf("dgrid-loading"))break; +p=m[f];q+=x;s+=m.count||1;h.removeRow(m,!0);r.push(m)}a.count+=s;g?(k.rowIndex-=s,e(a)):k.style.height=k.offsetHeight+q+"px";var w=c("div",r);setTimeout(function(){c(w,"!")},1)}}function e(a,b){a.node.style.height=Math.min(a.count*h.rowHeight,b?Infinity:h.maxEmptySpace)+"px"}function g(a,b){do a=b?a.next:a.previous;while(a&&!a.node.offsetWidth);return a}var h=this,k=h.bodyNode;a=a&&a.scrollTop||this.getScrollPosition().y;var k=k.offsetHeight+a,m,s,x=h.preload,w=h.lastScrollTop,y=h.bufferRows*h.rowHeight, +A=y-h.rowHeight,B,C,F,K=!0;for(h.lastScrollTop=a;x&&!x.node.offsetWidth;)x=x.previous;for(;x&&x!=m;){m=h.preload;h.preload=x;s=x.node;var G=s.offsetTop;if(k+1+AG+s.offsetHeight)x=g(x,K=!0);else{var I=((s.rowIndex?a-y:k)-G)/h.rowHeight,G=(k-a+2*y)/h.rowHeight,O=Math.max(Math.min((a-w)*h.rowHeight,h.maxRowsPerPage/2),h.maxRowsPerPage/-2),G=G+Math.min(Math.abs(O),10);0==s.rowIndex&&(I-=G);I=Math.max(I,0);10>I&&(0a)&&x){var L=x.previous;L&&(d(L,a-(L.node.offsetTop+L.node.offsetHeight),"nextSibling"),0h._total||0>N.count)){s=c(T,"-div.dgrid-loading[style\x3dheight:"+G*h.rowHeight+"px]");c(s,"div.dgrid-"+(O?"below": +"above")).innerHTML=h.loadingMessage;s.count=G;var J=x.query(N);if(void 0===h._trackError(function(){return J})){c(s,"!");return}(function(a,d,f,g){F=b.when(h.renderArray(g,a,N),function(l){C=g;T=a.nextSibling;c(a,"!");if(f&&T&&T.offsetWidth){var k=h.getScrollPosition();h.scrollTo({x:k.x,y:k.y+T.offsetTop-f,preserveMomentum:!0})}b.when(g.total||g.length,function(a){"queryLevel"in N||(h._total=a);d&&(d.count=a-d.node.rowIndex,0===d.count&&N.count++,e(d))});h._processScroll();return l},function(b){c(a, +"!");throw b;})}).call(this,s,O,P,J);x=x.previous}}}}if(F&&(B=this._refreshDeferred))delete this._refreshDeferred,b.when(F,function(){B.resolve(C)})},removeRow:function(a,b){if(a){var c=a.previousSibling,d=a.nextSibling,c=c&&(null!=c.observerIndex?c.observerIndex:c.previousObserverIndex),e=d&&(null!=d.observerIndex?d.observerIndex:d.nextObserverIndex),d=a.observerIndex;a.observerIndex=void 0;b&&(a.nextObserverIndex=e,a.previousObserverIndex=c);if(this.cleanEmptyObservers&&(-1this._numObservers&&this.refresh({keepScrollPosition:!0})},refresh:function(){var a=this.inherited(arguments);this.store||(this.noDataNode=d(this.contentNode, +"div.dgrid-no-data"),this.noDataNode.innerHTML=this.noDataMessage);return a},renderArray:function(){var a=this,b=this.inherited(arguments);this.store||l.when(b,function(b){b.length&&a.noDataNode&&d(a.noDataNode,"!")});return b},insertRow:function(a,b,c,d,e){var g=this.store,l=this.dirty,g=g&&g.getIdentity(a),k;g in l&&!(g in this._updating)&&(k=l[g]);k&&(a=h.delegate(a,k));return this.inherited(arguments)},updateDirty:function(a,b,c){var d=this.dirty,e=d[a];e||(e=d[a]={});e[b]=c},setDirty:function(a, +b,c){e.deprecated("setDirty(...)","use updateDirty() instead","dgrid 0.4");this.updateDirty(a,b,c)},save:function(){function a(a,e){return function(g){var h=b._columnsWithSet,k=b._updating,n,m;if("function"===typeof g.set)g.set(e);else for(n in e)g[n]=e[n];for(n in h)m=h[n].set(g),void 0!==m&&(g[n]=m);k[a]=!0;return l.when(c.put(g),function(){delete d[a];delete k[a]})}}var b=this,c=this.store,d=this.dirty,e=new l,g=e.promise,h=function(a){var d;return b.getBeforePut||!(d=b.row(a).data)?function(){return c.get(a)}: +function(){return d}},k;for(k in d)var m=a(k,d[k]),g=g.then(h(k)).then(m);e.resolve();return g},revert:function(){this.dirty={};this.refresh()},_trackError:function(a){var b;"string"==typeof a&&(a=h.hitch(this,a));try{b=a()}catch(d){c.call(this,d)}return l.when(b,g,h.hitch(this,c))},newRow:function(){var a=this.inherited(arguments);this.noDataNode&&(d(this.noDataNode,"!"),delete this.noDataNode);return a},removeRow:function(a,b){var c={element:a};!b&&(this.noDataMessage&&this.up(c).element===a&&this.down(c).element=== +a)&&(this.noDataNode=d(this.contentNode,"div.dgrid-no-data"),this.noDataNode.innerHTML=this.noDataMessage);return this.inherited(arguments)}})})},"dgrid/Selection":function(){define("dojo/_base/kernel dojo/_base/declare dojo/_base/Deferred dojo/on dojo/has dojo/aspect ./List ./util/has-pointer ./util/touch put-selector/put dojo/query dojo/_base/sniff".split(" "),function(e,k,h,l,b,m,d,g,c,a){function f(a,b){for(var c=a.unselectable=b?"on":"",d=a.getElementsByTagName("*"),e=d.length;--e;)"INPUT"=== +d[e].tagName||"TEXTAREA"===d[e].tagName||(d[e].unselectable=c)}function u(a,c){var d=a.bodyNode,e=c?"text":21>b("ff")?"-moz-none":"none";n&&"msUserSelect"!==n?d.style[n]=e:b("dom-selectstart")?!c&&!a._selectstartHandle?a._selectstartHandle=l(d,"selectstart",function(a){var b=a.target&&a.target.tagName;"INPUT"!==b&&"TEXTAREA"!==b&&a.preventDefault()}):c&&a._selectstartHandle&&(a._selectstartHandle.remove(),delete a._selectstartHandle):(f(d,!c),!c&&!a._unselectableHandle?a._unselectableHandle=m.after(a, +"renderRow",function(a){f(a,!0);return a}):c&&a._unselectableHandle&&(a._unselectableHandle.remove(),delete a._unselectableHandle))}b.add("dom-comparedocumentposition",function(a,b,c){return!!c.compareDocumentPosition});b.add("css-user-select",function(a,b,c){a=c.style;b=["Khtml","O","ms","Moz","Webkit"];c=b.length;var d="userSelect";do if("undefined"!==typeof a[d])return d;while(c--&&(d=b[c]+"UserSelect"));return!1});b.add("dom-selectstart","undefined"!==typeof document.onselectstart);var p=b("mac")? +"metaKey":"ctrlKey",n=b("css-user-select");d=g.pointer;g=g.MSPointer;var q=d?d+(g?"Down":"down"):"mousedown",r=d?d+(g?"Up":"up"):"mouseup";return k(null,{selectionDelegate:".dgrid-row",selectionEvents:q+","+r+",dgrid-cellfocusin",selectionTouchEvents:b("touch")?c.tap:null,deselectOnRefresh:!0,allowSelectAll:!1,selection:{},selectionMode:"extended",allowTextSelection:void 0,_selectionTargetType:"rows",create:function(){this.selection={};return this.inherited(arguments)},postCreate:function(){this.inherited(arguments); +this._initSelectionEvents();var a=this.selectionMode;this.selectionMode="";this._setSelectionMode(a)},destroy:function(){this.inherited(arguments);this._selectstartHandle&&this._selectstartHandle.remove();this._unselectableHandle&&this._unselectableHandle.remove();this._removeDeselectSignals&&this._removeDeselectSignals()},_setSelectionMode:function(a){a!=this.selectionMode&&(this.clearSelection(),this.selectionMode=a,this._selectionHandlerName="_"+a+"SelectionHandler",this._setAllowTextSelection(this.allowTextSelection))}, +setSelectionMode:function(a){e.deprecated("setSelectionMode(...)",'use set("selectionMode", ...) instead',"dgrid 0.4");this.set("selectionMode",a)},_setAllowTextSelection:function(a){"undefined"!==typeof a?u(this,a):u(this,"none"===this.selectionMode);this.allowTextSelection=a},_handleSelect:function(a,b){if(this[this._selectionHandlerName]&&this.allowSelect(this.row(b))&&!("dgrid-cellfocusin"===a.type&&a.parentType===q||a.type===r&&b!=this._waitForMouseUp)){this._waitForMouseUp=null;this._selectionTriggerEvent= +a;if(!a.keyCode||!a.ctrlKey||32==a.keyCode)if(!a.shiftKey&&a.type===q&&this.isSelected(b))this._waitForMouseUp=b;else this[this._selectionHandlerName](a,b);this._selectionTriggerEvent=null}},_singleSelectionHandler:function(a,b){var c=a.keyCode?a.ctrlKey:a[p];this._lastSelected===b?this.select(b,null,!c||!this.isSelected(b)):(this.clearSelection(),this.select(b),this._lastSelected=b)},_multipleSelectionHandler:function(a,b){var c=this._lastSelected,d=a.keyCode?a.ctrlKey:a[p],e;a.shiftKey||(e=d?null: +!0,c=null);this.select(b,c,e);c||(this._lastSelected=b)},_extendedSelectionHandler:function(a,b){(2===a.button?!this.isSelected(b):!(a.keyCode?a.ctrlKey:a[p]))&&this.clearSelection(null,!0);this._multipleSelectionHandler(a,b)},_toggleSelectionHandler:function(a,b){this.select(b,null,null)},_initSelectionEvents:function(){var a=this,d=this.contentNode,e=this.selectionDelegate;this._selectionEventQueues={deselect:[],select:[]};b("touch")&&!b("pointer")&&this.selectionTouchEvents?(l(d,c.selector(e,this.selectionTouchEvents), +function(b){a._handleSelect(b,this);a._ignoreMouseSelect=this}),l(d,l.selector(e,this.selectionEvents),function(b){a._ignoreMouseSelect!==this?a._handleSelect(b,this):b.type===r&&(a._ignoreMouseSelect=null)})):l(d,l.selector(e,this.selectionEvents),function(b){a._handleSelect(b,this)});this.addKeyHandler&&this.addKeyHandler(32,function(b){a._handleSelect(b,b.target)});if(this.allowSelectAll)this.on("keydown",function(b){b[p]&&(65==b.keyCode&&!/\bdgrid-input\b/.test(b.target.className))&&(b.preventDefault(), +a[a.allSelected?"clearSelection":"selectAll"]())});this._setStore&&m.after(this,"_setStore",function(){a._updateDeselectionAspect()});this._updateDeselectionAspect()},_updateDeselectionAspect:function(){function a(c,d,e){c=d||c&&c[b.idProperty||"id"];if(null!=c&&(d=(c=b.row(c))&&b.selection[c.id]))b[e](c,null,d)}var b=this,c=this.store,d,e;this._removeDeselectSignals&&this._removeDeselectSignals();c&&c.notify?(d=m.before(c,"notify",function(b,c){b||a(b,c,"deselect")}),e=m.after(c,"notify",function(b, +c){a(b,c,"select")},!0),this._removeDeselectSignals=function(){d.remove();e.remove()}):(d=m.before(this,"removeRow",function(a,b){var c;b||(c=this.row(a))&&c.id in this.selection&&this.deselect(c)}),this._removeDeselectSignals=function(){d.remove()})},allowSelect:function(a){return!0},_fireSelectionEvent:function(a){var b=this._selectionEventQueues[a],c=this._selectionTriggerEvent,d;d={bubbles:!0,grid:this};c&&(d.parentType=c.type);d[this._selectionTargetType]=b;l.emit(this.contentNode,"dgrid-"+a, +d);this._selectionEventQueues[a]=[]},_fireSelectionEvents:function(){var a=this._selectionEventQueues,b;for(b in a)a[b].length&&this._fireSelectionEvent(b)},_select:function(b,c,d){var e,f,g;"undefined"===typeof d&&(d=!0);b.element||(b=this.row(b));if(!1===d||this.allowSelect(b))if(e=this.selection,f=!!e[b.id],null===d&&(d=!f),g=b.element,!d&&!this.allSelected?delete this.selection[b.id]:e[b.id]=d,g&&(d?a(g,".dgrid-selected"+(this.addUiClasses?".ui-state-active":"")):a(g,"!dgrid-selected!ui-state-active")), +d!==f&&g&&this._selectionEventQueues[(d?"":"de")+"select"].push(b),c)if(c.element||(c=this.row(c)),c){if(c=c.element){e=this._determineSelectionDirection(g,c);e||(c=document.getElementById(c.id),e=this._determineSelectionDirection(g,c));for(;b.element!=c&&(b=this[e](b));)this._select(b,null,d)}}else this._lastSelected=g,console.warn("The selection range has been reset because the beginning of the selection is no longer in the DOM. If you are using OnDemandList, you may wish to increase farOffRemoval to avoid this, but note that keeping more nodes in the DOM may impact performance.")}, +_determineSelectionDirection:b("dom-comparedocumentposition")?function(a,b){var c=b.compareDocumentPosition(a);return c&1?!1:2===c?"down":"up"}:function(a,b){return 1>b.sourceIndex?!1:b.sourceIndex>a.sourceIndex?"down":"up"},select:function(a,b,c){this._select(a,b,c);this._fireSelectionEvents()},deselect:function(a,b){this.select(a,b,!1)},clearSelection:function(a,b){this.allSelected=!1;for(var c in this.selection)a!==c&&this._select(c,null,!1);b||(this._lastSelected=null);this._fireSelectionEvents()}, +selectAll:function(){this.allSelected=!0;this.selection={};for(var a in this._rowIdToObject){var b=this.row(this._rowIdToObject[a]);this._select(b.id,null,!0)}this._fireSelectionEvents()},isSelected:function(a){if("undefined"===typeof a||null===a)return!1;a.element||(a=this.row(a));return a.id in this.selection?!!this.selection[a.id]:this.allSelected&&(!a.data||this.allowSelect(a))},refresh:function(){this.deselectOnRefresh&&this.clearSelection();this._lastSelected=null;return this.inherited(arguments)}, +renderArray:function(){var a=this,b=this.inherited(arguments);h.when(b,function(b){var c=a.selection,d,e,f;for(d=0;db("ie")&&(n.style.position="relative");n.focus();8>b("ie")&&(n.style.position="");r=!0;break}}null!==d&&(d=l.mixin({grid:this},d),d.type&&(d.parentType=d.type),d.bubbles||(d.bubbles=!0));c&&(m(c,"!dgrid-focus[!tabIndex]"),8>b("ie")&&(c.style.position=""),d&&(d[f]=this[f](c),h.emit(c,"dgrid-cellfocusout",d)));c=this[e]=a;d&&(d[f]=g);e=this.cellNavigation?u:p;!r&&e.test(a.className)&&(8>b("ie")&&(a.style.position="relative"), +a.tabIndex=this.tabIndex,a.focus());m(a,".dgrid-focus");d&&h.emit(c,"dgrid-cellfocusin",d)}},focusHeader:function(a){this._focusOnNode(a||this._focusedHeaderNode,!0)},focus:function(a){(a=a||this._focusedNode)?this._focusOnNode(a,!1):this.contentNode.focus()}}),s=r.moveFocusVertical=function(a,b){var c=this.cellNavigation,d=this[c?"cell":"row"](a),d=c&&d.column.id,e=this.down(this._focusedNode,b,!0);c&&(e=this.cell(e,d));this._focusOnNode(e,!1,a);a.preventDefault()};e=r.moveFocusUp=function(a){s.call(this, +a,-1)};n=r.moveFocusDown=function(a){s.call(this,a,1)};d=r.moveFocusPageUp=function(a){s.call(this,a,-this.pageSkip)};var x=r.moveFocusPageDown=function(a){s.call(this,a,this.pageSkip)},w=r.moveFocusHorizontal=function(a,b){if(this.cellNavigation){var c=!this.row(a);this._focusOnNode(this.right(this["_focused"+(c?"Header":"")+"Node"],b),c,a);a.preventDefault()}},y=r.moveFocusLeft=function(a){w.call(this,a,-1)},A=r.moveFocusRight=function(a){w.call(this,a,1)},B=r.moveHeaderFocusEnd=function(a,b){var c; +this.cellNavigation&&(c=this.headerNode.getElementsByTagName("th"),this._focusOnNode(c[b?0:c.length-1],!0,a));a.preventDefault()},C=r.moveHeaderFocusHome=function(a){B.call(this,a,!0)},F=r.moveFocusEnd=function(a,d){var e=this,f=this.cellNavigation,g=this.contentNode,h=g.scrollTop+(d?0:g.scrollHeight),g=g[d?"firstChild":"lastChild"],n=-1m.className.indexOf("dgrid-row");)m= +m[(d?"next":"previous")+"Sibling"];if(!m)return}!n||1>g.offsetHeight?(f&&(m=this.cell(m,this.cell(a).column.id)),this._focusOnNode(m,!1,a)):(b("dom-addeventlistener")||(a=l.mixin({},a)),q=k.after(this,"renderArray",function(b){q.remove();return c.when(b,function(b){b=b[d?0:b.length-1];f&&(b=e.cell(b,e.cell(a).column.id));e._focusOnNode(b,!1,a)})}));h===p&&a.preventDefault()},K=r.moveFocusHome=function(a){F.call(this,a,!0)};r.defaultKeyMap={32:a,33:d,34:x,35:F,36:K,37:y,38:e,39:A,40:n};r.defaultHeaderKeyMap= +{32:a,35:B,36:C,37:y,39:A};return r})},"dgrid/extensions/ColumnResizer":function(){define("dojo/_base/declare dojo/on dojo/query dojo/_base/lang dojo/dom dojo/dom-construct dojo/dom-geometry dojo/has ../util/misc put-selector/put dojo/_base/html xstyle/css!../css/extensions/ColumnResizer.css".split(" "),function(e,k,h,l,b,m,d,g,c,a){function f(a){for(var b=a.length,c=b,d=a[0].length,e=Array(b);b--;)e[b]=Array(d);for(var f={},b=0;b=d)){var g=a.columns[b],h;if(g&&(h={grid:a,columnId:b,width:d,bubbles:!0,cancelable:!0},e&&(h.parentType=e),!a._resizedColumns||k.emit(a.headerNode,"dgrid-columnresize",h)))return"auto"=== +d?delete g.width:(g.width=d,d+="px"),(e=a._columnSizes[b])?e.set("width",d):e=c.addCssRule("#"+c.escapeCssIdentifier(a.domNode.id)+" .dgrid-column-"+c.escapeCssIdentifier(b,"-"),"width: "+d+";"),a._columnSizes[b]=e,!1!==f&&a.resize(),!0}}var p,n,q=0,r={create:function(){p=a("div.dgrid-column-resizer");n=m.create("div",{className:"dgrid-resize-guard"})},destroy:function(){a(p,"!");m.destroy(n);p=n=null},show:function(b){var c=d.position(b.domNode,!0);p.style.top=c.y+"px";p.style.height=c.h+"px";a(document.body, +p);b.domNode.appendChild(n)},move:function(a){p.style.left=a+"px"},hide:function(){p.parentNode.removeChild(p);n.parentNode.removeChild(n)}};return e(null,{resizeNode:null,minWidth:40,adjustLastColumn:!0,_resizedColumns:!1,buildRendering:function(){this.inherited(arguments);q++||r.create()},destroy:function(){this.inherited(arguments);for(var a in this._columnSizes)this._columnSizes[a].remove();--q||r.destroy()},resizeColumnWidth:function(a,b){return u(this,a,b)},configStructure:function(){var a= +this._oldColumnSizes=l.mixin({},this._columnSizes),b;this._resizedColumns=!1;this._columnSizes={};this.inherited(arguments);for(b in a)b in this._columnSizes||a[b].remove();delete this._oldColumnSizes},_configColumn:function(a){this.inherited(arguments);var b=a.id,d;"width"in a&&((d=this._oldColumnSizes[b])?d.set("width",a.width+"px"):d=c.addCssRule("#"+c.escapeCssIdentifier(this.domNode.id)+" .dgrid-column-"+c.escapeCssIdentifier(b,"-"),"width: "+a.width+"px;"),this._columnSizes[b]=d)},renderHeader:function(){this.inherited(arguments); +var b=this,d;if(this.columnSets&&this.columnSets.length)for(var e=this.columnSets.length;e--;)d=l.mixin(d||{},f(this.columnSets[e]));else this.subRows&&1b?f.w=b:ed("ie")&&this.defer(function(){try{var a=h.getComputedStyle(this.domNode);if(a){var b=a.fontFamily;if(b){var c=this.domNode.getElementsByTagName("INPUT");if(c)for(a=0;ad("ie")&&(e.prototype._isTextSelected=function(){var a=this.ownerDocument.selection.createRange(); +return a.parentElement()==this.textbox&&0=c||48<=c&&57>=c||c==b.SPACE)return;c=!1;for(var e in b)if(b[e]===a.keyCode){c=!0;break}if(!c)return}}(c=32<=a.charCode?String.fromCharCode(a.charCode):a.charCode)||(c=65<=a.keyCode&&90>=a.keyCode||48<=a.keyCode&&57>=a.keyCode||a.keyCode==b.SPACE?String.fromCharCode(a.keyCode):a.keyCode);c||(c=229);if("keypress"==a.type){if("string"!=typeof c)return;if("a"<=c&&"z">=c||"A"<=c&&"Z">=c||"0"<=c&&"9">=c||" "===c)if(a.ctrlKey||a.metaKey||a.altKey)return}var g={faux:!0},h;for(h in a)/^(layer[XY]|returnValue|keyLocation)$/.test(h)|| +(e=a[h],"function"!=typeof e&&"undefined"!=typeof e&&(g[h]=e));m.mixin(g,{charOrCode:c,_wasConsumed:!1,preventDefault:function(){g._wasConsumed=!0;a.preventDefault()},stopPropagation:function(){a.stopPropagation()}});this._lastInputProducingEvent=g;!1===this.onInput(g)&&(g.preventDefault(),g.stopPropagation());if(!g._wasConsumed&&9>=l("ie"))switch(a.keyCode){case b.TAB:case b.ESCAPE:case b.DOWN_ARROW:case b.UP_ARROW:case b.LEFT_ARROW:case b.RIGHT_ARROW:break;default:if(a.keyCode==b.ENTER&&"textarea"!= +this.textbox.tagName.toLowerCase())break;this.defer(function(){this.textbox.value!==this._lastInputEventValue&&d.emit(this.textbox,"input",{bubbles:!0})})}})),d(this.textbox,"input",m.hitch(this,"_onInput")),d(this.domNode,"keypress",function(a){a.stopPropagation()}))},_blankValue:"",filter:function(a){if(null===a)return this._blankValue;if("string"!=typeof a)return a;this.trim&&(a=m.trim(a));this.uppercase&&(a=a.toUpperCase());this.lowercase&&(a=a.toLowerCase());this.propercase&&(a=a.replace(/[^\s]+/g, +function(a){return a.substring(0,1).toUpperCase()+a.substring(1)}));return a},_setBlurValue:function(){this._setValueAttr(this.get("value"),!0)},_onBlur:function(a){this.disabled||(this._setBlurValue(),this.inherited(arguments))},_isTextSelected:function(){return this.textbox.selectionStart!=this.textbox.selectionEnd},_onFocus:function(a){!this.disabled&&!this.readOnly&&(this.selectOnClick&&"mouse"==a&&(this._selectOnClickHandle=d.once(this.domNode,"mouseup, touchend",m.hitch(this,function(a){this._isTextSelected()|| +c.selectInputText(this.textbox)})),this.own(this._selectOnClickHandle),this.defer(function(){this._selectOnClickHandle&&(this._selectOnClickHandle.remove(),this._selectOnClickHandle=null)},500)),this.inherited(arguments),this._refreshState())},reset:function(){this.textbox.value="";this.inherited(arguments)}});c._setSelectionRange=g._setSelectionRange=function(a,b,c){a.setSelectionRange&&a.setSelectionRange(b,c)};c.selectInputText=g.selectInputText=function(a,b,d){a=h.byId(a);isNaN(b)&&(b=0);isNaN(d)&& +(d=a.value?a.value.length:0);try{a.focus(),c._setSelectionRange(a,b,d)}catch(e){}};return c})},"dijit/TooltipDialog":function(){define("dojo/_base/declare dojo/dom-class dojo/has dojo/keys dojo/_base/lang dojo/on ./focus ./layout/ContentPane ./_DialogMixin ./form/_FormMixin ./_TemplatedMixin dojo/text!./templates/TooltipDialog.html ./main".split(" "),function(e,k,h,l,b,m,d,g,c,a,f,u,p){return e("dijit.TooltipDialog",[g,f,a,c],{title:"",doLayout:!1,autofocus:!0,baseClass:"dijitTooltipDialog",_firstFocusItem:null, +_lastFocusItem:null,templateString:u,_setTitleAttr:"containerNode",postCreate:function(){this.inherited(arguments);this.own(m(this.domNode,"keydown",b.hitch(this,"_onKey")))},orient:function(a,b,c){a={"MR-ML":"dijitTooltipRight","ML-MR":"dijitTooltipLeft","TM-BM":"dijitTooltipAbove","BM-TM":"dijitTooltipBelow","BL-TL":"dijitTooltipBelow dijitTooltipABLeft","TL-BL":"dijitTooltipAbove dijitTooltipABLeft","BR-TR":"dijitTooltipBelow dijitTooltipABRight","TR-BR":"dijitTooltipAbove dijitTooltipABRight", +"BR-BL":"dijitTooltipRight","BL-BR":"dijitTooltipLeft","BR-TL":"dijitTooltipBelow dijitTooltipABLeft","BL-TR":"dijitTooltipBelow dijitTooltipABRight","TL-BR":"dijitTooltipAbove dijitTooltipABRight","TR-BL":"dijitTooltipAbove dijitTooltipABLeft"}[b+"-"+c];k.replace(this.domNode,a,this._currentOrientClass||"");this._currentOrientClass=a},focus:function(){this._getFocusItems();d.focus(this._firstFocusItem)},onOpen:function(a){this.orient(this.domNode,a.aroundCorner,a.corner);var b=a.aroundNodePos;"M"== +a.corner.charAt(0)&&"M"==a.aroundCorner.charAt(0)?(this.connectorNode.style.top=b.y+(b.h-this.connectorNode.offsetHeight>>1)-a.y+"px",this.connectorNode.style.left=""):"M"==a.corner.charAt(1)&&"M"==a.aroundCorner.charAt(1)&&(this.connectorNode.style.left=b.x+(b.w-this.connectorNode.offsetWidth>>1)-a.x+"px");this._onShow()},onClose:function(){this.onHide()},_onKey:function(a){if(a.keyCode==l.ESCAPE)this.defer("onCancel"),a.stopPropagation(),a.preventDefault();else if(a.keyCode==l.TAB){var b=a.target; +this._getFocusItems();this._firstFocusItem==this._lastFocusItem?(a.stopPropagation(),a.preventDefault()):b==this._firstFocusItem&&a.shiftKey?(d.focus(this._lastFocusItem),a.stopPropagation(),a.preventDefault()):b==this._lastFocusItem&&!a.shiftKey?(d.focus(this._firstFocusItem),a.stopPropagation(),a.preventDefault()):a.stopPropagation()}}})})},"dijit/_DialogMixin":function(){define(["dojo/_base/declare","./a11y"],function(e,k){return e("dijit._DialogMixin",null,{actionBarTemplate:"",execute:function(){}, +onCancel:function(){},onExecute:function(){},_onSubmit:function(){this.onExecute();this.execute(this.get("value"))},_getFocusItems:function(){var e=k._getTabNavigable(this.domNode);this._firstFocusItem=e.lowest||e.first||this.closeButtonNode||this.domNode;this._lastFocusItem=e.last||e.highest||this._firstFocusItem}})})},"webview/search/SearchFieldsPanel":function(){define("dojo/_base/declare dojo/_base/array dojo/dom dojo/store/Memory dijit/_WidgetBase dijit/_TemplatedMixin dijit/form/CheckBox dojo/i18n!../resources/slreportgen_webview/nls/modelviewer dojo/text!./templates/SearchFieldsPanel.html".split(" "), +function(e,k,h,l,b,m,d,g,c){return e([b,m],{templateString:c,startup:function(){var a=this.finder.searchFields,b=new l,c=this,e=function(b){a.set(this.searchField,b)};this.inherited(arguments);k.forEach(["name","blockType","maskType","propertyName","propertyValue"],function(k){var l=c.id+"-"+k,m=new d({searchField:k,checked:a[k],onChange:e},l);h.byId(l+"-label").innerHTML=g[k];b.add({id:k,checkBox:m});m.startup();c.own(m)});this.own(a.watch(function(a,c,d){(a=b.get(a))&&a.checkBox&&a.checkBox.set("checked", +d)}))}})})},"dijit/form/CheckBox":function(){define("require dojo/_base/declare dojo/dom-attr dojo/has dojo/query dojo/ready ./ToggleButton ./_CheckBoxMixin dojo/text!./templates/CheckBox.html ../_mw/utils/deprecation dojo/NodeList-dom ../a11yclick".split(" "),function(e,k,h,l,b,m,d,g,c,a){a.deprecated({deprecated:{module:"dijit/form/Checkbox"},replacement:{module:"MW/form/Checkbox"},geckNumber:1352405});l("dijit-legacy-requires")&&m(0,function(){e(["dijit/form/RadioButton"])});return k("dijit.form.CheckBox", +[d,g],{templateString:c,baseClass:"dijitCheckBox",_setValueAttr:function(a,b){"string"==typeof a&&(this.inherited(arguments),a=!0);this._created&&this.set("checked",a,b)},_getValueAttr:function(){return this.checked&&this._get("value")},_setIconClassAttr:null,_setNameAttr:"focusNode",postMixInProperties:function(){this.inherited(arguments);this.checkedAttrSetting=""},_fillContent:function(){},_onFocus:function(){this.id&&b("label[for\x3d'"+this.id+"']").addClass("dijitFocusedLabel");this.inherited(arguments)}, +_onBlur:function(){this.id&&b("label[for\x3d'"+this.id+"']").removeClass("dijitFocusedLabel");this.inherited(arguments)}})})},"dijit/form/_CheckBoxMixin":function(){define(["dojo/_base/declare","dojo/dom-attr"],function(e,k){return e("dijit.form._CheckBoxMixin",null,{type:"checkbox",value:"on",readOnly:!1,_aria_attr:"aria-checked",_setReadOnlyAttr:function(e){this._set("readOnly",e);k.set(this.focusNode,"readOnly",e)},_setLabelAttr:void 0,_getSubmitValue:function(e){return null==e||""===e?"on":e}, +_setValueAttr:function(e){e=this._getSubmitValue(e);this._set("value",e);k.set(this.focusNode,"value",e)},reset:function(){this.inherited(arguments);this._set("value",this._getSubmitValue(this.params.value));k.set(this.focusNode,"value",this.value)},_onClick:function(e){return this.readOnly?(e.stopPropagation(),e.preventDefault(),!1):this.inherited(arguments)}})})},"webview/widgets/SystemButton":function(){define("dojo/_base/declare dojo/dom-style dijit/_WidgetBase dijit/_CssStateMixin dijit/_TemplatedMixin dijit/form/Button dijit/form/DropDownButton dijit/Menu dijit/MenuItem dojo/text!./templates/SystemButton.html".split(" "), +function(e,k,h,l,b,m,d,g,c,a){var f=e([c],{onClick:function(){var a=this.app;a.open(this.diagram,{tab:"reuse"}).then(function(){a.modelViewer.focus()})}});return e([h,l,b],{templateString:a,baseClass:"system-button-widget",postCreate:function(){var a=this.app,b=this.diagram,c=new g({"class":"system-button-widget"}),e=new d({dropDown:c},this.arrowButtonNode),h=new m({label:b.label,iconClass:b.icon,diagram:b,onClick:function(){a.open(this.diagram,{tab:"reuse"}).then(function(){a.modelViewer.focus()})}}, +this.buttonNode),l=e.domNode,b=b.getChildren(),x,w=b.length,y;for(y=0;y/g,"\x26gt;").replace(/"/g,"\x26quot;")});return d},_getInspectorData:function(a){var b;a.inspector&&(b={title:"",params:[],values:[],tabs:[],tabs_idx:[]},a=a.inspector,a.params&&(b.params=a.params),a.values&&(b.values=a.values),a.tabs&&(b.tabs=a.tabs instanceof Array?a.tabs:[a.tabs]),a.tabs_idx instanceof Array?b.tabs_idx=a.tabs_idx:"number"===typeof a.tabs_idx&& +(b.tabs_idx=[a.tabs_idx]),0=b.w||d.h>=b.h?(a={w:Math.min(d.w,b.w),h:Math.min(d.h,b.h)},this._shrunk=!0):this._shrunk=!1}if(a){g.setMarginBox(this.domNode,a);b=[];this.titleBar&&b.push({domNode:this.titleBar, +region:"top"});this.actionBarNode&&b.push({domNode:this.actionBarNode,region:"bottom"});d={domNode:this.containerNode,region:"center"};b.push(d);var e=N.marginBox2contentBox(this.domNode,a);N.layoutChildren(this.domNode,e,b);this._singleChild?(b=N.marginBox2contentBox(this.containerNode,d),this._singleChild.resize({w:b.w,h:b.h})):(this.containerNode.style.overflow="auto",this._layoutChildren())}else this._layoutChildren();!r("touch")&&!a&&this._position()}},_layoutChildren:function(){k.forEach(this.getChildren(), +function(a){a.resize&&a.resize()})},destroy:function(){this._fadeInDeferred&&this._fadeInDeferred.cancel();this._fadeOutDeferred&&this._fadeOutDeferred.cancel();this._moveable&&this._moveable.destroy();for(var a;a=this._modalconnects.pop();)a.remove();J.hide(this);this.inherited(arguments)}});var L=l("dijit.Dialog",[O,A],{});L._DialogBase=A;var J=L._DialogLevelManager={_beginZIndex:950,show:function(a,b){H[H.length-1].focus=y.curNode;var d=H[H.length-1].dialog?H[H.length-1].zIndex+2:L._DialogLevelManager._beginZIndex; +c.set(a.domNode,"zIndex",d);I.show(b,d-1);H.push({dialog:a,underlayAttrs:b,zIndex:d})},hide:function(a){if(H[H.length-1].dialog==a){H.pop();var b=H[H.length-1];1==H.length?I.hide():I.show(b.underlayAttrs,b.zIndex-1);if(a.refocus){a=b.focus;if(b.dialog&&(!a||!m.isDescendant(a,b.dialog.domNode)))b.dialog._getFocusItems(),a=b.dialog._firstFocusItem;if(a)try{a.focus()}catch(c){}}}else b=k.indexOf(k.map(H,function(a){return a.dialog}),a),-1!=b&&H.splice(b,1)},isTop:function(a){return H[H.length-1].dialog== +a}},H=L._dialogStack=[{dialog:null,focus:null,underlayAttrs:null}];y.watch("curNode",function(a,b,c){a=H[H.length-1].dialog;if(c&&a&&!a._fadeOutDeferred&&c.ownerDocument==a.ownerDocument){do if(c==a.domNode||d.contains(c,"dijitPopup"))return;while(c=c.parentNode);a.focus()}});r("dijit-legacy-requires")&&q(0,function(){e(["dijit/TooltipDialog"])});return L})},"dojo/dnd/Moveable":function(){define("../_base/array ../_base/declare ../_base/lang ../dom ../dom-class ../Evented ../on ../topic ../touch ./common ./Mover ../_base/window".split(" "), +function(e,k,h,l,b,m,d,g,c,a,f,u){return k("dojo.dnd.Moveable",[m],{handle:"",delay:0,skip:!1,constructor:function(a,b){this.node=l.byId(a);b||(b={});this.handle=b.handle?l.byId(b.handle):null;this.handle||(this.handle=this.node);this.delay=0this.delay||Math.abs(a.pageY- +this._lastY)>this.delay)this.onMouseUp(a),this.onDragDetected(a);a.stopPropagation();a.preventDefault()},onMouseUp:function(a){for(var b=0;2>b;++b)this.events.pop().remove();a.stopPropagation();a.preventDefault()},onSelectStart:function(b){if(!this.skip||!a.isFormElement(b))b.stopPropagation(),b.preventDefault()},onDragDetected:function(a){new this.mover(this.node,a,this)},onMoveStart:function(a){g.publish("/dnd/move/start",a);b.add(u.body(),"dojoMove");b.add(this.node,"dojoMoveItem")},onMoveStop:function(a){g.publish("/dnd/move/stop", +a);b.remove(u.body(),"dojoMove");b.remove(this.node,"dojoMoveItem")},onFirstMove:function(){},onMove:function(a,b){this.onMoving(a,b);var c=a.node.style;c.left=b.l+"px";c.top=b.t+"px";this.onMoved(a,b)},onMoving:function(){},onMoved:function(){}})})},"dojo/dnd/Mover":function(){define("../_base/array ../_base/declare ../_base/lang ../sniff ../_base/window ../dom ../dom-geometry ../dom-style ../Evented ../on ../touch ./common ./autoscroll".split(" "),function(e,k,h,l,b,m,d,g,c,a,f,u,p){return k("dojo.dnd.Mover", +[c],{constructor:function(b,c,d){function e(a){a.preventDefault();a.stopPropagation()}this.node=m.byId(b);this.marginBox={l:c.pageX,t:c.pageY};this.mouseButton=c.button;c=this.host=d;b=b.ownerDocument;this.events=[a(b,f.move,h.hitch(this,"onFirstMove")),a(b,f.move,h.hitch(this,"onMouseMove")),a(b,f.release,h.hitch(this,"onMouseUp")),a(b,"dragstart",e),a(b.body,"selectstart",e)];p.autoScrollStart(b);if(c&&c.onMoveStart)c.onMoveStart(this)},onMouseMove:function(a){p.autoScroll(a);var b=this.marginBox; +this.host.onMove(this,{l:b.l+a.pageX,t:b.t+a.pageY},a);a.preventDefault();a.stopPropagation()},onMouseUp:function(a){(l("webkit")&&l("mac")&&2==this.mouseButton?0==a.button:this.mouseButton==a.button)&&this.destroy();a.preventDefault();a.stopPropagation()},onFirstMove:function(a){var c=this.node.style,e,f=this.host;switch(c.position){case "relative":case "absolute":e=Math.round(parseFloat(c.left))||0;c=Math.round(parseFloat(c.top))||0;break;default:c.position="absolute";c=d.getMarginBox(this.node); +e=b.doc.body;var h=g.getComputedStyle(e),k=d.getMarginBox(e,h),h=d.getContentBox(e,h);e=c.l-(h.l-k.l);c=c.t-(h.t-k.t)}this.marginBox.l=e-this.marginBox.l;this.marginBox.t=c-this.marginBox.t;if(f&&f.onFirstMove)f.onFirstMove(this,a);this.events.shift().remove()},destroy:function(){e.forEach(this.events,function(a){a.remove()});var a=this.host;if(a&&a.onMoveStop)a.onMoveStop(this);this.events=this.node=this.host=null}})})},"dojo/dnd/autoscroll":function(){define("../_base/lang ../sniff ../_base/window ../dom-geometry ../dom-style ../window".split(" "), +function(e,k,h,l,b,m){var d={};e.setObject("dojo.dnd.autoscroll",d);d.getViewport=m.getBox;d.V_TRIGGER_AUTOSCROLL=32;d.H_TRIGGER_AUTOSCROLL=32;d.V_AUTOSCROLL_VALUE=16;d.H_AUTOSCROLL_VALUE=16;var g,c=h.doc,a=Infinity,f=Infinity;d.autoScrollStart=function(b){c=b;g=m.getBox(c);b=h.body(c).parentNode;a=Math.max(b.scrollHeight-g.h,0);f=Math.max(b.scrollWidth-g.w,0)};d.autoScroll=function(b){var e=g||m.getBox(c),k=h.body(c).parentNode,l=0,r=0;b.clientX +e.w-d.H_TRIGGER_AUTOSCROLL&&(l=Math.min(d.H_AUTOSCROLL_VALUE,f-k.scrollLeft));b.clientYe.h-d.V_TRIGGER_AUTOSCROLL&&(r=Math.min(d.V_AUTOSCROLL_VALUE,a-k.scrollTop));window.scrollBy(l,r)};d._validNodes={div:1,p:1,td:1};d._validOverflow={auto:1,scroll:1};d.autoScrollNodes=function(a){for(var c,e,f,g,m,x,w=0,y=0,A=a.target;A;){if(1==A.nodeType&&A.tagName.toLowerCase()in d._validNodes){f=b.getComputedStyle(A);g=f.overflow.toLowerCase()in d._validOverflow; +m=f.overflowX.toLowerCase()in d._validOverflow;x=f.overflowY.toLowerCase()in d._validOverflow;if(g||m||x)c=l.getContentBox(A,f),e=l.position(A,!0);if(g||m){f=Math.min(d.H_TRIGGER_AUTOSCROLL,c.w/2);m=a.pageX-e.x;if(k("webkit")||k("opera"))m+=h.body().scrollLeft;w=0;0c.w-f&&(w=f),A.scrollLeft+=w)}if(g||x){g=Math.min(d.V_TRIGGER_AUTOSCROLL,c.h/2);x=a.pageY-e.y;if(k("webkit")||k("opera"))x+=h.body().scrollTop;y=0;0c.h-g&&(y=g),A.scrollTop+=y)}if(w||y)return}try{A= +A.parentNode}catch(B){A=null}}d.autoScroll(a)};return d})},"dojo/dnd/TimedMoveable":function(){define(["../_base/declare","./Moveable"],function(e,k){var h=k.prototype.onMove;return e("dojo.dnd.TimedMoveable",k,{timeout:40,constructor:function(e,b){b||(b={});b.timeout&&("number"==typeof b.timeout&&0<=b.timeout)&&(this.timeout=b.timeout)},onMoveStop:function(e){e._timer&&(clearTimeout(e._timer),h.call(this,e,e._leftTop));k.prototype.onMoveStop.apply(this,arguments)},onMove:function(e,b){e._leftTop= +b;if(!e._timer){var k=this;e._timer=setTimeout(function(){e._timer=null;h.call(k,e,e._leftTop)},this.timeout)}}})})},"dijit/DialogUnderlay":function(){define("dojo/_base/declare dojo/_base/lang dojo/aspect dojo/dom-attr dojo/dom-style dojo/on dojo/window ./_Widget ./_TemplatedMixin ./BackgroundIframe ./Viewport ./main".split(" "),function(e,k,h,l,b,m,d,g,c,a,f,u){var p=e("dijit.DialogUnderlay",[g,c],{templateString:"\x3cdiv class\x3d'dijitDialogUnderlayWrapper'\x3e\x3cdiv class\x3d'dijitDialogUnderlay' tabIndex\x3d'-1' data-dojo-attach-point\x3d'node'\x3e\x3c/div\x3e\x3c/div\x3e", +dialogId:"","class":"",_modalConnects:[],_setDialogIdAttr:function(a){l.set(this.node,"id",a+"_underlay");this._set("dialogId",a)},_setClassAttr:function(a){this.node.className="dijitDialogUnderlay "+a;this._set("class",a)},postCreate:function(){this.ownerDocumentBody.appendChild(this.domNode);this.own(m(this.domNode,"keydown",k.hitch(this,"_onKeyDown")));this.inherited(arguments)},layout:function(){var a=this.node.style,b=this.domNode.style;b.display="none";var c=d.getBox(this.ownerDocument);b.top= +c.t+"px";b.left=c.l+"px";a.width=c.w+"px";a.height=c.h+"px";b.display="block"},show:function(){this.domNode.style.display="block";this.open=!0;this.layout();this.bgIframe=new a(this.domNode);var b=d.get(this.ownerDocument);this._modalConnects=[f.on("resize",k.hitch(this,"layout")),m(b,"scroll",k.hitch(this,"layout"))]},hide:function(){this.bgIframe.destroy();delete this.bgIframe;for(this.domNode.style.display="none";this._modalConnects.length;)this._modalConnects.pop().remove();this.open=!1},destroy:function(){for(;this._modalConnects.length;)this._modalConnects.pop().remove(); +this.inherited(arguments)},_onKeyDown:function(){}});p.show=function(a,c){var d=p._singleton;!d||d._destroyed?d=u._underlay=p._singleton=new p(a):a&&d.set(a);b.set(d.domNode,"zIndex",c);d.open||d.show()};p.hide=function(){var a=p._singleton;a&&!a._destroyed&&a.hide()};return p})},"webview/interface":function(){define(["dijit/registry","dojo/Deferred","dojo/topic","webview/utils/hash"],function(e,k,h,l){function b(a){a=a.getBoundingClientRect();return 0<=a.top&&0<=a.left&&a.bottom<=(window.innerHeight|| +document.documentElement.clientHeight)&&a.right<=(window.innerWidth||document.documentElement.clientWidth)}function m(a){var b=a.indexOf(":"),c,d;-1===b?c=e.byId(a):(c=e.byId(a.substring(0,b)),d=a.substring(b+1));return{app:c,path:d}}function d(a){return u[a.id]&&"undefined"!==typeof f[a.id]}function g(a,b,c){var d,e=1,f;d=a;do f=document.querySelector(".slwebview-anchor["+d+"\x3d'"+b+"'], .slwebview-anchor["+d+"\x3d'"+c+"']"),"boolean"!==typeof p[d]&&(p[d]=null!==f||null!==document.querySelector(".slwebview-anchor["+ +d+"]")),!f&&p[d]&&(e+=1,d=a+"-"+String(e));while(null===f&&(p[d]||"undefined"===typeof p[d]));return f}function c(a){d(a)||(f[a.id]||(f[a.id]=a.on("open",function(c){var e=a.id+":"+c.sid;d(a)&&(a.isElement(c)?(c=a.id+":"+c.diagram.fullname+"/"+c.name,e=g("data-slwebview-elem-anchor",c,e)):(c=a.id+":"+c.fullname,e=g("data-slwebview-diag-anchor",c,e)),e&&(b(e)||e.scrollIntoView(),e.classList.remove("slwebview-anchor-highlight"),top.slwebview.__tmp=e.offsetWidth,e.classList.add("slwebview-anchor-highlight")))})), +u[a.id]=!0)}function a(a,c){function d(a){return a.replace(/-([a-z])/g,function(a){return a[1].toUpperCase()})}var e=a.substring(a.indexOf("-")+1),f=d(e),g=d(e+"-id");return function(){function d(a){var h=1,k=this.dataset[f],m=this.dataset[g],n=a&&a.nohash;for(a=a&&a.highlight;k;)c(k),k=this.dataset[f+"-"+String(h+=1)];m&&(!n&&l()!==m)&&(e=!0,l(m));a&&(b(this)||this.scrollIntoView(),this.classList.remove("slwebview-anchor-highlight"),top.slwebview.__tmp=this.offsetWidth,this.classList.add("slwebview-anchor-highlight"))} +var e=!1,k=document.querySelectorAll("["+a+"]"),m,p=k.length,r,s,u={};for(r=0;r|.+\s+))([\w\-\*]+)(\S*$)/).exec(f);h=h||l;if(m){var q=8===e("ie")&&e("quirks")?h.nodeType===l.nodeType:null!==h.parentNode&&9!==h.nodeType&&h.parentNode===l;if(m[2]&&q){var r=k.byId?k.byId(m[2],l):l.getElementById(m[2]);if(!r||m[1]&&m[1]!=r.tagName.toLowerCase())return[];if(h!=l)for(l=r;l!=h;)if(l=l.parentNode,!l)return[];return m[3]?d(m[3],r):[r]}if(m[3]&&h.getElementsByClassName)return h.getElementsByClassName(m[4]);if(m[5])if(r=h.getElementsByTagName(m[5]), +m[4]||m[6])f=(m[4]||"")+m[6];else return r}if(b)return 1===h.nodeType&&"object"!==h.nodeName.toLowerCase()?g(h,f,h.querySelectorAll):h.querySelectorAll(f);r||(r=h.getElementsByTagName("*"));m=[];l=0;for(q=r.length;l ])\s*)|(#|\.)?((?:\\.|[\w-])+)|\[\s*([\w-]+)\s*(.?=)?\s*("(?:\\.|[^"])+"|'(?:\\.|[^'])+'|(?:\\.|[^\]])*)\s*\]/g,function(e,h,k,l,q,s,w){l?m=d(m,g[k||""](l.replace(/\\/g,""))):h?m=(" "==h?b:c)(m):q&&(m=d(m,a(q,w,s)));return""}))throw Error("Syntax error in query");if(!m)return!0; +l[h]=m}return m(e,k)}}();if(!e("dom-qsa"))var a=function(a,b){for(var c=a.match(m),e=[],g=0;gg))a.onload=function(){a.onload=null;a.onerror=null;f&&d(a)},a.onerror=function(){console.error("Error loading stylesheet "+ +k);f&&d(a)};else if(f)var u=setInterval(function(){a.style&&(clearInterval(u),d(a))},15);(b||l.getElementsByTagName("head")[0]).appendChild(a);f||d(a)}var h="undefined"==typeof _css_cache?{}:_css_cache,l=document,b=l.head;k.insertCss=e;return k})},"url:dijit/templates/TreeNode.html":'\x3cdiv class\x3d"dijitTreeNode" role\x3d"presentation"\n\t\x3e\x3cdiv data-dojo-attach-point\x3d"rowNode" class\x3d"dijitTreeRow" role\x3d"presentation"\n\t\t\x3e\x3cspan data-dojo-attach-point\x3d"expandoNode" class\x3d"dijitInline dijitTreeExpando" role\x3d"presentation"\x3e\x3c/span\n\t\t\x3e\x3cspan data-dojo-attach-point\x3d"expandoNodeText" class\x3d"dijitExpandoText" role\x3d"presentation"\x3e\x3c/span\n\t\t\x3e\x3cspan data-dojo-attach-point\x3d"contentNode"\n\t\t\tclass\x3d"dijitTreeContent" role\x3d"presentation"\x3e\n\t\t\t\x3cspan role\x3d"presentation" class\x3d"dijitInline dijitIcon dijitTreeIcon" data-dojo-attach-point\x3d"iconNode"\x3e\x3c/span\n\t\t\t\x3e\x3cspan data-dojo-attach-point\x3d"labelNode,focusNode" class\x3d"dijitTreeLabel" role\x3d"treeitem"\n\t\t\t\t tabindex\x3d"-1" aria-selected\x3d"false" id\x3d"${id}_label"\x3e\x3c/span\x3e\n\t\t\x3c/span\n\t\x3e\x3c/div\x3e\n\t\x3cdiv data-dojo-attach-point\x3d"containerNode" class\x3d"dijitTreeNodeContainer" role\x3d"presentation"\n\t\t style\x3d"display: none;" aria-labelledby\x3d"${id}_label"\x3e\x3c/div\x3e\n\x3c/div\x3e\n', +"url:dijit/templates/Tree.html":'\x3cdiv role\x3d"tree"\x3e\n\t\x3cdiv class\x3d"dijitInline dijitTreeIndent" style\x3d"position: absolute; top: -9999px" data-dojo-attach-point\x3d"indentDetector"\x3e\x3c/div\x3e\n\t\x3cdiv class\x3d"dijitTreeExpando dijitTreeExpandoLoading" data-dojo-attach-point\x3d"rootLoadingIndicator"\x3e\x3c/div\x3e\n\t\x3cdiv data-dojo-attach-point\x3d"containerNode" class\x3d"dijitTreeContainer" role\x3d"presentation"\x3e\n\t\x3c/div\x3e\n\x3c/div\x3e\n',"url:dijit/templates/Menu.html":'\x3ctable class\x3d"dijit dijitMenu dijitMenuPassive dijitReset dijitMenuTable" role\x3d"menu" tabIndex\x3d"${tabIndex}"\n\t cellspacing\x3d"0"\x3e\n\t\x3ctbody class\x3d"dijitReset" data-dojo-attach-point\x3d"containerNode"\x3e\x3c/tbody\x3e\n\x3c/table\x3e\n', +"url:dijit/templates/MenuItem.html":'\x3ctr class\x3d"dijitReset" data-dojo-attach-point\x3d"focusNode" role\x3d"menuitem" tabIndex\x3d"-1"\x3e\n\t\x3ctd class\x3d"dijitReset dijitMenuItemIconCell" role\x3d"presentation"\x3e\n\t\t\x3cspan role\x3d"presentation" class\x3d"dijitInline dijitIcon dijitMenuItemIcon" data-dojo-attach-point\x3d"iconNode"\x3e\x3c/span\x3e\n\t\x3c/td\x3e\n\t\x3ctd class\x3d"dijitReset dijitMenuItemLabel" colspan\x3d"2" data-dojo-attach-point\x3d"containerNode,textDirNode"\n\t\trole\x3d"presentation"\x3e\x3c/td\x3e\n\t\x3ctd class\x3d"dijitReset dijitMenuItemAccelKey" style\x3d"display: none" data-dojo-attach-point\x3d"accelKeyNode"\x3e\x3c/td\x3e\n\t\x3ctd class\x3d"dijitReset dijitMenuArrowCell" role\x3d"presentation"\x3e\n\t\t\x3cspan data-dojo-attach-point\x3d"arrowWrapper" style\x3d"visibility: hidden"\x3e\n\t\t\t\x3cspan class\x3d"dijitInline dijitIcon dijitMenuExpand"\x3e\x3c/span\x3e\n\t\t\t\x3cspan class\x3d"dijitMenuExpandA11y"\x3e+\x3c/span\x3e\n\t\t\x3c/span\x3e\n\t\x3c/td\x3e\n\x3c/tr\x3e\n', +"url:webview/widgets/templates/ModelBrowser.html":'\x3cdiv class\x3d"wvModelBrowser"\x3e\n \x3cdiv data-dojo-attach-point\x3d"titleBar" class\x3d"wvModelBrowserTitleBar"\x3e\n \x3cspan data-dojo-attach-point\x3d"titleNode" class\x3d"wvModelBrowserTitleText"\x3e\x3c/span\x3e\n \x3c/div\x3e\n \x3cdiv data-dojo-attach-point\x3d"treeNode"\x3e\x3c/div\x3e\n\x3c/div\x3e',"url:dijit/layout/templates/TabContainer.html":'\x3cdiv class\x3d"dijitTabContainer"\x3e\n\t\x3cdiv class\x3d"dijitTabListWrapper" data-dojo-attach-point\x3d"tablistNode"\x3e\x3c/div\x3e\n\t\x3cdiv data-dojo-attach-point\x3d"tablistSpacer" class\x3d"dijitTabSpacer ${baseClass}-spacer"\x3e\x3c/div\x3e\n\t\x3cdiv class\x3d"dijitTabPaneWrapper ${baseClass}-container" data-dojo-attach-point\x3d"containerNode"\x3e\x3c/div\x3e\n\x3c/div\x3e\n', +"url:dijit/form/templates/Button.html":'\x3cspan class\x3d"dijit dijitReset dijitInline" role\x3d"presentation"\n\t\x3e\x3cspan class\x3d"dijitReset dijitInline dijitButtonNode"\n\t\tdata-dojo-attach-event\x3d"ondijitclick:__onClick" role\x3d"presentation"\n\t\t\x3e\x3cspan class\x3d"dijitReset dijitStretch dijitButtonContents"\n\t\t\tdata-dojo-attach-point\x3d"titleNode,focusNode"\n\t\t\trole\x3d"button" aria-labelledby\x3d"${id}_label"\n\t\t\t\x3e\x3cspan class\x3d"dijitReset dijitInline dijitIcon" data-dojo-attach-point\x3d"iconNode"\x3e\x3c/span\n\t\t\t\x3e\x3cspan class\x3d"dijitReset dijitToggleButtonIconChar"\x3e\x26#x25CF;\x3c/span\n\t\t\t\x3e\x3cspan class\x3d"dijitReset dijitInline dijitButtonText"\n\t\t\t\tid\x3d"${id}_label"\n\t\t\t\tdata-dojo-attach-point\x3d"containerNode"\n\t\t\t\x3e\x3c/span\n\t\t\x3e\x3c/span\n\t\x3e\x3c/span\n\t\x3e\x3cinput ${!nameAttrSetting} type\x3d"${type}" value\x3d"${value}" class\x3d"dijitOffScreen"\n\t\tdata-dojo-attach-event\x3d"onclick:_onClick"\n\t\ttabIndex\x3d"-1" aria-hidden\x3d"true" data-dojo-attach-point\x3d"valueNode"\n/\x3e\x3c/span\x3e\n', +"url:dijit/layout/templates/_TabButton.html":'\x3cdiv role\x3d"presentation" data-dojo-attach-point\x3d"titleNode,innerDiv,tabContent" class\x3d"dijitTabInner dijitTabContent"\x3e\n\t\x3cspan role\x3d"presentation" class\x3d"dijitInline dijitIcon dijitTabButtonIcon" data-dojo-attach-point\x3d"iconNode"\x3e\x3c/span\x3e\n\t\x3cspan data-dojo-attach-point\x3d\'containerNode,focusNode\' class\x3d\'tabLabel\'\x3e\x3c/span\x3e\n\t\x3cspan class\x3d"dijitInline dijitTabCloseButton dijitTabCloseIcon" data-dojo-attach-point\x3d\'closeNode\'\n\t\t role\x3d"presentation"\x3e\n\t\t\x3cspan data-dojo-attach-point\x3d\'closeText\' class\x3d\'dijitTabCloseText\'\x3e[x]\x3c/span\n\t\t\t\t\x3e\x3c/span\x3e\n\x3c/div\x3e\n', +"url:dijit/layout/templates/ScrollingTabController.html":'\x3cdiv class\x3d"dijitTabListContainer-${tabPosition}" style\x3d"visibility:hidden"\x3e\n\t\x3cdiv data-dojo-type\x3d"dijit.layout._ScrollingTabControllerMenuButton"\n\t\t class\x3d"tabStripButton-${tabPosition}"\n\t\t id\x3d"${id}_menuBtn"\n\t\t data-dojo-props\x3d"containerId: \'${containerId}\', iconClass: \'dijitTabStripMenuIcon\',\n\t\t\t\t\tdropDownPosition: [\'below-alt\', \'above-alt\']"\n\t\t data-dojo-attach-point\x3d"_menuBtn" showLabel\x3d"false" title\x3d""\x3e\x26#9660;\x3c/div\x3e\n\t\x3cdiv data-dojo-type\x3d"dijit.layout._ScrollingTabControllerButton"\n\t\t class\x3d"tabStripButton-${tabPosition}"\n\t\t id\x3d"${id}_leftBtn"\n\t\t data-dojo-props\x3d"iconClass:\'dijitTabStripSlideLeftIcon\', showLabel:false, title:\'\'"\n\t\t data-dojo-attach-point\x3d"_leftBtn" data-dojo-attach-event\x3d"onClick: doSlideLeft"\x3e\x26#9664;\x3c/div\x3e\n\t\x3cdiv data-dojo-type\x3d"dijit.layout._ScrollingTabControllerButton"\n\t\t class\x3d"tabStripButton-${tabPosition}"\n\t\t id\x3d"${id}_rightBtn"\n\t\t data-dojo-props\x3d"iconClass:\'dijitTabStripSlideRightIcon\', showLabel:false, title:\'\'"\n\t\t data-dojo-attach-point\x3d"_rightBtn" data-dojo-attach-event\x3d"onClick: doSlideRight"\x3e\x26#9654;\x3c/div\x3e\n\t\x3cdiv class\x3d\'dijitTabListWrapper\' data-dojo-attach-point\x3d\'tablistWrapper\'\x3e\n\t\t\x3cdiv role\x3d\'tablist\' data-dojo-attach-event\x3d\'onkeydown:onkeydown\'\n\t\t\t data-dojo-attach-point\x3d\'containerNode\' class\x3d\'nowrapTabStrip\'\x3e\x3c/div\x3e\n\t\x3c/div\x3e\n\x3c/div\x3e', +"url:dijit/layout/templates/_ScrollingTabControllerButton.html":'\x3cdiv data-dojo-attach-event\x3d"ondijitclick:_onClick" class\x3d"dijitTabInnerDiv dijitTabContent dijitButtonContents" data-dojo-attach-point\x3d"focusNode" role\x3d"button"\x3e\n\t\x3cspan role\x3d"presentation" class\x3d"dijitInline dijitTabStripIcon" data-dojo-attach-point\x3d"iconNode"\x3e\x3c/span\x3e\n\t\x3cspan data-dojo-attach-point\x3d"containerNode,titleNode" class\x3d"dijitButtonText"\x3e\x3c/span\x3e\n\x3c/div\x3e',"url:webview/widgets/templates/ModelGraphicsPane.html":'\x3cdiv id\x3d${id} \n class\x3d"model-graphics-widget"\n tabindex\x3d"0"\x3e\n \x3cdiv data-dojo-attach-point\x3d"CanvasNode" \n class\x3d"model-graphics-canvas"\x3e\n \x3c/div\x3e\n\x3c/div\x3e', +"url:webview/widgets/templates/LightBox.html":'\x3cdiv class\x3d"lightbox-widget"\x3e\n \x3cdiv class\x3d\'dijitDialogUnderlay\'\n tabIndex\x3d\'-1\'\n id\x3d"${id}_underlay"\n data-dojo-attach-point\x3d\'underlayNode\'\x3e\n \x3c/div\x3e\n\n \x3cdiv class\x3d"dijitDialog dijitDialogFixed"\n tabindex\x3d"0"\n role\x3d"dialog"\n aria-labelledby\x3d"${id}_title"\n data-dojo-attach-point\x3d"dialogNode"\x3e\n \x3cdiv data-dojo-attach-point\x3d"titleBar"\n class\x3d"dijitDialogTitleBar"\x3e\n \x3cspan data-dojo-attach-point\x3d"titleNode"\n class\x3d"dijitDialogTitle"\n id\x3d"${id}_title"\n role\x3d"heading"\n level\x3d"1"\x3e\x3c/span\x3e\n \x3cspan data-dojo-attach-point\x3d"closeButtonNode"\n class\x3d"dijitDialogCloseIcon"\n data-dojo-attach-event\x3d"onclick:close"\n title\x3d"${buttonCancel}"\n role\x3d"button"\n tabindex\x3d"0"\x3e\x3cspan data-dojo-attach-point\x3d"closeText"\n class\x3d"closeText"\n title\x3d"${buttonCancel}"\x3ex\x3c/span\x3e\x3c/span\x3e\n \x3c/div\x3e\n \x3cdiv data-dojo-attach-point\x3d"contentNode"\n class\x3d"dijitDialogPaneContent"\x3e\n \x3c/div\x3e\n \x3c/div\x3e\n\x3c/div\x3e', +"url:webview/palette/templates/Palette.html":'\x3cdiv class\x3d"palette-widget" \n role\x3d"toolbar"\n data-dojo-attach-point\x3d"containerNode"\x3e\n\x3c/div\x3e\n\n',"url:dijit/templates/Tooltip.html":'\x3cdiv class\x3d"dijitTooltip dijitTooltipLeft" id\x3d"dojoTooltip" data-dojo-attach-event\x3d"mouseenter:onMouseEnter,mouseleave:onMouseLeave"\n\t\x3e\x3cdiv class\x3d"dijitTooltipConnector" data-dojo-attach-point\x3d"connectorNode"\x3e\x3c/div\n\t\x3e\x3cdiv class\x3d"dijitTooltipContainer dijitTooltipContents" data-dojo-attach-point\x3d"containerNode" role\x3d\'alert\'\x3e\x3c/div\n\x3e\x3c/div\x3e\n', +"url:webview/palette/templates/PaletteSeparator.html":'\x3cdiv id\x3d${id}\n class\x3d"palette-separator"\n role\x3d"presentation"\x3e\n \x3cdiv class\x3d"palette-separator-icon" data-dojo-attach-point\x3d"iconNode"\x3e\x3c/div\x3e\n\x3c/div\x3e\n\n',"url:webview/search/templates/SearchResultsPane.html":'\x3cdiv class\x3d"wvSearchResultsPane" data-dojo-attach-point\x3d"focusNode" tabIndex\x3d"-1"\x3e\n\x3c!-- revisit focusNOde--\x3e\n \x3cdiv data-dojo-attach-point\x3d"titleBar" class\x3d"wvSearchResultsPaneTitleBar"\x3e\n \x3cspan data-dojo-attach-point\x3d"titleNode" class\x3d"wvSearchResultsPaneTitleText"\x3e\x3c/span\x3e\n \x3cspan data-dojo-attach-point\x3d"closeButtonNode" class\x3d"dijitDialogCloseIcon"\n data-dojo-attach-event\x3d"onclick:close"\x3e\x3c/span\x3e\n \x3c/div\x3e \n \x3cdiv data-dojo-attach-point\x3d"containerNode" class\x3d"wvSearchResultsPaneContent"\x3e\x3c/div\x3e\n\x3c/div\x3e\n', +"url:dijit/form/templates/DropDownButton.html":'\x3cspan class\x3d"dijit dijitReset dijitInline"\n\t\x3e\x3cspan class\x3d\'dijitReset dijitInline dijitButtonNode\'\n\t\tdata-dojo-attach-event\x3d"ondijitclick:__onClick" data-dojo-attach-point\x3d"_buttonNode"\n\t\t\x3e\x3cspan class\x3d"dijitReset dijitStretch dijitButtonContents"\n\t\t\tdata-dojo-attach-point\x3d"focusNode,titleNode,_arrowWrapperNode,_popupStateNode"\n\t\t\trole\x3d"button" aria-haspopup\x3d"true" aria-labelledby\x3d"${id}_label"\n\t\t\t\x3e\x3cspan class\x3d"dijitReset dijitInline dijitIcon"\n\t\t\t\tdata-dojo-attach-point\x3d"iconNode"\n\t\t\t\x3e\x3c/span\n\t\t\t\x3e\x3cspan class\x3d"dijitReset dijitInline dijitButtonText"\n\t\t\t\tdata-dojo-attach-point\x3d"containerNode"\n\t\t\t\tid\x3d"${id}_label"\n\t\t\t\x3e\x3c/span\n\t\t\t\x3e\x3cspan class\x3d"dijitReset dijitInline dijitArrowButtonInner"\x3e\x3c/span\n\t\t\t\x3e\x3cspan class\x3d"dijitReset dijitInline dijitArrowButtonChar"\x3e\x26#9660;\x3c/span\n\t\t\x3e\x3c/span\n\t\x3e\x3c/span\n\t\x3e\x3cinput ${!nameAttrSetting} type\x3d"${type}" value\x3d"${value}" class\x3d"dijitOffScreen" tabIndex\x3d"-1"\n\t\tdata-dojo-attach-event\x3d"onclick:_onClick" data-dojo-attach-point\x3d"valueNode" aria-hidden\x3d"true"\n/\x3e\x3c/span\x3e\n', +"url:dijit/form/templates/TextBox.html":'\x3cdiv class\x3d"dijit dijitReset dijitInline dijitLeft" id\x3d"widget_${id}" role\x3d"presentation"\n\t\x3e\x3cdiv class\x3d"dijitReset dijitInputField dijitInputContainer"\n\t\t\x3e\x3cinput class\x3d"dijitReset dijitInputInner" data-dojo-attach-point\x3d\'textbox,focusNode\' autocomplete\x3d"off"\n\t\t\t${!nameAttrSetting} type\x3d\'${type}\'\n\t/\x3e\x3c/div\n\x3e\x3c/div\x3e\n',"url:dijit/templates/TooltipDialog.html":'\x3cdiv role\x3d"alertdialog" tabIndex\x3d"-1"\x3e\n\t\x3cdiv class\x3d"dijitTooltipContainer" role\x3d"presentation"\x3e\n\t\t\x3cdiv data-dojo-attach-point\x3d"contentsNode" class\x3d"dijitTooltipContents dijitTooltipFocusNode"\x3e\n\t\t\t\x3cdiv data-dojo-attach-point\x3d"containerNode"\x3e\x3c/div\x3e\n\t\t\t${!actionBarTemplate}\n\t\t\x3c/div\x3e\n\t\x3c/div\x3e\n\t\x3cdiv class\x3d"dijitTooltipConnector" role\x3d"presentation" data-dojo-attach-point\x3d"connectorNode"\x3e\x3c/div\x3e\n\x3c/div\x3e\n', +"url:dijit/form/templates/CheckBox.html":'\x3cdiv class\x3d"dijit dijitReset dijitInline" role\x3d"presentation"\n\t\x3e\x3cinput\n\t \t${!nameAttrSetting} type\x3d"${type}" role\x3d"${type}" aria-checked\x3d"false" ${checkedAttrSetting}\n\t\tclass\x3d"dijitReset dijitCheckBoxInput"\n\t\tdata-dojo-attach-point\x3d"focusNode"\n\t \tdata-dojo-attach-event\x3d"ondijitclick:_onClick"\n/\x3e\x3c/div\x3e\n',"url:webview/search/templates/SearchFieldsPanel.html":'\x3ctable\x3e\n \x3ctr\x3e\n \x3ctd\x3e\x3cinput id\x3d"${id}-name"/\x3e\x3c/td\x3e\n \x3ctd\x3e\x3clabel id\x3d"${id}-name-label" for\x3d"${id}-name"\x3eName\x3c/label\x3e\x3c/td\x3e\n \x3c/tr\x3e\n \x3ctr\x3e\n \x3ctd\x3e\x3cinput id\x3d"${id}-blockType"/\x3e\x3c/td\x3e\n \x3ctd\x3e\x3clabel id\x3d"${id}-blockType-label" for\x3d"${id}-blockType"\x3eBlockType\x3c/label\x3e\x3c/td\x3e\n \x3c/tr\x3e\n \x3ctr\x3e\n \x3ctd\x3e\x3cinput id\x3d"${id}-maskType"/\x3e\x3c/td\x3e\n \x3ctd\x3e\x3clabel id\x3d"${id}-maskType-label" for\x3d"${id}-maskType"\x3eMaskType\x3c/label\x3e\x3c/td\x3e\n \x3c/tr\x3e\n \x3ctr\x3e\n \x3ctd\x3e\x3cinput id\x3d"${id}-propertyName"/\x3e\x3c/td\x3e\n \x3ctd\x3e\x3clabel id\x3d"${id}-propertyName-label" for\x3d"${id}-propertyName"\x3eProperty Name\x3c/label\x3e\x3c/td\x3e\n \x3c/tr\x3e\n \x3ctr\x3e\n \x3ctd\x3e\x3cinput id\x3d"${id}-propertyValue"/\x3e\x3c/td\x3e\n \x3ctd\x3e\x3clabel id\x3d"${id}-propertyValue-label" for\x3d"${id}-propertyValue"\x3eProperty Value\x3c/label\x3e\x3c/td\x3e\n \x3c/tr\x3e\n\x3c/table\x3e', +"url:webview/search/templates/InlineSearch.html":'\x3cdiv class\x3d"wvInlineSearch"\x3e\x3cdiv data-dojo-attach-point\x3d"fieldsButtonNode"\x3e\x3c/div\x3e\x3cdiv data-dojo-attach-point\x3d"formNode"\x3e\x3cdiv data-dojo-attach-point\x3d"textBoxNode"\x3e\x3c/div\x3e\x3c/div\x3e\x3cdiv data-dojo-attach-point\x3d"searchButtonNode"\x3e\x3c/div\x3e\x3c/div\x3e',"url:webview/widgets/templates/SystemButton.html":'\x3cdiv class\x3d"system-button-widget dijit dijitReset dijitInline dijitLeft"\n role\x3d"presentation"\x3e\n \x3cdiv role\x3d"presentation"\x3e\n \x3cdiv role\x3d"presentation"\x3e\n \x3cdiv data-dojo-attach-point\x3d"buttonNode"\x3e\x3c/div\x3e\n \x3cdiv data-dojo-attach-point\x3d"arrowButtonNode"\x3e\x3c/div\x3e\n \x3c/div\x3e\n \x3c/div\x3e\n\x3c/div\x3e\n', +"url:dijit/templates/TitlePane.html":'\x3cdiv\x3e\n\t\x3cdiv data-dojo-attach-event\x3d"ondijitclick:_onTitleClick, onkeydown:_onTitleKey"\n\t\t\tclass\x3d"dijitTitlePaneTitle" data-dojo-attach-point\x3d"titleBarNode" id\x3d"${id}_titleBarNode"\x3e\n\t\t\x3cdiv class\x3d"dijitTitlePaneTitleFocus" data-dojo-attach-point\x3d"focusNode"\x3e\n\t\t\t\x3cspan data-dojo-attach-point\x3d"arrowNode" class\x3d"dijitInline dijitArrowNode" role\x3d"presentation"\x3e\x3c/span\n\t\t\t\x3e\x3cspan data-dojo-attach-point\x3d"arrowNodeInner" class\x3d"dijitArrowNodeInner"\x3e\x3c/span\n\t\t\t\x3e\x3cspan data-dojo-attach-point\x3d"titleNode" class\x3d"dijitTitlePaneTextNode"\x3e\x3c/span\x3e\n\t\t\x3c/div\x3e\n\t\x3c/div\x3e\n\t\x3cdiv class\x3d"dijitTitlePaneContentOuter" data-dojo-attach-point\x3d"hideNode" role\x3d"presentation"\x3e\n\t\t\x3cdiv class\x3d"dijitReset" data-dojo-attach-point\x3d"wipeNode" role\x3d"presentation"\x3e\n\t\t\t\x3cdiv class\x3d"dijitTitlePaneContentInner" data-dojo-attach-point\x3d"containerNode" role\x3d"region" id\x3d"${id}_pane" aria-labelledby\x3d"${id}_titleBarNode"\x3e\n\t\t\t\t\x3c!-- nested divs because wipeIn()/wipeOut() doesn\'t work right on node w/padding etc. Put padding on inner div. --\x3e\n\t\t\t\x3c/div\x3e\n\t\t\x3c/div\x3e\n\t\x3c/div\x3e\n\x3c/div\x3e\n', +"url:webview/widgets/templates/ModelInspector.html":'\x3cdiv class\x3d"wvModelInspector"\x3e\n \x3cdiv data-dojo-attach-point\x3d"titleBar" class\x3d"wvModelInspectorTitleBar"\x3e\n \x3cspan data-dojo-attach-point\x3d"titleNode" class\x3d"wvModelInspectorTitleText"\x3e\x3c/span\x3e\n \x3c/div\x3e \n \x3cdiv data-dojo-attach-point\x3d"containerNode" class\x3d"wvModelInspectorContainer"\x3e\x3c/div\x3e\n\x3c/div\x3e\n\n',"url:webview/widgets/templates/Informer.html":'\x3cdiv class\x3d"wvInformer"\x3e\n \x3cdiv data-dojo-attach-point\x3d"titleBar" class\x3d"wvInformerTitleBar"\x3e\n \x3cspan data-dojo-attach-point\x3d"titleNode" class\x3d"wvInformerTitleText"\x3e\x3c/span\x3e\n \x3c/div\x3e \n \x3cdiv data-dojo-attach-point\x3d"containerNode" class\x3d"wvInformerContent"\x3e\x3c/div\x3e\n\x3c/div\x3e\n', +"url:dijit/templates/Dialog.html":'\x3cdiv class\x3d"dijitDialog" role\x3d"dialog" aria-labelledby\x3d"${id}_title"\x3e\n\t\x3cdiv data-dojo-attach-point\x3d"titleBar" class\x3d"dijitDialogTitleBar"\x3e\n\t\t\x3cspan data-dojo-attach-point\x3d"titleNode" class\x3d"dijitDialogTitle" id\x3d"${id}_title"\n\t\t\t\trole\x3d"heading" level\x3d"1"\x3e\x3c/span\x3e\n\t\t\x3cspan data-dojo-attach-point\x3d"closeButtonNode" class\x3d"dijitDialogCloseIcon" data-dojo-attach-event\x3d"ondijitclick: onCancel" title\x3d"${buttonCancel}" role\x3d"button" tabindex\x3d"-1"\x3e\n\t\t\t\x3cspan data-dojo-attach-point\x3d"closeText" class\x3d"closeText" title\x3d"${buttonCancel}"\x3ex\x3c/span\x3e\n\t\t\x3c/span\x3e\n\t\x3c/div\x3e\n\t\x3cdiv data-dojo-attach-point\x3d"containerNode" class\x3d"dijitDialogPaneContent"\x3e\x3c/div\x3e\n\t${!actionBarTemplate}\n\x3c/div\x3e\n\n', +"*now":function(e){e(['dojo/i18n!*preload*webview/nls/webview*["ar","ca","cs","da","de","el","en-gb","en-us","es-es","fi-fi","fr-fr","he-il","hu","it-it","ja-jp","ko-kr","nl-nl","nb","pl","pt-br","pt-pt","ru","sk","sl","sv","th","tr","zh-tw","zh-cn","ROOT"]'])}}});(function(){var e=this.require;e({cache:{}});!e.async&&e(["dojo"]);e.boot&&e.apply(null,e.boot)})(); +//# sourceMappingURL=webview.js.map \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/xstyle/LICENSE b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/xstyle/LICENSE new file mode 100644 index 00000000..bfdd9ab4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/lib/xstyle/LICENSE @@ -0,0 +1,190 @@ +xstyle is available under *either* the terms of the modified BSD license *or* the +Academic Free License version 2.1. As a recipient of xstyle, you may choose which +license to receive this code under. + +The text of the AFL and BSD licenses is reproduced below. + +------------------------------------------------------------------------------- +The "New" BSD License: +********************** + +Copyright (c) 2010-2011, The Dojo Foundation +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of the Dojo Foundation nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +------------------------------------------------------------------------------- +The Academic Free License, v. 2.1: +********************************** + +This Academic Free License (the "License") applies to any original work of +authorship (the "Original Work") whose owner (the "Licensor") has placed the +following notice immediately following the copyright notice for the Original +Work: + +Licensed under the Academic Free License version 2.1 + +1) Grant of Copyright License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license to do the +following: + +a) to reproduce the Original Work in copies; + +b) to prepare derivative works ("Derivative Works") based upon the Original +Work; + +c) to distribute copies of the Original Work and Derivative Works to the +public; + +d) to perform the Original Work publicly; and + +e) to display the Original Work publicly. + +2) Grant of Patent License. Licensor hereby grants You a world-wide, +royalty-free, non-exclusive, perpetual, sublicenseable license, under patent +claims owned or controlled by the Licensor that are embodied in the Original +Work as furnished by the Licensor, to make, use, sell and offer for sale the +Original Work and Derivative Works. + +3) Grant of Source Code License. The term "Source Code" means the preferred +form of the Original Work for making modifications to it and all available +documentation describing how to modify the Original Work. Licensor hereby +agrees to provide a machine-readable copy of the Source Code of the Original +Work along with each copy of the Original Work that Licensor distributes. +Licensor reserves the right to satisfy this obligation by placing a +machine-readable copy of the Source Code in an information repository +reasonably calculated to permit inexpensive and convenient access by You for as +long as Licensor continues to distribute the Original Work, and by publishing +the address of that information repository in a notice immediately following +the copyright notice that applies to the Original Work. + +4) Exclusions From License Grant. Neither the names of Licensor, nor the names +of any contributors to the Original Work, nor any of their trademarks or +service marks, may be used to endorse or promote products derived from this +Original Work without express prior written permission of the Licensor. Nothing +in this License shall be deemed to grant any rights to trademarks, copyrights, +patents, trade secrets or any other intellectual property of Licensor except as +expressly stated herein. No patent license is granted to make, use, sell or +offer to sell embodiments of any patent claims other than the licensed claims +defined in Section 2. No right is granted to the trademarks of Licensor even if +such marks are included in the Original Work. Nothing in this License shall be +interpreted to prohibit Licensor from licensing under different terms from this +License any Original Work that Licensor otherwise would have a right to +license. + +5) This section intentionally omitted. + +6) Attribution Rights. You must retain, in the Source Code of any Derivative +Works that You create, all copyright, patent or trademark notices from the +Source Code of the Original Work, as well as any notices of licensing and any +descriptive text identified therein as an "Attribution Notice." You must cause +the Source Code for any Derivative Works that You create to carry a prominent +Attribution Notice reasonably calculated to inform recipients that You have +modified the Original Work. + +7) Warranty of Provenance and Disclaimer of Warranty. Licensor warrants that +the copyright in and to the Original Work and the patent rights granted herein +by Licensor are owned by the Licensor or are sublicensed to You under the terms +of this License with the permission of the contributor(s) of those copyrights +and patent rights. Except as expressly stated in the immediately proceeding +sentence, the Original Work is provided under this License on an "AS IS" BASIS +and WITHOUT WARRANTY, either express or implied, including, without limitation, +the warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY OF THE ORIGINAL WORK IS WITH YOU. +This DISCLAIMER OF WARRANTY constitutes an essential part of this License. No +license to Original Work is granted hereunder except under this disclaimer. + +8) Limitation of Liability. Under no circumstances and under no legal theory, +whether in tort (including negligence), contract, or otherwise, shall the +Licensor be liable to any person for any direct, indirect, special, incidental, +or consequential damages of any character arising as a result of this License +or the use of the Original Work including, without limitation, damages for loss +of goodwill, work stoppage, computer failure or malfunction, or any and all +other commercial damages or losses. This limitation of liability shall not +apply to liability for death or personal injury resulting from Licensor's +negligence to the extent applicable law prohibits such limitation. Some +jurisdictions do not allow the exclusion or limitation of incidental or +consequential damages, so this exclusion and limitation may not apply to You. + +9) Acceptance and Termination. If You distribute copies of the Original Work or +a Derivative Work, You must make a reasonable effort under the circumstances to +obtain the express assent of recipients to the terms of this License. Nothing +else but this License (or another written agreement between Licensor and You) +grants You permission to create Derivative Works based upon the Original Work +or to exercise any of the rights granted in Section 1 herein, and any attempt +to do so except under the terms of this License (or another written agreement +between Licensor and You) is expressly prohibited by U.S. copyright law, the +equivalent laws of other countries, and by international treaty. Therefore, by +exercising any of the rights granted to You in Section 1 herein, You indicate +Your acceptance of this License and all of its terms and conditions. + +10) Termination for Patent Action. This License shall terminate automatically +and You may no longer exercise any of the rights granted to You by this License +as of the date You commence an action, including a cross-claim or counterclaim, +against Licensor or any licensee alleging that the Original Work infringes a +patent. This termination provision shall not apply for an action alleging +patent infringement by combinations of the Original Work with other software or +hardware. + +11) Jurisdiction, Venue and Governing Law. Any action or suit relating to this +License may be brought only in the courts of a jurisdiction wherein the +Licensor resides or in which Licensor conducts its primary business, and under +the laws of that jurisdiction excluding its conflict-of-law provisions. The +application of the United Nations Convention on Contracts for the International +Sale of Goods is expressly excluded. Any use of the Original Work outside the +scope of this License or after its termination shall be subject to the +requirements and penalties of the U.S. Copyright Act, 17 U.S.C. § 101 et +seq., the equivalent laws of other countries, and international treaty. This +section shall survive the termination of this License. + +12) Attorneys Fees. In any action to enforce the terms of this License or +seeking damages relating thereto, the prevailing party shall be entitled to +recover its costs and expenses, including, without limitation, reasonable +attorneys' fees and costs incurred in connection with such action, including +any appeal of such action. This section shall survive the termination of this +License. + +13) Miscellaneous. This License represents the complete agreement concerning +the subject matter hereof. If any provision of this License is held to be +unenforceable, such provision shall be reformed only to the extent necessary to +make it enforceable. + +14) Definition of "You" in This License. "You" throughout this License, whether +in upper or lower case, means an individual or a legal entity exercising rights +under, and complying with all of the terms of, this License. For legal +entities, "You" includes any entity that controls, is controlled by, or is +under common control with you. For purposes of this definition, "control" means +(i) the power, direct or indirect, to cause the direction or management of such +entity, whether by contract or otherwise, or (ii) ownership of fifty percent +(50%) or more of the outstanding shares, or (iii) beneficial ownership of such +entity. + +15) Right to Use. You may use the Original Work in all ways not otherwise +restricted or conditioned by this License or by law, and Licensor promises not +to interfere with or be responsible for such uses by You. + +This license is Copyright (C) 2003-2004 Lawrence E. Rosen. All rights reserved. +Permission is hereby granted to copy and distribute this license without +modification. This license may not be modified without the express written +permission of its copyright owner. diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview.json new file mode 100644 index 00000000..6bbb7e4b --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview.json @@ -0,0 +1,50 @@ +{ + "baseUrl":"support/slwebview_files", + "homeHid":2, + "initialElement":"", + "sections":[ + { + "hid":1, + "sid":"BLDCmotorControl_R2017b", + "name":"BLDCmotorControl_R2017b", + "fullname":"BLDCmotorControl_R2017b", + "label":"BLDCmotorControl_R2017b", + "parent":0, + "descendants":[ + 2, + 3, + 4, + 5, + 6, + 7, + 8, + 9, + 10, + 11, + 12, + 13, + 14, + 15, + 16, + 17, + 18, + 19, + 20, + 21, + 22, + 23, + 24, + 25, + 26 + ], + "hierarchyUrl":"support/slwebview_files/BLDCmotorControl_R2017b_h_1.json", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_m.json" + } + ], + "optViews":[ + ], + "display":{ + "informer":false + }, + "iconsUrl":"support/slwebview_files/BLDCmotorControl_R2017b_29_icons.css" +} \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.json new file mode 100644 index 00000000..f5d824ae --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.json @@ -0,0 +1,147 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:1830", + "className":"Simulink.Terminator", + "icon":"WebViewIcon2", + "name":"Terminator_1", + "label":"Terminator_1", + "parent":"BLDCmotorControl_R2017b:1828", + "inspector":{ + "params":[ + ], + "values":[ + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Terminator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1829", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallA", + "label":"b_hallA", + "parent":"BLDCmotorControl_R2017b:1828", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1829#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"b_hallA", + "label":"b_hallA", + "parent":"BLDCmotorControl_R2017b:1828", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "b_hallA", + "off", + "off", + "on", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.png new file mode 100644 index 00000000..42b5212d Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.svg new file mode 100644 index 00000000..79d0e8e7 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1828_d.svg @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.json new file mode 100644 index 00000000..ec5ce748 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.json @@ -0,0 +1,147 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:1833", + "className":"Simulink.Terminator", + "icon":"WebViewIcon2", + "name":"Terminator_1", + "label":"Terminator_1", + "parent":"BLDCmotorControl_R2017b:1831", + "inspector":{ + "params":[ + ], + "values":[ + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Terminator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1832", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallB", + "label":"b_hallB", + "parent":"BLDCmotorControl_R2017b:1831", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1832#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"b_hallB", + "label":"b_hallB", + "parent":"BLDCmotorControl_R2017b:1831", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "b_hallB", + "off", + "off", + "on", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.png new file mode 100644 index 00000000..e3eaa319 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.svg new file mode 100644 index 00000000..f36c97cb --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1831_d.svg @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.json new file mode 100644 index 00000000..9fbc9711 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.json @@ -0,0 +1,147 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:1836", + "className":"Simulink.Terminator", + "icon":"WebViewIcon2", + "name":"Terminator_1", + "label":"Terminator_1", + "parent":"BLDCmotorControl_R2017b:1834", + "inspector":{ + "params":[ + ], + "values":[ + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Terminator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1835", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallC", + "label":"b_hallC", + "parent":"BLDCmotorControl_R2017b:1834", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1835#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"b_hallC", + "label":"b_hallC", + "parent":"BLDCmotorControl_R2017b:1834", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "b_hallC", + "off", + "off", + "on", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.png new file mode 100644 index 00000000..3789fe71 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.svg new file mode 100644 index 00000000..33388586 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1834_d.svg @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.json new file mode 100644 index 00000000..1f73496a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.json @@ -0,0 +1,147 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:1839", + "className":"Simulink.Terminator", + "icon":"WebViewIcon2", + "name":"Terminator_1", + "label":"Terminator_1", + "parent":"BLDCmotorControl_R2017b:1837", + "inspector":{ + "params":[ + ], + "values":[ + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Terminator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1838", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DC", + "label":"r_DC", + "parent":"BLDCmotorControl_R2017b:1837", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1838#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"r_DC", + "label":"r_DC", + "parent":"BLDCmotorControl_R2017b:1837", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "r_DC", + "off", + "off", + "on", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.png new file mode 100644 index 00000000..21457e87 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.svg new file mode 100644 index 00000000..f3d331a5 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_1837_d.svg @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.json new file mode 100644 index 00000000..64d37774 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.json @@ -0,0 +1,1065 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:25", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

This calculates the low resolution position based on Hall sensors.

", + "label":"

This calculates the low resolution position based on Hall sensors.

", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

This calculates the low resolution position based on Hall sensors.

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:11", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallA", + "label":"b_hallA", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:12", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallB", + "label":"b_hallB", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:13", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallC", + "label":"b_hallC", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:23", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_pos ", + "label":"z_pos ", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:15", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum", + "label":"Sum", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "rectangular", + "off", + "+++", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:17", + "className":"Simulink.Gain", + "icon":"WebViewIcon2", + "name":"g_Ha", + "label":"g_Ha", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Gain", + "OutDataTypeStr", + "ParamDataTypeStr", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "ParamMax", + "ParamMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "4", + "Inherit: Inherit via back propagation", + "Inherit: Same as input", + "off", + "Element-wise(K.*u)", + "[]", + "[]", + "[]", + "[]", + "Zero", + "-1", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "Parameter Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Gain", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:18", + "className":"Simulink.Gain", + "icon":"WebViewIcon2", + "name":"g_Hb", + "label":"g_Hb", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Gain", + "OutDataTypeStr", + "ParamDataTypeStr", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "ParamMax", + "ParamMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "2", + "Inherit: Inherit via back propagation", + "Inherit: Same as input", + "off", + "Element-wise(K.*u)", + "[]", + "[]", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "Parameter Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Gain", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:14", + "className":"Simulink.Selector", + "icon":"WebViewIcon2", + "name":"Selector", + "label":"Selector", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "NumberOfDimensions", + "IndexMode", + "IndexOptionArray", + "IndexParamArray", + "OutputSizeArray", + "InputPortWidth", + "SampleTime", + "IndexOptions", + "NumberOfDimensions", + "IndexMode", + "IndexOptionArray", + "IndexParamArray", + "OutputSizeArray", + "InputPortWidth", + "SampleTime", + "IndexOptions", + "NumberOfDimensions", + "IndexMode", + "IndexOptionArray", + "IndexParamArray", + "OutputSizeArray", + "InputPortWidth", + "SampleTime", + "IndexOptions", + "Indices", + "OutputSizes" + ], + "values":[ + "1", + "Zero-based", + [ + "Index vector (port)" + ], + [ + "[1 3]" + ], + [ + "1" + ], + "length(vec_hallToPos)", + "-1", + "Index vector (port)", + "1", + "Zero-based", + [ + "Index vector (port)" + ], + [ + "[1 3]" + ], + [ + "1" + ], + "length(vec_hallToPos)", + "-1", + "Index vector (port)", + "1", + "Zero-based", + [ + "Index vector (port)" + ], + [ + "[1 3]" + ], + [ + "1" + ], + "length(vec_hallToPos)", + "-1", + "Index vector (port)", + "[1 3]", + "1" + ], + "tabs":[ + "Parameter Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 24 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Selector", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:22", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"vec_hallToPos", + "label":"vec_hallToPos", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "vec_hallToPos", + "int8", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:13#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:17#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:18#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:15#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:11#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:12#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:22#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:14#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:10", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.png new file mode 100644 index 00000000..cb2bbd49 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.svg new file mode 100644 index 00000000..b206aa9e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.svg @@ -0,0 +1,704 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + This calculates the low resolution position based on Hall sensors. + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_pos + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + U + + + + + + + + Idx1 + + + + + + + + 0 + + + + + + + + Y + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + vec_hallToPos + + + + + + + + + + + + + + + + + + + + + + vec_hallToPos + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.json new file mode 100644 index 00000000..9cd26aa3 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.json @@ -0,0 +1,518 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:1359", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"dz_counter", + "label":"dz_counter", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:169", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"z_counter2", + "label":"z_counter2", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "z_maxCntRst", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1454", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum4", + "label":"Sum4", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "rectangular", + "on", + "+-", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1344", + "className":"Simulink.ActionPort", + "icon":"WebViewIcon2", + "name":"Action Port", + "label":"Action Port", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "InitializeStates", + "PropagateVarSize" + ], + "values":[ + "held", + "Only when execution is resumed" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"ActionPort", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1358", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_counter", + "label":"z_counter", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "z_maxCntRst", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1341", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_counterRawPrev", + "label":"z_counterRawPrev", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1341#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:169#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1454#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1340", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.png new file mode 100644 index 00000000..06b930fc Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.svg new file mode 100644 index 00000000..241096af --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.svg @@ -0,0 +1,450 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + dz_counter + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + if { } + + + + + + + + + + + + + + + + + + + + + + Action Port + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_counter + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_counterRawPrev + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.json new file mode 100644 index 00000000..d208397c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.json @@ -0,0 +1,3294 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:1452", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Speed calculations:

Speed_radps = (f_ctrl_Hz * Mechanical_angle_radps) / z_counter

cf_spd_coef = f_ctrl_Hz * Mechanical_angle_deg * pi/180 * 30/pi

Speed_radps = cf_spd_coef / z_counter

", + "label":"

Speed calculations:

Speed_radps = (f_ctrl_Hz * Mechanical_angle_radps) / z_counter

cf_spd_coef = f_ctrl_Hz * Mechanical_angle_deg * pi/180 * 30/pi

Speed_radps = cf_spd_coef / z_counter

", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Speed calculations:

\n

Speed_radps = (f_ctrl_Hz * Mechanical_angle_radps) / z_counter

\n

cf_spd_coef = f_ctrl_Hz * Mechanical_angle_deg * pi/180 * 30/pi

\n

Speed_radps = cf_spd_coef / z_counter

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1453", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Low pass speed filter

", + "label":"

Low pass speed filter

", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Low pass speed filter

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1430", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_counter", + "label":"z_counter", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1447", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"cf_spdCoef", + "label":"cf_spdCoef", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "cf_speedCoef", + "int32", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1431", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_dir", + "label":"z_dir", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1438", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide4", + "label":"Divide4", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "**/", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1451", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_mot", + "label":"n_mot", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1440", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto22", + "label":"Goto22", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_motRaw", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1673", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_motAbs", + "label":"n_motAbs", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1625", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"z_maxCntRst", + "label":"z_maxCntRst", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "z_maxCntRst", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1448", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"cf_speedFilt", + "label":"cf_speedFilt", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "cf_speedFilt", + "int32", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1638", + "className":"Simulink.Switch", + "icon":"WebViewIcon2", + "name":"Switch1", + "label":"Switch1", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllowDiffInputSizes", + "Criteria", + "InputSameDT", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "Threshold", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "u2 ~= 0", + "off", + "off", + "[]", + "[]", + "Zero", + "-1", + "off", + "0", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Switch", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1446", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay2", + "label":"UnitDelay2", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "0", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1444", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum2", + "label":"Sum2", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "rectangular", + "on", + "+-", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1450", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_motRaw", + "label":"n_motRaw", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1650", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto3", + "label":"Goto3", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1649", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counter", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1647", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_dir", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1645", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From42", + "label":"From42", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1636", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From17", + "label":"From17", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dirPrev", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1635", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From15", + "label":"From15", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1623", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From14", + "label":"From14", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1439", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From1", + "label":"From1", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_motRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1648", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_dirPrev", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1435", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide1", + "label":"Divide1", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "**", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1434", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant3", + "label":"Constant3", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "100", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1433", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant2", + "label":"Constant2", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "100", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1637", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant1", + "label":"Constant1", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "0", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1443", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum1", + "label":"Sum1", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "rectangular", + "on", + "++", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1628", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator5", + "label":"Relational Operator5", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + "~=", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1672", + "className":"Simulink.Abs", + "icon":"WebViewIcon2", + "name":"Abs5", + "label":"Abs5", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "[]", + "[]", + "Zero", + "-1", + "off", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Abs", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1639", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_counterRaw", + "label":"z_counterRaw", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1437", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide3", + "label":"Divide3", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "**", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1640", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_dirPrev", + "label":"z_dirPrev", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1646", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From8", + "label":"From8", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counter", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1624", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator2", + "label":"Relational Operator2", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + ">", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1436", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide2", + "label":"Divide2", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "*/", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1627", + "className":"Simulink.Logic", + "icon":"WebViewIcon2", + "name":"Logical Operator1", + "label":"Logical Operator1", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllPortsSameDT", + "IconShape", + "Inputs", + "Operator", + "SampleTime" + ], + "values":[ + "boolean", + "off", + "rectangular", + "2", + "OR", + "-1" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Logic", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1439#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1448#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1444#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1433#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1437#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1638#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"rpm_signed", + "label":"rpm_signed", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "rpm_signed", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1447#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1646#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1446#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1435#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1436#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1443#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1434#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1645#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1624#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1625#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1635#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1636#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1623#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1628#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1627#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1637#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1438#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"rpm_signed", + "label":"rpm_signed", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "rpm_signed", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1431#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1640#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1430#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1639#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1672#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1401", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.png new file mode 100644 index 00000000..3723e19c Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.svg new file mode 100644 index 00000000..8c7d755e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.svg @@ -0,0 +1,2709 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + Speed calculations: + + + + + + + + Speed_radps = (f_ctrl_Hz * Mechanical_angle_radps) / z_counter + + + + + + + + cf_spd_coef = f_ctrl_Hz * Mechanical_angle_deg * pi/180 * 30/pi + + + + + + + + Speed_radps = cf_spd_coef / z_counter + + + + + + + + + + + + + + + + + + + Low pass speed filter + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + z_counter + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + cf_speedCoef + + + + + + + + + + + + + + + + + + + + + + cf_spdCoef + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_dir + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + n_mot + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motRaw] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + n_motAbs + + + + + + + + + + + + + + + + + + + + + + + + + + z_maxCntRst + + + + + + + + + + + + + + + + + + + + + + z_maxCntRst + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + cf_speedFilt + + + + + + + + + + + + + + + + + + + + + + cf_speedFilt + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + T + + + + + + + + F + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + n_motRaw + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dirPrev] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motRaw] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dirPrev] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 100 + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 100 + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + z_counterRaw + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + z_dirPrev + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + rpm_signed + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + rpm_signed + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.json new file mode 100644 index 00000000..59ce0f76 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.json @@ -0,0 +1,923 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1619", + "className":"Simulink.Switch", + "icon":"WebViewIcon2", + "name":"Switch1", + "label":"Switch1", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllowDiffInputSizes", + "Criteria", + "InputSameDT", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "Threshold", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "u2 ~= 0", + "off", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off", + "0", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Switch", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1617", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant23", + "label":"Constant23", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "0", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1621", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay1", + "label":"UnitDelay1", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "z_cntMaxLim", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1615", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"rst", + "label":"rst", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1622", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"y", + "label":"y", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1614", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"u", + "label":"u", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1620", + "className":"Simulink.Switch", + "icon":"WebViewIcon2", + "name":"Switch2", + "label":"Switch2", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllowDiffInputSizes", + "Criteria", + "InputSameDT", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "Threshold", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "u2 ~= 0", + "off", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off", + "0", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Switch", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1618", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator1", + "label":"Relational Operator1", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + "<", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1616", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant1", + "label":"Constant1", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "z_cntMaxLim", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1620#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1618#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1616#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1621#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1617#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1615#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1614#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651:1619#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:1651", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.png new file mode 100644 index 00000000..13483f54 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.svg new file mode 100644 index 00000000..eb4158eb --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.svg @@ -0,0 +1,959 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ~= 0 + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + rst + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + y + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + u + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + T + + + + + + + + F + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + z_cntMaxLim + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.json new file mode 100644 index 00000000..3f7667cc --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.json @@ -0,0 +1,4937 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:524", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Phase Advance map as a function of the Duty Cycle.

", + "label":"

Phase Advance map as a function of the Duty Cycle.

", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Phase Advance map as a function of the Duty Cycle.

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:280", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Phase Advance / Field weakening

", + "label":"

Phase Advance / Field weakening

", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Phase Advance / Field weakening

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:281", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Electrical angle calculation

", + "label":"

Electrical angle calculation

", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Electrical angle calculation

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:216", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_pos", + "label":"z_pos", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:217", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_dir", + "label":"z_dir", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:242", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_pos", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:243", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_dir", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:278", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"a_elecAngleAdv", + "label":"a_elecAngleAdv", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:231", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From10", + "label":"From10", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngleAdv", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:221", + "className":"Simulink.ActionPort", + "icon":"WebViewIcon2", + "name":"Action Port", + "label":"Action Port", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "InitializeStates", + "PropagateVarSize" + ], + "values":[ + "held", + "Only when execution is resumed" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"ActionPort", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:262", + "className":"Simulink.Scope", + "icon":"WebViewIcon2", + "name":"Scope", + "label":"Scope", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":[ + ], + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Scope", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:258", + "className":"Simulink.Mux", + "icon":"WebViewIcon2", + "name":"Mux", + "label":"Mux", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Inputs", + "DisplayOption" + ], + "values":[ + "2", + "bar" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Mux", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:232", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From2", + "label":"From2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:233", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From3", + "label":"From3", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngleAdv", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:279", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"a_elecAngle", + "label":"a_elecAngle", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:235", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From5", + "label":"From5", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:241", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From6", + "label":"From6", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_phaAdv_M1", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:512", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"a_elecPeriod1", + "label":"a_elecPeriod1", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "b_phaAdvEna", + "boolean", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:514", + "className":"Simulink.Switch", + "icon":"WebViewIcon2", + "name":"Switch_PhaAdv", + "label":"Switch_PhaAdv", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllowDiffInputSizes", + "Criteria", + "InputSameDT", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "Threshold", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "u2 ~= 0", + "off", + "off", + "[]", + "[]", + "Zero", + "-1", + "off", + "0", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Switch", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:521", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"a_phaAdv_M2", + "label":"a_phaAdv_M2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "a_phaAdv_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "off", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:522", + "className":"Simulink.PreLookup", + "icon":"WebViewIcon2", + "name":"r_phaAdvDC_XA", + "label":"r_phaAdvDC_XA", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "BreakpointsSpecification", + "BreakpointsDataSource", + "BreakpointsData", + "OutputSelection", + "IndexSearchMethod", + "ExtrapMethod", + "UseLastBreakpoint", + "DiagnosticForOutOfRangeInput", + "RemoveProtectionInput", + "BreakpointMin", + "BreakpointMax", + "LockScale", + "RndMeth", + "BeginIndexSearchUsingPreviousIndexResult", + "BreakpointDataTypeStr", + "BreakpointObject", + "BreakpointsFirstPoint", + "BreakpointsNumPoints", + "BreakpointsSpacing", + "FractionDataTypeStr", + "IndexDataTypeStr", + "OutputBusDataTypeStr", + "SampleTime" + ], + "values":[ + "Explicit values", + "Dialog", + "r_phaAdvDC_XA", + "Index and fraction", + "Evenly spaced points", + "Clip", + "off", + "None", + "off", + "[]", + "[]", + "off", + "Simplest", + "on", + "Inherit: Same as input", + "", + "10", + "11", + "10", + "Inherit: Inherit via internal rule", + "uint8", + "Inherit: auto", + "-1" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 9, + 13 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"PreLookup", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:518", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From11", + "label":"From11", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:534", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From12", + "label":"From12", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:535", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DCabs", + "label":"r_DCabs", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:536", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto8", + "label":"Goto8", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:538", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto9", + "label":"Goto9", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "a_elecAngleAdv", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:547", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"a_elecPeriod2", + "label":"a_elecPeriod2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "a_elecPeriod", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:546", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum3", + "label":"Sum3", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "rectangular", + "off", + "++", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:542", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From7", + "label":"From7", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:545", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Product2", + "label":"Product2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "2", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:543", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From9", + "label":"From9", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:578", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto5", + "label":"Goto5", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "a_phaAdv_M1", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:623", + "className":"Simulink.Math", + "icon":"WebViewIcon2", + "name":"Math Function", + "label":"Math Function", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AlgorithmType", + "IntermediateResultsDataTypeStr", + "Iterations", + "LockScale", + "Operator", + "OutMax", + "OutMin", + "OutputSignalType", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Newton-Raphson", + "Inherit: Inherit via internal rule", + "3", + "off", + "mod", + "[]", + "[]", + "auto", + "Floor", + "-1", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Math", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1460", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_counter", + "label":"z_counter", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1462", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counter", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1461", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_counterRaw", + "label":"z_counterRaw", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1463", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto3", + "label":"Goto3", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1477", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum2", + "label":"Sum2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "rectangular", + "off", + "++", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1469", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From52", + "label":"From52", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counter", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1467", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide5", + "label":"Divide5", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "int32", + "1", + "All dimensions", + "off", + "**", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1470", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From53", + "label":"From53", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1479", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"a_elecAngle1", + "label":"a_elecAngle1", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "a_elecAngle", + "int32", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1466", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide4", + "label":"Divide4", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "int32", + "1", + "All dimensions", + "off", + "**/", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1475", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator7", + "label":"Relational Operator7", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + "==", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1464", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant16", + "label":"Constant16", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "1", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1478", + "className":"Simulink.Switch", + "icon":"WebViewIcon2", + "name":"Switch3", + "label":"Switch3", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllowDiffInputSizes", + "Criteria", + "InputSameDT", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "Threshold", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "u2 ~= 0", + "off", + "off", + "[]", + "[]", + "Zero", + "-1", + "off", + "0", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Switch", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1471", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From54", + "label":"From54", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1468", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From51", + "label":"From51", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_pos", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1474", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Product6", + "label":"Product6", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Inherit via back propagation", + "1", + "All dimensions", + "off", + "2", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1472", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From59", + "label":"From59", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1473", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto7", + "label":"Goto7", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1476", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum1", + "label":"Sum1", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "rectangular", + "off", + "++", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1465", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant2", + "label":"Constant2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "1", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1671", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"n_motPhaAdvEna", + "label":"n_motPhaAdvEna", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "n_motPhaAdvEna", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1670", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator4", + "label":"Relational Operator4", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + ">", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1681", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto4", + "label":"Goto4", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_motAbs", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1669", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From1", + "label":"From1", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_motAbs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1680", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"n_motAbs", + "label":"n_motAbs", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "6", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1668", + "className":"Simulink.Logic", + "icon":"WebViewIcon2", + "name":"Logical Operator2", + "label":"Logical Operator2", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllPortsSameDT", + "IconShape", + "Inputs", + "Operator", + "SampleTime" + ], + "values":[ + "boolean", + "off", + "rectangular", + "2", + "AND", + "-1" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Logic", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:521#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:543#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:216#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:217#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:258#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:232#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:233#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:235#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:231#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:241#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:522#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:522#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:534#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:535#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:514#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:545#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:542#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:518#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:547#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:623#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:546#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1461#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1460#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1470#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1478#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1472#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1477#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1468#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1465#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1469#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1474#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1475#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1464#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1479#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1471#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1476#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1466#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1467#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:512#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1671#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1669#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1670#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1668#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1680#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:215", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.png new file mode 100644 index 00000000..77ccd5cc Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.svg new file mode 100644 index 00000000..65419c31 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.svg @@ -0,0 +1,4231 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + Phase Advance map as a function of the Duty Cycle. + + + + + + + + + + + + + + + + + + + Phase Advance / Field weakening + + + + + + + + + + + + + + + + + + + Electrical angle calculation + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + z_pos + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + z_dir + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_pos] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngleAdv] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + if { } + + + + + + + + + + + + + + + + + + + + + + Action Port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngleAdv] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + a_elecAngle + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_phaAdv_M1] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + b_phaAdvEna + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + T + + + + + + + + F + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + a_phaAdv_M2 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_phaAdvDC_XA + + + + + + + + + + + + + + + ufix32_En31 + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_DCabs + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngleAdv] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + a_elecPeriod + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_phaAdv_M1] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + z_counter + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + z_counterRaw + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + a_elecAngle + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + T + + + + + + + + F + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_pos] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + n_motPhaAdvEna + + + + + + + + + + + + + + + + + + + + + + n_motPhaAdvEna + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motAbs] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motAbs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 6 + + + + + + + + + + + + + + + + + + + + + + n_motAbs + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.json new file mode 100644 index 00000000..606656b0 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.json @@ -0,0 +1,821 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:31", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay", + "label":"UnitDelay", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "0", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:32", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay1", + "label":"UnitDelay1", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "0", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:33", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay2", + "label":"UnitDelay2", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "0", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:27", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallA", + "label":"b_hallA", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:28", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallB", + "label":"b_hallB", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:29", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallC", + "label":"b_hallC", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:37", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"b_edge ", + "label":"b_edge ", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1535", + "className":"Simulink.SFunction", + "icon":"WebViewIcon2", + "name":"Bitwise Operator", + "label":"Bitwise Operator", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "logicop", + "UseBitMask", + "NumInputPorts", + "BitMask", + "BitMaskRealWorld" + ], + "values":[ + "XOR", + "off", + "6", + "bin2dec('11011001')", + "Stored Integer" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"S-Function", + "masktype":"Bitwise Operator" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:27#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:29#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:28#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1535#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:32#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:33#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:31#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:26", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.png new file mode 100644 index 00000000..a1e83fe7 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.svg new file mode 100644 index 00000000..39e88b88 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.svg @@ -0,0 +1,708 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_edge + + + + + + + + + + + + + + + + + + + + + + + + + + Bitwise + + + + + + + + XOR + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.json new file mode 100644 index 00000000..0ce3cacb --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.json @@ -0,0 +1,3751 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:284", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"a_elecAngleAdv", + "label":"a_elecAngleAdv", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:360", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaC ", + "label":"r_phaC ", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:331", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "a_elecAngleAdv", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:359", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaB", + "label":"r_phaB", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:358", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaA", + "label":"r_phaA", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:344", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto9", + "label":"Goto9", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaA_Trap", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:335", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto12", + "label":"Goto12", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaB_Trap", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:336", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto14", + "label":"Goto14", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaC_Trap", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:348", + "className":"Simulink.SwitchCase", + "icon":"WebViewIcon2", + "name":"Switch Case", + "label":"Switch Case", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "CaseConditions", + "ShowDefaultCase", + "ZeroCross", + "SampleTime" + ], + "values":[ + "{CTRL_TRAP, CTRL_SIN, CTRL_SIN3}", + "off", + "on", + "-1" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SwitchCase", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:325", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From4", + "label":"From4", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_ctrlTypSel", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:315", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From", + "label":"From", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngleAdv", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:305", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_02_Sinusoidal_Method", + "label":"F03_02_Sinusoidal_Method", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:326", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From5", + "label":"From5", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngleAdv", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:295", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_03_Sinusoidal3rd_Method", + "label":"F03_03_Sinusoidal3rd_Method", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:327", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From6", + "label":"From6", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngleAdv", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:339", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto4", + "label":"Goto4", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:332", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:337", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:342", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto7", + "label":"Goto7", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaA_Sin", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:340", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto5", + "label":"Goto5", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaB_Sin", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:341", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto6", + "label":"Goto6", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaC_Sin", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:334", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto11", + "label":"Goto11", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaA_Sin3", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:343", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto8", + "label":"Goto8", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaB_Sin3", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:333", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto10", + "label":"Goto10", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaC_Sin3", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:345", + "className":"Simulink.Merge", + "icon":"WebViewIcon2", + "name":"Merge", + "label":"Merge", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "InitialOutput", + "AllowUnequalInputPortWidths", + "InputPortOffsets", + "Inputs" + ], + "values":[ + "[]", + "off", + "[]", + "3" + ], + "tabs":[ + "Parameter Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Merge", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:346", + "className":"Simulink.Merge", + "icon":"WebViewIcon2", + "name":"Merge1", + "label":"Merge1", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "InitialOutput", + "AllowUnequalInputPortWidths", + "InputPortOffsets", + "Inputs" + ], + "values":[ + "[]", + "off", + "[]", + "3" + ], + "tabs":[ + "Parameter Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Merge", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:347", + "className":"Simulink.Merge", + "icon":"WebViewIcon2", + "name":"Merge2", + "label":"Merge2", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "InitialOutput", + "AllowUnequalInputPortWidths", + "InputPortOffsets", + "Inputs" + ], + "values":[ + "[]", + "off", + "[]", + "3" + ], + "tabs":[ + "Parameter Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Merge", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:328", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From7", + "label":"From7", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaA_Trap", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:317", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From13", + "label":"From13", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaB_Trap", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:318", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From14", + "label":"From14", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaC_Trap", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:319", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From15", + "label":"From15", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaA_Sin", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:320", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From16", + "label":"From16", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaB_Sin", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:321", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From17", + "label":"From17", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaC_Sin", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:322", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From18", + "label":"From18", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaA_Sin3", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:323", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From19", + "label":"From19", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaB_Sin3", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:324", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From20", + "label":"From20", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaC_Sin3", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:329", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From8", + "label":"From8", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:330", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From9", + "label":"From9", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:316", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From10", + "label":"From10", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:283", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_ctrlTypSel", + "label":"z_ctrlTypSel", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:338", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto3", + "label":"Goto3", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_ctrlTypSel", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:355", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log6", + "label":"signal_log6", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:349", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log1", + "label":"signal_log1", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:352", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log2", + "label":"signal_log2", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:285", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_01_Pure_Trapezoidal_Method", + "label":"F03_01_Pure_Trapezoidal_Method", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:329#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:330#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:316#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:284#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:285#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:325#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:315#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:348#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:326#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:327#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:348#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:348#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:285#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:285#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:305#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:305#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:305#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:295#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:295#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:295#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:345#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:346#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:347#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:328#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:283#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:319#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:322#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:317#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:320#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:318#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:323#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:321#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:324#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.png new file mode 100644 index 00000000..78428564 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.svg new file mode 100644 index 00000000..b88d85f7 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.svg @@ -0,0 +1,3050 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + r_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngleAdv] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + r_phaB + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_phaA + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA_Trap] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB_Trap] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC_Trap] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + u1 + + + + + + + + case [ 1 ]: + + + + + + + + case [ 2 ]: + + + + + + + + case [ 3 ]: + + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + + + + + + [z_ctrlTypSel] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngleAdv] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + r_phaA_Sin + + + + + + + + r_phaB_Sin + + + + + + + + r_phaC_Sin + + + + + + + + case: { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F03_02_Sinusoidal_Method + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngleAdv] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + r_phaA_Sin3 + + + + + + + + r_phaB_Sin3 + + + + + + + + r_phaC_Sin3 + + + + + + + + case: { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F03_03_Sinusoidal3rd_Method + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngleAdv] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA_Sin] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB_Sin] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC_Sin] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA_Sin3] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB_Sin3] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC_Sin3] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA_Trap] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB_Trap] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC_Trap] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA_Sin] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB_Sin] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC_Sin] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA_Sin3] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB_Sin3] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC_Sin3] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_ctrlTypSel + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_ctrlTypSel] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_phaA + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_phaB + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + r_phaA_Trap + + + + + + + + r_phaB_Trap + + + + + + + + r_phaC_Trap + + + + + + + + case: { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F03_01_Pure_Trapezoidal_Method + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.json new file mode 100644 index 00000000..356b1677 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.json @@ -0,0 +1,968 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:286", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"a_elecAngleAdv", + "label":"a_elecAngleAdv", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:292", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaA_Trap", + "label":"r_phaA_Trap", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:289", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_trapPhaA_M1", + "label":"r_trapPhaA_M1", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_trapPhaA_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:290", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_trapPhaB_M1", + "label":"r_trapPhaB_M1", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_trapPhaB_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:291", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_trapPhaC_M1", + "label":"r_trapPhaC_M1", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_trapPhaC_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:293", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaB_Trap", + "label":"r_phaB_Trap", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:294", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaC_Trap", + "label":"r_phaC_Trap", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:288", + "className":"Simulink.PreLookup", + "icon":"WebViewIcon2", + "name":"a_trapElecAngle_XA", + "label":"a_trapElecAngle_XA", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "BreakpointsSpecification", + "BreakpointsDataSource", + "BreakpointsData", + "OutputSelection", + "IndexSearchMethod", + "ExtrapMethod", + "UseLastBreakpoint", + "DiagnosticForOutOfRangeInput", + "RemoveProtectionInput", + "BreakpointMin", + "BreakpointMax", + "LockScale", + "RndMeth", + "BeginIndexSearchUsingPreviousIndexResult", + "BreakpointDataTypeStr", + "BreakpointObject", + "BreakpointsFirstPoint", + "BreakpointsNumPoints", + "BreakpointsSpacing", + "FractionDataTypeStr", + "IndexDataTypeStr", + "OutputBusDataTypeStr", + "SampleTime" + ], + "values":[ + "Explicit values", + "Dialog", + "a_trapElecAngle_XA", + "Index and fraction", + "Evenly spaced points", + "Clip", + "off", + "None", + "off", + "[]", + "[]", + "off", + "Simplest", + "on", + "Inherit: Same as input", + "", + "10", + "11", + "10", + "Inherit: Inherit via internal rule", + "uint8", + "Inherit: auto", + "-1" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 9, + 13 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"PreLookup", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:287", + "className":"Simulink.ActionPort", + "icon":"WebViewIcon2", + "name":"Action Port", + "label":"Action Port", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "InitializeStates", + "PropagateVarSize" + ], + "values":[ + "reset", + "Only when execution is resumed" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"ActionPort", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:288#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:288#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:289#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:290#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:291#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:286#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:285", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.png new file mode 100644 index 00000000..9d94dc5a Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.svg new file mode 100644 index 00000000..4f5e03e4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.svg @@ -0,0 +1,1096 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_phaA_Trap + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_trapPhaA_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_trapPhaB_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_trapPhaC_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + r_phaB_Trap + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + r_phaC_Trap + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + a_trapElecAngle_XA + + + + + + + + + + + + + + + ufix32_En31 + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + case: { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.json new file mode 100644 index 00000000..659ca6f7 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.json @@ -0,0 +1,968 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:296", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"a_elecAngleAdv", + "label":"a_elecAngleAdv", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:302", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaA_Sin3", + "label":"r_phaA_Sin3", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:299", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_sin3PhaA_M1", + "label":"r_sin3PhaA_M1", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_sin3PhaA_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:300", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_sin3PhaB_M1", + "label":"r_sin3PhaB_M1", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_sin3PhaB_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:301", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_sin3PhaC_M1", + "label":"r_sin3PhaC_M1", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_sin3PhaC_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:303", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaB_Sin3", + "label":"r_phaB_Sin3", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:304", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaC_Sin3", + "label":"r_phaC_Sin3", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:298", + "className":"Simulink.PreLookup", + "icon":"WebViewIcon2", + "name":"a_sinElecAngle_XA", + "label":"a_sinElecAngle_XA", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "BreakpointsSpecification", + "BreakpointsDataSource", + "BreakpointsData", + "OutputSelection", + "IndexSearchMethod", + "ExtrapMethod", + "UseLastBreakpoint", + "DiagnosticForOutOfRangeInput", + "RemoveProtectionInput", + "BreakpointMin", + "BreakpointMax", + "LockScale", + "RndMeth", + "BeginIndexSearchUsingPreviousIndexResult", + "BreakpointDataTypeStr", + "BreakpointObject", + "BreakpointsFirstPoint", + "BreakpointsNumPoints", + "BreakpointsSpacing", + "FractionDataTypeStr", + "IndexDataTypeStr", + "OutputBusDataTypeStr", + "SampleTime" + ], + "values":[ + "Explicit values", + "Dialog", + "a_sinElecAngle_XA", + "Index and fraction", + "Evenly spaced points", + "Clip", + "off", + "None", + "off", + "[]", + "[]", + "off", + "Simplest", + "on", + "Inherit: Same as input", + "", + "10", + "11", + "10", + "Inherit: Inherit via internal rule", + "uint8", + "Inherit: auto", + "-1" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 9, + 13 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"PreLookup", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:297", + "className":"Simulink.ActionPort", + "icon":"WebViewIcon2", + "name":"Action Port", + "label":"Action Port", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "InitializeStates", + "PropagateVarSize" + ], + "values":[ + "reset", + "Only when execution is resumed" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"ActionPort", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:298#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:298#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:299#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:300#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:301#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:296#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:295", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.png new file mode 100644 index 00000000..a00ceddd Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.svg new file mode 100644 index 00000000..26eb7ebf --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.svg @@ -0,0 +1,1816 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_phaA_Sin3 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_sin3PhaA_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_sin3PhaB_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_sin3PhaC_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + r_phaB_Sin3 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + r_phaC_Sin3 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + a_sinElecAngle_XA + + + + + + + + + + + + + + + ufix32_En31 + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + case: { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.json new file mode 100644 index 00000000..5c2fd866 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.json @@ -0,0 +1,968 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:306", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"a_elecAngleAdv", + "label":"a_elecAngleAdv", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:312", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaA_Sin", + "label":"r_phaA_Sin", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:309", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_sinPhaA_M1", + "label":"r_sinPhaA_M1", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_sinPhaA_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:310", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_sinPhaB_M1", + "label":"r_sinPhaB_M1", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_sinPhaB_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:311", + "className":"Simulink.Interpolation_nD", + "icon":"WebViewIcon2", + "name":"r_sinPhaC_M1", + "label":"r_sinPhaC_M1", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "RequireIndexFractionAsBus", + "TableSpecification", + "TableSource", + "Table", + "InterpMethod", + "ExtrapMethod", + "DiagnosticForOutOfRangeInput", + "ValidIndexMayReachLast", + "NumSelectionDims", + "RemoveProtectionIndex", + "TableMin", + "TableMax", + "OutMin", + "OutMax", + "InternalRulePriority", + "LockScale", + "RndMeth", + "SaturateOnIntegerOverflow", + "IntermediateResultsDataTypeStr", + "LookupTableObject", + "OutDataTypeStr", + "SampleTime", + "TableDataTypeStr" + ], + "values":[ + "1", + "off", + "Explicit values", + "Dialog", + "r_sinPhaC_M1", + "Linear", + "Clip", + "None", + "off", + "0", + "on", + "[]", + "[]", + "[]", + "[]", + "Speed", + "off", + "Simplest", + "off", + "Inherit: Same as output", + "", + "int16", + "-1", + "Inherit: Same as output" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 11, + 19 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Interpolation_n-D", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:313", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaB_Sin", + "label":"r_phaB_Sin", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:314", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"r_phaC_Sin", + "label":"r_phaC_Sin", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:308", + "className":"Simulink.PreLookup", + "icon":"WebViewIcon2", + "name":"a_sinElecAngle_XA", + "label":"a_sinElecAngle_XA", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "BreakpointsSpecification", + "BreakpointsDataSource", + "BreakpointsData", + "OutputSelection", + "IndexSearchMethod", + "ExtrapMethod", + "UseLastBreakpoint", + "DiagnosticForOutOfRangeInput", + "RemoveProtectionInput", + "BreakpointMin", + "BreakpointMax", + "LockScale", + "RndMeth", + "BeginIndexSearchUsingPreviousIndexResult", + "BreakpointDataTypeStr", + "BreakpointObject", + "BreakpointsFirstPoint", + "BreakpointsNumPoints", + "BreakpointsSpacing", + "FractionDataTypeStr", + "IndexDataTypeStr", + "OutputBusDataTypeStr", + "SampleTime" + ], + "values":[ + "Explicit values", + "Dialog", + "a_sinElecAngle_XA", + "Index and fraction", + "Evenly spaced points", + "Clip", + "off", + "None", + "off", + "[]", + "[]", + "off", + "Simplest", + "on", + "Inherit: Same as input", + "", + "10", + "11", + "10", + "Inherit: Inherit via internal rule", + "uint8", + "Inherit: auto", + "-1" + ], + "tabs":[ + "Main", + "Data Types", + "-Other" + ], + "tabs_idx":[ + 0, + 9, + 13 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"PreLookup", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:307", + "className":"Simulink.ActionPort", + "icon":"WebViewIcon2", + "name":"Action Port", + "label":"Action Port", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "InitializeStates", + "PropagateVarSize" + ], + "values":[ + "reset", + "Only when execution is resumed" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"ActionPort", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:308#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:306#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:311#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:310#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:309#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:308#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:305", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.png new file mode 100644 index 00000000..8256e239 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.svg new file mode 100644 index 00000000..7fec90d4 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.svg @@ -0,0 +1,1816 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + a_elecAngleAdv + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_phaA_Sin + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_sinPhaA_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_sinPhaB_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1-D T(k,f) + + + + + + + + k1 + + + + + + + + f1 + + + + + + + + + + + + + + + + + + + + + + r_sinPhaC_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + r_phaB_Sin + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + r_phaC_Sin + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + a_sinElecAngle_XA + + + + + + + + + + + + + + + ufix32_En31 + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + case: { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.json new file mode 100644 index 00000000..a05b6670 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.json @@ -0,0 +1,147 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:351", + "className":"Simulink.Terminator", + "icon":"WebViewIcon2", + "name":"Terminator_1", + "label":"Terminator_1", + "parent":"BLDCmotorControl_R2017b:2687:349", + "inspector":{ + "params":[ + ], + "values":[ + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Terminator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:350", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_phaB", + "label":"r_phaB", + "parent":"BLDCmotorControl_R2017b:2687:349", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:350#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"r_phaB", + "label":"r_phaB", + "parent":"BLDCmotorControl_R2017b:2687:349", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "r_phaB", + "off", + "off", + "on", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.png new file mode 100644 index 00000000..a0a21d1a Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.svg new file mode 100644 index 00000000..dedf4d75 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.svg @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_phaB + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + r_phaB + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.json new file mode 100644 index 00000000..ab6dc496 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.json @@ -0,0 +1,147 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:354", + "className":"Simulink.Terminator", + "icon":"WebViewIcon2", + "name":"Terminator_1", + "label":"Terminator_1", + "parent":"BLDCmotorControl_R2017b:2687:352", + "inspector":{ + "params":[ + ], + "values":[ + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Terminator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:353", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_phaC", + "label":"r_phaC", + "parent":"BLDCmotorControl_R2017b:2687:352", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:353#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"r_phaC", + "label":"r_phaC", + "parent":"BLDCmotorControl_R2017b:2687:352", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "r_phaC", + "off", + "off", + "on", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.png new file mode 100644 index 00000000..1a65e91d Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.svg new file mode 100644 index 00000000..3e0906dd --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.svg @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_phaC + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + r_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.json new file mode 100644 index 00000000..c4135d48 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.json @@ -0,0 +1,147 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:357", + "className":"Simulink.Terminator", + "icon":"WebViewIcon2", + "name":"Terminator_1", + "label":"Terminator_1", + "parent":"BLDCmotorControl_R2017b:2687:355", + "inspector":{ + "params":[ + ], + "values":[ + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Terminator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:356", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_phaA", + "label":"r_phaA", + "parent":"BLDCmotorControl_R2017b:2687:355", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:356#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"r_phaA", + "label":"r_phaA", + "parent":"BLDCmotorControl_R2017b:2687:355", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "r_phaA", + "off", + "off", + "on", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.png new file mode 100644 index 00000000..b3c8eca9 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.svg new file mode 100644 index 00000000..f98d40f3 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.svg @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_phaA + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + r_phaA + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.json new file mode 100644 index 00000000..f404ba33 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.json @@ -0,0 +1,2963 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:367", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_pos", + "label":"z_pos", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:414", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaC ", + "label":"DC_phaC ", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:387", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_pos", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:413", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaB", + "label":"DC_phaB", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:412", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaA", + "label":"DC_phaA", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:391", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto4", + "label":"Goto4", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:388", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:389", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:385", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From8", + "label":"From8", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:386", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From9", + "label":"From9", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:377", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From10", + "label":"From10", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:398", + "className":"Simulink.Mux", + "icon":"WebViewIcon2", + "name":"Mux2", + "label":"Mux2", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Inputs", + "DisplayOption" + ], + "values":[ + "3", + "bar" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Mux", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:380", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From39", + "label":"From39", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:381", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From40", + "label":"From40", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:382", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From41", + "label":"From41", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_phaC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:379", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From27", + "label":"From27", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:376", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From1", + "label":"From1", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_pos", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:401", + "className":"Simulink.Switch", + "icon":"WebViewIcon2", + "name":"Switch1", + "label":"Switch1", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllowDiffInputSizes", + "Criteria", + "InputSameDT", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "Threshold", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "u2 ~= 0", + "off", + "off", + "[]", + "[]", + "Zero", + "-1", + "off", + "0", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Switch", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:411", + "className":"Simulink.LookupNDDirect", + "icon":"WebViewIcon2", + "name":"z_commutMap_M1", + "label":"z_commutMap_M1", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "NumberOfTableDimensions", + "InputsSelectThisObjectFromTable", + "TableIsInput", + "Table", + "DiagnosticForOutOfRangeInput", + "TableMin", + "TableMax", + "TableDataTypeStr", + "LockScale", + "SampleTime" + ], + "values":[ + "2", + "Column", + "off", + "z_commutMap_M1", + "None", + "[]", + "[]", + "int16", + "off", + "-1" + ], + "tabs":[ + "Main", + "Table Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 5, + 9 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"LookupNDDirect", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:372", + "className":"Simulink.Demux", + "icon":"WebViewIcon2", + "name":"Demux", + "label":"Demux", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Outputs", + "DisplayOption", + "BusSelectionMode" + ], + "values":[ + "3", + "bar", + "off" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Demux", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:364", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_phaA", + "label":"r_phaA", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:393", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto6", + "label":"Goto6", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:365", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_phaB", + "label":"r_phaB", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:394", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto7", + "label":"Goto7", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:366", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_phaC", + "label":"r_phaC", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:395", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto8", + "label":"Goto8", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_phaC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:396", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto9", + "label":"Goto9", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:362", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DC", + "label":"r_DC", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:373", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide1", + "label":"Divide1", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "*/", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:370", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant1", + "label":"Constant1", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "1000", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:378", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From2", + "label":"From2", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:374", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide2", + "label":"Divide2", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "**", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:375", + "className":"Simulink.Product", + "icon":"WebViewIcon2", + "name":"Divide4", + "label":"Divide4", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "InputSameDT", + "Inputs", + "LockScale", + "Multiplication", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "1", + "All dimensions", + "off", + "**", + "off", + "Element-wise(.*)", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Product", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1385", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_advCtrlEna", + "label":"b_advCtrlEna", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "6", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1386", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto10", + "label":"Goto10", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_advCtrlEna", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1389", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From", + "label":"From", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_advCtrlEna", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:372#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:372#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:372#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:367#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:377#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:386#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:385#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:401#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:376#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:373#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:364#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:365#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:366#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:362#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:380#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:381#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:382#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:398#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:375#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:370#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:378#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:411#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:374#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:379#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1385#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1389#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:361", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.png new file mode 100644 index 00000000..cf555bcc Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.svg new file mode 100644 index 00000000..a5ae659a --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.svg @@ -0,0 +1,2438 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + z_pos + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + DC_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + [z_pos] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + DC_phaB + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + DC_phaA + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaA] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaB] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_pos] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + T + + + + + + + + F + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 2-D T[k] + + + + + + + + + + + + + + + + + + + + + + z_commutMap_M1 + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + r_phaA + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + r_phaB + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + r_phaC + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_phaC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 1000 + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 6 + + + + + + + + + + + + + + + + + + + + + + b_advCtrlEna + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + [b_advCtrlEna] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_advCtrlEna] + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.json new file mode 100644 index 00000000..ec240434 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.json @@ -0,0 +1,1405 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:39", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_pos", + "label":"z_pos", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:57", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_dir", + "label":"z_dir", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:51", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum2", + "label":"Sum2", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "round", + "on", + "|+-", + "off", + "[]", + "[]", + "Zero", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:48", + "className":"Simulink.Logic", + "icon":"WebViewIcon2", + "name":"Logical Operator3", + "label":"Logical Operator3", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllPortsSameDT", + "IconShape", + "Inputs", + "Operator", + "SampleTime" + ], + "values":[ + "boolean", + "off", + "rectangular", + "2", + "OR", + "-1" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Logic", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:49", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator1", + "label":"Relational Operator1", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + "==", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:45", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant8", + "label":"Constant8", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "1", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:50", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator6", + "label":"Relational Operator6", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + "==", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:42", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant20", + "label":"Constant20", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "-5", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:52", + "className":"Simulink.Switch", + "icon":"WebViewIcon2", + "name":"Switch2", + "label":"Switch2", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllowDiffInputSizes", + "Criteria", + "InputSameDT", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "Threshold", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "u2 ~= 0", + "off", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off", + "0", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Switch", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:43", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant23", + "label":"Constant23", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "-1", + "int8", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:44", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant24", + "label":"Constant24", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "1", + "int8", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1632", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_dirPrev", + "label":"z_dirPrev", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1631", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay1", + "label":"UnitDelay1", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "0", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1318", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay2", + "label":"UnitDelay2", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "0", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1314", + "className":"Simulink.ActionPort", + "icon":"WebViewIcon2", + "name":"Action Port", + "label":"Action Port", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "InitializeStates", + "PropagateVarSize" + ], + "values":[ + "held", + "Only when execution is resumed" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"ActionPort", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1318#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:49#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:45#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:51#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:50#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:42#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:44#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:43#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:48#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:39#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:52#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1631#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:38", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.png new file mode 100644 index 00000000..70347baa Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.svg new file mode 100644 index 00000000..3251a1bd --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.svg @@ -0,0 +1,1268 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_pos + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_dir + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + -5 + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + T + + + + + + + + F + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + -1 + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + z_dirPrev + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + if { } + + + + + + + + + + + + + + + + + + + + + + Action Port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.json new file mode 100644 index 00000000..32960f8c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.json @@ -0,0 +1,2 @@ +[ +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.png new file mode 100644 index 00000000..395b0d7f Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.svg new file mode 100644 index 00000000..b084ae26 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.svg @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.json new file mode 100644 index 00000000..32960f8c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.json @@ -0,0 +1,2 @@ +[ +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.png new file mode 100644 index 00000000..395b0d7f Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.svg new file mode 100644 index 00000000..ecb52cbe --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.svg @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.json new file mode 100644 index 00000000..badde555 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.json @@ -0,0 +1,5944 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:1655", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Authorize advance method only it is selected.

", + "label":"

Authorize advance method only it is selected.

", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Authorize advance method only it is selected.

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1654", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Authorize advance method only if command is larger than a threshold.

", + "label":"

Authorize advance method only if command is larger than a threshold.

", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Authorize advance method only if command is larger than a threshold.

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1653", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Authorize advance method only if error is small enough.

", + "label":"

Authorize advance method only if error is small enough.

", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Authorize advance method only if error is small enough.

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1652", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Authorize advance method only if command is in the spinning direction.

", + "label":"

Authorize advance method only if command is in the spinning direction.

", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Authorize advance method only if command is in the spinning direction.

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1330", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Authorize advance method only if speed is above a threshold.

", + "label":"

Authorize advance method only if speed is above a threshold.

", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

Authorize advance method only if speed is above a threshold.

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:141", + "className":"Simulink.Scope", + "icon":"WebViewIcon2", + "name":"Scope2", + "label":"Scope2", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":[ + ], + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Scope", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:142", + "className":"Simulink.Sum", + "icon":"WebViewIcon2", + "name":"Sum1", + "label":"Sum1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "AccumDataTypeStr", + "OutDataTypeStr", + "CollapseDim", + "CollapseMode", + "IconShape", + "InputSameDT", + "Inputs", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow" + ], + "values":[ + "Inherit: Same as first input", + "Inherit: Same as first input", + "1", + "All dimensions", + "round", + "on", + "|++", + "off", + "[]", + "[]", + "Simplest", + "-1", + "off" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Sum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:64", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"Constant6", + "label":"Constant6", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "1", + "int16", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:108", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto8", + "label":"Goto8", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:83", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From11", + "label":"From11", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_edge", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:86", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From16", + "label":"From16", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_edge", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:80", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From", + "label":"From", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:106", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto22", + "label":"Goto22", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counterRawPrev", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:60", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_edge", + "label":"b_edge", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:99", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_edge", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:173", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_mot", + "label":"n_mot", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:81", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From1", + "label":"From1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_mot", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:92", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From4", + "label":"From4", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_mot", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:61", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_dir", + "label":"z_dir", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:100", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_dir", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon6", + "name":"rst_DelayLim", + "label":"rst_DelayLim", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "z_cntMaxLim" + ], + "values":[ + "z_maxCntRst" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1525", + "className":"Simulink.Signum", + "icon":"WebViewIcon2", + "name":"Sign", + "label":"Sign", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "ZeroCross", + "SampleTime" + ], + "values":[ + "on", + "-1" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Signum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1327", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator4", + "label":"Relational Operator4", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + ">", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1524", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator1", + "label":"Relational Operator1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + "==", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1401", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"Motor_Speed_Calculation", + "label":"Motor_Speed_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1339", + "className":"Simulink.If", + "icon":"WebViewIcon2", + "name":"If1", + "label":"If1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "NumInputs", + "IfExpression", + "ElseIfExpressions", + "ShowElse", + "ZeroCross", + "SampleTime" + ], + "values":[ + "1", + "u1 ~= 0", + "", + "off", + "on", + "-1" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"If", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1526", + "className":"Simulink.Signum", + "icon":"WebViewIcon2", + "name":"Sign1", + "label":"Sign1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "ZeroCross", + "SampleTime" + ], + "values":[ + "on", + "-1" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Signum", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1374", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto18", + "label":"Goto18", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1372", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto17", + "label":"Goto17", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_advCtrlEna", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1664", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto10", + "label":"Goto10", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1518", + "className":"Simulink.Relay", + "icon":"WebViewIcon2", + "name":"dz_counter", + "label":"dz_counter", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "OnSwitchValue", + "OffSwitchValue", + "OnOutputValue", + "OffOutputValue", + "OutDataTypeStr", + "InputProcessing", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "ZeroCross" + ], + "values":[ + "dz_counterHi", + "dz_counterLo", + "0", + "1", + "boolean", + "Elements as channels (sample based)", + "off", + "[]", + "[]", + "-1", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 4, + 5 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Relay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1400", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto6", + "label":"Goto6", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_motRaw", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1533", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From9", + "label":"From9", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_edge", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1395", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From8", + "label":"From8", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counter", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:972", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From7", + "label":"From7", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_motRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1630", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_dirPrev", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1488", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_counterRaw", + "label":"z_counterRaw", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1371", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto16", + "label":"Goto16", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_ctrlTypSel", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1485", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From5", + "label":"From5", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1397", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From42", + "label":"From42", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1521", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From6", + "label":"From6", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1326", + "className":"Simulink.RelationalOperator", + "icon":"WebViewIcon2", + "name":"Relational Operator3", + "label":"Relational Operator3", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "OutDataTypeStr", + "InputSameDT", + "Operator", + "RndMeth", + "SampleTime", + "ZeroCross" + ], + "values":[ + "boolean", + "off", + "~=", + "Simplest", + "-1", + "on" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"RelationalOperator", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1665", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From17", + "label":"From17", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1517", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From3", + "label":"From3", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_advCtrlEna", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1329", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"r_commDCDeacv", + "label":"r_commDCDeacv", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "r_commDCDeacv", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1642", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From15", + "label":"From15", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1455", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From19", + "label":"From19", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "dz_counter", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1641", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From14", + "label":"From14", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dirPrev", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1323", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From29", + "label":"From29", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_motAbs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1487", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_counter", + "label":"z_counter", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1380", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From18", + "label":"From18", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_advCtrlEna", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1507", + "className":"Simulink.UnitDelay", + "icon":"WebViewIcon2", + "name":"UnitDelay1", + "label":"UnitDelay1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "InitialCondition", + "InputProcessing", + "SampleTime", + "CodeGenStateStorageTypeQualifier", + "StateMustResolveToSignalObject", + "StateName", + "StateSignalObject", + "StateStorageClass" + ], + "values":[ + "0", + "Elements as channels (sample based)", + "-1", + "", + "off", + "", + [ + ], + "Auto" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 3 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"UnitDelay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:659", + "className":"Simulink.Mux", + "icon":"WebViewIcon2", + "name":"Mux1", + "label":"Mux1", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Inputs", + "DisplayOption" + ], + "values":[ + "2", + "bar" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Mux", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1362", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto9", + "label":"Goto9", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "dz_counter", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1676", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_motAbs", + "label":"n_motAbs", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1340", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"Counter_Hold_and_Error_Calculation", + "label":"Counter_Hold_and_Error_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1361", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From2", + "label":"From2", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counterRawPrev", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:660", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From10", + "label":"From10", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counter", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1381", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"b_advCtrlEna", + "label":"b_advCtrlEna", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1366", + "className":"Simulink.Abs", + "icon":"WebViewIcon2", + "name":"Abs2", + "label":"Abs2", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "OutDataTypeStr", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "[]", + "[]", + "Zero", + "-1", + "off", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Abs", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1629", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_dirPrev", + "label":"z_dirPrev", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "6", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1674", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto3", + "label":"Goto3", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_motAbs", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1675", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From20", + "label":"From20", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_motAbs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1523", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From13", + "label":"From13", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1663", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DCabs", + "label":"r_DCabs", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1398", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto15", + "label":"Goto15", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_mot", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1328", + "className":"Simulink.Relay", + "icon":"WebViewIcon2", + "name":"n_commDeacv", + "label":"n_commDeacv", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "OnSwitchValue", + "OffSwitchValue", + "OnOutputValue", + "OffOutputValue", + "OutDataTypeStr", + "InputProcessing", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "ZeroCross" + ], + "values":[ + "n_commDeacvHi", + "n_commAcvLo", + "1", + "0", + "boolean", + "Elements as channels (sample based)", + "off", + "[]", + "[]", + "-1", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 4, + 5 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Relay", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1370", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"z_ctrlTypSel", + "label":"z_ctrlTypSel", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:842", + "className":"Simulink.Mux", + "icon":"WebViewIcon2", + "name":"Mux2", + "label":"Mux2", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Inputs", + "DisplayOption" + ], + "values":[ + "2", + "bar" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Mux", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:786", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto5", + "label":"Goto5", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counter", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1373", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DC", + "label":"r_DC", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1324", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From30", + "label":"From30", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_ctrlTypSel", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1486", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From12", + "label":"From12", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counter", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1321", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"CTRL_COMM", + "label":"CTRL_COMM", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "CTRL_COMM", + "Inherit: Inherit via back propagation", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1325", + "className":"Simulink.Logic", + "icon":"WebViewIcon2", + "name":"Logical Operator2", + "label":"Logical Operator2", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "OutDataTypeStr", + "AllPortsSameDT", + "IconShape", + "Inputs", + "Operator", + "SampleTime" + ], + "values":[ + "boolean", + "off", + "rectangular", + "5", + "AND", + "-1" + ], + "tabs":[ + "Data Type", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Logic", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1366#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1518#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:972#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:842#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:92#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:659#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:80#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:660#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:86#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:64#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:142#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:60#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:81#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:61#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1324#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1323#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1321#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1665#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1329#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1325#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1339#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1340#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1361#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1340#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1455#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1370#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1373#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1380#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1397#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1401#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1401#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1395#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1486#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1485#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:83#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1507#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1517#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1521#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1525#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1523#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1526#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1533#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1629#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1641#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1642#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1328#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1326#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1327#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1524#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1663#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1401#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1675#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.png new file mode 100644 index 00000000..da76322c Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.svg new file mode 100644 index 00000000..aaf0f676 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.svg @@ -0,0 +1,4858 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + Authorize advance method only it is selected. + + + + + + + + + + + + + + + + + + + Authorize advance method only if + + + + + + + + command is larger than a threshold. + + + + + + + + + + + + + + + + + + + Authorize advance method + + + + + + + + only if error is small enough. + + + + + + + + + + + + + + + + + + + Authorize advance method only if + + + + + + + + command is in the spinning direction. + + + + + + + + + + + + + + + + + + + Authorize advance method only + + + + + + + + if speed is above a threshold. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_edge] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_edge] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRawPrev] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + b_edge + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_edge] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + n_mot + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + z_dir + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + u + + + + + + + + rst + + + + + + + + y + + + + + + + + 1 + + + + + + + + z + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + z_dir + + + + + + + + z_dirPrev + + + + + + + + z_counter + + + + + + + + z_counterRaw + + + + + + + + n_motRaw + + + + + + + + n_mot + + + + + + + + n_motAbs + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Motor_Speed_Calculation + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + u1 + + + + + + + + if(u1 ~= 0) + + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_advCtrlEna] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + dz_counter + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motRaw] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_edge] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motRaw] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dirPrev] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + z_counterRaw + + + + + + + + + + + + + + + + + + + + + + + + + + [z_ctrlTypSel] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_advCtrlEna] + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + r_commDCDeacv + + + + + + + + + + + + + + + + + + + + + + r_commDCDeacv + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [dz_counter] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dirPrev] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motAbs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + z_counter + + + + + + + + + + + + + + + + + + + + + + + + + + [b_advCtrlEna] + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [dz_counter] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + n_motAbs + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + z_counterRawPrev + + + + + + + + z_counter + + + + + + + + dz_counter + + + + + + + + if { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Counter_Hold_and_Error_Calculation + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRawPrev] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + b_advCtrlEna + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + 6 + + + + + + + + + + + + + + + + + + + + + + z_dirPrev + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motAbs] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motAbs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + r_DCabs + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + n_commDeacv + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + z_ctrlTypSel + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_ctrlTypSel] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + CTRL_COMM + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.json new file mode 100644 index 00000000..85ceaebb --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.json @@ -0,0 +1,4568 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:7", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallA", + "label":"b_hallA", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:8", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallB", + "label":"b_hallB", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:9", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallC", + "label":"b_hallC", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:212", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_mot ", + "label":"n_mot ", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "8", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:26", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_01_Edge_Detector", + "label":"F01_01_Edge_Detector", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:186", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From2", + "label":"From2", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:187", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From3", + "label":"From3", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:190", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From4", + "label":"From4", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:191", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From5", + "label":"From5", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:192", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From6", + "label":"From6", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:193", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From7", + "label":"From7", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:205", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto7", + "label":"Goto7", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_edge", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:198", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto16", + "label":"Goto16", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_pos", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:188", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From36", + "label":"From36", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_pos", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:38", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_03_Direction_Detection", + "label":"F01_03_Direction_Detection", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:189", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From38", + "label":"From38", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_edge", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:200", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto21", + "label":"Goto21", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_dir", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:196", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:197", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:199", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:59", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_04_Speed_Calculation", + "label":"F01_04_Speed_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:10", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_02_Position_Calculation", + "label":"F01_02_Position_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:179", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From1", + "label":"From1", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_edge", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:202", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto4", + "label":"Goto4", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_mot", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:194", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From8", + "label":"From8", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_mot", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:211", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_dir", + "label":"z_dir", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:195", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From9", + "label":"From9", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:210", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_pos", + "label":"z_pos", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:180", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From10", + "label":"From10", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_pos", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:183", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From13", + "label":"From13", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dir", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:209", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_ctrlTypSel", + "label":"z_ctrlTypSel", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:184", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From14", + "label":"From14", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_ctrlTypSel", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:206", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto8", + "label":"Goto8", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_ctrlTypSel", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:208", + "className":"Simulink.Constant", + "icon":"WebViewIcon2", + "name":"z_ctrlTypSel1", + "label":"z_ctrlTypSel1", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Value", + "OutDataTypeStr", + "FramePeriod", + "LockScale", + "OutMax", + "OutMin", + "SampleTime", + "VectorParams1D" + ], + "values":[ + "z_ctrlTypSel", + "uint8", + "inf", + "off", + "[]", + "[]", + "inf", + "on" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1, + 2 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Constant", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1490", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto6", + "label":"Goto6", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1376", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto18", + "label":"Goto18", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1677", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto11", + "label":"Goto11", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_motAbs", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1662", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto10", + "label":"Goto10", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1666", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From17", + "label":"From17", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1633", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From15", + "label":"From15", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_dirPrev", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1382", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From18", + "label":"From18", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_advCtrlEna", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1383", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"b_advCtrlEna", + "label":"b_advCtrlEna", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "7", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1377", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From", + "label":"From", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_ctrlTypSel", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1482", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From16", + "label":"From16", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counter", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1384", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto3", + "label":"Goto3", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_advCtrlEna", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1483", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_counter", + "label":"z_counter", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1484", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"z_counterRaw", + "label":"z_counterRaw", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1678", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From19", + "label":"From19", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_motAbs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1661", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DCabs", + "label":"r_DCabs", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1679", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_motAbs", + "label":"n_motAbs", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "6", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "0", + "off", + "reset", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1375", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DC", + "label":"r_DC", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1378", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From11", + "label":"From11", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1489", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto5", + "label":"Goto5", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_counter", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1481", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From12", + "label":"From12", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "z_counterRaw", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1634", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto9", + "label":"Goto9", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "z_dirPrev", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1313", + "className":"Simulink.If", + "icon":"WebViewIcon2", + "name":"If2", + "label":"If2", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "NumInputs", + "IfExpression", + "ElseIfExpressions", + "ShowElse", + "ZeroCross", + "SampleTime" + ], + "values":[ + "1", + "u1 ~= 0", + "", + "off", + "on", + "-1" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"If", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1313#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:189#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:188#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:191#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:26#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:38#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:192#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:193#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:7#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:8#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:9#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:190#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:187#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:186#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:10#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:179#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:59#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:194#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:195#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:180#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:183#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:184#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:208#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1375#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1377#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1378#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1382#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:59#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1482#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1481#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:59#out:4", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:59#out:5", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:38#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1633#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1661#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1666#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:59#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1678#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.png new file mode 100644 index 00000000..a2556bff Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.svg new file mode 100644 index 00000000..df323403 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.svg @@ -0,0 +1,3553 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 8 + + + + + + + + + + + + + + + + + + + + + + n_mot + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + b_hallB + + + + + + + + b_hallC + + + + + + + + b_edge + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F01_01_Edge_Detector + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallA] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallB] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallC] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallA] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallB] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallC] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_edge] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_pos] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_pos] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + z_pos + + + + + + + + z_dir + + + + + + + + z_dirPrev + + + + + + + + if { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F01_03_Direction_Detection + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_edge] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + r_DCabs + + + + + + + + z_ctrlTypSel + + + + + + + + b_edge + + + + + + + + z_dir + + + + + + + + z_dirPrev + + + + + + + + n_mot + + + + + + + + n_motAbs + + + + + + + + b_advCtrlEna + + + + + + + + z_counter + + + + + + + + z_counterRaw + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F01_04_Speed_Calculation + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + b_hallB + + + + + + + + b_hallC + + + + + + + + z_pos + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F01_02_Position_Calculation + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_edge] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + z_dir + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + z_pos + + + + + + + + + + + + + + + + + + + + + + + + + + [z_pos] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dir] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + z_ctrlTypSel + + + + + + + + + + + + + + + + + + + + + + + + + + [z_ctrlTypSel] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_ctrlTypSel] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + z_ctrlTypSel + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motAbs] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dirPrev] + + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_advCtrlEna] + + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + + + + + + 7 + + + + + + + + + + + + + + + + + + + + + + b_advCtrlEna + + + + + + + + + + + + + + + + + + + + + + + + + + [z_ctrlTypSel] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_advCtrlEna] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + z_counter + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + z_counterRaw + + + + + + + + + + + + + + + + + + + + + + + + + + [n_motAbs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + r_DCabs + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 6 + + + + + + + + + + + + + + + + + + + + + + n_motAbs + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counter] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [z_counterRaw] + + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + [z_dirPrev] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + u1 + + + + + + + + if(u1 ~= 0) + + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.json new file mode 100644 index 00000000..01079efa --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.json @@ -0,0 +1,3868 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:2687:462", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

Hall_A

Hall_B

Hall_C

vev_hallToPos

0

0

0

0

1

1

1

1

0

0

1

1

0

0

1

1

0

1

0

1

0

1

0

1

0

5

3

4

1

0

2

0

", + "label":"

Hall_A

Hall_B

Hall_C

vev_hallToPos

0

0

0

0

1

1

1

1

0

0

1

1

0

0

1

1

0

1

0

1

0

1

0

1

0

5

3

4

1

0

2

0

", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n\n\n\n\n\n\n\n\n\n\n
\n

Hall_A

\n

Hall_B

\n

Hall_C

\n

vev_hallToPos

\n

0

\n

0

\n

0

\n

0

\n

1

\n

1

\n

1

\n

1

\n

0

\n

0

\n

1

\n

1

\n

0

\n

0

\n

1

\n

1

\n

0

\n

1

\n

0

\n

1

\n

0

\n

1

\n

0

\n

1

\n

0

\n

5

\n

3

\n

4

\n

1

\n

0

\n

2

\n

0

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:463", + "className":"Simulink.Annotation", + "icon":"WebViewIcon5", + "name":"

The rotor position is implemented based on the following table:

", + "label":"

The rotor position is implemented based on the following table:

", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Text", + "DropShadow", + "Interpreter", + "FontName", + "FontWeight", + "FontSize", + "FontAngle", + "ForegroundColor", + "BackgroundColor", + "HorizontalAlignment", + "UseDisplayTextAsClickCallback", + "ClickFcn" + ], + "values":[ + "\n\n

The rotor position is implemented based on the following table:

", + "off", + "rich", + "auto", + "auto", + -1, + "auto", + "black", + "white", + "left", + "off", + "" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:447", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaA", + "label":"DC_phaA", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:2", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallA ", + "label":"b_hallA ", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:426", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:427", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:428", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto3", + "label":"Goto3", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:450", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_mot", + "label":"n_mot", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:3", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallB", + "label":"b_hallB", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:4", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallC", + "label":"b_hallC", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_Preliminary_Calculations", + "label":"F01_Preliminary_Calculations", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:418", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From2", + "label":"From2", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:419", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From3", + "label":"From3", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:420", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From4", + "label":"From4", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:282", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_Control_Method_Selection", + "label":"F03_Control_Method_Selection", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:215", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F02_Electrical_Angle_Calculation", + "label":"F02_Electrical_Angle_Calculation", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:434", + "className":"Simulink.If", + "icon":"WebViewIcon2", + "name":"If1", + "label":"If1", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "NumInputs", + "IfExpression", + "ElseIfExpressions", + "ShowElse", + "ZeroCross", + "SampleTime" + ], + "values":[ + "1", + "u1 ~= CTRL_COMM", + "", + "off", + "on", + "-1" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"If", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:361", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F04_Control_Type_Management", + "label":"F04_Control_Type_Management", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:416", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From", + "label":"From", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:431", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto6", + "label":"Goto6", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:429", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto4", + "label":"Goto4", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:430", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto5", + "label":"Goto5", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:432", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto7", + "label":"Goto7", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_mot", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:417", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From1", + "label":"From1", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_mot", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:421", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From5", + "label":"From5", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:448", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaB", + "label":"DC_phaB", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:422", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From6", + "label":"From6", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:449", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaC", + "label":"DC_phaC", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:423", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From7", + "label":"From7", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:425", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:5", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DC", + "label":"r_DC", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:433", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto8", + "label":"Goto8", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:451", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"a_elecAngle", + "label":"a_elecAngle", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:424", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From8", + "label":"From8", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:457", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"Implemented_control_methods", + "label":"Implemented_control_methods", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "BlockChoice", + "TemplateBlock", + "MemberBlocks", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "MinAlgLoopOccurrences", + "PropExecContextOutsideSubsystem", + "SystemSampleTime", + "RTWSystemCode", + "RTWFcnNameOpts", + "RTWFcnName", + "RTWFileNameOpts", + "RTWFileName", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "RTWMemSecFuncInitTerm", + "RTWMemSecFuncExecute", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "IsSubsystemVirtual", + "Variant", + "VariantControl", + "OverrideUsingVariant", + "GeneratePreprocessorConditionals", + "AllowZeroVariantControls", + "PropagateVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "TreatAsGroupedWhenPropagatingVariantConditions" + ], + "values":[ + "FromPortIcon", + "", + "", + "", + "ReadWrite", + "", + "All", + "off", + "off", + "off", + "-1", + "Auto", + "Auto", + "", + "Auto", + "", + "void_void", + "off", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "on", + "off", + "", + "", + "off", + "off", + "off", + "", + "", + "on" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:537", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From9", + "label":"From9", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:589", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon6", + "name":"Model_Info", + "label":"Model_Info", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1379", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From10", + "label":"From10", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1659", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto9", + "label":"Goto9", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1667", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From11", + "label":"From11", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DCabs", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1660", + "className":"Simulink.Abs", + "icon":"WebViewIcon2", + "name":"Abs1", + "label":"Abs1", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "OutDataTypeStr", + "LockScale", + "OutMax", + "OutMin", + "RndMeth", + "SampleTime", + "SaturateOnIntegerOverflow", + "ZeroCross" + ], + "values":[ + "Inherit: Inherit via back propagation", + "off", + "[]", + "[]", + "Zero", + "-1", + "off", + "on" + ], + "tabs":[ + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 1 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Abs", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:2#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:3#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:4#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:417#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:421#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:418#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:420#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:419#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:8", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:434#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:215#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:282#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:282#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:282#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:416#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:361#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:361#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:361#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:422#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:423#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:5#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:424#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:215#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:537#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1379#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:7", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:4", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:5", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1660#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1667#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6#out:6", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.png new file mode 100644 index 00000000..7247e245 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.svg new file mode 100644 index 00000000..4259e5fe --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_2687_d.svg @@ -0,0 +1,3547 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Hall_A + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Hall_B + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Hall_C + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + vev_hallToPos + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 1 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 1 + 0 + 1 + 0 + 1 + 0 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 5 + 3 + 4 + 1 + 0 + 2 + 0 + + + + + + + + + + + + + + + + + + + The rotor position is implemented based on the following table: + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + DC_phaA + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + n_mot + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + b_hallB + + + + + + + + b_hallC + + + + + + + + r_DC + + + + + + + + r_DCabs + + + + + + + + z_ctrlTypSel + + + + + + + + z_pos + + + + + + + + z_dir + + + + + + + + z_counter + + + + + + + + z_counterRaw + + + + + + + + n_motAbs + + + + + + + + b_advCtrlEna + + + + + + + + n_mot + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F01_Preliminary_Calculations + + + + + + + + + + + + + + + + + + + + + boolean + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + int8 + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallA] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallB] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallC] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + z_ctrlTypSel + + + + + + + + a_elecAngleAdv + + + + + + + + r_phaA + + + + + + + + r_phaB + + + + + + + + r_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F03_Control_Method_Selection + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + int16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_DCabs + + + + + + + + z_pos + + + + + + + + z_dir + + + + + + + + z_counter + + + + + + + + z_counterRaw + + + + + + + + n_motAbs + + + + + + + + a_elecAngleAdv + + + + + + + + a_elecAngle + + + + + + + + if { } + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F02_Electrical_Angle_Calculation + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + u1 + + + + + + + + if(u1 ~= CTRL_COMM) + + + + + + + + + + + + + + + + + + + + + + action + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + r_phaA + + + + + + + + r_phaB + + + + + + + + r_phaC + + + + + + + + z_pos + + + + + + + + b_advCtrlEna + + + + + + + + DC_phaA + + + + + + + + DC_phaB + + + + + + + + DC_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + F04_Control_Type_Management + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaA] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + DC_phaB + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaB] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + DC_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + a_elecAngle + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Implemented_control_methods + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + MODEL INFO + + + + + + + + Version: 1.883 + + + + + + + + Author: Emanuel Feru + + + + + + + + Last modified by: eferu + + + + + + + + Last update: + + + + + + + + Copyright © 2019 Emanuel FERU + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DCabs] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.json new file mode 100644 index 00000000..b0ad966c --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.json @@ -0,0 +1,2649 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:39", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaA", + "label":"DC_phaA", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:365", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallA ", + "label":"b_hallA ", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "1", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:443", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto1", + "label":"Goto1", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:444", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto2", + "label":"Goto2", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:445", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto3", + "label":"Goto3", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "b_hallC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:628", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"n_mot", + "label":"n_mot", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1277", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallB", + "label":"b_hallB", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1278", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"b_hallC", + "label":"b_hallC", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1759", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From1", + "label":"From1", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "n_mot", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1760", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From5", + "label":"From5", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1762", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaB", + "label":"DC_phaB", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "2", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1761", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From6", + "label":"From6", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1764", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"DC_phaC", + "label":"DC_phaC", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "3", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1763", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From7", + "label":"From7", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "DC_phaC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1765", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto", + "label":"Goto", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "r_DC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1766", + "className":"Simulink.Inport", + "icon":"WebViewIcon2", + "name":"r_DC", + "label":"r_DC", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "InputConnect", + "Interpolate", + "LatchByDelayingOutsideSignal", + "LatchInputForFeedbackSignals", + "OutputFunctionCall" + ], + "values":[ + "4", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "", + "on", + "off", + "off", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Inport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1828", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log6", + "label":"signal_log6", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1831", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log1", + "label":"signal_log1", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1834", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log2", + "label":"signal_log2", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1837", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log3", + "label":"signal_log3", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2463", + "className":"Simulink.Outport", + "icon":"WebViewIcon2", + "name":"a_elecAngle", + "label":"a_elecAngle", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "Port", + "IconDisplay", + "OutMin", + "OutMax", + "OutDataTypeStr", + "LockScale", + "Unit", + "PortDimensions", + "VarSizeSig", + "SampleTime", + "SignalType", + "BusOutputAsStruct", + "EnsureOutportIsVirtual", + "InitialOutput", + "MustResolveToSignalObject", + "OutputWhenDisabled", + "OutputWhenUnConnected", + "OutputWhenUnconnectedValue", + "SignalName", + "SignalObject", + "SourceOfInitialOutputValue", + "StorageClass", + "VectorParamsAs1DForOutWhenUnconnected" + ], + "values":[ + "5", + "Port number", + "[]", + "[]", + "Inherit: auto", + "off", + "inherit", + "-1", + "Inherit", + "-1", + "auto", + "off", + "off", + "[]", + "off", + "held", + "off", + "0", + "", + [ + ], + "Dialog", + "Auto", + "off" + ], + "tabs":[ + "Main", + "Signal Attributes", + "-Other" + ], + "tabs_idx":[ + 0, + 2, + 11 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Outport", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2462", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From8", + "label":"From8", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon3", + "name":"BLDC_controller", + "label":"BLDC_controller", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "1e-5", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ContainerHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2688", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From18", + "label":"From18", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallA", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2689", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From19", + "label":"From19", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallB", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2690", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From20", + "label":"From20", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "b_hallC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2691", + "className":"Simulink.From", + "icon":"WebViewIcon2", + "name":"From21", + "label":"From21", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "IconDisplay" + ], + "values":[ + "r_DC", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"From", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2695", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto21", + "label":"Goto21", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaA", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2696", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto22", + "label":"Goto22", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaB", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2692", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto18", + "label":"Goto18", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "DC_phaC", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2693", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto19", + "label":"Goto19", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "n_mot", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2694", + "className":"Simulink.Goto", + "icon":"WebViewIcon2", + "name":"Goto20", + "label":"Goto20", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "GotoTag", + "TagVisibility", + "IconDisplay" + ], + "values":[ + "a_elecAngle", + "local", + "Tag" + ], + "tabs":[ + "Parameter Attributes" + ], + "tabs_idx":0 + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"Goto", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:365#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:1277#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:1278#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:1759#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:1760#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:1761#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:1763#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:1766#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2462#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2691#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2690#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2689#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2688#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687#out:5", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687#out:4", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687#out:3", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687#out:2", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + }, + { + "sid":"BLDCmotorControl_R2017b:2687#out:1", + "className":"Simulink.Line", + "icon":"WebViewIcon4", + "name":"", + "label":"", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "SignalNameFromLabel", + "MustResolveToSignal", + "ShowPropagatedSignal", + "DataLogging", + "TestPoint", + "SignalObjectPackage", + "StorageClass", + "Description", + "documentLink" + ], + "values":[ + "", + "off", + "off", + "off", + "off", + "Simulink", + "Auto", + "", + "" + ], + "tabs":[ + "Parameter Attributes", + "Logging and Accessibility", + "Code Generation", + "Documentation" + ], + "tabs_idx":[ + 0, + 3, + 5, + 7 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":[ + ] + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.png new file mode 100644 index 00000000..14fa3c06 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.svg b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.svg new file mode 100644 index 00000000..4d876016 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_d.svg @@ -0,0 +1,2051 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + DC_phaA + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + n_mot + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaA] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 2 + + + + + + + + + + + + + + + + + + + + + + DC_phaB + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaB] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + 3 + + + + + + + + + + + + + + + + + + + + + + DC_phaC + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4 + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallB + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_DC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 5 + + + + + + + + + + + + + + + + + + + + + + a_elecAngle + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + b_hallA + + + + + + + + b_hallB + + + + + + + + b_hallC + + + + + + + + r_DC + + + + + + + + DC_phaA + + + + + + + + DC_phaB + + + + + + + + DC_phaC + + + + + + + + n_mot + + + + + + + + a_elecAngle + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + BLDC_controller + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallA] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallB] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [b_hallC] + + + + + + + + + + + + + + + + + + + + + + uint8 + + + + + + + + + + + + + + + + + + + + + + + + + + [r_DC] + + + + + + + + + + + + + + + + + + + + + + int32 + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaA] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaB] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [DC_phaC] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [n_mot] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [a_elecAngle] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_icons.css b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_icons.css new file mode 100644 index 00000000..ef96522f --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_icons.css @@ -0,0 +1,15 @@ +.WebViewIcon0, +.WebViewIcon1, +.WebViewIcon2, +.WebViewIcon3, +.WebViewIcon4, +.WebViewIcon5, +.WebViewIcon6 { background-image: url('BLDCmotorControl_R2017b_29_icons.png'); width: 16px; height: 16px; } + +.WebViewIcon0 { background-position: -0px; } +.WebViewIcon1 { background-position: -16px; } +.WebViewIcon2 { background-position: -32px; } +.WebViewIcon3 { background-position: -48px; } +.WebViewIcon4 { background-position: -64px; } +.WebViewIcon5 { background-position: -80px; } +.WebViewIcon6 { background-position: -96px; } diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_icons.png b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_icons.png new file mode 100644 index 00000000..c06c4af9 Binary files /dev/null and b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_29_icons.png differ diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_h_1.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_h_1.json new file mode 100644 index 00000000..ab7a8b63 --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_h_1.json @@ -0,0 +1,1298 @@ +[ + { + "hid":1, + "sid":"BLDCmotorControl_R2017b", + "esid":"", + "parent":0, + "children":[ + 2 + ], + "name":"BLDCmotorControl_R2017b", + "fullname":"BLDCmotorControl_R2017b", + "label":"BLDCmotorControl_R2017b", + "icon":"WebViewIcon0", + "sameAsElement":false + }, + { + "hid":2, + "sid":"BLDCmotorControl_R2017b:29", + "esid":"BLDCmotorControl_R2017b:29", + "parent":1, + "children":[ + 3, + 23, + 24, + 25, + 26 + ], + "name":"BLDC_controller", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller", + "label":"BLDC_controller", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_29_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_29_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_29_d.json", + "elements":[ + ":39", + ":365", + ":443", + ":444", + ":445", + ":628", + ":1277", + ":1278", + ":1759", + ":1760", + ":1762", + ":1761", + ":1764", + ":1763", + ":1765", + ":1766", + ":1828", + ":1831", + ":1834", + ":1837", + ":2463", + ":2462", + ":2687", + ":2688", + ":2689", + ":2690", + ":2691", + ":2695", + ":2696", + ":2692", + ":2693", + ":2694", + ":365#out:1", + ":1277#out:1", + ":1278#out:1", + ":1759#out:1", + ":1760#out:1", + ":1761#out:1", + ":1763#out:1", + ":1766#out:1", + ":2462#out:1", + ":2691#out:1", + ":2690#out:1", + ":2689#out:1", + ":2688#out:1", + ":2687#out:5", + ":2687#out:4", + ":2687#out:3", + ":2687#out:2", + ":2687#out:1" + ], + "sameAsElement":true + }, + { + "hid":3, + "sid":"BLDCmotorControl_R2017b:2687", + "esid":"BLDCmotorControl_R2017b:2687", + "parent":2, + "children":[ + 4, + 12, + 13, + 20, + 21, + 22 + ], + "name":"BLDC_controller", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller", + "label":"BLDC_controller", + "icon":"WebViewIcon3", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_d.json", + "elements":[ + ":2687:462", + ":2687:463", + ":2687:447", + ":2687:2", + ":2687:426", + ":2687:427", + ":2687:428", + ":2687:450", + ":2687:3", + ":2687:4", + ":2687:6", + ":2687:418", + ":2687:419", + ":2687:420", + ":2687:282", + ":2687:215", + ":2687:434", + ":2687:361", + ":2687:416", + ":2687:431", + ":2687:429", + ":2687:430", + ":2687:432", + ":2687:417", + ":2687:421", + ":2687:448", + ":2687:422", + ":2687:449", + ":2687:423", + ":2687:425", + ":2687:5", + ":2687:433", + ":2687:451", + ":2687:424", + ":2687:457", + ":2687:537", + ":2687:589", + ":2687:1379", + ":2687:1659", + ":2687:1667", + ":2687:1660", + ":2687:2#out:1", + ":2687:3#out:1", + ":2687:4#out:1", + ":2687:417#out:1", + ":2687:421#out:1", + ":2687:418#out:1", + ":2687:420#out:1", + ":2687:419#out:1", + ":2687:6#out:2", + ":2687:6#out:3", + ":2687:6#out:8", + ":2687:6#out:1", + ":2687:434#out:1", + ":2687:215#out:1", + ":2687:282#out:1", + ":2687:282#out:2", + ":2687:282#out:3", + ":2687:416#out:1", + ":2687:361#out:1", + ":2687:361#out:2", + ":2687:361#out:3", + ":2687:422#out:1", + ":2687:423#out:1", + ":2687:5#out:1", + ":2687:424#out:1", + ":2687:215#out:2", + ":2687:537#out:1", + ":2687:1379#out:1", + ":2687:6#out:7", + ":2687:6#out:4", + ":2687:6#out:5", + ":2687:1660#out:1", + ":2687:1667#out:1", + ":2687:6#out:6" + ], + "sameAsElement":true + }, + { + "hid":4, + "sid":"BLDCmotorControl_R2017b:2687:6", + "esid":"BLDCmotorControl_R2017b:2687:6", + "parent":3, + "children":[ + 5, + 6, + 7, + 8 + ], + "name":"F01_Preliminary_Calculations", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations", + "label":"F01_Preliminary_Calculations", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_6_d.json", + "elements":[ + ":2687:7", + ":2687:8", + ":2687:9", + ":2687:212", + ":2687:26", + ":2687:186", + ":2687:187", + ":2687:190", + ":2687:191", + ":2687:192", + ":2687:193", + ":2687:205", + ":2687:198", + ":2687:188", + ":2687:38", + ":2687:189", + ":2687:200", + ":2687:196", + ":2687:197", + ":2687:199", + ":2687:59", + ":2687:10", + ":2687:179", + ":2687:202", + ":2687:194", + ":2687:211", + ":2687:195", + ":2687:210", + ":2687:180", + ":2687:183", + ":2687:209", + ":2687:184", + ":2687:206", + ":2687:208", + ":2687:1490", + ":2687:1376", + ":2687:1677", + ":2687:1662", + ":2687:1666", + ":2687:1633", + ":2687:1382", + ":2687:1383", + ":2687:1377", + ":2687:1482", + ":2687:1384", + ":2687:1483", + ":2687:1484", + ":2687:1678", + ":2687:1661", + ":2687:1679", + ":2687:1375", + ":2687:1378", + ":2687:1489", + ":2687:1481", + ":2687:1634", + ":2687:1313", + ":2687:1313#out:1", + ":2687:189#out:1", + ":2687:188#out:1", + ":2687:191#out:1", + ":2687:26#out:1", + ":2687:38#out:1", + ":2687:192#out:1", + ":2687:193#out:1", + ":2687:7#out:1", + ":2687:8#out:1", + ":2687:9#out:1", + ":2687:190#out:1", + ":2687:187#out:1", + ":2687:186#out:1", + ":2687:10#out:1", + ":2687:179#out:1", + ":2687:59#out:1", + ":2687:194#out:1", + ":2687:195#out:1", + ":2687:180#out:1", + ":2687:183#out:1", + ":2687:184#out:1", + ":2687:208#out:1", + ":2687:1375#out:1", + ":2687:1377#out:1", + ":2687:1378#out:1", + ":2687:1382#out:1", + ":2687:59#out:3", + ":2687:1482#out:1", + ":2687:1481#out:1", + ":2687:59#out:4", + ":2687:59#out:5", + ":2687:38#out:2", + ":2687:1633#out:1", + ":2687:1661#out:1", + ":2687:1666#out:1", + ":2687:59#out:2", + ":2687:1678#out:1" + ], + "sameAsElement":true + }, + { + "hid":5, + "sid":"BLDCmotorControl_R2017b:2687:26", + "esid":"BLDCmotorControl_R2017b:2687:26", + "parent":4, + "children":[ + ], + "name":"F01_01_Edge_Detector", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_01_Edge_Detector", + "label":"F01_01_Edge_Detector", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_26_d.json", + "elements":[ + ":2687:31", + ":2687:32", + ":2687:33", + ":2687:27", + ":2687:28", + ":2687:29", + ":2687:37", + ":2687:1535", + ":2687:27#out:1", + ":2687:29#out:1", + ":2687:28#out:1", + ":2687:1535#out:1", + ":2687:32#out:1", + ":2687:33#out:1", + ":2687:31#out:1" + ], + "sameAsElement":true + }, + { + "hid":6, + "sid":"BLDCmotorControl_R2017b:2687:10", + "esid":"BLDCmotorControl_R2017b:2687:10", + "parent":4, + "children":[ + ], + "name":"F01_02_Position_Calculation", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_02_Position_Calculation", + "label":"F01_02_Position_Calculation", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_10_d.json", + "elements":[ + ":2687:25", + ":2687:11", + ":2687:12", + ":2687:13", + ":2687:23", + ":2687:15", + ":2687:17", + ":2687:18", + ":2687:14", + ":2687:22", + ":2687:13#out:1", + ":2687:17#out:1", + ":2687:18#out:1", + ":2687:15#out:1", + ":2687:11#out:1", + ":2687:12#out:1", + ":2687:22#out:1", + ":2687:14#out:1" + ], + "sameAsElement":true + }, + { + "hid":7, + "sid":"BLDCmotorControl_R2017b:2687:38", + "esid":"BLDCmotorControl_R2017b:2687:38", + "parent":4, + "children":[ + ], + "name":"F01_03_Direction_Detection", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_03_Direction_Detection", + "label":"F01_03_Direction_Detection", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_38_d.json", + "elements":[ + ":2687:39", + ":2687:57", + ":2687:51", + ":2687:48", + ":2687:49", + ":2687:45", + ":2687:50", + ":2687:42", + ":2687:52", + ":2687:43", + ":2687:44", + ":2687:1632", + ":2687:1631", + ":2687:1318", + ":2687:1314", + ":2687:1318#out:1", + ":2687:49#out:1", + ":2687:45#out:1", + ":2687:51#out:1", + ":2687:50#out:1", + ":2687:42#out:1", + ":2687:44#out:1", + ":2687:43#out:1", + ":2687:48#out:1", + ":2687:39#out:1", + ":2687:52#out:1", + ":2687:1631#out:1" + ], + "sameAsElement":true + }, + { + "hid":8, + "sid":"BLDCmotorControl_R2017b:2687:59", + "esid":"BLDCmotorControl_R2017b:2687:59", + "parent":4, + "children":[ + 9, + 10, + 11 + ], + "name":"F01_04_Speed_Calculation", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation", + "label":"F01_04_Speed_Calculation", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_59_d.json", + "elements":[ + ":2687:1655", + ":2687:1654", + ":2687:1653", + ":2687:1652", + ":2687:1330", + ":2687:141", + ":2687:142", + ":2687:64", + ":2687:108", + ":2687:83", + ":2687:86", + ":2687:80", + ":2687:106", + ":2687:60", + ":2687:99", + ":2687:173", + ":2687:81", + ":2687:92", + ":2687:61", + ":2687:100", + ":2687:1651", + ":2687:1525", + ":2687:1327", + ":2687:1524", + ":2687:1401", + ":2687:1339", + ":2687:1526", + ":2687:1374", + ":2687:1372", + ":2687:1664", + ":2687:1518", + ":2687:1400", + ":2687:1533", + ":2687:1395", + ":2687:972", + ":2687:1630", + ":2687:1488", + ":2687:1371", + ":2687:1485", + ":2687:1397", + ":2687:1521", + ":2687:1326", + ":2687:1665", + ":2687:1517", + ":2687:1329", + ":2687:1642", + ":2687:1455", + ":2687:1641", + ":2687:1323", + ":2687:1487", + ":2687:1380", + ":2687:1507", + ":2687:659", + ":2687:1362", + ":2687:1676", + ":2687:1340", + ":2687:1361", + ":2687:660", + ":2687:1381", + ":2687:1366", + ":2687:1629", + ":2687:1674", + ":2687:1675", + ":2687:1523", + ":2687:1663", + ":2687:1398", + ":2687:1328", + ":2687:1370", + ":2687:842", + ":2687:786", + ":2687:1373", + ":2687:1324", + ":2687:1486", + ":2687:1321", + ":2687:1325", + ":2687:1366#out:1", + ":2687:1518#out:1", + ":2687:972#out:1", + ":2687:842#out:1", + ":2687:92#out:1", + ":2687:659#out:1", + ":2687:80#out:1", + ":2687:660#out:1", + ":2687:86#out:1", + ":2687:64#out:1", + ":2687:142#out:1", + ":2687:60#out:1", + ":2687:81#out:1", + ":2687:61#out:1", + ":2687:1651#out:1", + ":2687:1324#out:1", + ":2687:1323#out:1", + ":2687:1321#out:1", + ":2687:1665#out:1", + ":2687:1329#out:1", + ":2687:1325#out:1", + ":2687:1339#out:1", + ":2687:1340#out:1", + ":2687:1361#out:1", + ":2687:1340#out:2", + ":2687:1455#out:1", + ":2687:1370#out:1", + ":2687:1373#out:1", + ":2687:1380#out:1", + ":2687:1397#out:1", + ":2687:1401#out:2", + ":2687:1401#out:1", + ":2687:1395#out:1", + ":2687:1486#out:1", + ":2687:1485#out:1", + ":2687:83#out:1", + ":2687:1507#out:1", + ":2687:1517#out:1", + ":2687:1521#out:1", + ":2687:1525#out:1", + ":2687:1523#out:1", + ":2687:1526#out:1", + ":2687:1533#out:1", + ":2687:1629#out:1", + ":2687:1641#out:1", + ":2687:1642#out:1", + ":2687:1328#out:1", + ":2687:1326#out:1", + ":2687:1327#out:1", + ":2687:1524#out:1", + ":2687:1663#out:1", + ":2687:1401#out:3", + ":2687:1675#out:1" + ], + "sameAsElement":true + }, + { + "hid":9, + "sid":"BLDCmotorControl_R2017b:2687:1340", + "esid":"BLDCmotorControl_R2017b:2687:1340", + "parent":8, + "children":[ + ], + "name":"Counter_Hold_and_Error_Calculation", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation/Counter_Hold_and_Error_Calculation", + "label":"Counter_Hold_and_Error_Calculation", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1340_d.json", + "elements":[ + ":2687:1359", + ":2687:169", + ":2687:1454", + ":2687:1344", + ":2687:1358", + ":2687:1341", + ":2687:1341#out:1", + ":2687:169#out:1", + ":2687:1454#out:1" + ], + "sameAsElement":true + }, + { + "hid":10, + "sid":"BLDCmotorControl_R2017b:2687:1401", + "esid":"BLDCmotorControl_R2017b:2687:1401", + "parent":8, + "children":[ + ], + "name":"Motor_Speed_Calculation", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation/Motor_Speed_Calculation", + "label":"Motor_Speed_Calculation", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1401_d.json", + "elements":[ + ":2687:1452", + ":2687:1453", + ":2687:1430", + ":2687:1447", + ":2687:1431", + ":2687:1438", + ":2687:1451", + ":2687:1440", + ":2687:1673", + ":2687:1625", + ":2687:1448", + ":2687:1638", + ":2687:1446", + ":2687:1444", + ":2687:1450", + ":2687:1650", + ":2687:1649", + ":2687:1647", + ":2687:1645", + ":2687:1636", + ":2687:1635", + ":2687:1623", + ":2687:1439", + ":2687:1648", + ":2687:1435", + ":2687:1434", + ":2687:1433", + ":2687:1637", + ":2687:1443", + ":2687:1628", + ":2687:1672", + ":2687:1639", + ":2687:1437", + ":2687:1640", + ":2687:1646", + ":2687:1624", + ":2687:1436", + ":2687:1627", + ":2687:1439#out:1", + ":2687:1448#out:1", + ":2687:1444#out:1", + ":2687:1433#out:1", + ":2687:1437#out:1", + ":2687:1638#out:1", + ":2687:1447#out:1", + ":2687:1646#out:1", + ":2687:1446#out:1", + ":2687:1435#out:1", + ":2687:1436#out:1", + ":2687:1443#out:1", + ":2687:1434#out:1", + ":2687:1645#out:1", + ":2687:1624#out:1", + ":2687:1625#out:1", + ":2687:1635#out:1", + ":2687:1636#out:1", + ":2687:1623#out:1", + ":2687:1628#out:1", + ":2687:1627#out:1", + ":2687:1637#out:1", + ":2687:1438#out:1", + ":2687:1431#out:1", + ":2687:1640#out:1", + ":2687:1430#out:1", + ":2687:1639#out:1", + ":2687:1672#out:1" + ], + "sameAsElement":true + }, + { + "hid":11, + "sid":"BLDCmotorControl_R2017b:2687:1651", + "esid":"BLDCmotorControl_R2017b:2687:1651", + "parent":8, + "children":[ + ], + "name":"rst_DelayLim", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation/rst_DelayLim", + "label":"rst_DelayLim", + "icon":"WebViewIcon6", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_1651_d.json", + "elements":[ + ":2687:1651:1619", + ":2687:1651:1617", + ":2687:1651:1621", + ":2687:1651:1615", + ":2687:1651:1622", + ":2687:1651:1614", + ":2687:1651:1620", + ":2687:1651:1618", + ":2687:1651:1616", + ":2687:1651:1620#out:1", + ":2687:1651:1618#out:1", + ":2687:1651:1616#out:1", + ":2687:1651:1621#out:1", + ":2687:1651:1617#out:1", + ":2687:1651:1615#out:1", + ":2687:1651:1614#out:1", + ":2687:1651:1619#out:1" + ], + "sameAsElement":true + }, + { + "hid":12, + "sid":"BLDCmotorControl_R2017b:2687:215", + "esid":"BLDCmotorControl_R2017b:2687:215", + "parent":3, + "children":[ + ], + "name":"F02_Electrical_Angle_Calculation", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F02_Electrical_Angle_Calculation", + "label":"F02_Electrical_Angle_Calculation", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_215_d.json", + "elements":[ + ":2687:524", + ":2687:280", + ":2687:281", + ":2687:216", + ":2687:217", + ":2687:242", + ":2687:243", + ":2687:278", + ":2687:231", + ":2687:221", + ":2687:262", + ":2687:258", + ":2687:232", + ":2687:233", + ":2687:279", + ":2687:235", + ":2687:241", + ":2687:512", + ":2687:514", + ":2687:521", + ":2687:522", + ":2687:518", + ":2687:534", + ":2687:535", + ":2687:536", + ":2687:538", + ":2687:547", + ":2687:546", + ":2687:542", + ":2687:545", + ":2687:543", + ":2687:578", + ":2687:623", + ":2687:1460", + ":2687:1462", + ":2687:1461", + ":2687:1463", + ":2687:1477", + ":2687:1469", + ":2687:1467", + ":2687:1470", + ":2687:1479", + ":2687:1466", + ":2687:1475", + ":2687:1464", + ":2687:1478", + ":2687:1471", + ":2687:1468", + ":2687:1474", + ":2687:1472", + ":2687:1473", + ":2687:1476", + ":2687:1465", + ":2687:1671", + ":2687:1670", + ":2687:1681", + ":2687:1669", + ":2687:1680", + ":2687:1668", + ":2687:521#out:1", + ":2687:543#out:1", + ":2687:216#out:1", + ":2687:217#out:1", + ":2687:258#out:1", + ":2687:232#out:1", + ":2687:233#out:1", + ":2687:235#out:1", + ":2687:231#out:1", + ":2687:241#out:1", + ":2687:522#out:2", + ":2687:522#out:1", + ":2687:534#out:1", + ":2687:535#out:1", + ":2687:514#out:1", + ":2687:545#out:1", + ":2687:542#out:1", + ":2687:518#out:1", + ":2687:547#out:1", + ":2687:623#out:1", + ":2687:546#out:1", + ":2687:1461#out:1", + ":2687:1460#out:1", + ":2687:1470#out:1", + ":2687:1478#out:1", + ":2687:1472#out:1", + ":2687:1477#out:1", + ":2687:1468#out:1", + ":2687:1465#out:1", + ":2687:1469#out:1", + ":2687:1474#out:1", + ":2687:1475#out:1", + ":2687:1464#out:1", + ":2687:1479#out:1", + ":2687:1471#out:1", + ":2687:1476#out:1", + ":2687:1466#out:1", + ":2687:1467#out:1", + ":2687:512#out:1", + ":2687:1671#out:1", + ":2687:1669#out:1", + ":2687:1670#out:1", + ":2687:1668#out:1", + ":2687:1680#out:1" + ], + "sameAsElement":true + }, + { + "hid":13, + "sid":"BLDCmotorControl_R2017b:2687:282", + "esid":"BLDCmotorControl_R2017b:2687:282", + "parent":3, + "children":[ + 14, + 15, + 16, + 17, + 18, + 19 + ], + "name":"F03_Control_Method_Selection", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection", + "label":"F03_Control_Method_Selection", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_282_d.json", + "elements":[ + ":2687:284", + ":2687:360", + ":2687:331", + ":2687:359", + ":2687:358", + ":2687:344", + ":2687:335", + ":2687:336", + ":2687:348", + ":2687:325", + ":2687:315", + ":2687:305", + ":2687:326", + ":2687:295", + ":2687:327", + ":2687:339", + ":2687:332", + ":2687:337", + ":2687:342", + ":2687:340", + ":2687:341", + ":2687:334", + ":2687:343", + ":2687:333", + ":2687:345", + ":2687:346", + ":2687:347", + ":2687:328", + ":2687:317", + ":2687:318", + ":2687:319", + ":2687:320", + ":2687:321", + ":2687:322", + ":2687:323", + ":2687:324", + ":2687:329", + ":2687:330", + ":2687:316", + ":2687:283", + ":2687:338", + ":2687:355", + ":2687:349", + ":2687:352", + ":2687:285", + ":2687:329#out:1", + ":2687:330#out:1", + ":2687:316#out:1", + ":2687:284#out:1", + ":2687:285#out:1", + ":2687:325#out:1", + ":2687:315#out:1", + ":2687:348#out:1", + ":2687:326#out:1", + ":2687:327#out:1", + ":2687:348#out:2", + ":2687:348#out:3", + ":2687:285#out:2", + ":2687:285#out:3", + ":2687:305#out:3", + ":2687:305#out:2", + ":2687:305#out:1", + ":2687:295#out:3", + ":2687:295#out:2", + ":2687:295#out:1", + ":2687:345#out:1", + ":2687:346#out:1", + ":2687:347#out:1", + ":2687:328#out:1", + ":2687:283#out:1", + ":2687:319#out:1", + ":2687:322#out:1", + ":2687:317#out:1", + ":2687:320#out:1", + ":2687:318#out:1", + ":2687:323#out:1", + ":2687:321#out:1", + ":2687:324#out:1" + ], + "sameAsElement":true + }, + { + "hid":14, + "sid":"BLDCmotorControl_R2017b:2687:285", + "esid":"BLDCmotorControl_R2017b:2687:285", + "parent":13, + "children":[ + ], + "name":"F03_01_Pure_Trapezoidal_Method", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/F03_01_Pure_Trapezoidal_Method", + "label":"F03_01_Pure_Trapezoidal_Method", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_285_d.json", + "elements":[ + ":2687:286", + ":2687:292", + ":2687:289", + ":2687:290", + ":2687:291", + ":2687:293", + ":2687:294", + ":2687:288", + ":2687:287", + ":2687:288#out:1", + ":2687:288#out:2", + ":2687:289#out:1", + ":2687:290#out:1", + ":2687:291#out:1", + ":2687:286#out:1" + ], + "sameAsElement":true + }, + { + "hid":15, + "sid":"BLDCmotorControl_R2017b:2687:305", + "esid":"BLDCmotorControl_R2017b:2687:305", + "parent":13, + "children":[ + ], + "name":"F03_02_Sinusoidal_Method", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/F03_02_Sinusoidal_Method", + "label":"F03_02_Sinusoidal_Method", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_305_d.json", + "elements":[ + ":2687:306", + ":2687:312", + ":2687:309", + ":2687:310", + ":2687:311", + ":2687:313", + ":2687:314", + ":2687:308", + ":2687:307", + ":2687:308#out:2", + ":2687:306#out:1", + ":2687:311#out:1", + ":2687:310#out:1", + ":2687:309#out:1", + ":2687:308#out:1" + ], + "sameAsElement":true + }, + { + "hid":16, + "sid":"BLDCmotorControl_R2017b:2687:295", + "esid":"BLDCmotorControl_R2017b:2687:295", + "parent":13, + "children":[ + ], + "name":"F03_03_Sinusoidal3rd_Method", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/F03_03_Sinusoidal3rd_Method", + "label":"F03_03_Sinusoidal3rd_Method", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_295_d.json", + "elements":[ + ":2687:296", + ":2687:302", + ":2687:299", + ":2687:300", + ":2687:301", + ":2687:303", + ":2687:304", + ":2687:298", + ":2687:297", + ":2687:298#out:1", + ":2687:298#out:2", + ":2687:299#out:1", + ":2687:300#out:1", + ":2687:301#out:1", + ":2687:296#out:1" + ], + "sameAsElement":true + }, + { + "hid":17, + "sid":"BLDCmotorControl_R2017b:2687:349", + "esid":"BLDCmotorControl_R2017b:2687:349", + "parent":13, + "children":[ + ], + "name":"signal_log1", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/signal_log1", + "label":"signal_log1", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_349_d.json", + "elements":[ + ":2687:351", + ":2687:350", + ":2687:350#out:1" + ], + "sameAsElement":true + }, + { + "hid":18, + "sid":"BLDCmotorControl_R2017b:2687:352", + "esid":"BLDCmotorControl_R2017b:2687:352", + "parent":13, + "children":[ + ], + "name":"signal_log2", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/signal_log2", + "label":"signal_log2", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_352_d.json", + "elements":[ + ":2687:354", + ":2687:353", + ":2687:353#out:1" + ], + "sameAsElement":true + }, + { + "hid":19, + "sid":"BLDCmotorControl_R2017b:2687:355", + "esid":"BLDCmotorControl_R2017b:2687:355", + "parent":13, + "children":[ + ], + "name":"signal_log6", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/signal_log6", + "label":"signal_log6", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_355_d.json", + "elements":[ + ":2687:357", + ":2687:356", + ":2687:356#out:1" + ], + "sameAsElement":true + }, + { + "hid":20, + "sid":"BLDCmotorControl_R2017b:2687:361", + "esid":"BLDCmotorControl_R2017b:2687:361", + "parent":3, + "children":[ + ], + "name":"F04_Control_Type_Management", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F04_Control_Type_Management", + "label":"F04_Control_Type_Management", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_361_d.json", + "elements":[ + ":2687:367", + ":2687:414", + ":2687:387", + ":2687:413", + ":2687:412", + ":2687:391", + ":2687:388", + ":2687:389", + ":2687:385", + ":2687:386", + ":2687:377", + ":2687:398", + ":2687:380", + ":2687:381", + ":2687:382", + ":2687:379", + ":2687:376", + ":2687:401", + ":2687:411", + ":2687:372", + ":2687:364", + ":2687:393", + ":2687:365", + ":2687:394", + ":2687:366", + ":2687:395", + ":2687:396", + ":2687:362", + ":2687:373", + ":2687:370", + ":2687:378", + ":2687:374", + ":2687:375", + ":2687:1385", + ":2687:1386", + ":2687:1389", + ":2687:372#out:3", + ":2687:372#out:2", + ":2687:372#out:1", + ":2687:367#out:1", + ":2687:377#out:1", + ":2687:386#out:1", + ":2687:385#out:1", + ":2687:401#out:1", + ":2687:376#out:1", + ":2687:373#out:1", + ":2687:364#out:1", + ":2687:365#out:1", + ":2687:366#out:1", + ":2687:362#out:1", + ":2687:380#out:1", + ":2687:381#out:1", + ":2687:382#out:1", + ":2687:398#out:1", + ":2687:375#out:1", + ":2687:370#out:1", + ":2687:378#out:1", + ":2687:411#out:1", + ":2687:374#out:1", + ":2687:379#out:1", + ":2687:1385#out:1", + ":2687:1389#out:1" + ], + "sameAsElement":true + }, + { + "hid":21, + "sid":"BLDCmotorControl_R2017b:2687:457", + "esid":"BLDCmotorControl_R2017b:2687:457", + "parent":3, + "children":[ + ], + "name":"Implemented_control_methods", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/Implemented_control_methods", + "label":"Implemented_control_methods", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_457_d.json", + "elements":[ + ], + "sameAsElement":true + }, + { + "hid":22, + "sid":"BLDCmotorControl_R2017b:2687:589", + "esid":"BLDCmotorControl_R2017b:2687:589", + "parent":3, + "children":[ + ], + "name":"Model_Info", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/Model_Info", + "label":"Model_Info", + "icon":"WebViewIcon6", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_2687_589_d.json", + "elements":[ + ], + "sameAsElement":true + }, + { + "hid":23, + "sid":"BLDCmotorControl_R2017b:1831", + "esid":"BLDCmotorControl_R2017b:1831", + "parent":2, + "children":[ + ], + "name":"signal_log1", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/signal_log1", + "label":"signal_log1", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_1831_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_1831_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_1831_d.json", + "elements":[ + ":1833", + ":1832", + ":1832#out:1" + ], + "sameAsElement":true + }, + { + "hid":24, + "sid":"BLDCmotorControl_R2017b:1834", + "esid":"BLDCmotorControl_R2017b:1834", + "parent":2, + "children":[ + ], + "name":"signal_log2", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/signal_log2", + "label":"signal_log2", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_1834_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_1834_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_1834_d.json", + "elements":[ + ":1836", + ":1835", + ":1835#out:1" + ], + "sameAsElement":true + }, + { + "hid":25, + "sid":"BLDCmotorControl_R2017b:1837", + "esid":"BLDCmotorControl_R2017b:1837", + "parent":2, + "children":[ + ], + "name":"signal_log3", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/signal_log3", + "label":"signal_log3", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_1837_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_1837_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_1837_d.json", + "elements":[ + ":1839", + ":1838", + ":1838#out:1" + ], + "sameAsElement":true + }, + { + "hid":26, + "sid":"BLDCmotorControl_R2017b:1828", + "esid":"BLDCmotorControl_R2017b:1828", + "parent":2, + "children":[ + ], + "name":"signal_log6", + "fullname":"BLDCmotorControl_R2017b/BLDC_controller/signal_log6", + "label":"signal_log6", + "icon":"WebViewIcon1", + "svg":"support/slwebview_files/BLDCmotorControl_R2017b_1828_d.svg", + "thumbnail":"support/slwebview_files/BLDCmotorControl_R2017b_1828_d.png", + "backingUrl":"support/slwebview_files/BLDCmotorControl_R2017b_1828_d.json", + "elements":[ + ":1830", + ":1829", + ":1829#out:1" + ], + "sameAsElement":true + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_m.json b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_m.json new file mode 100644 index 00000000..bb093e2e --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/support/slwebview_files/BLDCmotorControl_R2017b_m.json @@ -0,0 +1,2355 @@ +[ + { + "sid":"BLDCmotorControl_R2017b:29", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"BLDC_controller", + "label":"BLDC_controller", + "parent":"BLDCmotorControl_R2017b", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "on", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "Ts_ctrl", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon3", + "name":"BLDC_controller", + "label":"BLDC_controller", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "1e-5", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:6", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_Preliminary_Calculations", + "label":"F01_Preliminary_Calculations", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:26", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_01_Edge_Detector", + "label":"F01_01_Edge_Detector", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:10", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_02_Position_Calculation", + "label":"F01_02_Position_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:38", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_03_Direction_Detection", + "label":"F01_03_Direction_Detection", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:59", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F01_04_Speed_Calculation", + "label":"F01_04_Speed_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:6", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1340", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"Counter_Hold_and_Error_Calculation", + "label":"Counter_Hold_and_Error_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1401", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"Motor_Speed_Calculation", + "label":"Motor_Speed_Calculation", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:1651", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon6", + "name":"rst_DelayLim", + "label":"rst_DelayLim", + "parent":"BLDCmotorControl_R2017b:2687:59", + "inspector":{ + "params":[ + "z_cntMaxLim" + ], + "values":[ + "z_maxCntRst" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:215", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F02_Electrical_Angle_Calculation", + "label":"F02_Electrical_Angle_Calculation", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:282", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_Control_Method_Selection", + "label":"F03_Control_Method_Selection", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:285", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_01_Pure_Trapezoidal_Method", + "label":"F03_01_Pure_Trapezoidal_Method", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:305", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_02_Sinusoidal_Method", + "label":"F03_02_Sinusoidal_Method", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:295", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F03_03_Sinusoidal3rd_Method", + "label":"F03_03_Sinusoidal3rd_Method", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "off", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:349", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log1", + "label":"signal_log1", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:352", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log2", + "label":"signal_log2", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:355", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log6", + "label":"signal_log6", + "parent":"BLDCmotorControl_R2017b:2687:282", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:361", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"F04_Control_Type_Management", + "label":"F04_Control_Type_Management", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:457", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"Implemented_control_methods", + "label":"Implemented_control_methods", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "BlockChoice", + "TemplateBlock", + "MemberBlocks", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "MinAlgLoopOccurrences", + "PropExecContextOutsideSubsystem", + "SystemSampleTime", + "RTWSystemCode", + "RTWFcnNameOpts", + "RTWFcnName", + "RTWFileNameOpts", + "RTWFileName", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "RTWMemSecFuncInitTerm", + "RTWMemSecFuncExecute", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "IsSubsystemVirtual", + "Variant", + "VariantControl", + "OverrideUsingVariant", + "GeneratePreprocessorConditionals", + "AllowZeroVariantControls", + "PropagateVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "TreatAsGroupedWhenPropagatingVariantConditions" + ], + "values":[ + "FromPortIcon", + "", + "", + "", + "ReadWrite", + "", + "All", + "off", + "off", + "off", + "-1", + "Auto", + "Auto", + "", + "Auto", + "", + "void_void", + "off", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "on", + "off", + "", + "", + "off", + "off", + "off", + "", + "", + "on" + ], + "tabs":[ + ], + "tabs_idx":[ + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:2687:589", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon6", + "name":"Model_Info", + "label":"Model_Info", + "parent":"BLDCmotorControl_R2017b:2687", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1831", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log1", + "label":"signal_log1", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1834", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log2", + "label":"signal_log2", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1837", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log3", + "label":"signal_log3", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + }, + { + "sid":"BLDCmotorControl_R2017b:1828", + "className":"Simulink.SubSystem", + "icon":"WebViewIcon1", + "name":"signal_log6", + "label":"signal_log6", + "parent":"BLDCmotorControl_R2017b:29", + "inspector":{ + "params":[ + "ShowPortLabels", + "Permissions", + "ErrorFcn", + "PermitHierarchicalResolution", + "TreatAsAtomicUnit", + "TreatAsGroupedWhenPropagatingVariantConditions", + "ActiveVariant", + "ActiveVariantBlock", + "AllowZeroVariantControls", + "BlockChoice", + "FunctionInterfaceSpec", + "FunctionWithSeparateData", + "GeneratePreprocessorConditionals", + "IsSubsystemVirtual", + "MemberBlocks", + "MinAlgLoopOccurrences", + "OverrideUsingVariant", + "PropExecContextOutsideSubsystem", + "PropagateVariantConditions", + "RTWFcnName", + "RTWFcnNameOpts", + "RTWFileName", + "RTWFileNameOpts", + "RTWMemSecDataConstants", + "RTWMemSecDataInternal", + "RTWMemSecDataParameters", + "RTWMemSecFuncExecute", + "RTWMemSecFuncInitTerm", + "RTWSystemCode", + "SystemSampleTime", + "TemplateBlock", + "Variant", + "VariantControl" + ], + "values":[ + "FromPortIcon", + "ReadWrite", + "", + "All", + "off", + "on", + "", + "", + "off", + "", + "void_void", + "off", + "off", + "on", + "", + "off", + "", + "off", + "off", + "", + "Auto", + "", + "Auto", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Inherit from model", + "Auto", + "-1", + "", + "off", + "" + ], + "tabs":[ + "Main", + "-Other" + ], + "tabs_idx":[ + 0, + 6 + ] + }, + "viewer":{ + "jshandler":"webview/handlers/ElementHandler" + }, + "obj_viewer":[ + ], + "finder":{ + "blocktype":"SubSystem", + "masktype":"" + } + } +] \ No newline at end of file diff --git a/01_Matlab/BLDC_controller_ert_rtw/html/webview/webview.html b/01_Matlab/BLDC_controller_ert_rtw/html/webview/webview.html new file mode 100644 index 00000000..93fbe2cd --- /dev/null +++ b/01_Matlab/BLDC_controller_ert_rtw/html/webview/webview.html @@ -0,0 +1,16 @@ + + + + + + Simulink Web View - Created by Simulink Report Generator + + + + + + + +
+ + \ No newline at end of file diff --git a/01_Matlab/BLDCmotorControl_R2017b.slx b/01_Matlab/BLDCmotorControl_R2017b.slx new file mode 100644 index 00000000..2aafa058 Binary files /dev/null and b/01_Matlab/BLDCmotorControl_R2017b.slx differ diff --git a/01_Matlab/init_model.m b/01_Matlab/init_model.m new file mode 100644 index 00000000..5356132a --- /dev/null +++ b/01_Matlab/init_model.m @@ -0,0 +1,193 @@ + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% This file is part of the hoverboard-new-firmware-hack project +% Compared to previouse commutation method, this project offers +% 3 more additional control method for BLDC motors. +% The new control methods offers superior performanace +% compared to previous method featuring: +% >> reduced noise and vibrations +% >> smooth torque output +% >> improved motor efficiency -> lower energy consumption +% +% Author: Emanuel FERU +% Copyright 2019 Emanuel FERU +% +% This program is free software: you can redistribute it and/or modify +% it under the terms of the GNU General Public License as published by +% the Free Software Foundation, either version 3 of the License, or +% (at your option) any later version. +% +% This program is distributed in the hope that it will be useful, +% but WITHOUT ANY WARRANTY; without even the implied warranty of +% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +% GNU General Public License for more details. +% +% You should have received a copy of the GNU General Public License +% along with this program. If not, see . +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% Clear workspace +close all +clear +clc + +% Load model parameters +load BLDCmotorControl_data; +Ts = 5e-6; % [s] Model samplind time (200 kHz) +Ts_ctrl = 6e-5; % [s] Controller samplid time (~16 kHz) +% Ts_ctrl = 12e-5; % [s] Controller samplid time (~8 kHz) + +% BLDC control parameters +CTRL_COMM = 0; % Commutation +CTRL_TRAP = 1; % Pure Trapezoidal +CTRL_SIN = 2; % Sinusoidal +CTRL_SIN3 = 3; % Sinusoidal 3rd armonic + +z_ctrlTypSel = CTRL_SIN3; % Control method selection + +% Motor Parameters +n_polePairs = 15; % [-] Number of pole pairs +a_elecPeriod = 360; % [deg] Electrical angle period +a_elecAngle = 60; % [deg] Electrical angle between two Hall sensor changing events +a_mechAngle = a_elecAngle / n_polePairs; % [deg] Mechanical angle +r_whl = 6.5 * 2.54 * 1e-2 / 2; % [m] Wheel radius. Diameter = 6.5 inch (1 inch = 2.54 cm) + +%% F01_Preliminary_Calculations + +% Position Calculation Parameters +% Hall = 4*hA + 2*hB + hC +% Hall = [0 1 2 3 4 5 6 7] +vec_hallToPos = [0 5 3 4 1 0 2 0]; % [-] Mapping Hall signal to position + +% Speed Calculation Parameters +f_ctrl = 1/Ts_ctrl; % [Hz] Controller frequency = 1/Ts_ctrl +cf_speedCoef = round(f_ctrl * a_mechAngle * (pi/180) * (30/pi)); % [-] Speed calculation coefficient (factors are due to conversions rpm <-> rad/s) +cf_speedFilt = 10; % [%] Speed filter in percent [1, 100]. Lower values mean softer filter +z_maxCntRst = 1500; % [-] Maximum counter value for reset (works also as time-out to detect standing still) +r_commDCDeacv = 70; % [-] Commutation method deactivation Duty Cycle threshold (arbitrary small number) +n_commDeacvHi = 30; % [rpm] Commutation method deactivation speed high +n_commAcvLo = 15; % [rpm] Commutation method activation speed low +dz_counterHi = 50; % [-] Counter gradient High. Above this value the control resets to Commudation method (to deal with the high dynamics) +dz_counterLo = 20; % [-] Counter gradient Low. Below this value the control authorizes the Advance method (high dynamics have passed) + +%% F02_Electrical_Angle_Calculation +b_phaAdvEna = 1; % [-] Phase advance enable parameter: 0 = disable, 1 = enable +n_motPhaAdvEna = 400; % [rpm] Phase advance enable motor speed threshold + +% The map below was experimentaly calibrated on the real motor. Objectives: minimum noise and minimum torque ripple +a_phaAdv_M1 = [0 0 0 0 0 2 3 5 9 16 25]; % [deg] Phase advance angle +r_phaAdvDC_XA = [0 100 200 300 400 500 600 700 800 900 1000]; % [-] Phase advance Duty Cycle grid +% plot(r_phaAdvDC_XA, a_phaAdv_M1); + +%% F03_Speed_Control +sca_factor = 1000; % [-] scalling factor (to avoid truncation approximations on integer data type) + +% Commutation method +z_commutMap_M1 = sca_factor*[ 1 1 0 -1 -1 0; % Phase A + -1 0 1 1 0 -1 ; % Phase B + 0 -1 -1 0 1 1]; % Phase C [-] Commutation method map + +% Trapezoidal method +a_trapElecAngle_XA = [0 60 120 180 240 300 360]; % [deg] Electrical angle grid +r_trapPhaA_M1 = sca_factor*[ 1 1 1 -1 -1 -1 1]; +r_trapPhaB_M1 = sca_factor*[-1 -1 1 1 1 -1 -1]; +r_trapPhaC_M1 = sca_factor*[ 1 -1 -1 -1 1 1 1]; + +% Sinusoidal method +a_sinElecAngle_XA = 0:10:360; +omega = a_sinElecAngle_XA*(pi/180); +pha_adv = 30; % [deg] Phase advance to mach commands with the Hall position +r_sinPhaA_M1 = sin(omega + pha_adv*(pi/180)); +r_sinPhaB_M1 = sin(omega - 120*(pi/180) + pha_adv*(pi/180)); +r_sinPhaC_M1 = sin(omega + 120*(pi/180) + pha_adv*(pi/180)); + +% Sinusoidal 3rd armonic method +A = 1.15; % Sine amplitude (tunable to get the Saddle sin maximum to value 1000) +sin3Arm = 0.238*sin(3*(omega + pha_adv*(pi/180))); % 3rd armonic +r_sin3PhaA_M1 = sin3Arm + A*r_sinPhaA_M1; +r_sin3PhaB_M1 = sin3Arm + A*r_sinPhaB_M1; +r_sin3PhaC_M1 = sin3Arm + A*r_sinPhaC_M1; + +% Rounding for representation on integer data type +r_sinPhaA_M1 = round(sca_factor * r_sinPhaA_M1); +r_sinPhaB_M1 = round(sca_factor * r_sinPhaB_M1); +r_sinPhaC_M1 = round(sca_factor * r_sinPhaC_M1); +r_sin3PhaA_M1 = round(sca_factor * r_sin3PhaA_M1); +r_sin3PhaB_M1 = round(sca_factor * r_sin3PhaB_M1); +r_sin3PhaC_M1 = round(sca_factor * r_sin3PhaC_M1); + +disp('---- BLDC_controller: Initialization OK ----'); + +%% Plot control methods + +show_fig = 0; +if show_fig + + hall_A = [1 1 1 0 0 0 0] + 4; + hall_B = [0 0 1 1 1 0 0] + 2; + hall_C = [1 0 0 0 1 1 1]; + + color = ['m' 'g' 'b']; + lw = 1.5; + figure + s1 = subplot(321); hold on + stairs(a_trapElecAngle_XA, hall_A, color(1), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_B, color(2), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_C, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + yticks(0:5); + yticklabels({'0','1','0','1','0','1'}); + title('Hall sensors'); + legend('Phase A','Phase B','Phase C','Location','NorthWest'); + + s2 = subplot(322); hold on + stairs(a_trapElecAngle_XA, hall_A, color(1), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_B, color(2), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, hall_C, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + yticks(0:5); + yticklabels({'0','1','0','1','0','1'}); + title('Hall sensors'); + legend('Phase A','Phase B','Phase C','Location','NorthWest'); + + s3 = subplot(323); hold on + stairs(a_trapElecAngle_XA, [z_commutMap_M1(1,:) z_commutMap_M1(1,end)] + 6000, color(1), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, [z_commutMap_M1(2,:) z_commutMap_M1(1,end)] + 3000, color(2), 'Linewidth', lw); + stairs(a_trapElecAngle_XA, [z_commutMap_M1(3,:) z_commutMap_M1(1,end)], color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + yticks(-1000:1000:7000); + yticklabels({'-1000','0','1000','-1000','0','1000','-1000','0','1000'}); + ylim([-1000 7000]); + grid + title('Commutation method [0]'); + + s5 = subplot(325); hold on + plot(a_trapElecAngle_XA, r_trapPhaA_M1, color(1), 'Linewidth', lw); + plot(a_trapElecAngle_XA, r_trapPhaB_M1, color(2), 'Linewidth', lw); + plot(a_trapElecAngle_XA, r_trapPhaC_M1, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + title('Pure trapezoidal method [1]'); + xlabel('Electrical angle [deg]'); + + s4 = subplot(324); hold on + plot(a_sinElecAngle_XA, r_sinPhaA_M1, color(1), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sinPhaB_M1, color(2), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sinPhaC_M1, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + title('Sinusoidal method [2]'); + + s6 = subplot(326); hold on + plot(a_sinElecAngle_XA, r_sin3PhaA_M1, color(1), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sin3PhaB_M1, color(2), 'Linewidth', lw); + plot(a_sinElecAngle_XA, r_sin3PhaC_M1, color(3), 'Linewidth', lw); + xticks(a_trapElecAngle_XA); + grid + title('Sinusoidal 3rd armonic [3]'); + xlabel('Electrical angle [deg]'); + linkaxes([s1 s2 s3 s4 s5 s6],'x'); + xlim([0 360]); +end diff --git a/Inc/BLDC_controller.h b/Inc/BLDC_controller.h new file mode 100644 index 00000000..0c90d0f0 --- /dev/null +++ b/Inc/BLDC_controller.h @@ -0,0 +1,253 @@ +/* + * + * File: BLDC_controller.h + * + * Code generated for Simulink model 'BLDC_controller'. + * + * Model version : 1.883 + * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 + * C/C++ source code generated on : Tue Jun 11 21:14:57 2019 + * + * Target selection: ert.tlc + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Emulation hardware selection: + * Differs from embedded hardware (MATLAB Host) + * Code generation objectives: + * 1. Execution efficiency + * 2. RAM efficiency + * Validation result: Not run + */ + +#ifndef RTW_HEADER_BLDC_controller_h_ +#define RTW_HEADER_BLDC_controller_h_ +#include "rtwtypes.h" +#ifndef BLDC_controller_COMMON_INCLUDES_ +# define BLDC_controller_COMMON_INCLUDES_ +#include "rtwtypes.h" +#endif /* BLDC_controller_COMMON_INCLUDES_ */ + +/* Macros for accessing real-time model data structure */ + +/* Forward declaration for rtModel */ +typedef struct tag_RTM RT_MODEL; + +/* Block signals and states (auto storage) for system '' */ +typedef struct { + int32_T Switch_PhaAdv; /* '/Switch_PhaAdv' */ + int32_T UnitDelay2_DSTATE; /* '/UnitDelay2' */ + int16_T Merge; /* '/Merge' */ + int16_T Merge1; /* '/Merge1' */ + int16_T Merge2; /* '/Merge2' */ + int16_T z_counterRawPrev; /* '/z_counterRawPrev' */ + int16_T Sum4; /* '/Sum4' */ + int16_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ + int16_T UnitDelay1_DSTATE_c; /* '/UnitDelay1' */ + int16_T z_counter2_DSTATE; /* '/z_counter2' */ + int8_T UnitDelay1; /* '/UnitDelay1' */ + int8_T Switch2; /* '/Switch2' */ + int8_T UnitDelay2_DSTATE_i; /* '/UnitDelay2' */ + int8_T If1_ActiveSubsystem; /* '/If1' */ + uint8_T UnitDelay_DSTATE; /* '/UnitDelay' */ + uint8_T UnitDelay1_DSTATE_i; /* '/UnitDelay1' */ + uint8_T UnitDelay2_DSTATE_h; /* '/UnitDelay2' */ + boolean_T n_commDeacv_Mode; /* '/n_commDeacv' */ + boolean_T dz_counter_Mode; /* '/dz_counter' */ +} DW; + +/* Constant parameters (auto storage) */ +typedef struct { + /* Computed Parameter: r_trapPhaA_M1_Table + * Referenced by: '/r_trapPhaA_M1' + */ + int16_T r_trapPhaA_M1_Table[7]; + + /* Computed Parameter: r_trapPhaB_M1_Table + * Referenced by: '/r_trapPhaB_M1' + */ + int16_T r_trapPhaB_M1_Table[7]; + + /* Computed Parameter: r_trapPhaC_M1_Table + * Referenced by: '/r_trapPhaC_M1' + */ + int16_T r_trapPhaC_M1_Table[7]; + + /* Computed Parameter: r_sinPhaA_M1_Table + * Referenced by: '/r_sinPhaA_M1' + */ + int16_T r_sinPhaA_M1_Table[37]; + + /* Computed Parameter: r_sinPhaB_M1_Table + * Referenced by: '/r_sinPhaB_M1' + */ + int16_T r_sinPhaB_M1_Table[37]; + + /* Computed Parameter: r_sinPhaC_M1_Table + * Referenced by: '/r_sinPhaC_M1' + */ + int16_T r_sinPhaC_M1_Table[37]; + + /* Computed Parameter: r_sin3PhaA_M1_Table + * Referenced by: '/r_sin3PhaA_M1' + */ + int16_T r_sin3PhaA_M1_Table[37]; + + /* Computed Parameter: r_sin3PhaB_M1_Table + * Referenced by: '/r_sin3PhaB_M1' + */ + int16_T r_sin3PhaB_M1_Table[37]; + + /* Computed Parameter: r_sin3PhaC_M1_Table + * Referenced by: '/r_sin3PhaC_M1' + */ + int16_T r_sin3PhaC_M1_Table[37]; + + /* Computed Parameter: z_commutMap_M1_table + * Referenced by: '/z_commutMap_M1' + */ + int16_T z_commutMap_M1_table[18]; + + /* Computed Parameter: vec_hallToPos_Value + * Referenced by: '/vec_hallToPos' + */ + int8_T vec_hallToPos_Value[8]; +} ConstP; + +/* External inputs (root inport signals with auto storage) */ +typedef struct { + uint8_T b_hallA; /* '/b_hallA ' */ + uint8_T b_hallB; /* '/b_hallB' */ + uint8_T b_hallC; /* '/b_hallC' */ + int32_T r_DC; /* '/r_DC' */ +} ExtU; + +/* External outputs (root outports fed by signals with auto storage) */ +typedef struct { + int32_T DC_phaA; /* '/DC_phaA' */ + int32_T DC_phaB; /* '/DC_phaB' */ + int32_T DC_phaC; /* '/DC_phaC' */ + int32_T n_mot; /* '/n_mot' */ + int32_T a_elecAngle; /* '/a_elecAngle' */ +} ExtY; + +/* Parameters (auto storage) */ +struct P_ { + int32_T cf_speedCoef; /* Variable: cf_speedCoef + * Referenced by: '/cf_spdCoef' + */ + int32_T cf_speedFilt; /* Variable: cf_speedFilt + * Referenced by: '/cf_speedFilt' + */ + int32_T n_commAcvLo; /* Variable: n_commAcvLo + * Referenced by: '/n_commDeacv' + */ + int32_T n_commDeacvHi; /* Variable: n_commDeacvHi + * Referenced by: '/n_commDeacv' + */ + int32_T n_motPhaAdvEna; /* Variable: n_motPhaAdvEna + * Referenced by: '/n_motPhaAdvEna' + */ + int32_T r_commDCDeacv; /* Variable: r_commDCDeacv + * Referenced by: '/r_commDCDeacv' + */ + int32_T r_phaAdvDC_XA[11]; /* Variable: r_phaAdvDC_XA + * Referenced by: '/r_phaAdvDC_XA' + */ + int16_T a_phaAdv_M1[11]; /* Variable: a_phaAdv_M1 + * Referenced by: '/a_phaAdv_M2' + */ + int16_T dz_counterHi; /* Variable: dz_counterHi + * Referenced by: '/dz_counter' + */ + int16_T dz_counterLo; /* Variable: dz_counterLo + * Referenced by: '/dz_counter' + */ + int16_T z_maxCntRst; /* Variable: z_maxCntRst + * Referenced by: + * '/z_counter' + * '/z_counter2' + * '/z_maxCntRst' + * '/Constant1' + * '/UnitDelay1' + */ + uint8_T z_ctrlTypSel; /* Variable: z_ctrlTypSel + * Referenced by: '/z_ctrlTypSel1' + */ + boolean_T b_phaAdvEna; /* Variable: b_phaAdvEna + * Referenced by: '/a_elecPeriod1' + */ +}; + +/* Parameters (auto storage) */ +typedef struct P_ P; + +/* Real-time Model Data Structure */ +struct tag_RTM { + P *defaultParam; + ExtU *inputs; + ExtY *outputs; + DW *dwork; +}; + +/* Constant parameters (auto storage) */ +extern const ConstP rtConstP; + +/* Model entry point functions */ +extern void BLDC_controller_initialize(RT_MODEL *const rtM); +extern void BLDC_controller_step(RT_MODEL *const rtM); + +/*- + * These blocks were eliminated from the model due to optimizations: + * + * Block '/Scope2' : Unused code path elimination + * Block '/Scope' : Unused code path elimination + */ + +/*- + * The generated code includes comments that allow you to trace directly + * back to the appropriate location in the model. The basic format + * is /block_name, where system is the system number (uniquely + * assigned by Simulink) and block_name is the name of the block. + * + * Note that this particular code originates from a subsystem build, + * and has its own system numbers different from the parent model. + * Refer to the system hierarchy for this subsystem below, and use the + * MATLAB hilite_system command to trace the generated code back + * to the parent model. For example, + * + * hilite_system('BLDCmotorControl_R2017b/BLDC_controller') - opens subsystem BLDCmotorControl_R2017b/BLDC_controller + * hilite_system('BLDCmotorControl_R2017b/BLDC_controller/Kp') - opens and selects block Kp + * + * Here is the system hierarchy for this model + * + * '' : 'BLDCmotorControl_R2017b' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/signal_log1' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/signal_log2' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/signal_log3' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/signal_log6' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F02_Electrical_Angle_Calculation' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F04_Control_Type_Management' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_01_Edge_Detector' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_02_Position_Calculation' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_03_Direction_Detection' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation/Counter_Hold_and_Error_Calculation' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation/Motor_Speed_Calculation' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F01_Preliminary_Calculations/F01_04_Speed_Calculation/rst_DelayLim' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/F03_01_Pure_Trapezoidal_Method' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/F03_02_Sinusoidal_Method' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/F03_03_Sinusoidal3rd_Method' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/signal_log1' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/signal_log2' + * '' : 'BLDCmotorControl_R2017b/BLDC_controller/BLDC_controller/F03_Control_Method_Selection/signal_log6' + */ +#endif /* RTW_HEADER_BLDC_controller_h_ */ + +/* + * File trailer for generated code. + * + * [EOF] + */ diff --git a/Inc/comms.h b/Inc/comms.h new file mode 100644 index 00000000..f293f091 --- /dev/null +++ b/Inc/comms.h @@ -0,0 +1,28 @@ +/* +* This file is part of the hoverboard-firmware-hack project. +* +* Copyright (C) 2017-2018 Rene Hopf +* Copyright (C) 2017-2018 Nico Stute +* Copyright (C) 2017-2018 Niklas Fauth +* +* This program is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with this program. If not, see . +*/ + +#pragma once + +#include "stm32f1xx_hal.h" + +void setScopeChannel(uint8_t ch, int16_t val); +void consoleScope(void); +void consoleLog(char *message); \ No newline at end of file diff --git a/Inc/config.h b/Inc/config.h index 2ecac25a..26536d4e 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -6,32 +6,32 @@ #define PWM_FREQ 16000 // PWM frequency in Hz #define DEAD_TIME 32 // PWM deadtime -#define DELAY_IN_MAIN_LOOP 5 // in ms. default 5. it is independent of all the timing critical stuff. do not touch if you do not know what you are doing. +#define DELAY_IN_MAIN_LOOP 5 // in ms. default 5. it is independent of all the timing critical stuff. do not touch if you do not know what you are doing. -#define TIMEOUT 5 // number of wrong / missing input commands before emergency off +#define TIMEOUT 5 // number of wrong / missing input commands before emergency off // ############################### GENERAL ############################### // How to calibrate: connect GND and RX of a 3.3v uart-usb adapter to the right sensor board cable (be careful not to use the red wire of the cable. 15v will destroye verything.). if you are using nunchuck, disable it temporarily. enable DEBUG_SERIAL_USART3 and DEBUG_SERIAL_ASCII use asearial terminal. // Battery voltage calibration: connect power source. see . write value nr 5 to BAT_CALIB_ADC. make and flash firmware. then you can verify voltage on value 6 (devide it by 100.0 to get calibrated voltage). -#define BAT_CALIB_REAL_VOLTAGE 43.0 // input voltage measured by multimeter +#define BAT_CALIB_REAL_VOLTAGE 43.0f // input voltage measured by multimeter #define BAT_CALIB_ADC 1704 // adc-value measured by mainboard (value nr 5 on UART debug output) #define BAT_NUMBER_OF_CELLS 10 // normal Hoverboard battery: 10s #define BAT_LOW_LVL1_ENABLE 0 // to beep or not to beep, 1 or 0 -#define BAT_LOW_LVL1 3.6 // gently beeps at this voltage level. [V/cell] +#define BAT_LOW_LVL1 3.6f // gently beeps at this voltage level. [V/cell] #define BAT_LOW_LVL2_ENABLE 1 // to beep or not to beep, 1 or 0 -#define BAT_LOW_LVL2 3.5 // your battery is almost empty. Charge now! [V/cell] -#define BAT_LOW_DEAD 3.37 // undervoltage poweroff. (while not driving) [V/cell] +#define BAT_LOW_LVL2 3.5f // your battery is almost empty. Charge now! [V/cell] +#define BAT_LOW_DEAD 3.37f // undervoltage poweroff. (while not driving) [V/cell] #define DC_CUR_LIMIT 15 // DC current limit in amps per motor. so 15 means it will draw 30A out of your battery. it does not disable motors, it is a soft current limit. // Board overheat detection: the sensor is inside the STM/GD chip. it is very inaccurate without calibration (up to 45°C). so only enable this funcion after calibration! let your board cool down. see . get the real temp of the chip by thermo cam or another temp-sensor taped on top of the chip and write it to TEMP_CAL_LOW_DEG_C. write debug value 8 to TEMP_CAL_LOW_ADC. drive around to warm up the board. it should be at least 20°C warmer. repeat it for the HIGH-values. enable warning and/or poweroff and make and flash firmware. #define TEMP_CAL_LOW_ADC 1655 // temperature 1: ADC value -#define TEMP_CAL_LOW_DEG_C 35.8 // temperature 1: measured temperature [°C] +#define TEMP_CAL_LOW_DEG_C 35.8f // temperature 1: measured temperature [°C] #define TEMP_CAL_HIGH_ADC 1588 // temperature 2: ADC value -#define TEMP_CAL_HIGH_DEG_C 48.9 // temperature 2: measured temperature [°C] +#define TEMP_CAL_HIGH_DEG_C 48.9f // temperature 2: measured temperature [°C] #define TEMP_WARNING_ENABLE 0 // to beep or not to beep, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION! #define TEMP_WARNING 60 // annoying fast beeps [°C] #define TEMP_POWEROFF_ENABLE 0 // to poweroff or not to poweroff, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION! @@ -64,16 +64,33 @@ // ###### CONTROL VIA TWO POTENTIOMETERS ###### // ADC-calibration to cover the full poti-range: connect potis to left sensor board cable (0 to 3.3V) (do NOT use the red 15V wire in the cable!). see . turn the potis to minimum position, write value 1 to ADC1_MIN and value 2 to ADC2_MIN. turn to maximum position and repeat it for ADC?_MAX. make, flash and test it. -#define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2! -#define ADC1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) -#define ADC1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) -#define ADC2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) -#define ADC2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) +#define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2! +#define ADC1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) +#define ADC1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) +#define ADC2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) +#define ADC2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) // ###### CONTROL VIA NINTENDO NUNCHUCK ###### // left sensor board cable. keep cable short, use shielded cable, use ferrits, stabalize voltage in nunchuck, use the right one of the 2 types of nunchucks, add i2c pullups. use original nunchuck. most clones does not work very well. //#define CONTROL_NUNCHUCK // use nunchuck as input. disable DEBUG_SERIAL_USART3! + +// ############################### MOTOR CONTROL (overwrite) ######################### +#define CTRL_TYP_SEL 3 // [-] Control method selection: 0 = Commutation , 1 = Pure Trapezoidal , 2 = Sinusoidal, 3 = Sinusoidal 3rd armonic (default) +#define PHASE_ADV_ENA 1 // [-] Phase advance enable parameter: 0 = disabled, 1 = enabled (default) + +// GENERAL NOTES: +// 1. All the available motor parameters can be found in the BLDC_controller_data.c +// 2. For more details regarding the parameters and the working principle of the controller please consult the Simulink model +// 3. A webview was created, so Matlab/Simulink installation is not needed, unless you want to regenerate the code + +// NOTES Phase Advance / Field weakening: +// 1. In BLDC_controller_data.c you can find the Phase advance Map as a function of Duty Cycle: MAP = a_phaAdv_M1, XAXIS = r_phaAdvDC_XA +// 2. The default calibration was experimentally calibrated on the real motor based on the minimum noise and minimum torque ripple +// 3. If you re-calibrate the Phase advance map please take all the safety measures! +// 4. I do not recommend more than 40 deg MAX Phase advance. The motors can spin VERY VERY FAST!!! Please use it with care!! + + // ############################### DRIVING BEHAVIOR ############################### // inputs: @@ -82,54 +99,24 @@ // - adc_buffer.l_tx2 and adc_buffer.l_rx2: unfiltered ADC values (you do not need them). 0 to 4095 // outputs: // - speedR and speedL: normal driving -1000 to 1000 -// - weakr and weakl: field weakening for extra boost at high speed (speedR > 700 and speedL > 700). 0 to ~400 -#define FILTER 0.1 // lower value == softer filter. do not use values <0.01, you will get float precision issues. -#define SPEED_COEFFICIENT 0.5 // higher value == stronger. 0.0 to ~2.0? -#define STEER_COEFFICIENT 0.5 // higher value == stronger. if you do not want any steering, set it to 0.0; 0.0 to 1.0 +#define FILTER 0.1f // lower value == softer filter. do not use values <0.01, you will get float precision issues. +#define SPEED_COEFFICIENT 1.0f // higher value == stronger. 0.0 to ~2.0? +#define STEER_COEFFICIENT 0.5f // higher value == stronger. if you do not want any steering, set it to 0.0; 0.0 to 1.0 #define INVERT_R_DIRECTION #define INVERT_L_DIRECTION -#define BEEPS_BACKWARD 1 // 0 or 1 - -//Turbo boost at high speeds while button1 is pressed: -//#define ADDITIONAL_CODE \ -if (button1 && speedR > 700) { /* field weakening at high speeds */ \ - weakl = cmd1 - 700; /* weak should never exceed 400 or 450 MAX!! */ \ - weakr = cmd1 - 700; } \ -else { \ - weakl = 0; \ - weakr = 0; } +#define BEEPS_BACKWARD 0 // 0 or 1 // ###### SIMPLE BOBBYCAR ###### // for better bobbycar code see: https://github.com/larsmm/hoverboard-firmware-hack-bbcar -// #define FILTER 0.1 -// #define SPEED_COEFFICIENT -1 -// #define STEER_COEFFICIENT 0 - -// #define ADDITIONAL_CODE \ -if (button1 && speedR < 300) { /* drive backwards */ \ - speedR = speedR * -0.2f; \ - speedL = speedL * -0.2f; } \ -else { \ - direction = 1; } \ -if (button1 && speedR > 700) { /* field weakening at high speeds */ \ - weakl = speedR - 600; /* weak should never exceed 400 or 450 MAX!! */ \ - weakr = speedR - 600; } \ -else { \ - weakl = 0; \ - weakr = 0; } +// #define FILTER 0.1f +// #define SPEED_COEFFICIENT -1f +// #define STEER_COEFFICIENT 0f // ###### ARMCHAIR ###### -// #define FILTER 0.05 -// #define SPEED_COEFFICIENT 0.5 -// #define STEER_COEFFICIENT -0.2 - -// #define ADDITIONAL_CODE if (button1 && scale > 0.8) { /* field weakening at high speeds */ \ - weakl = speedL - 600; /* weak should never exceed 400 or 450 MAX!! */ \ - weakr = speedR - 600; } \ -else {\ - weakl = 0;\ - weakr = 0; +// #define FILTER 0.05f +// #define SPEED_COEFFICIENT 0.5f +// #define STEER_COEFFICIENT -0.2f // ############################### VALIDATE SETTINGS ############################### diff --git a/Inc/defines.h b/Inc/defines.h index dc66f4f9..7ef5392e 100644 --- a/Inc/defines.h +++ b/Inc/defines.h @@ -123,7 +123,7 @@ #define DELAY_TIM_FREQUENCY_US 1000000 -#define MOTOR_AMP_CONV_DC_AMP 0.02 // A per bit (12) on ADC. +#define MOTOR_AMP_CONV_DC_AMP 0.02f // A per bit (12) on ADC. #define MILLI_R (R * 1000) #define MILLI_PSI (PSI * 1000) @@ -131,16 +131,16 @@ #define NO 0 #define YES 1 -#define ABS(a) (((a) < 0.0) ? -(a) : (a)) +#define ABS(a) (((a) < 0.0f) ? -(a) : (a)) #define LIMIT(x, lowhigh) (((x) > (lowhigh)) ? (lowhigh) : (((x) < (-lowhigh)) ? (-lowhigh) : (x))) -#define SAT(x, lowhigh) (((x) > (lowhigh)) ? (1.0) : (((x) < (-lowhigh)) ? (-1.0) : (0.0))) -#define SAT2(x, low, high) (((x) > (high)) ? (1.0) : (((x) < (low)) ? (-1.0) : (0.0))) +#define SAT(x, lowhigh) (((x) > (lowhigh)) ? (1.0f) : (((x) < (-lowhigh)) ? (-1.0f) : (0.0f))) +#define SAT2(x, low, high) (((x) > (high)) ? (1.0f) : (((x) < (low)) ? (-1.0f) : (0.0f))) #define STEP(from, to, step) (((from) < (to)) ? (MIN((from) + (step), (to))) : (MAX((from) - (step), (to)))) -#define DEG(a) ((a)*M_PI / 180.0) -#define RAD(a) ((a)*180.0 / M_PI) -#define SIGN(a) (((a) < 0.0) ? (-1.0) : (((a) > 0.0) ? (1.0) : (0.0))) +#define DEG(a) ((a)*M_PI / 180.0f) +#define RAD(a) ((a)*180.0f / M_PI) +#define SIGN(a) (((a) < 0.0f) ? (-1.0f) : (((a) > 0.0f) ? (1.0f) : (0.0f))) #define CLAMP(x, low, high) (((x) > (high)) ? (high) : (((x) < (low)) ? (low) : (x))) -#define SCALE(value, high, max) MIN(MAX(((max) - (value)) / ((max) - (high)), 0.0), 1.0) +#define SCALE(value, high, max) MIN(MAX(((max) - (value)) / ((max) - (high)), 0.0f), 1.0f) #define MIN(a, b) (((a) < (b)) ? (a) : (b)) #define MAX(a, b) (((a) > (b)) ? (a) : (b)) #define MIN3(a, b, c) MIN(a, MIN(b, c)) diff --git a/Inc/rtwtypes.h b/Inc/rtwtypes.h new file mode 100644 index 00000000..93f5f16f --- /dev/null +++ b/Inc/rtwtypes.h @@ -0,0 +1,105 @@ +/* + * + * File: rtwtypes.h + * + * Code generated for Simulink model 'BLDC_controller'. + * + * Model version : 1.883 + * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 + * C/C++ source code generated on : Tue Jun 11 21:14:57 2019 + * + * Target selection: ert.tlc + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Emulation hardware selection: + * Differs from embedded hardware (MATLAB Host) + * Code generation objectives: + * 1. Execution efficiency + * 2. RAM efficiency + * Validation result: Not run + */ + +#ifndef RTWTYPES_H +#define RTWTYPES_H + +/* Logical type definitions */ +#if (!defined(__cplusplus)) +# ifndef false +# define false (0U) +# endif + +# ifndef true +# define true (1U) +# endif +#endif + +/*=======================================================================* + * Target hardware information + * Device type: MATLAB Host + * Number of bits: char: 8 short: 16 int: 32 + * long: 32 long long: 64 + * native word size: 64 + * Byte ordering: LittleEndian + * Signed integer division rounds to: Zero + * Shift right on a signed integer as arithmetic shift: on + *=======================================================================*/ + +/*=======================================================================* + * Fixed width word size data types: * + * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * + * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * + * real32_T, real64_T - 32 and 64 bit floating point numbers * + *=======================================================================*/ +typedef signed char int8_T; +typedef unsigned char uint8_T; +typedef short int16_T; +typedef unsigned short uint16_T; +typedef int int32_T; +typedef unsigned int uint32_T; +typedef long long int64_T; +typedef unsigned long long uint64_T; +typedef float real32_T; +typedef double real64_T; + +/*===========================================================================* + * Generic type definitions: boolean_T, char_T, byte_T, int_T, uint_T, * + * real_T, time_T, ulong_T, ulonglong_T. * + *===========================================================================*/ +typedef double real_T; +typedef double time_T; +typedef unsigned char boolean_T; +typedef int int_T; +typedef unsigned int uint_T; +typedef unsigned long ulong_T; +typedef unsigned long long ulonglong_T; +typedef char char_T; +typedef unsigned char uchar_T; +typedef char_T byte_T; + +/*=======================================================================* + * Min and Max: * + * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * + * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * + *=======================================================================*/ +#define MAX_int8_T ((int8_T)(127)) +#define MIN_int8_T ((int8_T)(-128)) +#define MAX_uint8_T ((uint8_T)(255U)) +#define MAX_int16_T ((int16_T)(32767)) +#define MIN_int16_T ((int16_T)(-32768)) +#define MAX_uint16_T ((uint16_T)(65535U)) +#define MAX_int32_T ((int32_T)(2147483647)) +#define MIN_int32_T ((int32_T)(-2147483647-1)) +#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU)) +#define MAX_int64_T ((int64_T)(9223372036854775807LL)) +#define MIN_int64_T ((int64_T)(-9223372036854775807LL-1LL)) +#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFULL)) + +/* Block D-Work pointer type */ +typedef void * pointer_T; + +#endif /* RTWTYPES_H */ + +/* + * File trailer for generated code. + * + * [EOF] + */ diff --git a/Makefile b/Makefile index 832aab58..3a904394 100644 --- a/Makefile +++ b/Makefile @@ -42,6 +42,8 @@ Src/main.c \ Src/bldc.c \ Src/comms.c \ Src/stm32f1xx_it.c \ +Src/BLDC_controller_data.c \ +Src/BLDC_controller.c # ASM sources ASM_SOURCES = \ diff --git a/README.md b/README.md index c525fe3f..bde420bf 100644 --- a/README.md +++ b/README.md @@ -1,35 +1,70 @@ -# hoverboard-firmware-hack +# hoverboard-firmware-hack-SIN +## With Sinusoidal BLDC control and Phase Advance +[![Build Status](https://travis-ci.com/EmanuelFeru/hoverboard-firmware-hack-SIN.svg?branch=master)](https://travis-ci.com/EmanuelFeru/hoverboard-firmware-hack) -![](https://raw.githubusercontent.com/NiklasFauth/hoverboard-firmware-hack/master/docs/pictures/armchair.gif) ![](https://raw.githubusercontent.com/NiklasFauth/hoverboard-firmware-hack/master/docs/pictures/bobbycar.gif) -![](https://raw.githubusercontent.com/NiklasFauth/hoverboard-firmware-hack/master/docs/pictures/transpotter.gif) ![](https://raw.githubusercontent.com/NiklasFauth/hoverboard-firmware-hack/master/docs/pictures/chair.gif) +This repository improves significantly the performance of the previous BLDC motor control for hoverboards developed by [NiklasFauth](https://github.com/NiklasFauth/hoverboard-firmware-hack). Compared to previous commutation method, this project implements 3 more additional control methods. The new control methods offers superior performance featuring: + - reduced noise and vibrations + - smooth torque output + - improved motor efficiency. Thus, lower energy consumption + - automatic phase advance / field weakening + + ### This repository is not supported any more! See my new [firmware based on FOC motor control](https://github.com/EmanuelFeru/hoverboard-firmware-hack-FOC) for latest updates. The new firmware still offers the posiblity to select Sinusoidal control. + +![Schematic representation of the control methods](https://raw.githubusercontent.com/EmanuelFeru/hoverboard-firmware-hack/master/01_Matlab/02_Figures/control_methods.png) -This repo contains open source firmware for generic Hoverboard Mainboards. -The firmware you can find here allows you to use your Hoverboard Hardware (like the Mainboard, Motors and Battery) for cool projects like driving armchairs, person-tracking transportation robots and every other application you can imagine that requires controlling the Motors. +A classification of the BLDC control methods in terms of performance is as follows: -If you want an overview of what you can do with this firmware, here is a ~40min video of a talk about this project: -https://media.ccc.de/v/gpn18-95-howto-moving-objects +|Control method| Torque output | Noise performance | Efficiency | +|--|--|--|--| +|Commutation| High | Low | Low | +|Pure Trapezoidal| High | Medium | Medium | +|Sinusoidal| Medium | High | High +|Sinusoidal 3rd harmonic| High | High | High | + +> All these 4 methods are available in this repository and can be selected by a calibratable inside 'config.h' file. Default selected method: *Sinusoidal 3rd harmonic*. + +A short video showing the noise performance of the Commutation method vs Sinusoidal 3rd harmonic can be found here: +[►Video: Commutation method vs Sinusoidal 3rd harmonic](https://drive.google.com/file/d/1vC_kEkp2LE2lAaMCJcmK4z2m3jrPUoBD/view) + +![Hoverboard wheel](https://raw.githubusercontent.com/EmanuelFeru/hoverboard-firmware-hack/master/docs/pictures/hoverboard_wheel.JPG) + + +** A more detailed and better movie will come soon... so stay tuned ;) --- +GENERAL NOTES: + - All the calibratable motor parameters can be found in the 'BLDC_controller_data.c'. I provided you with an already calibrated controller, but if you feel like fine tuning it feel free to do so. + - The C code for the controller was auto-code generated using [Matlab/Simulink](https://nl.mathworks.com/solutions/embedded-code-generation.html) from a model which I developed from scratch specifically for hoverboard control. For more details regarding the parameters and the working principle of the controller please consult the [Matlab/Simulink model](https://github.com/EmanuelFeru/hoverboard-firmware-hack/tree/master/01_Matlab). + - A [webview](https://github.com/EmanuelFeru/hoverboard-firmware-hack/tree/master/01_Matlab/BLDC_controller_ert_rtw/html/webview) was created, so Matlab/Simulink installation is not needed, unless you want to regenerate the code + +NOTES Phase Advance / Field weakening: -## Build Instructions + - The Phase Advance engages automatically and smooth (no need for boost buttons or additional fancy arrangements). You can re-calibrate the Phase Advance to your needs and your liking. + - The default map was experimentally calibrated on the real motor based on the minimum noise and minimum torque ripple + - If you re-calibrate the Phase advance map please take all the safety measures! The motors can spin VERY VERY FAST! Please use it with care! + - I do not recommend more than 40 deg MAX Phase advance. -Here are detailed build instructions for some finished projects. -If possible, a prebuild firmware release is available for these usecases, so you don't need to compile the firmware yourself +--- +## Building +For building (and flashing) I recommend platform.io, plaformio.ini file included. Simply open the folder in the IDE of choice (vscode or Atom), and press the 'PlatformIO:Build' or the 'PlatformIO:Upload' button (bottom left in vscode). -TranspOtter: https://github.com/NiklasFauth/hoverboard-firmware-hack/wiki/Build-Instruction:-TranspOtter +Additionally, you can also flash using the method described below in the Flashing Section. --- ## Hardware -![otter](https://raw.githubusercontent.com/NiklasFauth/hoverboard-firmware-hack/master/pinout.png) +![otter](https://raw.githubusercontent.com/EmanuelFeru/hoverboard-firmware-hack/master/pinout.png) The original Hardware supports two 4-pin cables that originally were connected to the two sensor boards. They break out GND, 12/15V and USART2&3 of the Hoverboard mainboard. Both USART2 & 3 can be used for UART and I2C, PA2&3 can be used as 12bit ADCs. -The reverse-engineered schematics of the mainboard can be found here: +The mainboard reverse-engineered schematics (PCB Markings: 679393 20150722): http://vocke.tv/lib/exe/fetch.php?media=20150722_hoverboard_sch.pdf +The mainboard reverse-engineered schematics (PCB Markings: YST-DXT-J20 V4): +http://vocke.tv/lib/exe/fetch.php?media=20190620_at32_hover_sch.pdf + --- ## Flashing @@ -86,14 +121,3 @@ Have a look at the config.h in the Inc directory. That's where you configure to Currently supported: Wii Nunchuck, analog potentiometer and PPM-Sum signal from a RC remote. A good example of control via UART, eg. from an Arduino or raspberryPi, can be found here: https://github.com/p-h-a-i-l/hoverboard-firmware-hack - -If you need additional features like a boost button, have a look at the while(1) loop in the main.c - -### Additional Hardware - -* [breakout/interconnect boards](https://github.com/Jan--Henrik/hoverboard-breakout) Breakout/Interconnection boards for hoverboard hacking. - -### Projects based on it -* [bobbycar-optimized firmware](https://github.com/larsmm/hoverboard-firmware-hack-bbcar) based on this one with driving modes, acceleration ramps and some other features -* [wheel chair](https://github.com/Lahorde/steer_speed_ctrl) controlled with a joystick or using a CC2650 sensortag to control it over bluetooth with pitch/roll. -* [TranspOtterNG](https://github.com/Jan--Henrik/transpOtterNG) TranspOtter is an open source semi self driving transportation platform based on hoverboard hardware diff --git a/Src/BLDC_controller.c b/Src/BLDC_controller.c new file mode 100644 index 00000000..6c9843db --- /dev/null +++ b/Src/BLDC_controller.c @@ -0,0 +1,693 @@ +/* + * + * File: BLDC_controller.c + * + * Code generated for Simulink model 'BLDC_controller'. + * + * Model version : 1.883 + * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 + * C/C++ source code generated on : Tue Jun 11 21:14:57 2019 + * + * Target selection: ert.tlc + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Emulation hardware selection: + * Differs from embedded hardware (MATLAB Host) + * Code generation objectives: + * 1. Execution efficiency + * 2. RAM efficiency + * Validation result: Not run + */ + +#include "BLDC_controller.h" +#ifndef UCHAR_MAX +#include +#endif + +#if ( UCHAR_MAX != (0xFFU) ) || ( SCHAR_MAX != (0x7F) ) +#error Code was generated for compiler with different sized uchar/char. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( USHRT_MAX != (0xFFFFU) ) || ( SHRT_MAX != (0x7FFF) ) +#error Code was generated for compiler with different sized ushort/short. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( UINT_MAX != (0xFFFFFFFFU) ) || ( INT_MAX != (0x7FFFFFFF) ) +#error Code was generated for compiler with different sized uint/int. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( ULONG_MAX != (0xFFFFFFFFU) ) || ( LONG_MAX != (0x7FFFFFFF) ) +#error Code was generated for compiler with different sized ulong/long. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if 0 + +/* Skip this size verification because of preprocessor limitation */ +#if ( ULLONG_MAX != (0xFFFFFFFFFFFFFFFFULL) ) || ( LLONG_MAX != (0x7FFFFFFFFFFFFFFFLL) ) +#error Code was generated for compiler with different sized ulong_long/long_long. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif +#endif + +uint8_T plook_u8s32u32n31_evenc_s(int32_T u, int32_T bp0, uint32_T bpSpace, + uint32_T maxIndex, uint32_T *fraction); +int16_T intrp1d_s16s32s32u8u32n31l_s(uint8_T bpIndex, uint32_T frac, const + int16_T table[]); +int32_T div_nde_s32_floor(int32_T numerator, int32_T denominator); +uint8_T plook_u8s32u32n31_evenc_s(int32_T u, int32_T bp0, uint32_T bpSpace, + uint32_T maxIndex, uint32_T *fraction) +{ + uint8_T bpIndex; + uint32_T uAdjust; + uint32_T fbpIndex; + + /* Prelookup - Index and Fraction + Index Search method: 'even' + Extrapolation method: 'Clip' + Use previous index: 'off' + Use last breakpoint for index at or above upper limit: 'off' + Remove protection against out-of-range input in generated code: 'off' + Rounding mode: 'simplest' + */ + if (u <= bp0) { + bpIndex = 0U; + *fraction = 0U; + } else { + uAdjust = (uint32_T)u - bp0; + fbpIndex = uAdjust / bpSpace; + if (fbpIndex < maxIndex) { + bpIndex = (uint8_T)fbpIndex; + *fraction = (uint32_T)(((uint64_T)(uAdjust - bpIndex * bpSpace) << 31) / + bpSpace); + } else { + bpIndex = (uint8_T)(maxIndex - 1U); + *fraction = 2147483648U; + } + } + + return bpIndex; +} + +int16_T intrp1d_s16s32s32u8u32n31l_s(uint8_T bpIndex, uint32_T frac, const + int16_T table[]) +{ + uint32_T offset_0d; + + /* Interpolation 1-D + Interpolation method: 'Linear' + Use last breakpoint for index at or above upper limit: 'off' + Rounding mode: 'simplest' + Overflow mode: 'wrapping' + */ + offset_0d = bpIndex; + return (int16_T)((int16_T)(((int64_T)(table[offset_0d + 1U] - table[offset_0d]) + * frac) >> 31) + table[offset_0d]); +} + +int32_T div_nde_s32_floor(int32_T numerator, int32_T denominator) +{ + return (((numerator < 0) != (denominator < 0)) && (numerator % denominator != + 0) ? -1 : 0) + numerator / denominator; +} + +/* Model step function */ +void BLDC_controller_step(RT_MODEL *const rtM) +{ + P *rtP = ((P *) rtM->defaultParam); + DW *rtDW = ((DW *) rtM->dwork); + ExtU *rtU = (ExtU *) rtM->inputs; + ExtY *rtY = (ExtY *) rtM->outputs; + uint8_T rtb_Sum; + int32_T rtb_Abs1; + uint8_T rtb_BitwiseOperator; + int32_T rtb_Sum2; + int16_T rtb_Abs2; + int16_T rtb_Sum1_a; + int32_T rtb_Abs5; + int8_T rtAction; + int8_T rtb_Sum2_h; + uint32_T rtb_r_phaAdvDC_XA_o2; + int32_T rtb_Switch1_idx_1; + + /* Outputs for Atomic SubSystem: '/BLDC_controller' */ + /* Sum: '/Sum' incorporates: + * Gain: '/g_Ha' + * Gain: '/g_Hb' + * Inport: '/b_hallA ' + * Inport: '/b_hallB' + * Inport: '/b_hallC' + */ + rtb_Sum = (uint8_T)((uint32_T)(uint8_T)((uint32_T)(uint8_T)(rtU->b_hallA << 2) + + (uint8_T)(rtU->b_hallB << 1)) + rtU->b_hallC); + + /* Abs: '/Abs1' incorporates: + * Inport: '/r_DC' + */ + if (rtU->r_DC < 0) { + rtb_Abs1 = -rtU->r_DC; + } else { + rtb_Abs1 = rtU->r_DC; + } + + /* End of Abs: '/Abs1' */ + + /* S-Function (sfix_bitop): '/Bitwise Operator' incorporates: + * Inport: '/b_hallA ' + * Inport: '/b_hallB' + * Inport: '/b_hallC' + * UnitDelay: '/UnitDelay' + * UnitDelay: '/UnitDelay1' + * UnitDelay: '/UnitDelay2' + */ + rtb_BitwiseOperator = (uint8_T)(rtU->b_hallA ^ rtU->b_hallB ^ rtU->b_hallC ^ + rtDW->UnitDelay_DSTATE ^ rtDW->UnitDelay1_DSTATE_i ^ + rtDW->UnitDelay2_DSTATE_h); + + /* If: '/If1' incorporates: + * Constant: '/Constant6' + * Constant: '/Constant1' + * Constant: '/Constant23' + * If: '/If2' + * Inport: '/z_counterRawPrev' + * RelationalOperator: '/Relational Operator1' + * Sum: '/Sum1' + * Switch: '/Switch1' + * Switch: '/Switch2' + * UnitDelay: '/UnitDelay1' + * UnitDelay: '/UnitDelay1' + */ + if (rtb_BitwiseOperator != 0) { + /* Outputs for IfAction SubSystem: '/F01_03_Direction_Detection' incorporates: + * ActionPort: '/Action Port' + */ + /* UnitDelay: '/UnitDelay1' */ + rtDW->UnitDelay1 = rtDW->Switch2; + + /* Sum: '/Sum2' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + * UnitDelay: '/UnitDelay2' + */ + rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[rtb_Sum] - + rtDW->UnitDelay2_DSTATE_i); + + /* Switch: '/Switch2' incorporates: + * Constant: '/Constant20' + * Constant: '/Constant23' + * Constant: '/Constant24' + * Constant: '/Constant8' + * Logic: '/Logical Operator3' + * RelationalOperator: '/Relational Operator1' + * RelationalOperator: '/Relational Operator6' + */ + if ((rtb_Sum2_h == 1) || (rtb_Sum2_h == -5)) { + rtDW->Switch2 = 1; + } else { + rtDW->Switch2 = -1; + } + + /* End of Switch: '/Switch2' */ + + /* Update for UnitDelay: '/UnitDelay2' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + */ + rtDW->UnitDelay2_DSTATE_i = rtConstP.vec_hallToPos_Value[rtb_Sum]; + + /* End of Outputs for SubSystem: '/F01_03_Direction_Detection' */ + rtb_Abs2 = 1; + + /* Outputs for IfAction SubSystem: '/Counter_Hold_and_Error_Calculation' incorporates: + * ActionPort: '/Action Port' + */ + rtDW->z_counterRawPrev = rtDW->UnitDelay1_DSTATE_c; + + /* Sum: '/Sum4' incorporates: + * Constant: '/Constant6' + * Constant: '/Constant23' + * Inport: '/z_counterRawPrev' + * Sum: '/Sum1' + * UnitDelay: '/UnitDelay1' + * UnitDelay: '/z_counter2' + */ + rtDW->Sum4 = (int16_T)(rtDW->z_counterRawPrev - rtDW->z_counter2_DSTATE); + + /* Update for UnitDelay: '/z_counter2' */ + rtDW->z_counter2_DSTATE = rtDW->z_counterRawPrev; + + /* End of Outputs for SubSystem: '/Counter_Hold_and_Error_Calculation' */ + } else { + if (rtDW->UnitDelay1_DSTATE < rtP->z_maxCntRst) { + /* Switch: '/Switch2' incorporates: + * UnitDelay: '/UnitDelay1' + */ + rtb_Abs2 = rtDW->UnitDelay1_DSTATE; + } else { + /* Switch: '/Switch2' incorporates: + * Constant: '/Constant1' + */ + rtb_Abs2 = rtP->z_maxCntRst; + } + + rtb_Abs2++; + } + + /* End of If: '/If1' */ + + /* Sum: '/Sum1' */ + rtb_Sum1_a = rtb_Abs2; + + /* Switch: '/Switch1' incorporates: + * Constant: '/Constant1' + * Constant: '/cf_spdCoef' + * Constant: '/z_maxCntRst' + * Logic: '/Logical Operator1' + * Product: '/Divide4' + * RelationalOperator: '/Relational Operator2' + * RelationalOperator: '/Relational Operator5' + * Sum: '/Sum1' + */ + if ((rtb_Abs2 > rtP->z_maxCntRst) || (rtDW->Switch2 != rtDW->UnitDelay1)) { + rtb_Sum2 = 0; + } else { + rtb_Sum2 = rtP->cf_speedCoef * rtDW->Switch2 / rtDW->z_counterRawPrev; + } + + /* End of Switch: '/Switch1' */ + + /* Product: '/Divide2' incorporates: + * Constant: '/Constant2' + * Constant: '/Constant3' + * Constant: '/cf_speedFilt' + * Product: '/Divide1' + * Product: '/Divide3' + * Sum: '/Sum1' + * Sum: '/Sum2' + * UnitDelay: '/UnitDelay2' + */ + rtb_Sum2 = ((100 - rtP->cf_speedFilt) * rtDW->UnitDelay2_DSTATE + rtb_Sum2 * + rtP->cf_speedFilt) / 100; + + /* Abs: '/Abs5' */ + if (rtb_Sum2 < 0) { + rtb_Abs5 = -rtb_Sum2; + } else { + rtb_Abs5 = rtb_Sum2; + } + + /* End of Abs: '/Abs5' */ + + /* Relay: '/n_commDeacv' */ + if (rtb_Abs5 >= rtP->n_commDeacvHi) { + rtDW->n_commDeacv_Mode = true; + } else { + if (rtb_Abs5 <= rtP->n_commAcvLo) { + rtDW->n_commDeacv_Mode = false; + } + } + + /* Abs: '/Abs2' */ + if (rtDW->Sum4 < 0) { + rtb_Abs2 = (int16_T)-rtDW->Sum4; + } else { + rtb_Abs2 = rtDW->Sum4; + } + + /* End of Abs: '/Abs2' */ + + /* Relay: '/dz_counter' */ + if (rtb_Abs2 >= rtP->dz_counterHi) { + rtDW->dz_counter_Mode = true; + } else { + if (rtb_Abs2 <= rtP->dz_counterLo) { + rtDW->dz_counter_Mode = false; + } + } + + /* If: '/If1' incorporates: + * Constant: '/z_ctrlTypSel1' + */ + rtb_Sum2_h = rtDW->If1_ActiveSubsystem; + rtAction = -1; + if (rtP->z_ctrlTypSel != 0) { + rtAction = 0; + } + + rtDW->If1_ActiveSubsystem = rtAction; + if ((rtb_Sum2_h != rtAction) && (rtb_Sum2_h == 0)) { + /* Disable for Outport: '/a_elecAngleAdv' */ + rtDW->Switch_PhaAdv = 0; + + /* Disable for Outport: '/a_elecAngle' incorporates: + * Outport: '/a_elecAngle' + */ + rtY->a_elecAngle = 0; + } + + if (rtAction == 0) { + /* Outputs for IfAction SubSystem: '/F02_Electrical_Angle_Calculation' incorporates: + * ActionPort: '/Action Port' + */ + /* Switch: '/Switch3' incorporates: + * Constant: '/vec_hallToPos' + * Constant: '/Constant16' + * Gain: '/g_Ha' + * Gain: '/g_Hb' + * Inport: '/b_hallA ' + * Inport: '/b_hallB' + * Inport: '/b_hallC' + * RelationalOperator: '/Relational Operator7' + * Selector: '/Selector' + * Sum: '/Sum' + * Sum: '/Sum1' + */ + if (rtDW->Switch2 == 1) { + rtb_Sum2_h = rtConstP.vec_hallToPos_Value[rtb_Sum]; + } else { + rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[(uint8_T)((uint32_T) + (uint8_T)((uint32_T)(uint8_T)(rtU->b_hallA << 2) + (uint8_T) + (rtU->b_hallB << 1)) + rtU->b_hallC)] + 1); + } + + /* End of Switch: '/Switch3' */ + + /* Outport: '/a_elecAngle' incorporates: + * Constant: '/a_elecAngle1' + * Product: '/Divide4' + * Product: '/Divide5' + * Product: '/Product6' + * Sum: '/Sum2' + */ + rtY->a_elecAngle = 60 * rtb_Sum1_a / rtDW->z_counterRawPrev * rtDW->Switch2 + + rtb_Sum2_h * 60; + + /* Switch: '/Switch_PhaAdv' incorporates: + * Constant: '/a_elecPeriod1' + * Constant: '/n_motPhaAdvEna' + * Logic: '/Logical Operator2' + * Outport: '/a_elecAngle' + * RelationalOperator: '/Relational Operator4' + */ + if (rtP->b_phaAdvEna && (rtb_Abs5 > rtP->n_motPhaAdvEna)) { + /* PreLookup: '/r_phaAdvDC_XA' */ + rtb_BitwiseOperator = plook_u8s32u32n31_evenc_s(rtb_Abs1, + rtP->r_phaAdvDC_XA[0], (uint32_T)rtP->r_phaAdvDC_XA[1] - + rtP->r_phaAdvDC_XA[0], 10U, &rtb_r_phaAdvDC_XA_o2); + + /* Interpolation_n-D: '/a_phaAdv_M2' */ + rtb_Abs2 = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtP->a_phaAdv_M1); + + /* Sum: '/Sum3' incorporates: + * Outport: '/a_elecAngle' + * Product: '/Product2' + */ + rtb_Abs5 = (int16_T)(rtb_Abs2 * rtDW->Switch2) + rtY->a_elecAngle; + + /* Math: '/Math Function' */ + rtDW->Switch_PhaAdv = rtb_Abs5 - div_nde_s32_floor(rtb_Abs5, 360) * 360; + } else { + rtDW->Switch_PhaAdv = rtY->a_elecAngle; + } + + /* End of Switch: '/Switch_PhaAdv' */ + /* End of Outputs for SubSystem: '/F02_Electrical_Angle_Calculation' */ + } + + /* End of If: '/If1' */ + + /* SwitchCase: '/Switch Case' incorporates: + * Constant: '/z_ctrlTypSel1' + */ + switch (rtP->z_ctrlTypSel) { + case 1: + /* Outputs for IfAction SubSystem: '/F03_01_Pure_Trapezoidal_Method' incorporates: + * ActionPort: '/Action Port' + */ + /* PreLookup: '/a_trapElecAngle_XA' */ + rtb_BitwiseOperator = plook_u8s32u32n31_evenc_s(rtDW->Switch_PhaAdv, 0, 60U, + 6U, &rtb_r_phaAdvDC_XA_o2); + + /* Interpolation_n-D: '/r_trapPhaA_M1' */ + rtDW->Merge = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_trapPhaA_M1_Table); + + /* Interpolation_n-D: '/r_trapPhaB_M1' */ + rtDW->Merge1 = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_trapPhaB_M1_Table); + + /* Interpolation_n-D: '/r_trapPhaC_M1' */ + rtDW->Merge2 = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_trapPhaC_M1_Table); + + /* End of Outputs for SubSystem: '/F03_01_Pure_Trapezoidal_Method' */ + break; + + case 2: + /* Outputs for IfAction SubSystem: '/F03_02_Sinusoidal_Method' incorporates: + * ActionPort: '/Action Port' + */ + /* PreLookup: '/a_sinElecAngle_XA' */ + rtb_BitwiseOperator = plook_u8s32u32n31_evenc_s(rtDW->Switch_PhaAdv, 0, 10U, + 36U, &rtb_r_phaAdvDC_XA_o2); + + /* Interpolation_n-D: '/r_sinPhaA_M1' */ + rtDW->Merge = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_sinPhaA_M1_Table); + + /* Interpolation_n-D: '/r_sinPhaB_M1' */ + rtDW->Merge1 = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_sinPhaB_M1_Table); + + /* Interpolation_n-D: '/r_sinPhaC_M1' */ + rtDW->Merge2 = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_sinPhaC_M1_Table); + + /* End of Outputs for SubSystem: '/F03_02_Sinusoidal_Method' */ + break; + + case 3: + /* Outputs for IfAction SubSystem: '/F03_03_Sinusoidal3rd_Method' incorporates: + * ActionPort: '/Action Port' + */ + /* PreLookup: '/a_sinElecAngle_XA' */ + rtb_BitwiseOperator = plook_u8s32u32n31_evenc_s(rtDW->Switch_PhaAdv, 0, 10U, + 36U, &rtb_r_phaAdvDC_XA_o2); + + /* Interpolation_n-D: '/r_sin3PhaA_M1' */ + rtDW->Merge = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_sin3PhaA_M1_Table); + + /* Interpolation_n-D: '/r_sin3PhaB_M1' */ + rtDW->Merge1 = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_sin3PhaB_M1_Table); + + /* Interpolation_n-D: '/r_sin3PhaC_M1' */ + rtDW->Merge2 = intrp1d_s16s32s32u8u32n31l_s(rtb_BitwiseOperator, + rtb_r_phaAdvDC_XA_o2, rtConstP.r_sin3PhaC_M1_Table); + + /* End of Outputs for SubSystem: '/F03_03_Sinusoidal3rd_Method' */ + break; + } + + /* End of SwitchCase: '/Switch Case' */ + + /* Signum: '/Sign' */ + if (rtDW->Switch2 < 0) { + rtb_Sum2_h = -1; + } else { + rtb_Sum2_h = (int8_T)(rtDW->Switch2 > 0); + } + + /* End of Signum: '/Sign' */ + + /* Signum: '/Sign1' incorporates: + * Inport: '/r_DC' + */ + if (rtU->r_DC < 0) { + rtb_Abs5 = -1; + } else { + rtb_Abs5 = (rtU->r_DC > 0); + } + + /* End of Signum: '/Sign1' */ + + /* Switch: '/Switch1' incorporates: + * Constant: '/vec_hallToPos' + * Constant: '/CTRL_COMM' + * Constant: '/r_commDCDeacv' + * Constant: '/z_ctrlTypSel1' + * Inport: '/r_DC' + * Logic: '/Logical Operator2' + * LookupNDDirect: '/z_commutMap_M1' + * Product: '/Divide2' + * Product: '/Divide4' + * RelationalOperator: '/Relational Operator1' + * RelationalOperator: '/Relational Operator3' + * RelationalOperator: '/Relational Operator4' + * Relay: '/dz_counter' + * Relay: '/n_commDeacv' + * Selector: '/Selector' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + if ((rtP->z_ctrlTypSel != 0) && (rtb_Abs1 > rtP->r_commDCDeacv) && (rtb_Sum2_h + == rtb_Abs5) && rtDW->n_commDeacv_Mode && (!rtDW->dz_counter_Mode)) { + rtb_Abs5 = rtU->r_DC * rtDW->Merge; + rtb_Switch1_idx_1 = rtU->r_DC * rtDW->Merge1; + rtb_Abs1 = rtU->r_DC * rtDW->Merge2; + } else { + if (rtConstP.vec_hallToPos_Value[rtb_Sum] > 5) { + /* LookupNDDirect: '/z_commutMap_M1' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Sum2_h = 5; + } else if (rtConstP.vec_hallToPos_Value[rtb_Sum] < 0) { + /* LookupNDDirect: '/z_commutMap_M1' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Sum2_h = 0; + } else { + /* LookupNDDirect: '/z_commutMap_M1' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Sum2_h = rtConstP.vec_hallToPos_Value[rtb_Sum]; + } + + /* LookupNDDirect: '/z_commutMap_M1' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Abs1 = rtb_Sum2_h * 3; + rtb_Abs5 = rtU->r_DC * rtConstP.z_commutMap_M1_table[rtb_Abs1]; + rtb_Switch1_idx_1 = rtConstP.z_commutMap_M1_table[1 + rtb_Abs1] * rtU->r_DC; + rtb_Abs1 = rtConstP.z_commutMap_M1_table[2 + rtb_Abs1] * rtU->r_DC; + } + + /* End of Switch: '/Switch1' */ + + /* Outport: '/DC_phaA' incorporates: + * Constant: '/Constant1' + * Product: '/Divide1' + */ + rtY->DC_phaA = rtb_Abs5 / 1000; + + /* Outport: '/DC_phaB' incorporates: + * Constant: '/Constant1' + * Product: '/Divide1' + */ + rtY->DC_phaB = rtb_Switch1_idx_1 / 1000; + + /* Update for UnitDelay: '/UnitDelay' incorporates: + * Inport: '/b_hallA ' + */ + rtDW->UnitDelay_DSTATE = rtU->b_hallA; + + /* Update for UnitDelay: '/UnitDelay1' incorporates: + * Inport: '/b_hallB' + */ + rtDW->UnitDelay1_DSTATE_i = rtU->b_hallB; + + /* Update for UnitDelay: '/UnitDelay2' incorporates: + * Inport: '/b_hallC' + */ + rtDW->UnitDelay2_DSTATE_h = rtU->b_hallC; + + /* Update for UnitDelay: '/UnitDelay1' */ + rtDW->UnitDelay1_DSTATE = rtb_Sum1_a; + + /* Update for UnitDelay: '/UnitDelay1' */ + rtDW->UnitDelay1_DSTATE_c = rtb_Sum1_a; + + /* Update for UnitDelay: '/UnitDelay2' */ + rtDW->UnitDelay2_DSTATE = rtb_Sum2; + + /* Outport: '/DC_phaC' incorporates: + * Constant: '/Constant1' + * Product: '/Divide1' + */ + rtY->DC_phaC = rtb_Abs1 / 1000; + + /* End of Outputs for SubSystem: '/BLDC_controller' */ + + /* Outport: '/n_mot' */ + rtY->n_mot = rtb_Sum2; +} + +/* Model initialize function */ +void BLDC_controller_initialize(RT_MODEL *const rtM) +{ + P *rtP = ((P *) rtM->defaultParam); + DW *rtDW = ((DW *) rtM->dwork); + + /* Start for Atomic SubSystem: '/BLDC_controller' */ + /* Start for If: '/If1' */ + rtDW->If1_ActiveSubsystem = -1; + + /* End of Start for SubSystem: '/BLDC_controller' */ + + /* SystemInitialize for Atomic SubSystem: '/BLDC_controller' */ + /* InitializeConditions for UnitDelay: '/UnitDelay1' */ + rtDW->UnitDelay1_DSTATE = rtP->z_maxCntRst; + + /* SystemInitialize for IfAction SubSystem: '/Counter_Hold_and_Error_Calculation' */ + /* InitializeConditions for UnitDelay: '/z_counter2' */ + rtDW->z_counter2_DSTATE = rtP->z_maxCntRst; + + /* SystemInitialize for Outport: '/z_counter' */ + rtDW->z_counterRawPrev = rtP->z_maxCntRst; + + /* End of SystemInitialize for SubSystem: '/Counter_Hold_and_Error_Calculation' */ + /* End of SystemInitialize for SubSystem: '/BLDC_controller' */ +} + +/* + * File trailer for generated code. + * + * [EOF] + */ diff --git a/Src/BLDC_controller_data.c b/Src/BLDC_controller_data.c new file mode 100644 index 00000000..8f75821d --- /dev/null +++ b/Src/BLDC_controller_data.c @@ -0,0 +1,170 @@ +/* + * + * File: BLDC_controller_data.c + * + * Code generated for Simulink model 'BLDC_controller'. + * + * Model version : 1.883 + * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 + * C/C++ source code generated on : Tue Jun 11 21:14:57 2019 + * + * Target selection: ert.tlc + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Emulation hardware selection: + * Differs from embedded hardware (MATLAB Host) + * Code generation objectives: + * 1. Execution efficiency + * 2. RAM efficiency + * Validation result: Not run + */ + +#include "BLDC_controller.h" + +/* Constant parameters (auto storage) */ +const ConstP rtConstP = { + /* Computed Parameter: r_trapPhaA_M1_Table + * Referenced by: '/r_trapPhaA_M1' + */ + { 1000, 1000, 1000, -1000, -1000, -1000, 1000 }, + + /* Computed Parameter: r_trapPhaB_M1_Table + * Referenced by: '/r_trapPhaB_M1' + */ + { -1000, -1000, 1000, 1000, 1000, -1000, -1000 }, + + /* Computed Parameter: r_trapPhaC_M1_Table + * Referenced by: '/r_trapPhaC_M1' + */ + { 1000, -1000, -1000, -1000, 1000, 1000, 1000 }, + + /* Computed Parameter: r_sinPhaA_M1_Table + * Referenced by: '/r_sinPhaA_M1' + */ + { 500, 643, 766, 866, 940, 985, 1000, 985, 940, 866, 766, 643, 500, 342, 174, + 0, -174, -342, -500, -643, -766, -866, -940, -985, -1000, -985, -940, -866, + -766, -643, -500, -342, -174, 0, 174, 342, 500 }, + + /* Computed Parameter: r_sinPhaB_M1_Table + * Referenced by: '/r_sinPhaB_M1' + */ + { -1000, -985, -940, -866, -766, -643, -500, -342, -174, 0, 174, 342, 500, 643, + 766, 866, 940, 985, 1000, 985, 940, 866, 766, 643, 500, 342, 174, 0, -174, + -342, -500, -643, -766, -866, -940, -985, -1000 }, + + /* Computed Parameter: r_sinPhaC_M1_Table + * Referenced by: '/r_sinPhaC_M1' + */ + { 500, 342, 174, 0, -174, -342, -500, -643, -766, -866, -940, -985, -1000, + -985, -940, -866, -766, -643, -500, -342, -174, 0, 174, 342, 500, 643, 766, + 866, 940, 985, 1000, 985, 940, 866, 766, 643, 500 }, + + /* Computed Parameter: r_sin3PhaA_M1_Table + * Referenced by: '/r_sin3PhaA_M1' + */ + { 813, 945, 1000, 996, 962, 926, 912, 926, 962, 996, 1000, 945, 813, 599, 319, + 0, -319, -599, -813, -945, -1000, -996, -962, -926, -912, -926, -962, -996, + -1000, -945, -813, -599, -319, 0, 319, 599, 813 }, + + /* Computed Parameter: r_sin3PhaB_M1_Table + * Referenced by: '/r_sin3PhaB_M1' + */ + { -912, -926, -962, -996, -1000, -945, -813, -599, -319, 0, 319, 599, 813, 945, + 1000, 996, 962, 926, 912, 926, 962, 996, 1000, 945, 813, 599, 319, 0, -319, + -599, -813, -945, -1000, -996, -962, -926, -912 }, + + /* Computed Parameter: r_sin3PhaC_M1_Table + * Referenced by: '/r_sin3PhaC_M1' + */ + { 813, 599, 319, 0, -319, -599, -813, -945, -1000, -996, -962, -926, -912, + -926, -962, -996, -1000, -945, -813, -599, -319, 0, 319, 599, 813, 945, 1000, + 996, 962, 926, 912, 926, 962, 996, 1000, 945, 813 }, + + /* Computed Parameter: z_commutMap_M1_table + * Referenced by: '/z_commutMap_M1' + */ + { 1000, -1000, 0, 1000, 0, -1000, 0, 1000, -1000, -1000, 1000, 0, -1000, 0, + 1000, 0, -1000, 1000 }, + + /* Computed Parameter: vec_hallToPos_Value + * Referenced by: '/vec_hallToPos' + */ + { 0, 5, 3, 4, 1, 0, 2, 0 } +}; + +P rtP = { + /* Variable: cf_speedCoef + * Referenced by: '/cf_spdCoef' + */ + 11111, + + /* Variable: cf_speedFilt + * Referenced by: '/cf_speedFilt' + */ + 10, + + /* Variable: n_commAcvLo + * Referenced by: '/n_commDeacv' + */ + 15, + + /* Variable: n_commDeacvHi + * Referenced by: '/n_commDeacv' + */ + 30, + + /* Variable: n_motPhaAdvEna + * Referenced by: '/n_motPhaAdvEna' + */ + 400, + + /* Variable: r_commDCDeacv + * Referenced by: '/r_commDCDeacv' + */ + 70, + + /* Variable: r_phaAdvDC_XA + * Referenced by: '/r_phaAdvDC_XA' + */ + { 0, 100, 200, 300, 400, 500, 600, 700, 800, 900, 1000 }, + + /* Variable: a_phaAdv_M1 + * Referenced by: '/a_phaAdv_M2' + */ + { 0, 0, 0, 0, 0, 2, 3, 5, 9, 16, 25 }, + + /* Variable: dz_counterHi + * Referenced by: '/dz_counter' + */ + 50, + + /* Variable: dz_counterLo + * Referenced by: '/dz_counter' + */ + 20, + + /* Variable: z_maxCntRst + * Referenced by: + * '/z_counter' + * '/z_counter2' + * '/z_maxCntRst' + * '/Constant1' + * '/UnitDelay1' + */ + 1500, + + /* Variable: z_ctrlTypSel + * Referenced by: '/z_ctrlTypSel1' + */ + 3U, + + /* Variable: b_phaAdvEna + * Referenced by: '/a_elecPeriod1' + */ + 1 +}; + +/* + * File trailer for generated code. + * + * [EOF] + */ diff --git a/Src/bldc.c b/Src/bldc.c index e5c609cd..faab39e0 100644 --- a/Src/bldc.c +++ b/Src/bldc.c @@ -1,154 +1,83 @@ +/* +* This file has been re-implemented with 4 new selectable motor control methods. +* Recommended control method: 3 = Sinusoidal 3rd order. This control method offers superior performanace +* compared to previous method. The new method features: +* ► reduced noise and vibrations +* ► smooth torque output +* ► improved motor efficiency -> lower energy consumption +* +* Copyright (C) 2019 Emanuel FERU +* +* This program is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with this program. If not, see . +*/ #include "stm32f1xx_hal.h" #include "defines.h" #include "setup.h" #include "config.h" +// Matlab includes and defines - from auto-code generation +// ############################################################################### +#include "BLDC_controller.h" /* Model's header file */ +#include "rtwtypes.h" + +extern RT_MODEL *const rtM_Left; +extern RT_MODEL *const rtM_Right; + +extern DW rtDW_Left; /* Observable states */ +extern ExtU rtU_Left; /* External inputs */ +extern ExtY rtY_Left; /* External outputs */ + +extern DW rtDW_Right; /* Observable states */ +extern ExtU rtU_Right; /* External inputs */ +extern ExtY rtY_Right; /* External outputs */ +// ############################################################################### + -volatile int posl = 0; -volatile int posr = 0; volatile int pwml = 0; volatile int pwmr = 0; -volatile int weakl = 0; -volatile int weakr = 0; - -extern volatile int speed; extern volatile adc_buf_t adc_buffer; extern volatile uint32_t timeout; -uint32_t buzzerFreq = 0; -uint32_t buzzerPattern = 0; - -uint8_t enable = 0; - -const int pwm_res = 64000000 / 2 / PWM_FREQ; // = 2000 - -const uint8_t hall_to_pos[8] = { - 0, - 0, - 2, - 1, - 4, - 5, - 3, - 0, -}; - -inline void blockPWM(int pwm, int pos, int *u, int *v, int *w) { - switch(pos) { - case 0: - *u = 0; - *v = pwm; - *w = -pwm; - break; - case 1: - *u = -pwm; - *v = pwm; - *w = 0; - break; - case 2: - *u = -pwm; - *v = 0; - *w = pwm; - break; - case 3: - *u = 0; - *v = -pwm; - *w = pwm; - break; - case 4: - *u = pwm; - *v = -pwm; - *w = 0; - break; - case 5: - *u = pwm; - *v = 0; - *w = -pwm; - break; - default: - *u = 0; - *v = 0; - *w = 0; - } -} +uint8_t buzzerFreq = 0; +uint8_t buzzerPattern = 0; +static uint32_t buzzerTimer = 0; -inline void blockPhaseCurrent(int pos, int u, int v, int *q) { - switch(pos) { - case 0: - *q = u - v; - // *u = 0; - // *v = pwm; - // *w = -pwm; - break; - case 1: - *q = u; - // *u = -pwm; - // *v = pwm; - // *w = 0; - break; - case 2: - *q = u; - // *u = -pwm; - // *v = 0; - // *w = pwm; - break; - case 3: - *q = v; - // *u = 0; - // *v = -pwm; - // *w = pwm; - break; - case 4: - *q = v; - // *u = pwm; - // *v = -pwm; - // *w = 0; - break; - case 5: - *q = -(u - v); - // *u = pwm; - // *v = 0; - // *w = -pwm; - break; - default: - *q = 0; - // *u = 0; - // *v = 0; - // *w = 0; - } -} +uint8_t enable = 0; -uint32_t buzzerTimer = 0; +static const uint16_t pwm_res = 64000000 / 2 / PWM_FREQ; // = 2000 -int offsetcount = 0; -int offsetrl1 = 2000; -int offsetrl2 = 2000; -int offsetrr1 = 2000; -int offsetrr2 = 2000; -int offsetdcl = 2000; -int offsetdcr = 2000; +static int offsetcount = 0; +static int offsetrl1 = 2000; +static int offsetrl2 = 2000; +static int offsetrr1 = 2000; +static int offsetrr2 = 2000; +static int offsetdcl = 2000; +static int offsetdcr = 2000; float batteryVoltage = BAT_NUMBER_OF_CELLS * 4.0; -int curl = 0; -// int errorl = 0; -// int kp = 5; -// volatile int cmdl = 0; - -int last_pos = 0; -int timer = 0; -const int max_time = PWM_FREQ / 10; -volatile int vel = 0; - //scan 8 channels with 2ADCs @ 20 clk cycles per sample //meaning ~80 ADC clock cycles @ 8MHz until new DMA interrupt =~ 100KHz //=640 cpu cycles -void DMA1_Channel1_IRQHandler() { +void DMA1_Channel1_IRQHandler(void) { + DMA1->IFCR = DMA_IFCR_CTCIF1; // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1); + // HAL_GPIO_TogglePin(LED_PORT, LED_PIN); if(offsetcount < 1000) { // calibrate ADC offsets offsetcount++; @@ -162,7 +91,7 @@ void DMA1_Channel1_IRQHandler() { } if (buzzerTimer % 1000 == 0) { // because you get float rounding errors if it would run every time - batteryVoltage = batteryVoltage * 0.99 + ((float)adc_buffer.batt1 * ((float)BAT_CALIB_REAL_VOLTAGE / (float)BAT_CALIB_ADC)) * 0.01; + batteryVoltage = batteryVoltage * 0.99f + ((float)adc_buffer.batt1 * ((float)BAT_CALIB_REAL_VOLTAGE / (float)BAT_CALIB_ADC)) * 0.01f; } //disable PWM when current limit is reached (current chopping) @@ -180,61 +109,6 @@ void DMA1_Channel1_IRQHandler() { RIGHT_TIM->BDTR |= TIM_BDTR_MOE; } - int ul, vl, wl; - int ur, vr, wr; - - //determine next position based on hall sensors - uint8_t hall_ul = !(LEFT_HALL_U_PORT->IDR & LEFT_HALL_U_PIN); - uint8_t hall_vl = !(LEFT_HALL_V_PORT->IDR & LEFT_HALL_V_PIN); - uint8_t hall_wl = !(LEFT_HALL_W_PORT->IDR & LEFT_HALL_W_PIN); - - uint8_t hall_ur = !(RIGHT_HALL_U_PORT->IDR & RIGHT_HALL_U_PIN); - uint8_t hall_vr = !(RIGHT_HALL_V_PORT->IDR & RIGHT_HALL_V_PIN); - uint8_t hall_wr = !(RIGHT_HALL_W_PORT->IDR & RIGHT_HALL_W_PIN); - - uint8_t halll = hall_ul * 1 + hall_vl * 2 + hall_wl * 4; - posl = hall_to_pos[halll]; - posl += 2; - posl %= 6; - - uint8_t hallr = hall_ur * 1 + hall_vr * 2 + hall_wr * 4; - posr = hall_to_pos[hallr]; - posr += 2; - posr %= 6; - - blockPhaseCurrent(posl, adc_buffer.rl1 - offsetrl1, adc_buffer.rl2 - offsetrl2, &curl); - - //setScopeChannel(2, (adc_buffer.rl1 - offsetrl1) / 8); - //setScopeChannel(3, (adc_buffer.rl2 - offsetrl2) / 8); - - - // uint8_t buzz(uint16_t *notes, uint32_t len){ - // static uint32_t counter = 0; - // static uint32_t timer = 0; - // if(len == 0){ - // return(0); - // } - - // struct { - // uint16_t freq : 4; - // uint16_t volume : 4; - // uint16_t time : 8; - // } note = notes[counter]; - - // if(timer / 500 == note.time){ - // timer = 0; - // counter++; - // } - - // if(counter == len){ - // counter = 0; - // } - - // timer++; - // return(note.freq); - // } - - //create square wave for buzzer buzzerTimer++; if (buzzerFreq != 0 && (buzzerTimer / 5000) % (buzzerPattern + 1) == 0) { @@ -245,35 +119,81 @@ void DMA1_Channel1_IRQHandler() { HAL_GPIO_WritePin(BUZZER_PORT, BUZZER_PIN, 0); } - //update PWM channels based on position - blockPWM(pwml, posl, &ul, &vl, &wl); - blockPWM(pwmr, posr, &ur, &vr, &wr); + // ############################### MOTOR CONTROL ############################### - int weakul, weakvl, weakwl; - if (pwml > 0) { - blockPWM(weakl, (posl+5) % 6, &weakul, &weakvl, &weakwl); - } else { - blockPWM(-weakl, (posl+1) % 6, &weakul, &weakvl, &weakwl); - } - ul += weakul; - vl += weakvl; - wl += weakwl; - - int weakur, weakvr, weakwr; - if (pwmr > 0) { - blockPWM(weakr, (posr+5) % 6, &weakur, &weakvr, &weakwr); - } else { - blockPWM(-weakr, (posr+1) % 6, &weakur, &weakvr, &weakwr); + static boolean_T OverrunFlag = false; + /* Check for overrun */ + if (OverrunFlag) { + return; } - ur += weakur; - vr += weakvr; - wr += weakwr; - - LEFT_TIM->LEFT_TIM_U = CLAMP(ul + pwm_res / 2, 10, pwm_res-10); - LEFT_TIM->LEFT_TIM_V = CLAMP(vl + pwm_res / 2, 10, pwm_res-10); - LEFT_TIM->LEFT_TIM_W = CLAMP(wl + pwm_res / 2, 10, pwm_res-10); + OverrunFlag = true; + + int ul, vl, wl; + int ur, vr, wr; + // ========================= LEFT MOTOR ============================ + // Get hall sensors values + uint8_t hall_ul = !(LEFT_HALL_U_PORT->IDR & LEFT_HALL_U_PIN); + uint8_t hall_vl = !(LEFT_HALL_V_PORT->IDR & LEFT_HALL_V_PIN); + uint8_t hall_wl = !(LEFT_HALL_W_PORT->IDR & LEFT_HALL_W_PIN); + + /* Set motor inputs here */ + rtU_Left.b_hallA = hall_ul; + rtU_Left.b_hallB = hall_vl; + rtU_Left.b_hallC = hall_wl; + rtU_Left.r_DC = pwml; + + /* Step the controller if motor is enabled*/ + if (enable) { + BLDC_controller_step(rtM_Left); + } + + /* Get motor outputs here */ + ul = rtY_Left.DC_phaA; + vl = rtY_Left.DC_phaB; + wl = rtY_Left.DC_phaC; + // motSpeedLeft = rtY_Left.n_mot; + // motAngleLeft = rtY_Left.a_elecAngle; + + /* Apply commands */ + LEFT_TIM->LEFT_TIM_U = (uint16_t)CLAMP(ul + pwm_res / 2, 10, pwm_res-10); + LEFT_TIM->LEFT_TIM_V = (uint16_t)CLAMP(vl + pwm_res / 2, 10, pwm_res-10); + LEFT_TIM->LEFT_TIM_W = (uint16_t)CLAMP(wl + pwm_res / 2, 10, pwm_res-10); + // ================================================================= + + + // ========================= RIGHT MOTOR =========================== + // Get hall sensors values + uint8_t hall_ur = !(RIGHT_HALL_U_PORT->IDR & RIGHT_HALL_U_PIN); + uint8_t hall_vr = !(RIGHT_HALL_V_PORT->IDR & RIGHT_HALL_V_PIN); + uint8_t hall_wr = !(RIGHT_HALL_W_PORT->IDR & RIGHT_HALL_W_PIN); + + /* Set motor inputs here */ + rtU_Right.b_hallA = hall_ur; + rtU_Right.b_hallB = hall_vr; + rtU_Right.b_hallC = hall_wr; + rtU_Right.r_DC = pwmr; + + /* Step the controller if motor is enabled*/ + if (enable) { + BLDC_controller_step(rtM_Right); + } + + /* Get motor outputs here */ + ur = rtY_Right.DC_phaA; + vr = rtY_Right.DC_phaB; + wr = rtY_Right.DC_phaC; + // motSpeedRight = rtY_Right.n_mot; + // motAngleRight = rtY_Right.a_elecAngle; + + /* Apply commands */ + RIGHT_TIM->RIGHT_TIM_U = (uint16_t)CLAMP(ur + pwm_res / 2, 10, pwm_res-10); + RIGHT_TIM->RIGHT_TIM_V = (uint16_t)CLAMP(vr + pwm_res / 2, 10, pwm_res-10); + RIGHT_TIM->RIGHT_TIM_W = (uint16_t)CLAMP(wr + pwm_res / 2, 10, pwm_res-10); + // ================================================================= + + /* Indicate task complete */ + OverrunFlag = false; + + // ############################################################################### - RIGHT_TIM->RIGHT_TIM_U = CLAMP(ur + pwm_res / 2, 10, pwm_res-10); - RIGHT_TIM->RIGHT_TIM_V = CLAMP(vr + pwm_res / 2, 10, pwm_res-10); - RIGHT_TIM->RIGHT_TIM_W = CLAMP(wr + pwm_res / 2, 10, pwm_res-10); } diff --git a/Src/comms.c b/Src/comms.c index 5e437a18..58b71fcb 100644 --- a/Src/comms.c +++ b/Src/comms.c @@ -1,9 +1,10 @@ +#include +#include #include "stm32f1xx_hal.h" #include "defines.h" #include "setup.h" #include "config.h" -#include "stdio.h" -#include "string.h" +#include "comms.h" UART_HandleTypeDef huart2; @@ -16,15 +17,15 @@ UART_HandleTypeDef huart2; #endif -volatile uint8_t uart_buf[100]; -volatile int16_t ch_buf[8]; +static volatile uint8_t uart_buf[100]; +static volatile int16_t ch_buf[8]; //volatile char char_buf[300]; void setScopeChannel(uint8_t ch, int16_t val) { ch_buf[ch] = val; } -void consoleScope() { +void consoleScope(void) { #if defined DEBUG_SERIAL_SERVOTERM && (defined DEBUG_SERIAL_USART2 || defined DEBUG_SERIAL_USART3) uart_buf[0] = 0xff; uart_buf[1] = CLAMP(ch_buf[0]+127, 0, 255); @@ -46,12 +47,12 @@ void consoleScope() { #endif #if defined DEBUG_SERIAL_ASCII && (defined DEBUG_SERIAL_USART2 || defined DEBUG_SERIAL_USART3) - memset(uart_buf, 0, sizeof(uart_buf)); - sprintf(uart_buf, "1:%i 2:%i 3:%i 4:%i 5:%i 6:%i 7:%i 8:%i\r\n", ch_buf[0], ch_buf[1], ch_buf[2], ch_buf[3], ch_buf[4], ch_buf[5], ch_buf[6], ch_buf[7]); + memset((void *)(uintptr_t)uart_buf, 0, sizeof(uart_buf)); + sprintf((char *)(uintptr_t)uart_buf, "1:%i 2:%i 3:%i 4:%i 5:%i 6:%i 7:%i 8:%i\r\n", ch_buf[0], ch_buf[1], ch_buf[2], ch_buf[3], ch_buf[4], ch_buf[5], ch_buf[6], ch_buf[7]); if(UART_DMA_CHANNEL->CNDTR == 0) { UART_DMA_CHANNEL->CCR &= ~DMA_CCR_EN; - UART_DMA_CHANNEL->CNDTR = strlen(uart_buf); + UART_DMA_CHANNEL->CNDTR = strlen((char *)(uintptr_t)uart_buf); UART_DMA_CHANNEL->CMAR = (uint32_t)uart_buf; UART_DMA_CHANNEL->CCR |= DMA_CCR_EN; } @@ -60,5 +61,5 @@ void consoleScope() { void consoleLog(char *message) { - HAL_UART_Transmit_DMA(&huart2, (uint8_t *)message, strlen(message)); + HAL_UART_Transmit_DMA(&huart2, (uint8_t *)message, (uint16_t)strlen(message)); } diff --git a/Src/control.c b/Src/control.c index c3ec8df8..3e36bd9c 100644 --- a/Src/control.c +++ b/Src/control.c @@ -1,10 +1,10 @@ +#include +#include #include "stm32f1xx_hal.h" #include "defines.h" #include "setup.h" #include "config.h" -#include -#include TIM_HandleTypeDef TimHandle; uint8_t ppm_count = 0; @@ -14,8 +14,8 @@ uint8_t nunchuck_data[6] = {0}; uint8_t i2cBuffer[2]; extern I2C_HandleTypeDef hi2c2; -DMA_HandleTypeDef hdma_i2c2_rx; -DMA_HandleTypeDef hdma_i2c2_tx; +extern DMA_HandleTypeDef hdma_i2c2_rx; +extern DMA_HandleTypeDef hdma_i2c2_tx; #ifdef CONTROL_PPM uint16_t ppm_captured_value[PPM_NUM_CHANNELS + 1] = {500, 500}; @@ -26,7 +26,7 @@ bool ppm_valid = true; #define IN_RANGE(x, low, up) (((x) >= (low)) && ((x) <= (up))) -void PPM_ISR_Callback() { +void PPM_ISR_Callback(void) { // Dummy loop with 16 bit count wrap around uint16_t rc_delay = TIM2->CNT; TIM2->CNT = 0; @@ -48,7 +48,7 @@ void PPM_ISR_Callback() { } // SysTick executes once each ms -void PPM_SysTick_Callback() { +void PPM_SysTick_Callback(void) { ppm_timeout++; // Stop after 500 ms without PPM signal if(ppm_timeout > 500) { @@ -60,7 +60,7 @@ void PPM_SysTick_Callback() { } } -void PPM_Init() { +void PPM_Init(void) { GPIO_InitTypeDef GPIO_InitStruct; /*Configure GPIO pin : PA3 */ GPIO_InitStruct.Pin = GPIO_PIN_3; @@ -84,7 +84,7 @@ void PPM_Init() { } #endif -void Nunchuck_Init() { +void Nunchuck_Init(void) { //-- START -- init WiiNunchuck i2cBuffer[0] = 0xF0; i2cBuffer[1] = 0x55; @@ -99,7 +99,7 @@ void Nunchuck_Init() { HAL_Delay(10); } -void Nunchuck_Read() { +void Nunchuck_Read(void) { i2cBuffer[0] = 0x00; HAL_I2C_Master_Transmit(&hi2c2,0xA4,(uint8_t*)i2cBuffer, 1, 100); HAL_Delay(5); diff --git a/Src/main.c b/Src/main.c index b737a77c..02c7ff51 100644 --- a/Src/main.c +++ b/Src/main.c @@ -19,13 +19,37 @@ * along with this program. If not, see . */ +#include // for abs() #include "stm32f1xx_hal.h" #include "defines.h" #include "setup.h" #include "config.h" +#include "comms.h" //#include "hd44780.h" +// Matlab includes and defines - from auto-code generation +// ############################################################################### +#include "BLDC_controller.h" /* Model's header file */ +#include "rtwtypes.h" + +RT_MODEL rtM_Left_; /* Real-time model */ +RT_MODEL rtM_Right_; /* Real-time model */ +RT_MODEL *const rtM_Left = &rtM_Left_; +RT_MODEL *const rtM_Right = &rtM_Right_; + +P rtP; /* Block parameters (auto storage) */ + +DW rtDW_Left; /* Observable states */ +ExtU rtU_Left; /* External inputs */ +ExtY rtY_Left; /* External outputs */ + +DW rtDW_Right; /* Observable states */ +ExtU rtU_Right; /* External inputs */ +ExtY rtY_Right; /* External outputs */ +// ############################################################################### + void SystemClock_Config(void); +void poweroff(void); extern TIM_HandleTypeDef htim_left; extern TIM_HandleTypeDef htim_right; @@ -36,9 +60,8 @@ extern volatile adc_buf_t adc_buffer; extern I2C_HandleTypeDef hi2c2; extern UART_HandleTypeDef huart2; -int cmd1; // normalized input values. -1000 to 1000 -int cmd2; -int cmd3; +static int cmd1; // normalized input values. -1000 to 1000 +static int cmd2; typedef struct{ int16_t steer; @@ -46,17 +69,15 @@ typedef struct{ //uint32_t crc; } Serialcommand; -volatile Serialcommand command; +static volatile Serialcommand command; -uint8_t button1, button2; +static uint8_t button1, button2; -int steer; // global variable for steering. -1000 to 1000 -int speed; // global variable for speed. -1000 to 1000 +static int steer; // global variable for steering. -1000 to 1000 +static int speed; // global variable for speed. -1000 to 1000 extern volatile int pwml; // global variable for pwm left. -1000 to 1000 extern volatile int pwmr; // global variable for pwm right. -1000 to 1000 -extern volatile int weakl; // global variable for field weakening left. -1000 to 1000 -extern volatile int weakr; // global variable for field weakening right. -1000 to 1000 extern uint8_t buzzerFreq; // global variable for the buzzer pitch. can be 1, 2, 3, 4, 5, 6, 7... extern uint8_t buzzerPattern; // global variable for the buzzer pattern. can be 1, 2, 3, 4, 5, 6, 7... @@ -66,31 +87,30 @@ extern uint8_t enable; // global variable for motor enable extern volatile uint32_t timeout; // global variable for timeout extern float batteryVoltage; // global variable for battery voltage -uint32_t inactivity_timeout_counter; +static uint32_t inactivity_timeout_counter; extern uint8_t nunchuck_data[6]; #ifdef CONTROL_PPM extern volatile uint16_t ppm_captured_value[PPM_NUM_CHANNELS+1]; #endif -int milli_vel_error_sum = 0; - -void poweroff() { - if (abs(speed) < 20) { +void poweroff(void) { + // if (abs(speed) < 20) { // wait for the speed to drop, then shut down -> this is commented out for SAFETY reasons buzzerPattern = 0; enable = 0; for (int i = 0; i < 8; i++) { - buzzerFreq = i; + buzzerFreq = (uint8_t)i; HAL_Delay(100); } HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, 0); while(1) {} - } + // } } int main(void) { + HAL_Init(); __HAL_RCC_AFIO_CLK_ENABLE(); HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); @@ -127,8 +147,33 @@ int main(void) { HAL_ADC_Start(&hadc1); HAL_ADC_Start(&hadc2); +// Matlab Init +// ############################################################################### + + /* Set BLDC controller parameters */ + rtP.z_ctrlTypSel = CTRL_TYP_SEL; + rtP.b_phaAdvEna = PHASE_ADV_ENA; + + /* Pack LEFT motor data into RTM */ + rtM_Left->defaultParam = &rtP; + rtM_Left->dwork = &rtDW_Left; + rtM_Left->inputs = &rtU_Left; + rtM_Left->outputs = &rtY_Left; + + /* Pack RIGHT motor data into RTM */ + rtM_Right->defaultParam = &rtP; + rtM_Right->dwork = &rtDW_Right; + rtM_Right->inputs = &rtU_Right; + rtM_Right->outputs = &rtY_Right; + + /* Initialize BLDC controllers */ + BLDC_controller_initialize(rtM_Left); + BLDC_controller_initialize(rtM_Right); + +// ############################################################################### + for (int i = 8; i >= 0; i--) { - buzzerFreq = i; + buzzerFreq = (uint8_t)i; HAL_Delay(100); } buzzerFreq = 0; @@ -137,7 +182,6 @@ int main(void) { int lastSpeedL = 0, lastSpeedR = 0; int speedL = 0, speedR = 0; - float direction = 1; #ifdef CONTROL_PPM PPM_Init(); @@ -178,7 +222,8 @@ int main(void) { float board_temp_adc_filtered = (float)adc_buffer.temp; float board_temp_deg_c; - enable = 1; // enable motors + enable = 0; // initially motors are disabled for SAFETY + while(1) { HAL_Delay(DELAY_IN_MAIN_LOOP); //delay in ms @@ -201,8 +246,8 @@ int main(void) { #ifdef CONTROL_ADC // ADC values range: 0-4095, see ADC-calibration in config.h - cmd1 = CLAMP(adc_buffer.l_tx2 - ADC1_MIN, 0, ADC1_MAX) / (ADC1_MAX / 1000.0f); // ADC1 - cmd2 = CLAMP(adc_buffer.l_rx2 - ADC2_MIN, 0, ADC2_MAX) / (ADC2_MAX / 1000.0f); // ADC2 + cmd1 = CLAMP(adc_buffer.l_tx2 - ADC1_MIN, 0, ADC1_MAX) / (ADC1_MAX / 1000.0f); // ADC1 + cmd2 = CLAMP(adc_buffer.l_rx2 - ADC2_MIN, 0, ADC2_MAX) / (ADC2_MAX / 1000.0f); // ADC2 // use ADCs as button inputs: button1 = (uint8_t)(adc_buffer.l_tx2 > 2000); // ADC1 @@ -218,15 +263,22 @@ int main(void) { timeout = 0; #endif + // Bypass - only for testing purposes + // cmd1 = cmd1-500; + // cmd2 = cmd2-500; - // ####### LOW-PASS FILTER ####### - steer = steer * (1.0 - FILTER) + cmd1 * FILTER; - speed = speed * (1.0 - FILTER) + cmd2 * FILTER; + // ####### MOTOR ENABLING: Only if the initial input is very small (SAFETY) ####### + if (enable == 0 && (cmd1 > -50 && cmd1 < 50) && (cmd2 > -50 && cmd2 < 50)){ + enable = 1; // enable motors + } + // ####### LOW-PASS FILTER ####### + steer = (int)(steer * (1.0f - FILTER) + cmd1 * FILTER); + speed = (int)(speed * (1.0f - FILTER) + cmd2 * FILTER); // ####### MIXER ####### - speedR = CLAMP(speed * SPEED_COEFFICIENT - steer * STEER_COEFFICIENT, -1000, 1000); - speedL = CLAMP(speed * SPEED_COEFFICIENT + steer * STEER_COEFFICIENT, -1000, 1000); + speedR = CLAMP((int)(speed * SPEED_COEFFICIENT - steer * STEER_COEFFICIENT), -1000, 1000); + speedL = CLAMP((int)(speed * SPEED_COEFFICIENT + steer * STEER_COEFFICIENT), -1000, 1000); #ifdef ADDITIONAL_CODE @@ -234,8 +286,8 @@ int main(void) { #endif - // ####### SET OUTPUTS ####### - if ((speedL < lastSpeedL + 50 && speedL > lastSpeedL - 50) && (speedR < lastSpeedR + 50 && speedR > lastSpeedR - 50) && timeout < TIMEOUT) { + // ####### SET OUTPUTS (if the target change less than +/- 50) ####### + if ((speedL > lastSpeedL-50 && speedL < lastSpeedL+50) && (speedR > lastSpeedR-50 && speedR < lastSpeedR+50) && timeout < TIMEOUT) { #ifdef INVERT_R_DIRECTION pwmr = speedR; #else @@ -254,26 +306,28 @@ int main(void) { if (inactivity_timeout_counter % 25 == 0) { // ####### CALC BOARD TEMPERATURE ####### - board_temp_adc_filtered = board_temp_adc_filtered * 0.99 + (float)adc_buffer.temp * 0.01; + board_temp_adc_filtered = board_temp_adc_filtered * 0.99f + (float)adc_buffer.temp * 0.01f; board_temp_deg_c = ((float)TEMP_CAL_HIGH_DEG_C - (float)TEMP_CAL_LOW_DEG_C) / ((float)TEMP_CAL_HIGH_ADC - (float)TEMP_CAL_LOW_ADC) * (board_temp_adc_filtered - (float)TEMP_CAL_LOW_ADC) + (float)TEMP_CAL_LOW_DEG_C; - + // ####### DEBUG SERIAL OUT ####### #ifdef CONTROL_ADC - setScopeChannel(0, (int)adc_buffer.l_tx2); // 1: ADC1 - setScopeChannel(1, (int)adc_buffer.l_rx2); // 2: ADC2 + // setScopeChannel(0, (int)adc_buffer.l_tx2); // 1: ADC1 + // setScopeChannel(1, (int)adc_buffer.l_rx2); // 2: ADC2 #endif - setScopeChannel(2, (int)speedR); // 3: output speed: 0-1000 - setScopeChannel(3, (int)speedL); // 4: output speed: 0-1000 - setScopeChannel(4, (int)adc_buffer.batt1); // 5: for battery voltage calibration - setScopeChannel(5, (int)(batteryVoltage * 100.0f)); // 6: for verifying battery voltage calibration - setScopeChannel(6, (int)board_temp_adc_filtered); // 7: for board temperature calibration - setScopeChannel(7, (int)board_temp_deg_c); // 8: for verifying board temperature calibration + setScopeChannel(0, (int16_t)speedR); // 1: output command: [-1000, 1000] + setScopeChannel(1, (int16_t)speedL); // 2: output command: [-1000, 1000] + setScopeChannel(2, (int16_t)rtY_Right.n_mot); // 3: Real motor speed [rpm] + setScopeChannel(3, (int16_t)rtY_Left.n_mot); // 4: Real motor speed [rpm] + setScopeChannel(4, (int16_t)adc_buffer.batt1); // 5: for battery voltage calibration + setScopeChannel(5, (int16_t)(batteryVoltage * 100.0f)); // 6: for verifying battery voltage calibration + setScopeChannel(6, (int16_t)board_temp_adc_filtered); // 7: for board temperature calibration + setScopeChannel(7, (int16_t)board_temp_deg_c); // 8: for verifying board temperature calibration consoleScope(); } // ####### POWEROFF BY POWER-BUTTON ####### - if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && weakr == 0 && weakl == 0) { + if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { enable = 0; while (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {} poweroff(); diff --git a/Src/setup.c b/Src/setup.c index 8de657a0..1b05b7fa 100644 --- a/Src/setup.c +++ b/Src/setup.c @@ -53,7 +53,7 @@ volatile adc_buf_t adc_buffer; #ifdef CONTROL_SERIAL_USART2 -void UART_Control_Init() { +void UART_Control_Init(void) { GPIO_InitTypeDef GPIO_InitStruct; __HAL_RCC_USART2_CLK_ENABLE(); /* DMA1_Channel6_IRQn interrupt configuration */ @@ -123,7 +123,7 @@ HAL_DMA_Init(&hdma_usart2_tx); #endif #ifdef DEBUG_SERIAL_USART3 -void UART_Init() { +void UART_Init(void) { __HAL_RCC_USART3_CLK_ENABLE(); __HAL_RCC_DMA1_CLK_ENABLE(); @@ -156,7 +156,7 @@ void UART_Init() { #endif #ifdef DEBUG_SERIAL_USART2 -void UART_Init() { +void UART_Init(void) { __HAL_RCC_USART2_CLK_ENABLE(); __HAL_RCC_DMA1_CLK_ENABLE(); @@ -189,7 +189,7 @@ void UART_Init() { #endif /* -void UART_Init() { +void UART_Init(void) { __HAL_RCC_USART2_CLK_ENABLE(); __HAL_RCC_DMA1_CLK_ENABLE(); @@ -224,7 +224,7 @@ void UART_Init() { DMA_HandleTypeDef hdma_i2c2_rx; DMA_HandleTypeDef hdma_i2c2_tx; -void I2C_Init() +void I2C_Init(void) { __HAL_RCC_I2C2_CLK_ENABLE(); @@ -549,7 +549,15 @@ void MX_ADC1_Init(void) { multimode.Mode = ADC_DUALMODE_REGSIMULT; HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode); + // sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5; sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_13CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_41CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_55CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_71CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_239CYCLES_5; + sConfig.Channel = ADC_CHANNEL_14; // pc4 left b sConfig.Rank = 1; @@ -612,7 +620,15 @@ void MX_ADC2_Init(void) { hadc2.Init.NbrOfConversion = 5; HAL_ADC_Init(&hadc2); + + // sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5; sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_13CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_41CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_55CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_71CYCLES_5; + // sConfig.SamplingTime = ADC_SAMPLETIME_239CYCLES_5; sConfig.Channel = ADC_CHANNEL_15; // pc5 left c sConfig.Rank = 1; diff --git a/build/firmware.bin b/build/firmware.bin new file mode 100644 index 00000000..e0b693d4 Binary files /dev/null and b/build/firmware.bin differ diff --git a/build/firmware.elf b/build/firmware.elf new file mode 100644 index 00000000..ed4d95fa Binary files /dev/null and b/build/firmware.elf differ diff --git a/build/hover.hex b/build/hover.hex deleted file mode 100644 index 20d6a418..00000000 --- a/build/hover.hex +++ /dev/null @@ -1,1153 +0,0 @@ -:020000040800F2 -:1000000000C00020913D0008753D0008773D0008C4 -:10001000793D00087B3D00087D3D000800000000A0 -:100020000000000000000000000000007F3D00080C -:10003000813D000800000000833D0008853D000868 -:10004000D93D0008D93D0008D93D0008D93D000838 -:10005000D93D0008D93D0008D93D0008D93D000828 -:10006000D93D0008D93D0008D93D0008A135000858 -:10007000D93D0008D93D0008D93D0008D93D000808 -:10008000D93D0008D93D0008D93D0008D93D0008F8 -:10009000D93D0008D93D0008D93D0008D93D0008E8 -:1000A000D93D0008D93D0008D93D0008D93D0008D8 -:1000B000D93D0008D93D0008D93D0008D93D0008C8 -:1000C000D93D0008D93D0008D93D0008D93D0008B8 -:1000D000D93D0008D93D0008D93D0008D93D0008A8 -:1000E000D93D0008D93D0008D93D0008D93D000898 -:1000F000D93D0008D93D0008D93D0008D93D000888 -:10010000D93D0008D93D0008D93D0008D93D000877 -:10011000D93D0008D93D0008D93D0008D93D000867 -:10012000D93D0008D93D0008D93D0008D93D000857 -:1001300000000000000000000000000000000000BF -:1001400000000000000000000000000000000000AF -:10015000000000000000000000000000000000009F -:10016000000000000000000000000000000000008F -:10017000000000000000000000000000000000007F -:10018000000000000000000000000000000000006F -:10019000000000000000000000000000000000005F -:1001A000000000000000000000000000000000004F -:1001B000000000000000000000000000000000003F -:1001C000000000000000000000000000000000002F -:1001D000000000000000000000000000000000001F -:0401E0005FF8E0F1F3 -:1001E80010B5054C237833B9044B13B10448AFF369 -:1001F80000800123237010BD88000020000000004B -:100208007046000808B5034B1BB103490348AFF318 -:10021800008008BD000000008C0000207046000827 -:10022800034613F8012B002AFBD1181A013870472E -:1002380081F0004102E000BF83F0004330B54FEA8F -:1002480041044FEA430594EA050F08BF90EA020FFC -:100258001FBF54EA000C55EA020C7FEA645C7FEA8F -:10026800655C00F0E2804FEA5454D4EB5555B8BFB2 -:100278006D420CDD2C4480EA020281EA030382EA23 -:10028800000083EA010180EA020281EA0303362DB5 -:1002980088BF30BD11F0004F4FEA01314FF4801C88 -:1002A8004CEA113102D0404261EB410113F0004F9A -:1002B8004FEA03334CEA133302D0524263EB430351 -:1002C80094EA050F00F0A780A4F10104D5F1200EEF -:1002D8000DDB02FA0EFC22FA05F2801841F100014A -:1002E80003FA0EF2801843FA05F359410EE0A5F11E -:1002F80020050EF1200E012A03FA0EFC28BF4CF04F -:10030800020C43FA05F3C01851EBE37101F0004504 -:1003180007D54FF0000EDCF1000C7EEB00006EEB11 -:100328000101B1F5801F1BD3B1F5001F0CD349089B -:100338005FEA30004FEA3C0C04F101044FEA4452F2 -:1003480012F5800F80F09A80BCF1004F08BF5FEA79 -:10035800500C50F1000041EB045141EA050130BD59 -:100368005FEA4C0C404141EB010111F4801FA4F1FC -:100378000104E9D191F0000F04BF01460020B1FA51 -:1003880081F308BF2033A3F10B03B3F120020CDA89 -:100398000C3208DD02F1140CC2F10C0201FA0CF067 -:1003A80021FA02F10CE002F11402D8BFC2F1200CCC -:1003B80001FA02F120FA0CFCDCBF41EA0C01904082 -:1003C800E41AA2BF01EB0451294330BD6FEA0404CB -:1003D8001F3C1CDA0C340EDC04F11404C4F12002B6 -:1003E80020FA04F001FA02F340EA030021FA04F3C8 -:1003F80045EA030130BDC4F10C04C4F1200220FA1F -:1004080002F001FA04F340EA0300294630BD21FA5C -:1004180004F0294630BD94F0000F83F4801306BF22 -:1004280081F480110134013D4EE77FEA645C18BF16 -:100438007FEA655C29D094EA050F08BF90EA020FAD -:1004480005D054EA000C04BF1946104630BD91EAA5 -:10045800030F1EBF0021002030BD5FEA545C05D1A8 -:100468004000494128BF41F0004130BD14F58004E7 -:100478003CBF01F5801130BD01F0004545F0FE415B -:1004880041F470014FF0000030BD7FEA645C1ABF90 -:10049800194610467FEA655C1CBF0B46024650EAC7 -:1004A800013406BF52EA033591EA030F41F40021F3 -:1004B80030BD00BF90F0000F04BF0021704730B579 -:1004C8004FF4806404F132044FF000054FF000014E -:1004D80050E700BF90F0000F04BF0021704730B50F -:1004E8004FF4806404F1320410F0004548BF4042E4 -:1004F8004FF000013EE700BF42004FEAE2014FEA39 -:1005080031014FEA02701FBF12F07F4393F07F4F13 -:1005180081F06051704732F07F4208BF704793F016 -:100528007F4F04BF41F40021704730B54FF4607429 -:1005380001F0004521F000411CE700BF50EA01022C -:1005480008BF704730B54FF000050AE050EA0102D5 -:1005580008BF704730B511F0004502D5404261EB45 -:1005680041014FF4806404F132045FEA915C3FF486 -:10057800D8AE4FF003025FEADC0C18BF03325FEA23 -:10058800DC0C18BF033202EBDC02C2F1200300FAD4 -:1005980003FC20FA02F001FA03FE40EA0E0021FAF9 -:1005A80002F11444BDE600BF70B54FF0FF0C4CF4E7 -:1005B800E06C1CEA11541DBF1CEA135594EA0C0F99 -:1005C80095EA0C0F00F0DEF82C4481EA030621EAD4 -:1005D8004C5123EA4C5350EA013518BF52EA03350F -:1005E80041F4801143F4801338D0A0FB02CE4FF0C1 -:1005F8000005E1FB02E506F00042E0FB03E54FF0F1 -:100608000006E1FB03569CF0000F18BF4EF0010EE8 -:10061800A4F1FF04B6F5007F64F5407404D25FEAE4 -:100628004E0E6D4146EB060642EAC62141EA555197 -:100638004FEAC52040EA5E504FEACE2EB4F1FD0CD9 -:1006480088BFBCF5E06F1ED8BEF1004F08BF5FEA57 -:10065800500E50F1000041EB045170BD06F0004609 -:1006680046EA010140EA020081EA0301B4EB5C04B6 -:10067800C2BFD4EB0C0541EA045170BD41F48011AE -:100688004FF0000E013C00F3AB8014F1360FDEBFD3 -:10069800002001F0004170BDC4F10004203C35DAAF -:1006A8000C341BDC04F11404C4F1200500FA05F332 -:1006B80020FA04F001FA05F240EA020001F00042D3 -:1006C80021F0004110EBD37021FA04F642EB060149 -:1006D8005EEA430E08BF20EAD37070BDC4F10C0473 -:1006E800C4F1200500FA04F320FA05F001FA04F237 -:1006F80040EA020001F0004110EBD37041F1000123 -:100708005EEA430E08BF20EAD37070BDC4F120052D -:1007180000FA05F24EEA020E20FA04F301FA05F295 -:1007280043EA020321FA04F001F0004121FA04F23D -:1007380020EA020000EBD3705EEA430E08BF20EA0D -:10074800D37070BD94F0000F0FD101F00046400047 -:1007580041EB010111F4801F08BF013CF7D041EAC9 -:10076800060195F0000F18BF704703F000465200CD -:1007780043EB030313F4801F08BF013DF7D043EA9E -:100788000603704794EA0C0F0CEA135518BF95EA54 -:100798000C0F0CD050EA410618BF52EA4306D1D1DB -:1007A80081EA030101F000414FF0000070BD50EAFA -:1007B800410606BF1046194652EA430619D094EA84 -:1007C8000C0F02D150EA013613D195EA0C0F05D16E -:1007D80052EA03361CBF104619460AD181EA0301C2 -:1007E80001F0004141F0FE4141F470014FF000007A -:1007F80070BD41F0FE4141F4780170BD70B54FF015 -:10080800FF0C4CF4E06C1CEA11541DBF1CEA135594 -:1008180094EA0C0F95EA0C0F00F0A7F8A4EB050476 -:1008280081EA030E52EA03354FEA013100F088806D -:100838004FEA03334FF0805545EA131343EA126336 -:100848004FEA022245EA111545EA10654FEA0026EB -:100858000EF000419D4208BF964244F1FD0404F5A4 -:10086800407402D25B084FEA3202B61A65EB030500 -:100878005B084FEA32024FF480104FF4002CB6EBBD -:10088800020E75EB030E22BFB61A754640EA0C003D -:100898005B084FEA3202B6EB020E75EB030E22BF7D -:1008A800B61A754640EA5C005B084FEA3202B6EBBE -:1008B800020E75EB030E22BFB61A754640EA9C007D -:1008C8005B084FEA3202B6EB020E75EB030E22BF4D -:1008D800B61A754640EADC0055EA060E18D04FEA0B -:1008E800051545EA16754FEA06164FEAC30343EAAB -:1008F80052734FEAC2025FEA1C1CC0D111F4801F78 -:100908000BD141EA00014FF000004FF0004CB6E770 -:1009180011F4801F04BF01430020B4F1FD0C88BF0F -:10092800BCF5E06F3FF6AFAEB5EB030C04BFB6EB1A -:10093800020C5FEA500C50F1000041EB045170BD0D -:100948000EF0004E4EEA113114EB5C04C2BFD4EB3A -:100958000C0541EA045170BD41F480114FF0000EBE -:10096800013C90E645EA060E8DE60CEA135594EA3A -:100978000C0F08BF95EA0C0F3FF43BAF94EA0C0F3D -:100988000AD150EA01347FF434AF95EA0C0F7FF4B2 -:1009980025AF104619462CE795EA0C0F06D152EA06 -:1009A80003353FF4FDAE1046194622E750EA4106EA -:1009B80018BF52EA43067FF4C5AE50EA41047FF4FB -:1009C8000DAF52EA43057FF4EBAE12E74FF0FF3C60 -:1009D80006E000BF4FF0010C02E000BF4FF0010C31 -:1009E8004DF804CD4FEA410C7FEA6C5C4FEA430CAA -:1009F80018BF7FEA6C5C1BD001B050EA410C0CBFF9 -:100A080052EA430C91EA030F02BF90EA020F00205A -:100A1800704710F1000F91EA030F58BF994208BFC1 -:100A280090422CBFD8176FEAE37040F0010070477E -:100A38004FEA410C7FEA6C5C02D150EA013C07D1D5 -:100A48004FEA430C7FEA6C5CD6D152EA033CD3D020 -:100A58005DF8040B704700BF8446104662468C461A -:100A68001946634600E000BF01B5FFF7B7FF00284D -:100A780048BF10F1000F01BD4DF808EDFFF7F4FF76 -:100A88000CBF012000205DF808FB00BF4DF808ED01 -:100A9800FFF7EAFF34BF012000205DF808FB00BF24 -:100AA8004DF808EDFFF7E0FF94BF012000205DF846 -:100AB80008FB00BF4DF808EDFFF7CEFF94BF0120FB -:100AC80000205DF808FB00BF4DF808EDFFF7C4FFF4 -:100AD80034BF012000205DF808FB00BF4FEA410247 -:100AE80012F5001215D211D56FF47873B3EB625278 -:100AF80012D94FEAC12343F0004343EA505311F09F -:100B0800004F23FA02F018BF404270474FF0000030 -:100B1800704750EA013005D111F0004008BF6FF06E -:100B2800004070474FF00000704700BF4FEA410295 -:100B3800B2F1E04324BFB3F5001CDCF1FE5C0DD933 -:100B480001F0004C4FEAC0024CEA5070B2F1004F7D -:100B580040EB830008BF20F00100704711F0804F80 -:100B680021D113F13872BCBF01F00040704741F445 -:100B780080114FEA5252C2F11802C2F1200C10FA49 -:100B88000CF320FA02F018BF40F001004FEAC1232D -:100B98004FEAD32303FA0CFC40EA0C0023FA02F3D1 -:100BA8004FEA4303CCE77FEA625307D150EA0133A7 -:100BB8001EBF4FF0FE4040F44000704701F0004077 -:100BC80040F0FE4040F40000704700BF80F0004055 -:100BD80002E000BF81F0004142001FBF5FEA41030D -:100BE80092EA030F7FEA226C7FEA236C6AD04FEA0D -:100BF8001262D2EB1363C1BFD21841404840414052 -:100C0800B8BF5B42192B88BF704710F0004F40F403 -:100C1800000020F07F4018BF404211F0004F41F41F -:100C2800000121F07F4118BF494292EA030F3FD0EB -:100C3800A2F1010241FA03FC10EB0C00C3F12003FE -:100C480001FA03F100F0004302D5494260EB40008D -:100C5800B0F5000F13D3B0F1807F06D340084FEAF8 -:100C6800310102F10102FE2A51D2B1F1004F40EBED -:100C7800C25008BF20F0010040EA03007047490055 -:100C880040EB000010F4000FA2F10102EDD1B0FA20 -:100C980080FCACF1080CB2EB0C0200FA0CF0AABF15 -:100CA80000EBC25052421843BCBFD04018437047B3 -:100CB80092F0000F81F4000106BF80F400000132B9 -:100CC800013BB5E74FEA41037FEA226C18BF7FEA90 -:100CD800236C21D092EA030F04D092F0000F08BFD2 -:100CE8000846704790EA010F1CBF0020704712F0B9 -:100CF8007F4F04D1400028BF40F00040704712F1F8 -:100D080000723CBF00F50000704700F0004343F05C -:100D1800FE4040F4000070477FEA226216BF084692 -:100D28007FEA23630146420206BF5FEA412390EA55 -:100D3800010F40F4800070474FF0000304E000BF4B -:100D480010F0004348BF40425FEA000C08BF7047FC -:100D580043F0964301464FF000001CE050EA0102C0 -:100D680008BF70474FF000030AE000BF50EA0102D5 -:100D780008BF704711F0004302D5404261EB4101C2 -:100D88005FEA010C02BF84460146002043F0B643E7 -:100D980008BFA3F18053A3F50003BCFA8CF2083A0C -:100DA800A3EBC25310DB01FA02FC634400FA02FC15 -:100DB800C2F12002BCF1004F20FA02F243EB02001C -:100DC80008BF20F00100704702F1200201FA02FC7E -:100DD800C2F1200250EA4C0021FA02F243EB020071 -:100DE80008BF20EADC7070474FF0FF0C1CEAD052B5 -:100DF8001EBF1CEAD15392EA0C0F93EA0C0F6FD076 -:100E08001A4480EA010C400218BF5FEA41211ED053 -:100E18004FF0006343EA501043EA5111A0FB01313F -:100E28000CF00040B1F5000F3EBF490041EAD37114 -:100E38005B0040EA010062F17F02FD2A1DD8B3F190 -:100E4800004F40EBC25008BF20F00100704790F0FF -:100E5800000F0CF0004C08BF49024CEA502040EA51 -:100E680051207F3AC2BFD2F1FF0340EAC250704717 -:100E780040F400004FF00003013A5DDC12F1190F55 -:100E8800DCBF00F000407047C2F10002410021FAC7 -:100E980002F1C2F1200200FA02FC5FEA310040F1DF -:100EA800000053EA4C0308BF20EADC70704792F058 -:100EB800000F00F0004C02BF400010F4000F013A90 -:100EC800F9D040EA0C0093F0000F01F0004C02BF8B -:100ED800490011F4000F013BF9D041EA0C018FE7FA -:100EE8000CEAD15392EA0C0F18BF93EA0C0F0AD000 -:100EF80030F0004C18BF31F0004CD8D180EA010026 -:100F080000F00040704790F0000F17BF90F0004FBE -:100F1800084691F0000F91F0004F14D092EA0C0FA0 -:100F280001D142020FD193EA0C0F03D14B0218BF33 -:100F3800084608D180EA010000F0004040F0FE4079 -:100F480040F40000704740F0FE4040F44000704715 -:100F58004FF0FF0C1CEAD0521EBF1CEAD15392EA94 -:100F68000C0F93EA0C0F69D0A2EB030280EA010C84 -:100F780049024FEA402037D04FF0805343EA11111D -:100F880043EA10130CF000408B4238BF5B0042F17B -:100F98007D024FF4000C8B4224BF5B1A40EA0C0020 -:100FA800B3EB510F24BFA3EB510340EA5C00B3EB52 -:100FB800910F24BFA3EB910340EA9C00B3EBD10F40 -:100FC80024BFA3EBD10340EADC001B0118BF5FEA92 -:100FD8001C1CE0D1FD2A3FF650AF8B4240EBC250BB -:100FE80008BF20F0010070470CF0004C4CEA50207C -:100FF8007F32C2BFD2F1FF0340EAC250704740F4CB -:1010080000004FF00003013A37E792F0000F00F0BC -:10101800004C02BF400010F4000F013AF9D040EA3A -:101028000C0093F0000F01F0004C02BF490011F4CE -:10103800000F013BF9D041EA0C0195E70CEAD153C6 -:1010480092EA0C0F08D142027FF47DAF93EA0C0FAD -:101058007FF470AF084676E793EA0C0F04D14B0291 -:101068003FF44CAF08466EE730F0004C18BF31F043 -:10107800004CCAD130F000427FF45CAF31F000433D -:101088007FF43CAF5FE700BF4FF0FF3C06E000BFD6 -:101098004FF0010C02E000BF4FF0010C4DF804CDF9 -:1010A8004FEA40024FEA41037FEA226C18BF7FEA09 -:1010B800236C11D001B052EA530C18BF90EA010F0B -:1010C80058BFB2EB030088BFC81738BF6FEAE1709A -:1010D80018BF40F0010070477FEA226C02D15FEA36 -:1010E800402C05D17FEA236CE4D15FEA412CE1D0A2 -:1010F8005DF8040B704700BF844608466146FFE769 -:101108000FB5FFF7C9FF002848BF10F1000F0FBD4A -:101118004DF808EDFFF7F4FF0CBF012000205DF843 -:1011280008FB00BF4DF808EDFFF7EAFF34BF0120C8 -:1011380000205DF808FB00BF4DF808EDFFF7E0FF61 -:1011480094BF012000205DF808FB00BF4DF808EDB2 -:10115800FFF7D2FF94BF012000205DF808FB00BF15 -:101168004DF808EDFFF7C8FF34BF012000205DF8F7 -:1011780008FB00BF4FEA4002B2F1FE4F0FD34FF019 -:101188009E03B3EB12620DD94FEA002343F00043EC -:1011980010F0004F23FA02F018BF404270474FF09A -:1011A8000000704712F1610F01D1420205D110F021 -:1011B800004008BF6FF0004070474FF000007047D4 -:1011C80082B0084B1B68084AA2FB03235B0A00FB9A -:1011D80003F0019000BF019B5A1E0192002BF9D128 -:1011E80002B0704700000020D34D621070B582B085 -:1011F8000446036813F0010F2CD0AB4B5B6803F077 -:101208000C03042B1DD0A84B5B6803F00C03082BC0 -:1012180012D06368B3F5803F41D0002B55D103F15C -:10122800804303F504331A6822F480321A601A687E -:1012380022F480221A6037E09B4B5B6813F4803FEE -:10124800E7D0994B1B6813F4003F03D06368002B69 -:1012580000F0AE81236813F0020F76D0924B5B68E2 -:1012680013F00C0F5FD0904B5B6803F00C03082B56 -:1012780054D02369002B00F08A808C4B01221A601D -:1012880000F0F8FF0546884B1B6813F0020F75D174 -:1012980000F0F0FF401B0228F5D903208BE1824AB9 -:1012A800136843F480331360636843B300F0E2FFCC -:1012B80005467D4B1B6813F4003FCBD100F0DAFFE5 -:1012C800401B6428F5D9032075E1B3F5A02F09D098 -:1012D800754B1A6822F480321A601A6822F4802248 -:1012E8001A60E1E703F18043A3F53C331A6842F43E -:1012F80080221A601A6842F480321A60D4E700F03B -:10130800B9FF0546684B1B6813F4003FA2D000F0F4 -:10131800B1FF401B6428F5D903204CE1624B5B68A0 -:1013280013F4803FA5D1604B1B6813F0020F04D063 -:101338002369012B01D001203DE15B4A136823F0AA -:10134800F803616943EAC1031360236813F0080FC7 -:1013580032D0A369002B5BD0554B01221A6000F0F4 -:1013680089FF0546504B5B6A13F0020F21D100F04C -:1013780081FF401B0228F5D903201CE14A4A136863 -:1013880023F0F803616943EAC1031360DDE7474BC3 -:1013980000221A6000F06EFF0546434B1B6813F0ED -:1013A800020FD2D000F066FF401B0228F5D90320B7 -:1013B80001E10120FFF704FF236813F0040F00F098 -:1013C8009780394BDB6913F0805F33D1364BDA698C -:1013D80042F08052DA61DB6903F080530193019B8C -:1013E8000125344B1B6813F4807F25D0E368012B5B -:1013F80036D0002B4CD103F1804303F504331A6A2D -:1014080022F001021A621A6A22F004021A622CE01F -:10141800274B00221A6000F02DFF0546224B5B6A1D -:1014280013F0020FC8D000F025FF401B0228F5D9A1 -:101438000320C0E00025D4E71E4A136843F48073F4 -:10144800136000F017FF06461A4B1B6813F4807FE1 -:10145800CCD100F00FFF801B6428F5D90320AAE047 -:10146800114A136A43F001031362E36873B300F08F -:1014780001FF06460C4B1B6A13F0020F37D100F030 -:10148800F9FE801B41F288339842F3D9032092E099 -:10149800052B11D0044B1A6A22F001021A621A6A4B -:1014A80022F004021A62E0E7001002400000424203 -:1014B8008004424200700040414B1A6A42F0040224 -:1014C8001A621A6A42F001021A62CEE700F0D2FEEE -:1014D80006463B4B1B6A13F0020F08D000F0CAFE09 -:1014E800801B41F288339842F3D9032063E0E5B9C1 -:1014F800E369002B5ED0324A526802F00C02082AD7 -:101508005BD0022B17D02F4B00221A6000F0B2FEDE -:1015180004462B4B1B6813F0007F47D000F0AAFE4F -:10152800001B0228F5D9032045E0254AD36923F09A -:101538008053D361DCE7234B00221A6000F09AFE47 -:1015480005461F4B1B6813F0007F06D000F092FE83 -:10155800401B0228F5D903202DE0236AB3F5803F0C -:101568001AD017494B6823F47413226A606A02433D -:1015780013434B60134B01221A6000F07BFE0446B4 -:101588000F4B1B6813F0007F0ED100F073FE001B99 -:101598000228F5D903200EE0094A536823F40033E2 -:1015A800A1680B435360DCE7002004E0002002E060 -:1015B800012000E0002002B070BD0120FBE700BF61 -:1015C800001002406000424210B487B0164C94E804 -:1015D8000F000DF1180C0CE90F00238AADF8043048 -:1015E800124B5B6803F00C02082A1AD1C3F383423A -:1015F800624412F8100C13F4803F05D10C4B03FB26 -:1016080000F007B010BC7047084B5B68C3F3404359 -:10161800634413F8142C074BB3FBF2F300FB03F0FD -:10162800EFE70448EDE700BF8846000800100240D5 -:1016380000093D0000127A00594B1B6803F00703AC -:101648008B420CD2564A136823F007030B431360EE -:10165800136803F007038B4201D00120704770B56F -:10166800036813F0020F06D04E4A536823F0F003C4 -:101678008468234353600C460546036813F0010F42 -:1016880052D04368012B23D0022B28D0454A126838 -:1016980012F0020F00F0828042494A6822F00302E9 -:1016A80013434B6000F0E6FD06466B68012B1DD026 -:1016B800022B2AD03B4B5B6813F00C0F34D000F0A0 -:1016C800D9FD801B41F288339842F3D9032064E0A6 -:1016D800344A126812F4003FDED101205DE0314A3D -:1016E800126812F0007FD7D1012056E02D4B5B68BD -:1016F80003F00C03042B17D000F0BCFD801B41F253 -:1017080088339842F2D9032047E0264B5B6803F000 -:101718000C03082B08D000F0ADFD801B41F2883384 -:101728009842F2D9032038E01D4B1B6803F00703E9 -:10173800A3420CD91A4A136823F007032343136002 -:10174800136803F00703A34201D0012025E02B68AA -:1017580013F0040F06D0134A536823F4E063E968D2 -:101768000B4353602B6813F0080F07D00D4A5368DA -:1017780023F46053296943EAC1035360FFF724FF48 -:10178800084B5B68C3F30313074AD35CD840074B85 -:101798001860002000F03EFD002070BD0120FCE72D -:1017A80000200240001002409C4600080000002073 -:1017B800014B1868704700BF0000002008B5FFF70C -:1017C800F7FF044B5B68C3F30223034AD35CD8409A -:1017D80008BD00BF00100240AC46000808B5FFF77E -:1017E800E7FF044B5B68C3F3C223034AD35CD840CA -:1017F80008BD00BF00100240AC46000830B4036AC0 -:1018080023F001030362056A4268846924F07304C3 -:101818000B681C4325F002058B682B43104DA8422A -:1018280003D005F50065A84205D123F00803CD686B -:101838002B4323F004030A4DA84203D005F50065A5 -:10184800A84205D122F440724D6915438A692A439A -:10185800426084614A684263036230BC704700BFDB -:10186800002C014030B4036A23F480730362036AD6 -:101878004268C46924F073040D682C4323F4007390 -:101888008D6843EA0523124DA84203D005F500658B -:10189800A84206D123F40063CD6843EA052323F464 -:1018A80080630B4DA84203D005F50065A84207D117 -:1018B80022F440524D6942EA05128D6942EA051246 -:1018C8004260C4614A68C263036230BC704700BFAB -:1018D800002C014030B4036A23F480530362036A86 -:1018E8004468C26922F4E6420D6842EA052223F4FC -:1018F80000538D6843EA0533094DA84203D005F526 -:101908000065A84204D124F480444D6944EA851452 -:101918004460C2614A680264036230BC704700BF19 -:10192800002C014010B4036A046A24F00104046224 -:10193800846924F0F00444EA021223F00A030B43FA -:101948008261036210BC704710B4036A23F010036D -:1019580003628469036A24F4704444EA023223F07F -:10196800A00343EA01138261036210BC704710B4FC -:10197800846824F47F4442EA03230B4323438360AF -:1019880010BC704710B50468A26822F070024B685A -:10199800134323F007030A681343A3604B68502BD3 -:1019A8001ED00AD9602B21D0702B05D10B698A680B -:1019B800C9680068FFF7DBFF10BD402BFCD1036846 -:1019C8001C6A1A6A22F001021A620268936923F0FB -:1019D800F003096943EA0113936103681C62EBE7AA -:1019E8000A6989680068FFF79DFFE5E70A69896861 -:1019F8000068FFF7A9FFDFE7704738B590F83C307B -:101A0800012B18D00446012580F83C50022380F8A9 -:101A18003D30FFF7B7FF2268D36823F04003D36057 -:101A28002268D36823F48043D36084F83D500020B3 -:101A380084F83C0038BD0220FCE700000368244A13 -:101A4800904212D002F5006290420ED0B0F1804F61 -:101A58000BD0A2F59832904207D002F580629042EE -:101A680003D002F58062904203D123F070034A68E4 -:101A78001343174A904212D002F5006290420ED0EA -:101A8800B0F1804F0BD0A2F59832904207D002F502 -:101A98008062904203D002F58062904203D123F421 -:101AA8004073CA68134323F080034A6913430360F1 -:101AB8008B68C3620B688362054B984203D003F5B9 -:101AC8000063984201D10B690363012343617047A6 -:101AD800002C0140A8B110B5044690F83D305BB128 -:101AE800022384F83D30211D2068FFF7A7FF01235A -:101AF80084F83D30002010BD80F83C30FFF77CFFB3 -:101B0800EEE701207047000030B4036A23F01003A9 -:101B18000362036A4468826922F4E6420D6842EA75 -:101B2800052223F020038D6843EA0513114DA842CE -:101B380003D005F50065A84206D123F08003CD68DF -:101B480043EA051323F040030A4DA84203D005F5E4 -:101B58000065A84207D124F440644D6944EA85042D -:101B68008D6944EA8504446082614A68826303623D -:101B780030BC7047002C014038B590F83C30012B40 -:101B880066D00D460446012380F83C30022380F8D5 -:101B98003D300C2A1AD8DFE802F007191919201964 -:101BA80019193419191947000068FFF727FE226828 -:101BB800936943F0080393612268936923F004034F -:101BC80093612268936929690B439361012384F81F -:101BD8003D30002084F83C0038BD0068FFF794FFD2 -:101BE8002268936943F4006393612268936923F43C -:101BF8008063936122689369296943EA01239361A9 -:101C0800E4E70068FFF72EFE2268D36943F0080373 -:101C1800D3612268D36923F00403D3612268D369AE -:101C280029690B43D361D1E70068FFF753FE2268A7 -:101C3800D36943F40063D3612268D36923F48063D2 -:101C4800D3612268D369296943EA0123D361BDE7D7 -:101C58000220C1E710B4012303FA01F4036A23EA5E -:101C680004030362036A8A401343036210BC70478B -:101C780010B5044601220068FFF7ECFF2368094A03 -:101C8800934203D002F50062934203D15A6C42F4A6 -:101C980000425A642268136843F00103136000206D -:101CA80010BD00BF002C014010B4042303FA01F456 -:101CB800036A23EA04030362036A8A401343036244 -:101CC80010BC704710B5044604220068FFF7ECFF0B -:101CD8002268536C43F4004353642268136843F04A -:101CE80001031360002010BD90F83C30012B25D073 -:101CF800012380F83C30CB6823F440738A6813438F -:101D080023F480634A68134323F400630A68134387 -:101D180023F480530A69134323F400534A69134395 -:101D280023F480438A69134323F40043134302686E -:101D38005364002380F83C301846704702207047EF -:101D480090F83C30012B22D030B4012280F83C209E -:101D5800022380F83D300468636823F070036360F1 -:101D6800046863680D682B4363600468A36823F004 -:101D78008003A3600468A36849680B43A36080F8E4 -:101D88003D20002380F83C30184630BC70470220C4 -:101D980070470000034690F82420012A20D0012231 -:101DA80080F824200268906810F0010F07D10D48D0 -:101DB800806810F0010F02D10B48824208D09A6A5D -:101DC80042F020029A620120002283F82420704702 -:101DD800506820F470200968014351600020F3E73F -:101DE800022070470028014000240140074AD368B8 -:101DF80023F4E0631B041B0C000200F4E0601843AA -:101E080040F0BF6040F40030D060704700ED00E063 -:101E180030B4174BDB68C3F30223C3F10704042C67 -:101E280028BF04241D1D062D18D9033B4FF0FF358C -:101E380005FA04F421EA0401994005FA03F322EAB9 -:101E48000303194300280BDB0901C9B200F1604004 -:101E580000F5614080F8001330BC70470023E5E7C7 -:101E680000F00F000901C9B2024B1954F4E700BF92 -:101E780000ED00E014ED00E000F01F02400901232E -:101E88009340024A42F82030704700BF00E100E06A -:101E98000138B0F1807F0AD2064B5860064AF0211B -:101EA80082F823100020986007221A6070470120EA -:101EB800704700BF10E000E000ED00E0042805D006 -:101EC800054A136823F0040313607047024A136835 -:101ED80043F004031360704710E000E0704708B552 -:101EE800FFF7FCFF08BD0000F0B482B000263546BD -:101EF800ABE0002C63D0012C00D1CE68FF2B72D848 -:101F08008446FF2B72D8AC00DCF800200F27A740CE -:101F180022EA070206FA04F42243CCF800204A68B1 -:101F280012F0805F00F09080654A946944F00104E3 -:101F38009461926902F001020192019AAC08A71C0F -:101F4800604A52F827C005F0030297000F22BA40F2 -:101F58002CEA020C5C4A90424ED002F58062904214 -:101F680000F08B8002F58062904200F0888002F5D4 -:101F78008062904200F0858002F58062904200F015 -:101F8800828002F58062904234D0062235E04F4FBD -:101F9800BC4214D00BD94E4FBC4210D007F5803745 -:101FA800BC420CD0A7F58017BC42A7D107E0A7F523 -:101FB8008017BC4203D007F58037BC429ED18C689D -:101FC8007CB1012C08D04261082697E7CE68083614 -:101FD80094E7CE680C3691E7026108268EE7002662 -:101FE8008CE704268AE700F1040C8AE7A5F10804C7 -:101FF800A40089E7052200E00022BA4042EA0C0268 -:102008000234304F47F824204A6812F4803F3CD00D -:10201800304C22681A4322604A6812F4003F3AD0D2 -:102028002C4C62681A4362604A6812F4801F38D0E8 -:10203800284CA2681A43A2604A6812F4001F36D0DE -:10204800244CE2681343E36001350F2D35D8012293 -:10205800AA400B6813409A42F6D14C68122CB8D0AB -:1020680095D8022CB2D07FF644AF032CB7D0112CF0 -:102078007FF444AFCE68043640E70122BDE7022270 -:10208800BBE70322B9E70422B7E7124C226822EA29 -:1020980003022260C0E70F4C626822EA0302626012 -:1020A800C2E70C4CA26822EA0302A260C4E7094C0A -:1020B800E26822EA0303E360C6E702B0F0BC7047B7 -:1020C80000100240000001400008014000002110FB -:1020D80000003110000401408368194201D100203A -:1020E80070470120704712B9090401617047016106 -:1020F8007047C3685940C1607047000070B582B02E -:102108000446036813F0010F34D03E4BDB6913F02B -:10211800805F48D13B4BDA6942F08052DA61DB6973 -:1021280003F080530193019B0125374B1B6813F47F -:10213800807F3AD0334B1B6A13F4407311D0626826 -:1021480002F440729A420CD02E4A136A23F440706B -:102158002E4901260E6000260E60106213F0010F52 -:1021680037D1284A136A23F4407361680B4313621A -:10217800002D3FD1236813F0020F06D0214A53687F -:1021880023F44043A1680B435360236813F0100FF6 -:1021980035D01C4A536823F4800361690B435360AC -:1021A800002002B070BD0025BFE7174A136843F44A -:1021B8008073136000F05EF80646134B1B6813F437 -:1021C800807FB7D100F056F8801B6428F5D903202A -:1021D800E7E700F04FF806460A4B1B6A13F0020FB8 -:1021E800BFD100F047F8801B41F288339842F3D9F9 -:1021F8000320D6E7D36923F08053D361BAE70020E0 -:10220800CFE700BF00100240007000404004424287 -:102218007047000010B50446074B1868074BA3FB2E -:1022280000308009FFF734FE002221464FF0FF30CE -:10223800FFF7EEFD002010BD00000020D34D621016 -:1022480008B5074A136843F0100313600320FFF72B -:10225800CDFD0020FFF7DEFFFFF7DAFF002008BD05 -:1022680000200240024A136801331360704700BF20 -:10227800E0000020014B1868704700BFE000002014 -:1022880030B583B00190FFF7F5FF0546019CB4F126 -:10229800FF3F00D00134FFF7EDFF401BA042FAD307 -:1022A80003B030BD7047000030B482B00023019302 -:1022B80090F82430012B00F08B800246012380F82F -:1022C80024304B68062B29D80568686B03EB830319 -:1022D800053B1F249C4020EA04000C6804FA03F321 -:1022E80003436B630B68092B38D91568E86803EB5F -:1022F80043031E3B07249C4020EA04008C6804FA30 -:1023080003F30343EB600B68103B012B34D9002027 -:10231800002382F8243002B030BC70470C2B0ED852 -:102328000568286B03EB8303233B1F249C4020EAAA -:1023380004000C6804FA03F303432B63D2E705682F -:10234800E86A03EB8303413B1F249C4020EA040016 -:102358000C6804FA03F30343EB62C3E715682869C2 -:1023680003EB430307249C4020EA04008C6804FA2A -:1023780003F303432B61C6E713681648834205D06D -:10238800936A43F0200393620120C1E7986810F430 -:10239800000F1BD1986840F4000098600B68102B60 -:1023A80001D00020B4E70C4B1B680C49A1FB0313B8 -:1023B8009B0C03EB83035900019102E0019B013B55 -:1023C8000193019B002BF9D10020A1E700209FE792 -:1023D8000220A0E7002401400000002083DE1B4308 -:1023E80030B583B00023019303689A6812F0010F97 -:1023F8002ED19A6842F001029A60174B1B68174A5F -:10240800A2FB03239B0C019302E0019B013B019378 -:10241800019B002BF9D10446FFF72CFF05462368E2 -:102428009B6813F0010F11D1FFF724FF401B02280E -:10243800F5D9A36A43F01003A362E36A43F00103EA -:10244800E362002384F82430012002E0002000E049 -:10245800002003B030BD00BF0000002083DE1B4316 -:1024680090F82430012B6AD010B50446012380F877 -:102478002430FFF7B5FF024600285BD1A36A23F496 -:10248800407323F0010343F48073A36223682D494A -:102498008B4227D0A16A21F48011A162596811F4F6 -:1024A800806F05D0A16A21F4405141F48051A162A6 -:1024B800A16A11F4805F2BD0E16A21F00601E16284 -:1024C800002184F824106FF00201196023689968CC -:1024D80001F46021B1F5602F1DD0996841F4801195 -:1024E80099602AE0A1F58061496811F4702FD1D074 -:1024F800A16A41F48011A1621349496811F4806FFF -:10250800D6D0A16A21F4405141F48051A162CFE7AD -:102518000021E162D4E70B498B4204D0996841F469 -:10252800A001996009E0A1F58061496811F4702F54 -:10253800D3D1F3E7002384F82430104610BD0222DB -:1025480010467047002801400024014038B5036850 -:102558009A6812F0010F01D1002038BD04469A682C -:1025680022F001029A60FFF785FE054623689B6802 -:1025780013F0010F0ED0FFF77DFE401B0228F5D99E -:10258800A36A43F01003A362E36A43F00103E36222 -:102598000120E2E70020E0E7002800F08A8070B51B -:1025A8000446836A002B36D02046FFF7CFFFA36A84 -:1025B80013F0100377D1002875D1A26A22F488524B -:1025C80022F0020242F00202A262626825683A49D9 -:1025D8008D4226D0E1690A43E66842EA4602A168CC -:1025E800B1F5807F27D0012922D06169012925D042 -:1025F800696821F469410B436B6021688D682F4B32 -:102608002B4013438B60A368B3F5807F27D0012B41 -:1026180025D0002126E0C36280F82430FFF742FE6F -:10262800C2E7E169B1F5402FD5D14FF40021D2E7D7 -:102638004FF48073D9E74FF48073D6E736B9A169B0 -:10264800013943EA413343F40063D1E7A16A41F019 -:102658002001A162E16A41F00101E162C8E7236952 -:10266800013B19052568EB6A23F470030B43EB6201 -:1026780023689968124B0B409A420BD0A36A23F047 -:10268800120343F01003A362E36A43F00103E36219 -:1026980001200DE00023E362A36A23F0030343F063 -:1026A8000103A36204E0A36A43F01003A3620120BC -:1026B80070BD0120704700BF003C0140FDF7E1FFFD -:1026C800FE0E1FFF2DE9F84305460268136923F43F -:1026D8004053C1680B43136183680269134342691D -:1026E80013430168CA6822F4B05222F00C02134363 -:1026F800CB600268536923F4407381690B435361CB -:102708000268594B9A4257D0FFF758F800EB8000FF -:1027180000EB80006C68A400B0FBF4F4534FA7FBF7 -:10272800043464092601FFF749F800EB800000EB48 -:1027380080006C68A400B0FBF4F9FFF73FF800EBE9 -:10274800800000EB80006C68A400B0FBF4F4A7FBE9 -:10275800043464094FF0640808FB149424013234EB -:10276800A7FB0434640904F0F0043444FFF726F8A6 -:1027780000EB800000EB80006E68B600B0FBF6F658 -:10278800FFF71CF800EB800000EB80006B689B00F3 -:10279800B0FBF3F0A7FB0030400908FB10684FEAD4 -:1027A800081808F13208A7FB0837C7F343172B6846 -:1027B80027449F60BDE8F883FFF710F800EB80001E -:1027C80000EB80006C68A400B0FBF4F4274FA7FB73 -:1027D800043464092601FFF701F800EB800000EBE0 -:1027E80080006C68A400B0FBF4F9FEF7F7FF00EB7B -:1027F800800000EB80006C68A400B0FBF4F4A7FB39 -:10280800043464094FF0640808FB1494240132343A -:10281800A7FB0434640904F0F0043444FEF7DEFF37 -:1028280000EB800000EB80006E68B600B0FBF6F6A7 -:10283800FEF7D4FF00EB800000EB80006B689B0084 -:10284800B0FBF3F0A7FB0030400908FB10684FEA23 -:10285800081808F13208A7FB0837C7F343172B6895 -:1028680027449F60A6E700BF003801401F85EB5151 -:10287800704758B310B5044690F839300BB3242389 -:1028880084F839302268D36823F40053D360204693 -:10289800FFF718FF2268136923F490431361226835 -:1028A800536923F02A0353612268D36843F4005321 -:1028B800D3600020E063202384F8393084F83A306C -:1028C80010BD80F83830FFF7D3FFD8E701207047F4 -:1028D8000F4B1A6842F001021A6059680D4A0A4003 -:1028E8005A601A6822F0847222F480321A601A68D8 -:1028F80022F480221A605A6822F4FE025A604FF4C9 -:102908001F029A60044B4FF000629A60704700BF44 -:10291800001002400000FFF800ED00E030B597B06D -:102928001F4BDA6942F48022DA61DA6902F4802204 -:102938000092009A5A6942F001025A615B6903F0F9 -:1029480001030193019B174D06954FF4E13307935B -:102958000024089409940A9408230B930C940D946A -:1029680006A8FFF786FF6B6943F080036B614FF49D -:1029780080630293012304930223039303230593A3 -:1029880002A90948FFF7B0FA084B1C60084A9A6088 -:102998005C6090221A601C3B70225A6017B030BDF0 -:1029A8000010024000480040000C01401C0002409A -:1029B800044800402DE9F04F89B07B4B9A6942F0FA -:1029C80004029A619A6902F004020192019A9A69D2 -:1029D80042F008029A619A6902F008020292029A89 -:1029E8009A6942F010029A619B6903F010030393FD -:1029F800039B002305930693022707974FF0200AAD -:102A08000DEB0A0444F810AD21466848FFF76CFA4C -:102A18004023049321466548FFF766FA802504950C -:102A280021466248FFF760FA4FF480630493214619 -:102A38005F48FFF759FA4FF40063049321465C4856 -:102A4800FFF752FA4FF48056049621465848FFF78C -:102A58004BFA049621465748FFF746FA0497214651 -:102A68005448FFF741FA4FF00108CDF814804FF0B1 -:102A78000409CDF8109021464C48FFF735FA102686 -:102A8800049621464B48FFF72FFACDF810A02146AF -:102A98004848FFF729FA03230593CDF8108021460B -:102AA8004348FFF721FACDF8108021464148FFF747 -:102AB8001BFA4FF0080BCDF810B021463C48FFF741 -:102AC80013FA049721463A48FFF70EFA049621466E -:102AD8003748FFF709FACDF810A021463448FFF728 -:102AE80003FACDF8109021463148FFF7FDF9CDF8EB -:102AF80010B021462F48FFF7F7F9CDF8109021467E -:102B08002C48FFF7F1F905974023049321462848FC -:102B1800FFF7EAF9049521462548FFF7E5F94FF450 -:102B28008079CDF8109021462148FFF7DDF904950A -:102B380021462048FFF7D8F9CDF8108021461B48D8 -:102B4800FFF7D2F9049721461848FFF7CDF9CDF8D9 -:102B5800109021461748FFF7C7F94FF40073049304 -:102B680021461448FFF7C0F94FF4806304932146C7 -:102B78001048FFF7B9F94FF40053049321460B4866 -:102B8800FFF7B2F94FF48043049321460748FFF753 -:102B9800ABF94FF40043049321460448FFF7A4F926 -:102BA80009B0BDE8F08F00BF00100240000C0140E2 -:102BB80000100140000801402DE9F04F99B0754B15 -:102BC8009A6942F400629A619A6902F40062019279 -:102BD800019A9A6942F400529A619B6903F400537E -:102BE8000293029B6C4EDFF8B891C6F8009000245F -:102BF80074604FF02008C6F808804FF4FA6BC6F8E6 -:102C08000CB034617461B4613046FEF763FF102381 -:102C18001693179416A93046FFF792F860230F937E -:102C28001094119408271297139414944FF4007376 -:102C3800159322460FA93046FEF79EFF04220FA9DE -:102C48003046FEF799FF3A460FA93046FEF794FF43 -:102C58004FF4006308934FF4806309930A94CDF806 -:102C68002C800C940D940E940DEB08013046FFF760 -:102C78003BF84A4DDFF82CA1C5F800A06C60C5F8F8 -:102C88000880C5F80CB02C616C61AC612846FEF771 -:102C980021FFCDF858808023179316A92846FFF7FF -:102CA8004FF8049418A9052341F8543D2846FEF727 -:102CB800A4FE60230F931094119412971394149404 -:102CC8004FF40073159322460FA92846FEF754FFC8 -:102CD80004220FA92846FEF74FFF3A460FA92846B7 -:102CE800FEF74AFF4FF4006308934FF4806309939B -:102CF8000A94CDF82C800C940D940E940DEB0801D9 -:102D08002846FEF7F1FFDAF8443023F40043CAF806 -:102D18004430D9F8443023F40043C9F844302146FC -:102D28002846FEF7A5FF04212846FEF7A1FF3946ED -:102D38002846FEF79DFF21462846FEF7C3FF0421DB -:102D48002846FEF7BFFF39462846FEF7BBFF214657 -:102D58003046FEF78DFF04213046FEF789FF3946DD -:102D68003046FEF785FF21463046FEF7ABFF0421CB -:102D78003046FEF7A7FF39463046FEF7A3FF2B681B -:102D880001221A633268136843F00103136019B013 -:102D9800BDE8F08F00100240AC0100203C03002089 -:102DA800002C0140003401402DE9F04186B0424E2C -:102DB800B36943F40073B361B36903F40073009318 -:102DC800009B3E4C3E4B23604FF48073A36000256C -:102DD800E56065614FF44023E36165604FF00508E5 -:102DE800C4F810802046FFF7D7FB364A536843F4EF -:102DF8008023536006A94FF4C02341F8043D2046C0 -:102E0800FEF7C8FF012304930E220292039302A93E -:102E18002046FFF749FA02950227039702A92046A0 -:102E2800FFF742FA04970B2702970323039302A99B -:102E38002046FFF739FA0C2302930423039302A9CF -:102E48002046FFF731FA0723049310230293CDF8A5 -:102E58000C8002A92046FFF727FA2268936843F4FA -:102E6800000343F480739360936843F00103936015 -:102E7800736943F001037361736903F001030193FC -:102E8800019B114B1D60C3F80480104A9A60104AD8 -:102E9800DA6040F6A2221A601A6842F001021A604B -:102EA8002A4629463846FEF7B3FF3846FEF7E4FFC0 -:102EB80006B0BDE8F08100BF001002407402002097 -:102EC8000024014000000140080002404C24014059 -:102ED800E8020020F0B585B0284B9A6942F4806278 -:102EE8009A619B6903F480630093009B244C254BF3 -:102EF80023604FF48073A3600023E36063614FF4A1 -:102F08006022E2616360052626612046FFF744FBE4 -:102F1800012303930F220192029301A92046FFF790 -:102F2800C3F90D2301930225029501A92046FFF755 -:102F3800BBF903950A2301930327029701A92046A9 -:102F4800FFF7B2F90195042302930DEB0301204624 -:102F5800FFF7AAF9072303930197029601A92046D0 -:102F6800FFF7A2F923689A6842F480729A609A6817 -:102F780042F001029A6005B0F0BD00BF00100240A7 -:102F880028010020002801400D4B1B681333262B15 -:102F980014D810B500240B4B1C700B4B1C7005E0AB -:102FA8000A4B1C706420FFF76BF90134072CF7DD1E -:102FB800002220210648FFF796F8FEE7704700BF79 -:102FC80094030020A8000020B4000020A4000020E2 -:102FD8000008014030B597B002250C9501231093E5 -:102FE800102311931395002414944FF46013159330 -:102FF8000CA8FEF7FBF80F230793089509944FF4E4 -:1030080080630A930B94294607A8FEF715FB0195E0 -:103018004FF44043039301A8FFF770F8FEF7C8FB8D -:10302800084BA3FB00308009FEF732FF0420FEF7AF -:1030380045FF224621464FF0FF30FEF7E9FE17B064 -:1030480030BD00BFD34D62102DE9F04F85B0FFF7BA -:10305800F7F8B34CA36943F00103A361A36903F034 -:1030680001030393039B0320FEF7C0FE00221146D1 -:103078006FF00B00FEF7CCFE002211466FF00A003D -:10308800FEF7C6FE002211466FF00900FEF7C0FEEB -:10309800002211466FF00400FEF7BAFE0022114626 -:1030A8006FF00300FEF7B4FE002211466FF0010036 -:1030B800FEF7AEFE002211464FF0FF30FEF7A8FEE5 -:1030C800FFF788FF636923F001036361FFF772FC70 -:1030D800FFF772FDFFF768FEFFF7FCFEFFF71EFC27 -:1030E800012220218F48FEF7FEFF8F48FFF7B8F92D -:1030F8008E48FFF7B5F9082405E08D4B1C70642055 -:10310800FFF7BEF8013C002CF7DA4FF0000A884BB5 -:1031180083F800A0012204218648FEF7E4FF864BCD -:10312800188AFDF709FE0190844B01221A70D346D4 -:103138004FE14FF47A7861E14FF47A7473E14FF418 -:103148007A7642464B4620462946FDF777F80446EC -:103158000D4600227A4BFDF7B7FC80B96AA3D3E984 -:10316800002320462946FDF791FC00285DD1204622 -:103178002946FDF7B3FC074603E0724EE1E74FF43A -:103188007A77714B1A68714BA3FB0213DB0803EBC8 -:10319800830303EB83039A4249D00AF13203BB420B -:1031A80014DDAAF1320ABA4510DA0BF13203B34240 -:1031B8000CDDABF1320BB34508DA654B1B68042B09 -:1031C80004D8644B1E607B42634A13600221554851 -:1031D800FEF782FF38B1614B1B6823B9604B1B684F -:1031E800002B00F082805F4B1C685F492046FDF78A -:1031F80099FF28B15D4B1B681333262B40F2818061 -:103208005B492046FDF78EFF002800F0BD80564937 -:103218002046FDF7A5FF002800F0B680444B0522A4 -:103228001A70544B06221A70BAE0464FA9E7019863 -:10323800FDF762F936A3D3E90023FDF7B5F9044693 -:103248000D46DFF8F480B8F81000FDF775FDFDF7BE -:1032580053F931A3D3E90023FDF7A6F902460B463B -:1032680020462946FCF7EAFFFDF760FC0546019079 -:103278004149FDF7AFFC4149FDF7B6FD4049FDF76F -:10328800ABFC0446B8F80E10002000F029FDB8F891 -:103298001210012000F024FD3146022000F020FD2C -:1032A8003946032000F01CFDB8F80C10042000F08B -:1032B80017FD34492B4B1868FDF796FDFDF75AFFAB -:1032C8000146052000F00CFD2846FDF753FF014696 -:1032D800062000F005FD2046FDF74CFF01460720BB -:1032E80000F0FEFC00F002FD57E7144B00221A70B4 -:1032F80002210C48FEF7F0FE0028F9D1FFF744FE42 -:1033080071E7FFF741FE4BE00000000000408FC06E -:10331800AE47E17A14AEEF3F7B14AE47E17A843FC3 -:10332800001002400008014074020020280100201B -:10333800A4000020000C0140E8020020B400002096 -:1033480000408F4018FCFFFF7C0300201F85EB51D5 -:1033580004000020C8000020C4000020D000002085 -:10336800CC00002008000020CCCC064294030020AA -:1033780000000C42A800002000E0CE44083748BEF8 -:1033880033330F420000C842734B1B6813F1320FEE -:1033980080F2CA80714B05221A70714B01221A7093 -:1033A80087EAE773A3EBE773322B06DC86EAE6735A -:1033B800A3EBE673322B40F3BD806A4B00221A6000 -:1033C800684B1A68684B9A4201D9FFF7DDFDB3468E -:1033D800BA460220FEF754FF644BDB899BB2B3F573 -:1033E800805FBFF4A6AE614BDA89D889FDF7A8FCE7 -:1033F8005F49FDF7ADFDFDF7BDFE80465D4BC3F8A7 -:1034080000805A4B5B8A9BB2B3F5805FBFF494AEE1 -:10341800564B5A8A588AFDF793FC5549FDF798FD93 -:10342800FDF7A8FE0446544B1C60504AD3899BB252 -:10343800B3F5FA6F94BF0023012350490B70538AE8 -:103448009BB2B3F5FA6F94BF002301234C4A137063 -:103458004C4B00221A604C4D2868FDF73BF838A306 -:10346800D3E90023FDF7A0F806460F464046FDF7CE -:1034780031F835A3D3E90023FDF796F802460B4649 -:1034880030463946FCF7DAFEFDF728FB0646286089 -:10349800314D2868FDF71EF829A3D3E90023FDF76D -:1034A80083F8804689462046FDF714F826A3D3E919 -:1034B8000023FDF779F802460B4640464946FCF7DB -:1034C800BDFEFDF70BFB2860FDF704F800222F4B2B -:1034D800FDF76AF804460D463046FCF7FBFF00226C -:1034E8002A4BFDF761F88046894602460B4620467E -:1034F8002946FCF7A1FE06460F460022244BFDF79D -:10350800E3FA00287FF41BAE11A3D3E90023304669 -:103518003946FDF7BBFA00287FF42FAE304639460E -:10352800FDF7DCFA06460CE600230C4A13700C4A39 -:10353800137035E70B4A13680133136040E700BF87 -:10354800CDCCCCCCCCCCEC3F9A9999999999B93FF0 -:103558000000000000408FC094030020A400002059 -:10356800A80000207C03002000710200E80200206F -:103578003D0A83409C030020880300209803002014 -:1035880084030020040000208C0300200000E03F9A -:1035980000408F4000000000774B02225A60774BB2 -:1035A8001B68B3F57A7F5EDB2DE9F041744B1A682E -:1035B800744BA3FB02139B094FF47A7101FB13238D -:1035C8000BBB714C2068FCF797FF65A3D3E9002378 -:1035D800FCF7EAFF06460F466C4B9889FDF7ACFBF3 -:1035E8006B49FDF701FCFCF787FF5FA3D3E90023D4 -:1035F800FCF7DAFF02460B4630463946FCF71EFE5A -:10360800FDF794FA2060614B5889624B1C68001BD7 -:10361800FCF760FF56A3D3E90023FCF7C5FF00229F -:103628000023FDF733FA002852D1584B5889001B64 -:10363800FCF750FF4EA3D3E90023FCF7B5FF0022A7 -:10364800554BFDF741FA002852D1544B1B68052B06 -:103658004ED8534B1B78002B4AD0524A536C43F434 -:103668000043536449E00133444A1360474A908851 -:103678004D490B68034403EBD3735B100B60D08890 -:103688004A490B68034403EBD3735B100B60108843 -:1036980047490B68034403EBD3735B100B605088F6 -:1036A80044490B68034403EBD3735B100B605089E8 -:1036B80038490B68034403EBD3735B100B60118923 -:1036C8003D4A13680B4403EBD3735B1013607047D8 -:1036D8002E4B5889001BFCF7FDFE25A3D3E90023D8 -:1036E800FCF762FF0022354BFDF7D0F90028ACD07B -:1036F8002C4A536C23F400435364244B18892E4BF3 -:103708001C68001BFCF7E6FE19A3D3E90023FCF7AD -:103718004BFF00220023FDF7B9F9002852D11B4BBB -:103728001889001BFCF7D6FE11A3D3E90023FCF788 -:103738003BFF0022184BFDF7C7F9002852D1174B61 -:103748001B68052B4ED8164B1B78002B4AD01C4AF9 -:10375800536C43F40043536449E000BFAFF3008067 -:10376800AE47E17A14AEEF3F7B14AE47E17A843F6F -:103778007B14AE47E17A943F00000240B800002075 -:10378800AC000020D34D621008000020E8020020A1 -:1037980017B9CE3C0C00002000002E400400002089 -:1037A800B40000200034014014000020180000205C -:1037B8001C000020200000201000002000002EC067 -:1037C800002C0140904B1889001BFCF783FE8CA34A -:1037D800D3E90023FCF7E8FE00228C4BFDF756F9ED -:1037E8000028ACD08A4A536C23F4004353648949B7 -:1037F8008B6813F0200F0CBF012300238A6812F096 -:10380800400F0CBF01220022896811F0800F0CBF05 -:10381800012500258049886810F4806F0CBF0120BD -:1038280000208C6814F4006F0CBF01240024896800 -:1038380011F4805F02EB450203EB4203774EF35C21 -:1038480077490B600B6803F102030B600D68754B39 -:1038580083FB0572A2EBE57202EB42024FEA4207D4 -:10386800A5EB07020A600CBF02220022224400EBEB -:103878004202B05C6C4A1060106802301060106838 -:1038880083FB0043A3EBE07303EB43035C00031BE0 -:10389800136009685C488388644A12689A1AC38866 -:1038A800634800681B1A052934D8DFE801F00323B0 -:1038B80026292C2FD31A5F4A13605F4A13680133F5 -:1038C80013605E4A14684CB35D4AA2FB0312120BE4 -:1038D8005C4909680131B2FBF1F001FB1022EAB939 -:1038E800B3FBF4F204FB1233EBB910215648FEF790 -:1038F80000FC18E04F4B1A60DFE74E4B1A60DCE71C -:103908004C4A1360D9E74B4A1360D6E79B1A494AD9 -:103918001360D2E7474B00221A60CEE7002210213D -:103928004948FEF7E0FB494BD3F800C03C4B1B6805 -:10393800052B2BD8DFE803F00312171C2226CCF145 -:10394800000064469C46424B1968374B1B68052BA0 -:1039580052D8DFE803F01F3F43474B4E6446CCF193 -:10396800000C0020EFE76046CCF1000C0024EAE7E9 -:10397800CCF1000460464FF0000CE4E7CCF1000401 -:103988000020E0E7CCF100000024DCE7002004463A -:103998008446D8E74E420F4619462C4B1B68002B2D -:1039A80040F398802B4B1D681D4B1B6805331D4A3F -:1039B80082FB03E2A2EBE37202EB42024FEA420E01 -:1039C800A3EB0E02052A00F2B980DFE802F0456A8F -:1039D8006F74797E0F4649420026DEE70E4649425B -:1039E8000027DAE74F420E460021D6E74F4200266D -:1039F800D3E74E420027D0E7002637463146CCE7CA -:103A08007B14AE47E17A943FE802002000002EC004 -:103A1800002C0140000C014000100140B446000891 -:103A2800BC000020ABAAAA2AC00000201400002075 -:103A380018000020B0000020AC000020A4000020E6 -:103A48005917B7D1A800002000080140C400002081 -:103A5800C8000020CC000020C5F10008AE4615467D -:103A6800654474444044964B1B68002B40F3D78050 -:103A7800944B1B68944A126802F1050C934A82FB26 -:103A88000CE2A2EBEC7202EB42024FEA420EACEB04 -:103A98000E02052A00F2F980DFE802F058A8ADB25C -:103AA800B7BCAE466D424FF00008D9E7A8466D4254 -:103AB8004FF0000ED4E7C5F1000EA8460025CFE769 -:103AC800C5F1000E4FF00008CAE7C5F100084FF035 -:103AD800000EC5E77E4B1D68C5F1000E7D4B1A68C8 -:103AE80001327A4B83FB0283A3EBE27303EB4303BC -:103AF8004FEA4308A2EB0803052B1AD8DFE803F0C6 -:103B08000323060A0E14A8461D46A9E7F0464FF0FF -:103B1800000EA5E7F046AE460025A1E72B46754600 -:103B28009E464FF000089BE7A84675464FF0000EEA -:103B380096E74FF00008C646454691E74FF0000863 -:103B4800C64645468CE74FF0000889E7C3F10008F0 -:103B58009E461346194407EB0E0206EB080305F5CB -:103B68007A7540F2C676B54200F397800A2DB8BF41 -:103B78000A25594E756304F57A7440F2C675AC424D -:103B880000F38E800A2CB8BF0A24534DAC6300F5AD -:103B98007A7040F2C674A04200F385800A28B8BF44 -:103BA8000A204D4CE06301F57A7140F2C6708142FB -:103BB8007CDC0A29B8BF0A214848416302F57A72B9 -:103BC80040F2C6718A4274DC0A2AB8BF0A22434905 -:103BD8008A6303F57A7340F2C67293426CDC0A2B4F -:103BE800B8BF0A233D4AD363BDE8F0819E465B42D5 -:103BF8004FF00008AEE798465B424FF0000EA9E789 -:103C0800C3F1000E98460023A4E7C3F1000E4FF05D -:103C180000089FE7C3F100084FF0000E9AE7294B10 -:103C28001B68C3F1000E284A12680132DFF89CC0F5 -:103C38008CFB028CACEBE27C0CEB4C0C4FEA4C0896 -:103C4800A2EB080CBCF1050F1AD8DFE80CF003232F -:103C5800060A0E14984663467CE7F0464FF0000EBD -:103C680078E7F0469E46002374E71A467346964660 -:103C78004FF000086EE7984673464FF0000E69E76C -:103C88004FF00008C646434664E74FF00008C646B2 -:103C980043465FE74FF000085CE740F2C67568E707 -:103CA80040F2C67471E740F2C6707AE740F2C67116 -:103CB80082E740F2C6728AE740F2C67392E700BF15 -:103CC800C8000020D0000020C0000020ABAAAA2A0B -:103CD800CC000020BC00002000340140002C014032 -:103CE800014B23F81010704704040020F0B587B08A -:103CF8001A4F64220021384600F090F818490A88C3 -:103D0800B1F802C0888800B2CC8824B20D892DB2DF -:103D18004E8936B28B891BB2C98909B205910493C1 -:103D280003960295019400900FFA8CF312B20D4994 -:103D3800384600F07BF80C4B5B686BB90A4C23687B -:103D480023F0010323603846FCF76AFA6060E760F5 -:103D5800236843F00103236007B0F0BDA0030020EF -:103D680004040020BC4600081C0002407047FEE71F -:103D7800FEE7FEE7FEE770477047704708B5FEF7B5 -:103D880071FAFEF7ACF808BD002103E00B4B5B5855 -:103D9800435004310A480B4B42189A42F6D30A4A58 -:103DA80002E0002342F8043B084B9A42F9D3FEF79D -:103DB8008FFD00F00FF8FFF747F970472447000818 -:103DC800000000208800002088000020180400203F -:103DD800FEE7000070B500250C4E0D4CA41BA41086 -:103DE800A54209D100F040FC00250A4E0A4CA41B4C -:103DF800A410A54205D170BD56F825309847013565 -:103E0800EEE756F8253098470135F2E71C470008D9 -:103E18001C4700081C4700082047000803460244C6 -:103E2800934200D1704703F8011BF9E70EB46FF015 -:103E3800004100B59CB01DAB02900690079104911B -:103E48000848094953F8042B0591006802A9019311 -:103E580000F066F80022029B1A701CB05DF804EBB3 -:103E680003B07047240000200802FFFF2DE9F04747 -:103E78008E6882469E420C469046994637D88A8973 -:103E880012F4906F31D00223256809696F1A6569A9 -:103E980005EB450595FBF3F509F101033B449D420C -:103EA80038BF1D46530530D5294600F035FB064678 -:103EB80050B90C234FF0FF30CAF80030A38943F003 -:103EC8004003A381BDE8F0873A46216900F0B4FABF -:103ED800A38923F4906343F08003A38126613E44C1 -:103EE80026604E466561ED1BA5604E4500D94E46DD -:103EF80032464146206800F0AAFAA36800209B1BBE -:103F0800A36023681E442660DCE72A4600F05EFBB7 -:103F180006460028E2D12169504600F0B1FAC8E708 -:103F28002DE9F04F9DB003938B8980461D060C4602 -:103F380016460FD50B696BB9402100F0EDFA2060E9 -:103F4800206128B90C23C8F800304FF0FF30C7E0D3 -:103F5800402363610023099320238DF829303023FF -:103F68004FF0010B8DF82A3037463D4615F8013BD6 -:103F78000BB1252B3ED1B7EB060A0BD05346324680 -:103F880021464046FFF772FF013000F0A480099BEC -:103F9800534409933B78002B00F09D8000234FF099 -:103FA800FF32CDE90523049307938DF853301A9314 -:103FB8002F46052217F8011B4F4800F02FFA049BE3 -:103FC800D0B9D90644BF20228DF853201A0744BF20 -:103FD8002B228DF853202A782A2A15D02F46002024 -:103FE8000A25079A394611F8013B303B092B4DD970 -:103FF800B8B10FE02F46B8E73F4A3D46801A0BFAA2 -:1040080000F018430490D3E7039A111D1268039136 -:10401800002A01DB079204E0524243F002030792B0 -:1040280004933B782E2B0CD17B782A2B33D1039B1E -:1040380002371A1D1B680392002BB8BF4FF0FF33DD -:1040480005932E4D03223978284600F0E7F938B158 -:104058004023401B03FA00F0049B013703430493F9 -:104068003978062226487E1C8DF8281000F0D6F9EB -:10407800002838D0234B13BB039B073323F00703D7 -:1040880008330393099B4B4409936DE705FB023200 -:1040980001200F46A6E700230A2519460137059394 -:1040A800384610F8012B303A092A03D9002BC8D01A -:1040B8000591C6E705FB012101230746F0E703AB9D -:1040C80000932246104B04A94046AFF30080B0F19C -:1040D800FF3F8146D6D1A3895B063FF536AF0998E5 -:1040E8001DB0BDE8F08F03AB00932246064B04A930 -:1040F800404600F081F8EAE7E8460008EE46000886 -:10410800F246000800000000753E00082DE9F0475F -:1041180091461F468A680B6906469342B8BF134604 -:10412800C9F8003091F843200C46DDF8208012B120 -:104138000133C9F800302368990642BFD9F8003026 -:104148000233C9F80030256815F0060507D104F1D7 -:10415800190AE368D9F800209B1AAB4229DC94F8C5 -:1041680043302268003318BF012392062ED404F18D -:10417800430239463046C047013021D02368E568FC -:1041880003F00603042B18BF0025D9F800204FF0D0 -:10419800000908BFAD1AA368226908BF25EAE575BA -:1041A8009342C4BF9B1AED181A344D451AD100200A -:1041B80008E00123524639463046C047013003D152 -:1041C8004FF0FF30BDE8F0870135C2E73020E11835 -:1041D80081F843005A1C94F845102244023382F8AF -:1041E8004310C4E70123224639463046C047013010 -:1041F800E6D009F10109D8E72DE9F04301F1430CB4 -:104208000C46097E85B06E291746064698460C9AD4 -:1042180000F0B38022D8632936D00AD8002900F0EC -:10422800B980582900F0838004F1420584F84210CF -:1042380032E0642901D06929F6D12068136805069F -:1042480003F104012AD51B681160002B03DA2D2223 -:104258005B4284F843206F480A2239E0732900F052 -:104268009D8008D86F2920D07029DDD1236843F0BC -:104278002003236003E0752917D07829D4D1782347 -:10428800654884F8453055E0136804F14205191D66 -:104298001B68116084F8423001238CE01B6810F021 -:1042A800400F116018BF1BB2CFE713682568181DAF -:1042B8001060280601D51B6802E06806FBD51B883C -:1042C8006F2914BF0A2208225248002184F843109B -:1042D8006568002DA560C0F29580216821F0040171 -:1042E8002160002B3DD1002D40F08E806546082AC4 -:1042F8000BD12368DB0708D5236962689A42DEBFC1 -:10430800302305F8013C05F1FF35ACEB05032361CB -:10431800CDF800803B4603AA21463046FFF7F6FE5B -:1043280001304DD14FF0FF3005B0BDE8F08339487A -:1043380084F84510136821681D1D1B6815600A065E -:104348000BD5CA0744BF41F0200121601BB9226880 -:1043580022F0200222601022B7E74D0648BF9BB228 -:10436800EFE76546B3FBF2F102FB1133C35C05F8D6 -:10437800013D0B460029F5D1B9E713682568181DDA -:104388006169106028061B6801D5196002E06A0699 -:10439800FBD51980002365462361B9E71368191D09 -:1043A80011601D6862680021284600F037F808B1DE -:1043B800401B606063682361002384F84330A7E7EB -:1043C80023692A4639463046C0470130AAD02368B7 -:1043D8009B0713D4E068039B9842B8BF1846A3E72D -:1043E80001234A4639463046C04701309AD0013544 -:1043F800E368039A9B1AAB42F2DCEBE7002504F171 -:104408001909F5E7002BACD1037804F1420584F8CB -:1044180042306CE7F94600080A47000810B5C9B2EF -:1044280002449042034601D1002303E01C78013086 -:104438008C42F6D1184610BD10B5431E0A4491426D -:1044480000D110BD11F8014B03F8014FF7E788427E -:1044580010B501EB020307D8421E99420AD011F8A1 -:10446800014B02F8014FF8E78342F5D98118D21AB7 -:10447800D34200D110BD13F8014D01F8014DF7E703 -:1044880038B50546002943D051F8043C0C1F002BD1 -:10449800B8BFE41800F0D0F81E4A1368104633B9C4 -:1044A800636014602846BDE8384000F0C6B8A342EF -:1044B8000BD921686218934201BF1A685B685218C9 -:1044C800226063600460EDE713465A680AB1A242AD -:1044D800FAD919685818A0420BD120680144581815 -:1044E80082421960DED110685268014419605A602E -:1044F800D8E702D90C232B60D4E7206821188A4218 -:1045080001BF116852680918216062605C60C9E7E0 -:1045180038BD00BFD400002070B5CD1C25F00305C0 -:1045280008350C2D38BF0C25002D064601DBA942A5 -:1045380003D90C233360002070BD00F07DF8214AB8 -:104548001468214691B9204C23681BB9304600F005 -:1045580063F820602946304600F05EF8431C24D1F9 -:104568000C233046336000F068F8E4E70B685B1B07 -:1045780018D40B2B0FD90B60CC18CD50304600F057 -:104588005CF804F10B00231D20F00700C31AD3D0F8 -:104598005A42E250D0E74B688C4216BF6360136002 -:1045A8000C46EBE70C464968CCE7C41C24F003042E -:1045B800A04205D0211A304600F02EF80130CFD0A5 -:1045C8002560DBE7D4000020D8000020F8B50746B6 -:1045D80014460E4621B9BDE8F8401146FFF79CBFC6 -:1045E80022B9FFF74DFF25462846F8BD00F026F80A -:1045F800A0420FD221463846FFF78EFF0546002815 -:10460800F2D031462246FFF717FF31463846FFF70A -:1046180037FFE9E73546E7E738B50023054C054697 -:104628000846236000F012F8431C02D1236803B146 -:104638002B6038BD140400207047704751F8043CC3 -:10464800181F002BBCBF0B58C0187047044A0549F7 -:104658001368002B08BF0B461844106018467047B3 -:10466800DC00002018040020F8B500BFF8BC08BC26 -:104678009E467047F8B500BFF8BC08BC9E46704718 -:1046880002030405060708090A0B0C0D0E0F10108B -:104698000102000000000000000000000102030405 -:1046A80006070809000000000102030400000201D7 -:1046B80004050300313A256920323A256920333A46 -:1046C800256920343A256920353A256920363A2566 -:1046D8006920373A256920383A25690D0A00000013 -:1046E800232D302B2000686C4C00656667454647D3 -:1046F8000030313233343536373839414243444556 -:1047080046003031323334353637383961626364C4 -:0447180065660000D2 -:04471C000D02000882 -:04472000E9010008A3 -:1047240000A24A046400000000002042D0070000F8 -:10473400D0070000D0070000D0070000D007000019 -:10474400D007000028000020000000000000000046 -:104754000000000000000000000000000000000055 -:104764000000000000000000000000000000000045 -:104774000000000000000000000000000000000035 -:104784000000000000000000000000000000000025 -:104794000000000000000000000000000000000015 -:0847A40000000000000000000D -:0400000508003D9121 -:00000001FF diff --git a/docs/SideBoardMX.pdf b/docs/SideBoardMX.pdf new file mode 100644 index 00000000..cb36d3e3 Binary files /dev/null and b/docs/SideBoardMX.pdf differ diff --git a/docs/pictures/Motor_LEFT_SIN3.png b/docs/pictures/Motor_LEFT_SIN3.png new file mode 100644 index 00000000..f3b87991 Binary files /dev/null and b/docs/pictures/Motor_LEFT_SIN3.png differ diff --git a/docs/pictures/Motor_RIGHT_SIN3.png b/docs/pictures/Motor_RIGHT_SIN3.png new file mode 100644 index 00000000..748faedb Binary files /dev/null and b/docs/pictures/Motor_RIGHT_SIN3.png differ diff --git a/docs/pictures/STM32_pinout_hoverboard.png b/docs/pictures/STM32_pinout_hoverboard.png new file mode 100644 index 00000000..ecb5c3ee Binary files /dev/null and b/docs/pictures/STM32_pinout_hoverboard.png differ diff --git a/docs/pictures/armchair.gif b/docs/pictures/armchair.gif deleted file mode 100644 index 0d112d13..00000000 Binary files a/docs/pictures/armchair.gif and /dev/null differ diff --git a/docs/pictures/bobbycar.gif b/docs/pictures/bobbycar.gif deleted file mode 100644 index 7ee8cfe9..00000000 Binary files a/docs/pictures/bobbycar.gif and /dev/null differ diff --git a/docs/pictures/chair.gif b/docs/pictures/chair.gif deleted file mode 100644 index 23893bae..00000000 Binary files a/docs/pictures/chair.gif and /dev/null differ diff --git a/docs/pictures/hoverboard_wheel.JPG b/docs/pictures/hoverboard_wheel.JPG new file mode 100644 index 00000000..b95773a6 Binary files /dev/null and b/docs/pictures/hoverboard_wheel.JPG differ diff --git a/docs/pictures/transpotter.gif b/docs/pictures/transpotter.gif deleted file mode 100644 index 03341c52..00000000 Binary files a/docs/pictures/transpotter.gif and /dev/null differ diff --git a/platformio.ini b/platformio.ini new file mode 100644 index 00000000..6f3a7282 --- /dev/null +++ b/platformio.ini @@ -0,0 +1,27 @@ +; PlatformIO Project Configuration File2 +; http://docs.platformio.org/page/projectconf.html + +[platformio] +include_dir = Inc +src_dir = Src + +[env:genericSTM32F103RC] +platform = ststm32 +framework = stm32cube +board = genericSTM32F103RC +debug_tool = stlink +upload_protocol = stlink + +; Serial Port settings (make sure the COM port is correct) +monitor_port = COM5 +monitor_speed = 115200 + +build_flags = + -I${PROJECT_DIR}/inc/ + -DUSE_HAL_DRIVER + -DSTM32F103xE + -Wl,-T./STM32F103RCTx_FLASH.ld + -Wl,-lc + -Wl,-lm + -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization +# -Wl,-lnosys