58 Commits

Author SHA1 Message Date
98e03b469c Update README.md 2020-07-19 10:13:13 +02:00
e5d6ec5349 Update README.md 2020-06-22 09:27:37 +02:00
1accd16425 Update README.md 2019-10-20 20:17:44 +02:00
326637462f Update .gitignore 2019-09-14 17:00:23 +02:00
5bf21fcaa7 Added link for the YST board schematic 2019-07-10 13:25:24 +02:00
4f1348882b Add: Condition on motor control calculation
- The motors control calculation is done only if the motor is enabled to correctly initialize the controller.
2019-07-01 21:06:01 +02:00
8d21a73a09 Added current measurements figures 2019-06-27 21:48:59 +02:00
c998268e76 Update README.md 2019-06-26 19:29:29 +02:00
536aba7787 clean-up temporary files 2019-06-26 19:28:57 +02:00
9cf4988cde cleanup 2019-06-26 19:28:35 +02:00
fa0596c127 ADD STM hoverboard pinout and pdf 2019-06-19 23:06:27 +02:00
193160d37f Updated build 2019-06-18 18:49:21 +02:00
102eae5e62 Moved cmd bypasses before the motor enabling 2019-06-18 18:48:13 +02:00
285f65b4a6 Added some back-up files 2019-06-18 18:07:14 +02:00
8ebf9dc230 ► Added protection on start-up
For safety reasons, the motors are enabled on start-up, only if the input is very small.
2019-06-18 18:06:58 +02:00
60957481b6 Added temporary Matlab folder to ignore file 2019-06-11 21:27:03 +02:00
0d908b8238 deleted slprj 2019-06-11 21:24:35 +02:00
bf9725159d ► Added speed threshold to enable Phase Advance
- Phase Advance is enabled only when Motor Speed > n_motPhaAdvEna (400 rpm). This prevents that during a kick-down (100% duty cycle) the Phase advance kicks in even though we are running at low speed.
- This update improves the acceleration response
- no impact on code execution time
2019-06-11 21:24:08 +02:00
b828efffd5 Updated generated firmware 2019-06-10 20:37:33 +02:00
2ca1a1901b Removed #define static static inline 2019-06-10 20:20:45 +02:00
43b4f4aa20 ► Warning fixes
- Changed all float constants to use f suffix to prevent double conversions
- Removed compile warnings due to HAL_GPIO_* related calls
- Added comms.h with prototypes for functions which were used in main()
- Casts and externs to fix compile warnings in various files.
- Made a bunch of file-local variables static.
- Fixed buzzerFreq/buzzerPattern extern declarations with correct type (uint8_t)
- Since this is C, void func() { } needs to be void func(void) { }, so fixed that in all instances.
These updates follows from @trollcop
2019-06-10 20:18:37 +02:00
9fdbba1c37 Made z_maxCntRst as calibratable 2019-06-10 17:33:46 +02:00
116f75dae7 Added wheel speed calculation in km/h 2019-06-08 11:24:17 +02:00
aee1a958db Update README.md 2019-06-07 10:35:42 +02:00
ffb6a5236c added scr_dir 2019-06-07 10:30:01 +02:00
3c850eddb4 Added .travis.yml file 2019-06-07 10:18:25 +02:00
61aa161481 ► updated the 3rd harmonic to peak exactly at 1000 2019-06-06 22:54:04 +02:00
b90a2503b4 ► New BLDC control
- auto-code regenerated
2019-06-06 22:05:57 +02:00
fe4bd76d7e ► Improved controller: faster and better overall
- the controller is faster and more light in memory footprint
- motor control is now done intependenly using Reusable code generation setting in Simulink
- fixed bug when chaging direction fast
2019-06-05 22:39:30 +02:00
19e4115d06 Saved README.md with Dillinger.io 2019-05-29 17:26:53 +02:00
8619ee331b Saved README.md with Dillinger.io 2019-05-29 17:25:02 +02:00
0a6064d72d Merge pull request #1 from p-h-a-i-l/patch-1
Update Makefile
2019-05-29 08:47:57 +02:00
8adb223de2 ► added firmware.bin 2019-05-29 06:47:29 +02:00
79abd9dbf7 Update Makefile 2019-05-29 00:12:13 +02:00
90d7a3cf20 Saved README.md with Dillinger.io 2019-05-28 23:37:52 +02:00
a144a86a0e Saved README.md with Dillinger.io 2019-05-28 23:34:04 +02:00
ffe361aa7f Saved README.md with Dillinger.io 2019-05-28 23:04:17 +02:00
5d64ec07b0 Saved README.md with Dillinger.io 2019-05-28 22:49:36 +02:00
09edcf390a Saved README.md with Dillinger.io 2019-05-28 22:45:55 +02:00
d5e2d4641f Saved README.md with Dillinger.io 2019-05-28 22:45:11 +02:00
3dd416bb3b Saved README.md with Dillinger.io 2019-05-28 22:44:53 +02:00
f279ff4361 Merge branch 'master' of https://github.com/EmanuelFeru/hoverboard-firmware-hack 2019-05-28 22:43:55 +02:00
ade9a15438 Update hoverboard_wheel.JPG 2019-05-28 22:43:43 +02:00
7f9bbec505 Saved README.md with Dillinger.io 2019-05-28 22:40:25 +02:00
396807b6ed Saved README.md with Dillinger.io 2019-05-28 22:39:36 +02:00
e937fb3536 Saved README.md with Dillinger.io 2019-05-28 22:38:33 +02:00
2c4d44f1ba Saved README.md with Dillinger.io 2019-05-28 22:37:29 +02:00
5a4e42609f Update README.md 2019-05-28 22:24:52 +02:00
301418b4ff README.md updated from https://stackedit.io/ 2019-05-28 21:55:57 +02:00
8758369d07 README.md updated from https://stackedit.io/ 2019-05-28 21:55:16 +02:00
09e8d3f080 README.md updated from https://stackedit.io/ 2019-05-28 21:54:23 +02:00
ac0e680369 First release commit, dynamic tests done! 2019-05-28 21:38:39 +02:00
cdcafbaa5c Update .gitignore 2019-05-26 16:13:31 +02:00
b3cc517fdc update 2019-05-26 16:00:18 +02:00
959027b74f added Serial Port settings 2019-05-26 15:59:00 +02:00
fc267cd440 Added Matlab model for BLDC control 2019-05-26 15:42:33 +02:00
a732c60d2b deleted 2019-05-26 15:36:29 +02:00
febbfc823c Added new BLDC motor control 2019-05-26 15:33:57 +02:00
342 changed files with 86743 additions and 1510 deletions

5
.gitignore vendored
View File

@ -1,2 +1,5 @@
build/*
!build/hover.hex
.pio/
.pioenvs/
.vscode/
01_Matlab/slprj/

55
.travis.yml Normal file
View File

@ -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"

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 216 KiB

Binary file not shown.

View File

@ -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 <aerdronix@gmail.com>
*
* 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 <http://www.gnu.org/licenses/>.
*/
#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;
// ###############################################################################
}

View File

@ -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 <EFBFBD> 2019 Emanuel FERU <aerdronix@gmail.com>
%
% 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 <http://www.gnu.org/licenses/>.
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
% 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

View File

@ -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);

View File

@ -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.

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.3 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.9 KiB

View File

@ -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;}

View File

@ -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;}

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.8 KiB

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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;}

View File

@ -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.

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.2 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.3 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.1 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.7 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.1 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.3 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 630 B

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/ar/common", ({
buttonOk: "حسنا",
buttonCancel: "الغاء",
buttonSave: "حفظ",
itemClose: "اغلاق"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/ar/loading", ({
loadingState: "جاري التحميل...",
errorState: "عفوا، حدث خطأ"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/az/common", ({
"buttonOk" : "Ok",
"buttonCancel" : "Ləğv et",
"buttonSave" : "Saxla",
"itemClose" : "Bağla"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/az/loading", ({
"loadingState" : "Yüklənir...",
"errorState" : "Problem yarandı"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/bg/common", ({
buttonOk: "ОК",
buttonCancel: "Отмени",
buttonSave: "Запази",
itemClose: "Затвори"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/bg/loading", ({
loadingState: "Зареждане...",
errorState: "Съжаляваме, възникна грешка"
})
);

View File

@ -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
});

View File

@ -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
});

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/ca/common", ({
buttonOk: "D'acord",
buttonCancel: "Cancel·la",
buttonSave: "Desa",
itemClose: "Tanca"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/ca/loading", ({
loadingState: "S'està carregant...",
errorState: "Ens sap greu. S'ha produït un error."
})
);

View File

@ -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
});

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/cs/common", ({
buttonOk: "OK",
buttonCancel: "Storno",
buttonSave: "Uložit",
itemClose: "Zavřít"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/cs/loading", ({
loadingState: "Probíhá načítání...",
errorState: "Omlouváme se, došlo k chybě"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/da/common", ({
buttonOk: "OK",
buttonCancel: "Annullér",
buttonSave: "Gem",
itemClose: "Luk"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/da/loading", ({
loadingState: "Indlæser...",
errorState: "Der er opstået en fejl"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/de/common", ({
buttonOk: "OK",
buttonCancel: "Abbrechen",
buttonSave: "Speichern",
itemClose: "Schließen"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/de/loading", ({
loadingState: "Wird geladen...",
errorState: "Es ist ein Fehler aufgetreten."
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/el/common", ({
buttonOk: "ΟΚ",
buttonCancel: "Ακύρωση",
buttonSave: "Αποθήκευση",
itemClose: "Κλείσιμο"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/el/loading", ({
loadingState: "Φόρτωση...",
errorState: "Σας ζητούμε συγνώμη, παρουσιάστηκε σφάλμα"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/es/common", ({
buttonOk: "Aceptar",
buttonCancel: "Cancelar",
buttonSave: "Guardar",
itemClose: "Cerrar"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/es/loading", ({
loadingState: "Cargando...",
errorState: "Lo siento, se ha producido un error"
})
);

View File

@ -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
});

View File

@ -0,0 +1,7 @@
define("dijit/nls/eu/loading", {
//begin v1.x content
loadingState: "Kargatzen...",
errorState: "Barkatu, errorea gertatu da"
//end v1.x content
});

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/fi/common", ({
buttonOk: "OK",
buttonCancel: "Peruuta",
buttonSave: "Tallenna",
itemClose: "Sulje"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/fi/loading", ({
loadingState: "Lataus on meneillään...",
errorState: "On ilmennyt virhe."
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/fr/common", ({
buttonOk: "OK",
buttonCancel: "Annuler",
buttonSave: "Enregistrer",
itemClose: "Fermer"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/fr/loading", ({
loadingState: "Chargement...",
errorState: "Une erreur est survenue"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/he/common", ({
buttonOk: "אישור",
buttonCancel: "ביטול",
buttonSave: "שמירה",
itemClose: "סגירה"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/he/loading", ({
loadingState: "טעינה...",
errorState: "אירעה שגיאה"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/hr/common", ({
buttonOk: "OK",
buttonCancel: "Opoziv",
buttonSave: "Spremi",
itemClose: "Zatvori"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/hr/loading", ({
loadingState: "Učitavanje...",
errorState: "Žao nam je, došlo je do greške"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/hu/common", ({
buttonOk: "OK",
buttonCancel: "Mégse",
buttonSave: "Mentés",
itemClose: "Bezárás"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/hu/loading", ({
loadingState: "Betöltés...",
errorState: "Sajnálom, hiba történt"
})
);

View File

@ -0,0 +1,9 @@
define(
"dijit/nls/id/common", ({
buttonOk: "OK",
buttonCancel: "Batal",
buttonSave: "Simpan",
itemClose: "Tutup"
})
);

View File

@ -0,0 +1,7 @@
define(
"dijit/nls/id/loading", ({
loadingState: "Memuatkan...",
errorState: "Maaf, terjadi kesalahan"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/it/common", ({
buttonOk: "Ok",
buttonCancel: "Annulla",
buttonSave: "Salva",
itemClose: "Chiudi"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/it/loading", ({
loadingState: "Caricamento in corso...",
errorState: "Si è verificato un errore"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/ja/common", ({
buttonOk: "OK",
buttonCancel: "キャンセル",
buttonSave: "保存",
itemClose: "閉じる"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/ja/loading", ({
loadingState: "ロード中...",
errorState: "エラーが発生しました。"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/kk/common", ({
buttonOk: "OK",
buttonCancel: "Болдырмау",
buttonSave: "Сақтау",
itemClose: "Жабу"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/kk/loading", ({
loadingState: "Қотарылуда...",
errorState: "Кешіріңіз, қате орын алды"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/ko/common", ({
buttonOk: "확인",
buttonCancel: "취소",
buttonSave: "저장",
itemClose: "닫기"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/ko/loading", ({
loadingState: "로드 중...",
errorState: "죄송합니다. 오류가 발생했습니다."
})
);

View File

@ -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
});

View File

@ -0,0 +1,9 @@
define("dijit/nls/mk/common", {
//begin v1.x content
buttonOk: "OK",
buttonCancel: "Откажи",
buttonSave: "Зачувај",
itemClose: "Затвори"
//end v1.x content
});

View File

@ -0,0 +1,7 @@
define("dijit/nls/mk/loading", {
//begin v1.x content
loadingState: "Вчитување...",
errorState: "Се појави грешка"
//end v1.x content
});

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/nb/common", ({
buttonOk: "OK",
buttonCancel: "Avbryt",
buttonSave: "Lagre",
itemClose: "Lukk"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/nb/loading", ({
loadingState: "Laster inn...",
errorState: "Det oppsto en feil"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/nl/common", ({
buttonOk: "OK",
buttonCancel: "Annuleren",
buttonSave: "Opslaan",
itemClose: "Sluiten"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/nl/loading", ({
loadingState: "Bezig met laden...",
errorState: "Er is een fout opgetreden"
})
);

View File

@ -0,0 +1,8 @@
define(
"dijit/nls/pl/common", ({
buttonOk: "OK",
buttonCancel: "Anuluj",
buttonSave: "Zapisz",
itemClose: "Zamknij"
})
);

View File

@ -0,0 +1,6 @@
define(
"dijit/nls/pl/loading", ({
loadingState: "Ładowanie...",
errorState: "Niestety, wystąpił błąd"
})
);

Some files were not shown because too many files have changed in this diff Show More