Compare commits

...

13 Commits

Author SHA1 Message Date
9cb2d2c231 ТЕСТ 2025-01-23 15:34:55 +03:00
864a2dfcac #8 Чуть доработан модуль adc_sim и настройка режима ПЧ выведена в app_configs.h 2025-01-20 11:41:55 +03:00
3b5b9b86f7 #5 Работает и векторное и скалярное
Видимо была проблема в измерениях с двигателя, они принимались непонятно в каком формате. Сейчас сделан модуль АЦП, который все правильно преобразует
2025-01-20 10:45:47 +03:00
c2fb7c9684 Обновить README.md 2025-01-19 23:07:54 +03:00
654e0cf240 def.h -> app_configs.h
Плюс убраны пока ненужные дефайны из этого файла
2025-01-19 23:05:29 +03:00
49e4a8a7d6 Обновить README.md 2025-01-18 20:41:38 +03:00
988b9f8e76 readme для этой ветки 2025-01-18 20:41:05 +03:00
fbe8ab9f97 #5 С двигателем не все гладко, но ПЧ запускается, напряжение без двигателя трехуровневное
При SCALAR_OBOROTS
Двигатель не крутится, но при SIMULINK_SEQUENCE = V_PWM24_PHASE_SEQ_NORMAL_ABC на двигателе рисуются красивые синусоиды, пусть и с выбросом в начале и без трехуровнего напряжения

При FOC_OBOROTS
Двигатель крутится, но не уверен что как надо. Между двумя ПЧ почти нет сдвига фаз. Но он разгоняется, но кривовато до -0.9.
И еще как-то задание не работает, по крайней мере если менять только задание оборотов Гц

+ Перенесена структура из ветки RazvalyaevProject
2025-01-18 20:07:11 +03:00
6cd7146804 Добавлены библиотеки DSP281x 2025-01-16 15:39:04 +03:00
45beae3740 #5 С параметрами ГЭД 23550 тож не заводиться
- почему-то будто ограничена скважность и она менятся в очень небольшом диапазоне- второй ПЧ делает работает почему-то хуже при обоих управлениях
- синусоиды при векторном в целом ровнее, чем при скалярном
2025-01-16 13:45:59 +03:00
3003cae0a9 #5 Векторное управление завелось, но пока непонятно как. Двигатель вроде стоит, но рисуются красивые синусоиды тока. Хотя на втором инверторе не такие красивые 2025-01-16 13:45:39 +03:00
8418069d9a Инвертор запустился. Были перепутаны верхние и нижние ключи 2025-01-16 13:10:11 +03:00
a6023bbdcb попытка запустить 23550_on_ship. такая же фигня, шим красивый но неправильный 2025-01-15 13:39:33 +03:00
423 changed files with 20517 additions and 88838 deletions

View File

@ -152,7 +152,7 @@ static void mdlInitializeSizes(SimStruct *S)
*/
static void mdlStart(SimStruct *S)
{
SIM_Initialize_Simulation();
SIM_Initialize_Simulation(S);
}
#endif // MDL_START
@ -167,10 +167,10 @@ static void mdlStart(SimStruct *S)
static void mdlInitializeSampleTimes(SimStruct *S)
{
// Шаг дискретизации
hmcu.SimSampleTime = mxGetPr(ssGetSFcnParam(S,NPARAMS-1))[0];
hmcu.sSimSampleTime = mxGetPr(ssGetSFcnParam(S,NPARAMS-1))[0];
// Register one pair for each sample time
ssSetSampleTime(S, 0, hmcu.SimSampleTime);
ssSetSampleTime(S, 0, hmcu.sSimSampleTime);
ssSetOffsetTime(S, 0, 0.0);
}
@ -187,7 +187,7 @@ static void mdlTerminate(SimStruct *S)
hmcu.fMCU_Stop = 1;
ResumeThread(hmcu.hMCUThread);
WaitForSingleObject(hmcu.hMCUThread, 10000);
SIM_deInitialize_Simulation();
SIM_deInitialize_Simulation(S);
mexUnlock();
}

View File

@ -1,21 +0,0 @@
{
"configurations": [
{
"name": "Win32",
"includePath": [
"${workspaceFolder}/**;",
"C:/ti/ccs1011/ccs/tools/compiler/ti-cgt-c2000_20.2.1.LTS/**"
],
"defines": [
"_DEBUG",
"UNICODE",
"_UNICODE"
],
"cStandard": "c99",
"cppStandard": "c++17",
"intelliSenseMode": "clang-x64",
"compilerPath": "C:/ti/ccs1011/ccs/tools/compiler/ti-cgt-c2000_20.2.1.LTS/bin/cl2000.exe"
}
],
"version": 4
}

View File

@ -5,27 +5,21 @@
#include "DSP281x_Device.h"
#include "global_time.h"
#include "TuneUpPlane.h"
#include "profile_interrupt.h"
unsigned int CanTimeOutErrorTR = 0;
unsigned int CanBusOffError = 0;
int CanTimeOutErrorTR = 0;
int enable_can_recive_after_units_box = 0;
int flag_enable_can_from_mpu=0;
int flag_enable_can_from_terminal=0;
long time_pause_enable_can_from_mpu=0;
long time_pause_enable_can_from_terminal=0;
int flag_disable_update_modbus_in_can_from_mpu=0;
//unsigned long can_base_adr_terminal, can_base_adr_units, can_base_adr_mpu1, can_base_adr_alarm_log;
//unsigned int enable_profile_led1_can = 1;
//unsigned int enable_profile_led2_can = 0;
unsigned int enable_profile_led1_can = 1;
unsigned int enable_profile_led2_can = 0;
#pragma DATA_SECTION(cycle,".slow_vars")
CYCLE cycle[UNIT_QUA];
@ -83,7 +77,7 @@ int CAN_count_cycle_input_units[UNIT_QUA_UNITS];
#pragma DATA_SECTION(CAN_timeout_cicle,".fast_vars")
//#pragma DATA_SECTION(CAN_timeout_cicle, ".slow_vars")
// ñ÷åò÷èê
unsigned int CAN_timeout_cicle[UNIT_QUA];
int CAN_timeout_cicle[UNIT_QUA];
@ -211,7 +205,7 @@ int init_alarm_log_can_boxs(ALARM_LOG_CAN_SETUP *p )
int c,e;
e = 0;
for (c=0;c<MAX_COUNT_UNITES_ALARM_LOG;c++)
for (c=0;c<MAX_COUNT_UNITES_TERMINAL;c++)
{
if (p->active_box[c])
{
@ -410,24 +404,17 @@ void reset_CAN_timeout_cicle(int box)
#pragma CODE_SECTION(inc_CAN_timeout_cicle, ".fast_run2");
void inc_CAN_timeout_cicle()
{
unsigned int i, t_refresh;
static unsigned int old_time = 0;
t_refresh = get_delta_milisec(&old_time, 1);
if (t_refresh>1000)
t_refresh = 1000;
int i;
for(i = 0; i < UNIT_QUA; i++)
{
if (CAN_timeout_cicle[i] < MAX_CAN_WAIT_TIMEOUT)
{
CAN_timeout_cicle[i] += t_refresh;
CAN_timeout_cicle[i]++;
}
else
{
CAN_timeout[i] = 1;
CAN_refresh_cicle[i] = -1;
}
}
}
@ -556,44 +543,22 @@ void InitCan(unsigned long can_base_adr_units, unsigned long can_base_adr_mpu, u
ECanaShadow.CANBTC.all = ECanaRegs.CANBTC.all;
// ECanaShadow.CANBTC.bit.SJWREG = 1;
#if (CAN_SPEED_BITS==125000)
// ECanaShadow.CANBTC.bit.BRPREG = 23;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
// ECanaShadow.CANBTC.bit.TSEG1REG = 15;// 15; //5;//7;//14;//10;//7; // Bit time = 15
// ECanaShadow.CANBTC.bit.TSEG2REG = 2; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
// ECanaShadow.CANBTC.bit.SJWREG=1;
ECanaShadow.CANBTC.bit.BRPREG = 63;//29;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
ECanaShadow.CANBTC.bit.TSEG1REG = 9;//9;// 15; //5;//7;//14;//10;//7; // Bit time = 15
ECanaShadow.CANBTC.bit.TSEG2REG = 3;//4; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
ECanaShadow.CANBTC.bit.SJWREG = 3;//3;
// ECanaShadow.CANBTC.bit.BRPREG = 31;//29;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
// ECanaShadow.CANBTC.bit.TSEG1REG = 6;//9;// 15; //5;//7;//14;//10;//7; // Bit time = 15
// ECanaShadow.CANBTC.bit.TSEG2REG = 1;//4; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
// ECanaShadow.CANBTC.bit.SJWREG = 1;//3;
#else
#if (CAN_SPEED_BITS==250000)
// ECanaShadow.CANBTC.bit.BRPREG = 23;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
// ECanaShadow.CANBTC.bit.TSEG1REG = 15;// 15; //5;//7;//14;//10;//7; // Bit time = 15
// ECanaShadow.CANBTC.bit.TSEG2REG = 2; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
// ECanaShadow.CANBTC.bit.SJWREG = 1;
ECanaShadow.CANBTC.bit.BRPREG = 47;//29;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
ECanaShadow.CANBTC.bit.TSEG1REG = 6;//9;// 15; //5;//7;//14;//10;//7; // Bit time = 15
ECanaShadow.CANBTC.bit.TSEG2REG = 1;//4; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
ECanaShadow.CANBTC.bit.SJWREG = 1;//3;
ECanaShadow.CANBTC.bit.BRPREG = 23;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
ECanaShadow.CANBTC.bit.TSEG1REG = 15;// 15; //5;//7;//14;//10;//7; // Bit time = 15
ECanaShadow.CANBTC.bit.TSEG2REG = 2; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
#else
#if (CAN_SPEED_BITS==500000)
ECanaShadow.CANBTC.bit.BRPREG = 14;//11;//23;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
ECanaShadow.CANBTC.bit.TSEG1REG = 11;//12;//15;// 15; //5;//7;//14;//10;//7; // Bit time = 15
ECanaShadow.CANBTC.bit.TSEG2REG = 2; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
ECanaShadow.CANBTC.bit.SJWREG=1;
#else
#error "Set Can speed in CAN_project.h!!!"
#endif
#endif
#endif
ECanaShadow.CANBTC.bit.SJWREG=1;
ECanaRegs.CANBTC.all = ECanaShadow.CANBTC.all;
ECanaShadow.CANMC.all = ECanaRegs.CANMC.all;
@ -633,18 +598,18 @@ void InitCan(unsigned long can_base_adr_units, unsigned long can_base_adr_mpu, u
PieVectTable.ECAN0INTA = &CAN_handler;
PieCtrlRegs.PIEIER9.bit.INTx5=1; // PIE Group 9, INT6
ECanaShadow.CANGIM.bit.AAIM=1; //Abort Acknowledge Interrupt Mask.
ECanaShadow.CANGIM.bit.BOIM=1; // Bus-off interrupt mask
ECanaShadow.CANGIM.bit.EPIM=1; // Error-passive interrupt mask
ECanaShadow.CANGIM.bit.RMLIM=1; // Received-message-lost interrupt mask
ECanaShadow.CANGIM.bit.WUIM=1; // Wake-up interrupt mask
ECanaShadow.CANGIM.bit.WLIM=1; // Warning level interrupt mask
ECanaShadow.CANGIM.bit.WDIM=1; // Write denied interrupt mask
ECanaShadow.CANGIM.bit.TCOM=1; // Time stamp counter overflow mask
ECanaShadow.CANGIM.bit.AAIM=1;
ECanaShadow.CANGIM.bit.BOIM=1;
ECanaShadow.CANGIM.bit.EPIM=1;
ECanaShadow.CANGIM.bit.RMLIM=1;
ECanaShadow.CANGIM.bit.WUIM=1;
ECanaShadow.CANGIM.bit.WLIM=1;
ECanaShadow.CANGIM.bit.WDIM=1;
ECanaShadow.CANGIM.bit.TCOM=1;
ECanaShadow.CANGIM.bit.MTOM = 1; //Mailbox time-out interrupt mask
ECanaShadow.CANGIM.bit.I1EN = 1; //Interrupt 1 enable
ECanaShadow.CANGIM.bit.GIL = 1; // Global interrupt level for the interrupts TCOF, WDIF, WUIF, BOIF, EPIF, RMLIF, AAIF and WLIF.
ECanaShadow.CANGIM.bit.MTOM = 1;
ECanaShadow.CANGIM.bit.I1EN = 1;
ECanaShadow.CANGIM.bit.GIL = 1;
ECanaRegs.CANGIM.all = ECanaShadow.CANGIM.all;
PieVectTable.ECAN1INTA = &CAN_reset_err;
@ -673,14 +638,14 @@ void InitCan(unsigned long can_base_adr_units, unsigned long can_base_adr_mpu, u
for(i=0;i<UNIT_QUA;i++)
{
CAN_timeout[i]=1;
CAN_timeout_cicle[i] = MAX_CAN_WAIT_TIMEOUT;
CAN_refresh_cicle[i] = -1;
CAN_timeout_cicle[i]=0;
CAN_refresh_cicle[i]=0;
}
for(i=0;i<UNIT_QUA_UNITS;i++)
{
CAN_count_cycle_input_units[i] = 0;
CAN_count_cycle_input_units[i]=0;
for(c=0;c<UNIT_LEN;c++)
Unites[i][c]=0;
}
@ -690,7 +655,7 @@ void InitCan(unsigned long can_base_adr_units, unsigned long can_base_adr_mpu, u
{
// CAN_count_cycle_input_units[i]=0;
for(c=0;c<TERMINAL_UNIT_LEN;c++)
TerminalUnites[i][c] = 0;
TerminalUnites[i][c]=0;
}
@ -1321,7 +1286,7 @@ void CAN_cycle_send(int type_box, int box, unsigned long Addr, int * Data, unsig
////////////////////////////////////////////////////////////////
// èíêðåìåí ñ÷åò÷èêà ïîëíûõ ïîñûëîê äëÿ ÓÊÑÑ
// èíêðåìåí ñ÷åò÷èêà ïîëíûõ ïîñûëîê
////////////////////////////////////////////////////////////////
void detect_time_refresh_units(int box, int adr)
{
@ -1329,30 +1294,10 @@ void detect_time_refresh_units(int box, int adr)
return;
if (adr==unites_can_setup.adr_detect_refresh[box])
{
//CAN_count_cycle_input_units[box]++;
if (box<MAX_COUNT_UNITES_UKSS)
unites_can_setup.CAN_count_cycle_input_units[box]++;
}
CAN_count_cycle_input_units[box]++;
}
////////////////////////////////////////////////////////////////
// èíêðåìåí ñ÷åò÷èêà ïîëíûõ ïîñûëîê äëÿ ÌÏÓ
////////////////////////////////////////////////////////////////
void detect_time_refresh_mpu(int box, int adr)
{
if (box>=MPU_UNIT_QUA_UNITS)
return;
if (adr==mpu_can_setup.adr_detect_refresh[box])
{
//CAN_count_cycle_input_units[box]++;
if (box<MAX_COUNT_UNITES_MPU)
mpu_can_setup.CAN_count_cycle_input_units[box]++;
}
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
void messagePaserToUnitesIngitim(int box, unsigned long h_word, unsigned long l_word)
@ -1454,11 +1399,9 @@ void parse_data_from_mbox(unsigned int box, unsigned long hiword,
timer_pause_enable_can_from_mpu();
if (adr<SIZE_MODBUS_TABLE)
{
if (adr>0)
if ((adr>0) && flag_enable_can_from_mpu)
{
if (flag_enable_can_from_mpu && flag_disable_update_modbus_in_can_from_mpu==0)
modbus_table_can_in[adr-1].all = /*(unsigned int)*/((hiword ) & 0xffff);
detect_time_refresh_mpu(local_number_box,adr-1);
modbus_table_can_in[adr-1].all = /*(unsigned int)*/((hiword ) & 0xffff);
}
adr++;
}
@ -1472,11 +1415,9 @@ void parse_data_from_mbox(unsigned int box, unsigned long hiword,
timer_pause_enable_can_from_mpu();
if (adr<SIZE_MODBUS_TABLE)
{
if (adr>0)
if ((adr>0) && flag_enable_can_from_mpu)
{
if (flag_enable_can_from_mpu && flag_disable_update_modbus_in_can_from_mpu==0)
modbus_table_can_in[adr-1].all = /*(unsigned int)*/((loword>>16) & 0xffff);
detect_time_refresh_mpu(local_number_box,adr-1);
modbus_table_can_in[adr-1].all = /*(unsigned int)*/((loword>>16) & 0xffff);
}
adr++;
}
@ -1491,11 +1432,9 @@ void parse_data_from_mbox(unsigned int box, unsigned long hiword,
timer_pause_enable_can_from_mpu();
if (adr<SIZE_MODBUS_TABLE)
{
if (adr>0)
if ((adr>0) && flag_enable_can_from_mpu)
{
if (flag_enable_can_from_mpu && flag_disable_update_modbus_in_can_from_mpu==0)
modbus_table_can_in[adr-1].all = /*(unsigned int)*/((loword) & 0xffff);
detect_time_refresh_mpu(local_number_box,adr-1);
modbus_table_can_in[adr-1].all = /*(unsigned int)*/((loword) & 0xffff);
}
adr++;
}
@ -1625,11 +1564,11 @@ interrupt void CAN_handler(void)
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.can)
if (enable_profile_led1_can)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.can)
if (enable_profile_led2_can)
i_led2_on_off_special(1);
#endif
@ -1755,11 +1694,11 @@ interrupt void CAN_handler(void)
PieCtrlRegs.PIEIER9.all = TempPIEIER;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.can)
if (enable_profile_led1_can)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.can)
if (enable_profile_led2_can)
i_led2_on_off_special(0);
#endif
@ -1780,47 +1719,25 @@ interrupt void CAN_reset_err(void)
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.can)
if (enable_profile_led1_can)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.can)
if (enable_profile_led2_can)
i_led2_on_off_special(1);
#endif
EINT;
// ECanaShadow.CANGIM.bit.AAIM=1; //Abort Acknowledge Interrupt Mask.
// ECanaShadow.CANGIM.bit.BOIM=1; // Bus-off interrupt mask
// ECanaShadow.CANGIM.bit.EPIM=1; // Error-passive interrupt mask
// ECanaShadow.CANGIM.bit.RMLIM=1; // Received-message-lost interrupt mask
// ECanaShadow.CANGIM.bit.WUIM=1; // Wake-up interrupt mask
// ECanaShadow.CANGIM.bit.WLIM=1; // Warning level interrupt mask
// ECanaShadow.CANGIM.bit.WDIM=1; // Write denied interrupt mask
// ECanaShadow.CANGIM.bit.TCOM=1; // Time stamp counter overflow mask
//
// ECanaShadow.CANGIM.bit.MTOM = 1; //Mailbox time-out interrupt mask
if (ECanaRegs.CANGIF1.bit.AAIF1) // Abort-acknowledge interrupt flag
if (ECanaRegs.CANGIF1.bit.AAIF1)
{
ECanaRegs.CANAA.all = ECanaRegs.CANAA.all;
}
if (ECanaRegs.CANGIF1.bit.WDIF1) //Write-denied interrupt flag
if (ECanaRegs.CANGIF1.bit.WDIF1)
{
ECanaRegs.CANGIF1.bit.WDIF1=1;
}
if (ECanaRegs.CANGIF1.bit.BOIF1) // Bus off interrupt flag
{
ECanaRegs.CANGIF1.bit.BOIF1=1;
CanBusOffError++;
}
// ECanaRegs.CANTRR.all = 1;
CanTimeOutErrorTR++;
@ -1833,11 +1750,11 @@ interrupt void CAN_reset_err(void)
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.can)
if (enable_profile_led1_can)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.can)
if (enable_profile_led2_can)
i_led2_on_off_special(0);
#endif
@ -1888,311 +1805,6 @@ unsigned int test_can_live_terminal(int n)
void InitCanSoft(void)
{
struct ECAN_REGS ECanaShadow;
int i, c;
volatile struct MBOX *tmbox;
volatile Uint32 *tmoto;
unsigned long canme_bits = 0;
unsigned long canmd_bits = 0;
unsigned long canmim_bits = 0;
// Configure CAN pins using GPIO regs here
EALLOW;
// GpioMuxRegs.GPFMUX.bit.CANTXA_GPIOF6 = 1;
// GpioMuxRegs.GPFMUX.bit.CANRXA_GPIOF7 = 1;
// Configure the eCAN RX and TX pins for eCAN transmissions
// ECanaRegs.CANTIOC.all = 8; // only 3rd bit, TXFUNC, is significant
// ECanaRegs.CANRIOC.all = 8; // only 3rd bit, RXFUNC, is significant
// Specify that 8 bits will be sent/received
// for (c=0;c<32;c++)
// {
// tmbox = &ECanaMboxes.MBOX0 + c;
// tmbox->MSGCTRL.all = 0x00000008;
// }
// Disable all Mailboxes
// Required before writing the MSGIDs
// ECanaRegs.CANME.all = 0;
canme_bits = 0;
canmd_bits = 0;
canmim_bits = 0;
// receive+transive //Ura
for (c=0;c<32;c++)
{
if (mailboxs_can_setup.can_mbox_adr[c])
{
// tmbox = &ECanaMboxes.MBOX0 + c;
// if(mailboxs_can_setup.type_box[c] == UNITS_TYPE_BOX)
// {
//// tmbox->MSGID.bit.IDE = 0;
//// tmbox->MSGID.bit.STDMSGID = mailboxs_can_setup.can_mbox_adr[c];
// tmbox->MSGID.all = mailboxs_can_setup.can_mbox_adr[c];
// }
// else
// {
// if(mailboxs_can_setup.type_box[c] == CANOPEN_TYPE_BOX)
// {
// tmbox->MSGID.bit.IDE = 0;
// tmbox->MSGID.bit.STDMSGID = mailboxs_can_setup.can_mbox_adr[c];
// //tmbox->MSGID.all = mailboxs_can_setup.can_mbox_adr[c];
// }
// else
// tmbox->MSGID.all = mailboxs_can_setup.can_mbox_adr[c];
// }
canme_bits |= ((unsigned long)1<<c); // set select box bits
canmim_bits |= ((unsigned long)1<<c); // set interrupt bits
if (mailboxs_can_setup.type_in_out_box[c] == CAN_BOX_TYPE_IN)
{
canmd_bits |= ((unsigned long)1<<c); // set receive bits
}
if (mailboxs_can_setup.type_in_out_box[c] == CAN_BOX_TYPE_OUT)
{
}
}
}
// Ðåæèì ðàáîòû þùèêîâ (ïðè¸ì-ïåðåäà÷à)
// ECanaRegs.CANMD.all = canmd_bits;//0x0000FFFF;
// Âûáèðàåì þùèêè äëó ðàáîòû
// ECanaRegs.CANME.all = canme_bits;
// Clear all TAn bits
ECanaRegs.CANTA.all = 0xFFFFFFFF;
// Clear all RMPn bits
ECanaRegs.CANRMP.all = 0xFFFFFFFF;
// Clear all interrupt flag bits
ECanaRegs.CANGIF0.all = 0xFFFFFFFF;
ECanaRegs.CANGIF1.all = 0xFFFFFFFF;
// Clear all error and status bits
ECanaRegs.CANES.all=0xffffffff;
ECanaRegs.CANMIM.all = 0xFFFFFFFF;
// Request permission to change the configuration registers
ECanaShadow.CANMC.all = ECanaRegs.CANMC.all;
ECanaShadow.CANMC.all = 0;
ECanaShadow.CANMC.bit.MBCC = 1; // Mailbox timestamp counter clear bit
ECanaShadow.CANMC.bit.TCC = 1; // Time stamp counter MSB clear bit
ECanaShadow.CANMC.bit.SCB = 1; // eCAN mode (reqd to access 32 mailboxes)
ECanaShadow.CANMC.bit.WUBA = 1; // Wake up on bus activity
ECanaShadow.CANMC.bit.ABO = 1; // Auto bus on
ECanaShadow.CANMC.bit.CCR = 1;
// ECanaShadow.CANMC.bit.CCE = 0;
// ECanaShadow.CANMC.bit.STM = 1; // self-test loop-back
ECanaRegs.CANMC.all = ECanaShadow.CANMC.all;
EDIS;
do
{
ECanaShadow.CANES.all = ECanaRegs.CANES.all;
} while(ECanaShadow.CANES.bit.CCE != 1 ); // Wait for CCE bit to be set..
// while(!ECanaRegs.CANES.bit.CCE);
// íàñòðèâàåì ñêîðîñòü CAN
EALLOW;
/*
EALLOW;
ECanaShadow.CANBTC.all = ECanaRegs.CANBTC.all;
#if (CAN_SPEED_BITS==125000)
// ECanaShadow.CANBTC.bit.BRPREG = 23;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
// ECanaShadow.CANBTC.bit.TSEG1REG = 15;// 15; //5;//7;//14;//10;//7; // Bit time = 15
// ECanaShadow.CANBTC.bit.TSEG2REG = 2; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
// ECanaShadow.CANBTC.bit.SJWREG=1;
ECanaShadow.CANBTC.bit.BRPREG = 63;//29;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
ECanaShadow.CANBTC.bit.TSEG1REG = 9;//9;// 15; //5;//7;//14;//10;//7; // Bit time = 15
ECanaShadow.CANBTC.bit.TSEG2REG = 3;//4; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
ECanaShadow.CANBTC.bit.SJWREG = 3;//3;
#else
#if (CAN_SPEED_BITS==250000)
// ECanaShadow.CANBTC.bit.BRPREG = 23;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
// ECanaShadow.CANBTC.bit.TSEG1REG = 15;// 15; //5;//7;//14;//10;//7; // Bit time = 15
// ECanaShadow.CANBTC.bit.TSEG2REG = 2; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
// ECanaShadow.CANBTC.bit.SJWREG = 1;
ECanaShadow.CANBTC.bit.BRPREG = 47;//29;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
ECanaShadow.CANBTC.bit.TSEG1REG = 6;//9;// 15; //5;//7;//14;//10;//7; // Bit time = 15
ECanaShadow.CANBTC.bit.TSEG2REG = 1;//4; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
ECanaShadow.CANBTC.bit.SJWREG = 1;//3;
#else
#if (CAN_SPEED_BITS==500000)
ECanaShadow.CANBTC.bit.BRPREG = 14;//11;//23;//11;// 47; //59;//49;//4;//9; // (BRPREG + 1) = 10 feeds a 15 MHz CAN clock
ECanaShadow.CANBTC.bit.TSEG1REG = 11;//12;//15;// 15; //5;//7;//14;//10;//7; // Bit time = 15
ECanaShadow.CANBTC.bit.TSEG2REG = 2; // 2; //4;//5;//7;//2;//5 ; // to the CAN module. (150 / 10 = 15)
ECanaShadow.CANBTC.bit.SJWREG=1;
#else
#error "Set Can speed in CAN_project.h!!!"
#endif
#endif
#endif
ECanaRegs.CANBTC.all = ECanaShadow.CANBTC.all;
*/
ECanaShadow.CANMC.all = ECanaRegs.CANMC.all;
ECanaShadow.CANMC.bit.CCR = 0; // Set CCR = 0
ECanaRegs.CANMC.all = ECanaShadow.CANMC.all;
EDIS;
// Wait until the CPU no longer has permission to change the
// configuration registers
do
{
ECanaShadow.CANES.all = ECanaRegs.CANES.all;
} while(ECanaShadow.CANES.bit.CCE != 0 );
// while(ECanaRegs.CANES.bit.CCE); // Wait for CCE bit to be cleared..
EALLOW;
// çàäàåì òàéìàóòû äëà îæèäàíèà îòïðàâêè ïîëó÷åíèà ïîñûëêè
for (c=0;c<32;c++)
{
tmoto = &ECanaMOTORegs.MOTO0 + c;
(*(volatile Uint32 *)( tmoto )) = 550000;
}
ECanaRegs.CANTOC.all = 0;//0x000000ff;
ECanaRegs.CANTOS.all = 0; // clear all time-out flags
ECanaRegs.CANTSC = 0; // clear time-out counter
ECanaShadow.CANGIM.all = 0;
ECanaRegs.CANMIM.all = canmim_bits; // 26.01.2011 Dimas
ECanaRegs.CANMIL.all = 0x00000000; // All mailbox interrupts are generated on interrupt line 0.
ECanaShadow.CANGIM.bit.I0EN = 1;
// PieVectTable.ECAN0INTA = &CAN_handler;
PieCtrlRegs.PIEIER9.bit.INTx5=1; // PIE Group 9, INT6
ECanaShadow.CANGIM.bit.AAIM=1; //Abort Acknowledge Interrupt Mask.
ECanaShadow.CANGIM.bit.BOIM=1; // Bus-off interrupt mask
ECanaShadow.CANGIM.bit.EPIM=1; // Error-passive interrupt mask
ECanaShadow.CANGIM.bit.RMLIM=1; // Received-message-lost interrupt mask
ECanaShadow.CANGIM.bit.WUIM=1; // Wake-up interrupt mask
ECanaShadow.CANGIM.bit.WLIM=1; // Warning level interrupt mask
ECanaShadow.CANGIM.bit.WDIM=1; // Write denied interrupt mask
ECanaShadow.CANGIM.bit.TCOM=1; // Time stamp counter overflow mask
ECanaShadow.CANGIM.bit.MTOM = 1; //Mailbox time-out interrupt mask
ECanaShadow.CANGIM.bit.I1EN = 1; //Interrupt 1 enable
ECanaShadow.CANGIM.bit.GIL = 1; // Global interrupt level for the interrupts TCOF, WDIF, WUIF, BOIF, EPIF, RMLIF, AAIF and WLIF.
ECanaRegs.CANGIM.all = ECanaShadow.CANGIM.all;
// PieVectTable.ECAN1INTA = &CAN_reset_err;
PieCtrlRegs.PIEIER9.bit.INTx6=1; // PIE Group 9, INT6
// çàâåðøèëè íàñòðîéêó CAN àùèêîâ
// for(i=0;i<UNIT_QUA;i++)
// {
// cycle[i].busy = 0;
// cycle[i].FLY = 0;
// cycle[i].extended = 0;
// cycle[i].adr = 0;
// cycle[i].adr_from = 0;
// cycle[i].adr_to = 0;
// cycle[i].quant = 0;
// }
//
// fifo.adr=0;
// refo.adr=0;
CanTimeOutErrorTR=0;
// for(i=0;i<UNIT_QUA;i++)
// {
// CAN_timeout[i]=1;
// CAN_timeout_cicle[i] = MAX_CAN_WAIT_TIMEOUT;
// CAN_refresh_cicle[i] = -1;
// }
// for(i=0;i<UNIT_QUA_UNITS;i++)
// {
// CAN_count_cycle_input_units[i] = 0;
// for(c=0;c<UNIT_LEN;c++)
// Unites[i][c]=0;
// }
//
//
// for(i=0;i<TERMINAL_UNIT_QUA_UNITS;i++)
// {
// for(c=0;c<TERMINAL_UNIT_LEN;c++)
// TerminalUnites[i][c] = 0;
// }
//
// new_cycle_fifo.index_data = 0;
// new_cycle_fifo.index_send = 0;
// new_cycle_fifo.count_lost = 0;
// new_cycle_fifo.count_load = 0;
// new_cycle_fifo.count_free = 0;
// new_cycle_fifo.flag_inter = 0;
//
// for(i=0;i<NEW_CYCLE_FIFO_LEN;i++)
// {
// new_cycle_fifo.cycle_data[i].busy = 0;
// new_cycle_fifo.cycle_data[i].FLY = 0;
// new_cycle_fifo.cycle_data[i].extended = 0;
// new_cycle_fifo.cycle_data[i].adr = 0;
// new_cycle_fifo.cycle_data[i].adr_from = 0;
// new_cycle_fifo.cycle_data[i].adr_to = 0;
// new_cycle_fifo.cycle_data[i].quant = 0;
// new_cycle_fifo.cycle_data[i].box = 0;
// new_cycle_fifo.cycle_data[i].priority = 0;
// new_cycle_fifo.cycle_data[i].quant_block = 0;
// }
//
//
// for(i=0;i<UNIT_QUA;i++)
// {
// new_cycle_fifo.cycle_box[i] = 0;
// new_cycle_fifo.lost_box[i] = 0;
// }
//
//IER |= M_INT9; // Enable CPU INT
// EDIS;
enable_can_recive_after_units_box = 1;
}
/*
//===========================================================================
// No more.

View File

@ -473,8 +473,6 @@ typedef struct {
int adr_detect_refresh[MAX_COUNT_UNITES_UKSS];
int revers_box[MAX_COUNT_UNITES_UKSS];
unsigned int CAN_count_cycle_input_units[MAX_COUNT_UNITES_UKSS];
int max_number;
} UNITES_CAN_SETUP;
@ -492,11 +490,6 @@ typedef struct {
int active_box[MAX_COUNT_UNITES_MPU];
unsigned int CAN_count_cycle_input_units[MAX_COUNT_UNITES_MPU];
int adr_detect_refresh[MAX_COUNT_UNITES_MPU];
int max_number;
} MPU_CAN_SETUP;
@ -514,8 +507,6 @@ typedef struct {
int active_box[MAX_COUNT_UNITES_TERMINAL];
unsigned int CAN_count_cycle_input_units[MAX_COUNT_UNITES_TERMINAL];
int max_number;
} TERMINAL_CAN_SETUP;
@ -534,69 +525,52 @@ typedef struct {
int active_box[MAX_COUNT_UNITES_ALARM_LOG];
unsigned int CAN_count_cycle_input_units[MAX_COUNT_UNITES_ALARM_LOG];
int max_number;
} ALARM_LOG_CAN_SETUP;
////////////////////////////////////////////////////////////////////////////////
#define _UNITS_DEFAULT_ZERO {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
#define _UNITS_DEFAULT_MINUS_ONE {-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}
#define UNITES_CAN_SETUP_DEFAULT { START_CAN_ADR_UNITS_DEFAULT, _UNITS_DEFAULT_ZERO, \
_UNITS_DEFAULT_ZERO, \
_UNITS_DEFAULT_MINUS_ONE, \
_UNITS_DEFAULT_MINUS_ONE, \
_UNITS_DEFAULT_MINUS_ONE, \
#define UNITES_CAN_SETUP_DEFAULT { START_CAN_ADR_UNITS_DEFAULT, {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}, \
{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}, \
{-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}, \
{-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}, \
{-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}, \
{USE_UKSS_0,USE_UKSS_1,USE_UKSS_2,USE_UKSS_3,USE_UKSS_4,USE_UKSS_5, \
USE_UKSS_6,USE_UKSS_7,USE_UKSS_8,USE_UKSS_9,USE_UKSS_10, \
USE_UKSS_11,USE_UKSS_12,USE_UKSS_13,USE_UKSS_14,USE_UKSS_15}, \
_UNITS_DEFAULT_ZERO, \
{USE_R_B_0,USE_R_B_1,USE_R_B_2,USE_R_B_3,USE_R_B_4,USE_R_B_5,USE_R_B_6,USE_R_B_7,USE_R_B_8, \
USE_R_B_9,USE_R_B_10,USE_R_B_11,USE_R_B_12,USE_R_B_13,USE_R_B_14,USE_R_B_15}, \
_UNITS_DEFAULT_ZERO, \
USE_UKSS_6,USE_UKSS_7,USE_UKSS_8,USE_UKSS_9,USE_UKSS_10, \
USE_UKSS_11,USE_UKSS_12,USE_UKSS_13,USE_UKSS_14,USE_UKSS_15}, \
{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}, \
{USE_R_B_0,USE_R_B_1,USE_R_B_2,USE_R_B_3,USE_R_B_4,USE_R_B_5,USE_R_B_6,USE_R_B_7,USE_R_B_8,USE_R_B_9,USE_R_B_10,USE_R_B_11,USE_R_B_12,USE_R_B_13,USE_R_B_14,USE_R_B_15}, \
0}
/////////////////////////////////////////////////////////////////////
#define _MPU_DEFAULT_ZERO {0,0,0,0}
#define _MPU_DEFAULT_MINUS_ONE {-1,-1,-1,-1}
#define MPU_CAN_SETUP_DEFAULT { CAN_ADR_MPU_DEFAULT, _MPU_DEFAULT_ZERO, \
_MPU_DEFAULT_ZERO, \
_MPU_DEFAULT_MINUS_ONE, \
_MPU_DEFAULT_MINUS_ONE, \
_MPU_DEFAULT_MINUS_ONE, \
#define MPU_CAN_SETUP_DEFAULT { CAN_ADR_MPU_DEFAULT, {0,0,0,0}, \
{0,0,0,0}, \
{-1,-1,-1,-1}, \
{-1,-1,-1,-1}, \
{-1,-1,-1,-1}, \
{USE_MPU_0,USE_MPU_1,USE_MPU_2,USE_MPU_3}, \
_MPU_DEFAULT_ZERO, \
_MPU_DEFAULT_ZERO, \
0}
//-------------------------------------------------------------------------------//
#define _TERMINAL_DEFAULT_ZERO {0,0,0,0}
#define _TERMINAL_DEFAULT_MINUS_ONE {-1,-1,-1,-1}
#define TERMINAL_CAN_SETUP_DEFAULT {CAN_ADR_TERMINAL_DEFAULT, _TERMINAL_DEFAULT_ZERO, \
_TERMINAL_DEFAULT_ZERO, \
_TERMINAL_DEFAULT_MINUS_ONE, \
_TERMINAL_DEFAULT_MINUS_ONE, \
_TERMINAL_DEFAULT_MINUS_ONE, \
#define TERMINAL_CAN_SETUP_DEFAULT {CAN_ADR_TERMINAL_DEFAULT, {0,0,0,0}, \
{0,0,0,0}, \
{-1,-1,-1,-1}, \
{-1,-1,-1,-1}, \
{-1,-1,-1,-1}, \
{USE_TERMINAL_1_OSCIL,USE_TERMINAL_1_CMD,USE_TERMINAL_2_OSCIL,USE_TERMINAL_2_CMD}, \
_TERMINAL_DEFAULT_ZERO, \
0}
//-------------------------------------------------------------------------------//
#define _ALARM_LOG_DEFAULT_ZERO {0,0}
#define _ALARM_LOG_DEFAULT_MINUS_ONE {-1,-1}
#define ALARM_LOG_CAN_SETUP_DEFAULT {CAN_ADR_ALARM_LOG_DEFAULT, _ALARM_LOG_DEFAULT_ZERO, \
_ALARM_LOG_DEFAULT_ZERO, \
_ALARM_LOG_DEFAULT_MINUS_ONE, \
_ALARM_LOG_DEFAULT_MINUS_ONE, \
_ALARM_LOG_DEFAULT_MINUS_ONE, \
#define ALARM_LOG_CAN_SETUP_DEFAULT {CAN_ADR_ALARM_LOG_DEFAULT, {0,0}, \
{0,0}, \
{-1,-1}, \
{-1,-1}, \
{-1,-1}, \
{USE_ALARM_LOG_0,USE_ALARM_LOG_1}, \
_ALARM_LOG_DEFAULT_ZERO, \
0}
////////////////////////////////////////////////////////////////////////////////
@ -631,7 +605,7 @@ extern FIFO fifo;
extern int CAN_timeout[];
extern int CAN_request_sent[];
extern unsigned int CAN_timeout_cicle[];
extern int CAN_timeout_cicle[];
//////////////////////////////////////////////////
@ -689,14 +663,12 @@ void inc_CAN_timeout_cicle();
unsigned int test_can_live_mpu(void);
unsigned int test_can_live_terminal(int n);
void InitCanSoft(void);
void timer_pause_enable_can_from_mpu(void);
void timer_pause_enable_can_from_terminal(void);
void read_manch_can(void);
void write_manch_can(void);
void detect_time_refresh_units(int box, int adr);
void detect_time_refresh_mpu(int box, int adr);
@ -741,11 +713,6 @@ interrupt void CAN_reset_err(void);
extern UNITES_CAN_SETUP unites_can_setup;
extern MPU_CAN_SETUP mpu_can_setup;
extern unsigned int CanTimeOutErrorTR;
extern unsigned int CanBusOffError;
#endif // _CAN_SETUP

View File

@ -11,16 +11,16 @@
//#pragma DATA_SECTION(p_analog_data_in, ".logs");
#pragma DATA_SECTION(p_analog_data_in, ".logs");
MODBUS_REG_STRUCT *p_analog_data_in;
//#pragma DATA_SECTION(p_analog_data_out, ".logs");
#pragma DATA_SECTION(p_analog_data_out, ".logs");
MODBUS_REG_STRUCT *p_analog_data_out;
//#pragma DATA_SECTION(p_discrete_data_out, ".logs");
#pragma DATA_SECTION(p_discrete_data_out, ".logs");
MODBUS_REG_STRUCT *p_discrete_data_out;
//#pragma DATA_SECTION(p_discrete_data_in, ".logs");
#pragma DATA_SECTION(p_discrete_data_in, ".logs");
MODBUS_REG_STRUCT *p_discrete_data_in;
static int adres_wait_answer_cmd1 = 0;
@ -73,7 +73,6 @@ void ModbusRTUsend1(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_star
rs_arr->buffer[9] = 0;
rs_arr->RS_DataWillSend = 1;
rs_arr->RS_DataWillSend2 = 1;
RS_Send(rs_arr, rs_arr->buffer, 10);
@ -261,7 +260,6 @@ void ModbusRTUsend3(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_star
rs_arr->buffer[9] = 0;
rs_arr->RS_DataWillSend = 1;
rs_arr->RS_DataWillSend2 = 1;
RS_Send(rs_arr, rs_arr->buffer, 10);
@ -353,7 +351,6 @@ void ModbusRTUsend4(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_star
rs_arr->buffer[9] = 0;
rs_arr->RS_DataWillSend = 1;
rs_arr->RS_DataWillSend2 = 1;
RS_Send(rs_arr, rs_arr->buffer, 10);
@ -515,7 +512,6 @@ void ModbusRTUsend5(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_star
rs_arr->buffer[8] = 0;
rs_arr->buffer[9] = 0;
rs_arr->RS_DataWillSend = 1;
rs_arr->RS_DataWillSend2 = 1;
RS_Send(rs_arr, rs_arr->buffer, 10);
/* æäåì îòâåòà */
@ -590,7 +586,6 @@ void ModbusRTUsend6(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_star
rs_arr->buffer[9] = 0;
rs_arr->RS_DataWillSend = 1;
rs_arr->RS_DataWillSend2 = 1;
RS_Send(rs_arr, rs_arr->buffer, 10);
// control_station.flag_waiting_answer[CONTROL_STATION_INGETEAM_PULT_RS485] = 1;
@ -722,7 +717,6 @@ void ModbusRTUsend15(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_sta
rs_arr->buffer[count_data_bytes + 10] = 0;
rs_arr->RS_DataWillSend = 1;
rs_arr->RS_DataWillSend2 = 1;
// RS_Send(rs_arr, rs_arr->buffer, (count_data_bytes + 10 + 2));
RS_Send(rs_arr, rs_arr->buffer, (count_data_bytes + 10));
@ -885,7 +879,6 @@ void ModbusRTUsend16(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_sta
rs_arr->buffer[count_word * 2 + 10] = 0;
rs_arr->RS_DataWillSend = 1;
rs_arr->RS_DataWillSend2 = 1;
RS_Send(rs_arr, rs_arr->buffer, (count_word * 2 + 10));
// control_station.flag_waiting_answer[CONTROL_STATION_INGETEAM_PULT_RS485] = 1;
@ -893,7 +886,6 @@ void ModbusRTUsend16(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_sta
// æäåì îòâåòà
if (adr_contr > 0 && adr_contr < 0xff)
{
//rs_arr->RS_Length = -1;
RS_Len[CMD_RS232_MODBUS_16] = 8;
RS_SetControllerLeading(rs_arr, true);
RS_SetAdrAnswerController(rs_arr, adr_contr);

View File

@ -15,10 +15,3 @@ float build_time_f = BUILD_TIME;
int build_data_i = (BUILD_DATA*1000);
int build_time_i = (BUILD_TIME*1000);
int build_year = BUILD_YEAR;
int build_month = BUILD_MONTH;
int build_day = BUILD_DAY;

View File

@ -23,8 +23,4 @@ extern int build_data_i;
extern int build_time_i;
extern int build_year, build_month, build_day;
#endif /* SRC_N12_LIBS_BUILD_VERSION_H_ */

View File

@ -20,7 +20,7 @@ CONTROL_STATION control_station = CONTROL_STATION_DEFAULTS;
void control_station_clear(CONTROL_STATION_handle cs)
{
int i,k,j;
int i,k;
for (i=0;i<COUNT_CONTROL_STATION;i++)
{
@ -49,21 +49,10 @@ void control_station_clear(CONTROL_STATION_handle cs)
cs->time_detect_answer_485[i] = 0;
for (k=0;k<CONTROL_STATION_MAX_RAW_DATA;k++)
{
cs->raw_array_data[i][k].all = 0;
for (j=0;j<CONTROL_STATION_MAX_RAW_DATA_TEMP;j++)
cs->raw_array_data_temp[i][k][j].all = 0;
}
cs->flag_refresh_array[i] = 0;
cs->prev_CAN_count_cycle_input_units[i] = 0;
cs->count_raw_array_data_temp[i] = 0;
}
for (k=0;k<CONTROL_STATION_CMD_LAST;k++)
cs->active_array_cmd[k] = 0;
}
///////////////////////////////////////////////////////////////////

View File

@ -30,8 +30,7 @@
#define CONTROL_STATION_SETUP_TIME_DETECT_ACTIVE_RESEND_485 2 // â òèêàõ îò CONTROL_STATION_TIME_WAIT
#define CONTROL_STATION_SETUP_TIME_SEND_CMD_AFTER_OFF 5 // â òèêàõ îò CONTROL_STATION_TIME_WAIT
#define CONTROL_STATION_MAX_RAW_DATA 256 //128 // ìàêñèìàëüíîå êîë-âî äàííûõ äëÿ ñûðûõ äàííûõ ïîëó÷åííûõ îò ïîñòîâ
#define CONTROL_STATION_MAX_RAW_DATA_TEMP 3 //128 // ñêîëüêî äàííûõ õðàíèì äëÿ âðåìåííîãî áóôåðà
#define CONTROL_STATION_MAX_RAW_DATA 256 //128 // максимальное кол-во данных для сырых данных полученных от постов
//////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////
@ -59,7 +58,6 @@ typedef struct {
int active_array_cmd[CONTROL_STATION_CMD_LAST]; // ìàññèâ äàííûõ àêòóàëüíûõ äëÿ àâòèâíîãî ïîñòà, äàííûå ïîñëå parse
WORD_UINT2BITS_STRUCT raw_array_data[COUNT_CONTROL_STATION][CONTROL_STATION_MAX_RAW_DATA]; // ñûðîé ìàññèâ äàííûõ ïîëó÷åííûõ îò êàæäîãî èç ïîñòîâ, áåç parse.
WORD_UINT2BITS_STRUCT raw_array_data_temp[COUNT_CONTROL_STATION][CONTROL_STATION_MAX_RAW_DATA][CONTROL_STATION_MAX_RAW_DATA_TEMP]; // âðåìåííûé ñûðîé ìàññèâ äàííûõ ïîëó÷åííûõ îò êàæäîãî èç ïîñòîâ, áåç parse.
unsigned int flag_message_sent[COUNT_CONTROL_STATION]; // ôëàã íà îæèäàíèå îòâåòà ïî ñèñòåìå çàïðîñ-îòâåò
unsigned int flag_waiting_answer[COUNT_CONTROL_STATION]; // îæèäàòü ëè îòâåò ïî ñèñòåìå çàïðîñ-îòâåò
@ -78,8 +76,6 @@ typedef struct {
unsigned int cmd_checkback_from_control_station[COUNT_CONTROL_STATION]; // êâèòèðîâàíèå îò ïîñòà
unsigned int cmd_test_leds_from_control_station[COUNT_CONTROL_STATION]; // òåñò ëàìï îò ïîñòà
*/
unsigned int prev_CAN_count_cycle_input_units[COUNT_CONTROL_STATION]; // ïðåä êîë-âî îáíîâëåíèé èç CAN
unsigned int count_raw_array_data_temp[COUNT_CONTROL_STATION]; // èíäåêñ ïåðåáîðà ïî CONTROL_STATION_MAX_RAW_DATA_TEMP
void (*clear)(); // Clear buffers
void (*update_timers)(); // Îáíóëÿåì òàéìåðû íà ïîñòàõ ñ êîòîðûìè åñòü îáìåí
@ -109,9 +105,6 @@ typedef CONTROL_STATION *CONTROL_STATION_handle;
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
control_station_clear, \
control_station_update_timers, \
control_station_detect_active_station \

View File

@ -278,9 +278,6 @@ _iq19 exp_regul_iq19(_iq19 k_exp_regul, _iq19 InpVarCurr, _iq19 InpVarInstant)
#pragma CODE_SECTION(exp_regul_iq,".fast_run");
//
// Tñåê = Tïåðèîä/k_exp_regul
//
_iq exp_regul_iq(_iq k_exp_regul, _iq InpVarFiltered, _iq InpVarInstant)
{
_iq t1;

View File

@ -65,6 +65,9 @@ void exp_regul_iq_fast(_iq k_exp_regul, _iq *InpVarCurr, _iq InpVarInstant);
#ifdef __cplusplus
}
#endif

View File

@ -7,13 +7,9 @@ GLOBAL_TIME global_time = GLOBAL_TIME_DEFAULTS;
void init_global_time_struct(unsigned int freq_pwm)
{
global_time.total_seconds = 0;
global_time.total_seconds10 = 0;
global_time.total_seconds10full = 0;
global_time.microseconds = 0;
global_time.microseconds_temp = 0;
global_time.pwm_tics = 0;
global_time.miliseconds = 0;
global_time.miliseconds_long = 0;
global_time.seconds = 0;
global_time.minuts = 0;
global_time.hours = 0;
@ -24,40 +20,14 @@ void init_global_time_struct(unsigned int freq_pwm)
#pragma CODE_SECTION(global_time_calc,".fast_run2");
void global_time_calc(GLOBAL_TIME_handle gt)
{
unsigned int miliseconds_temp = 0;
static unsigned int miliseconds_temp10 = 0;
gt->pwm_tics++;
gt->microseconds += gt->microseconds_add;
gt->microseconds_temp += gt->microseconds_add;
if (gt->microseconds_temp>=1000)
{
if (gt->microseconds_temp>=2000)
{
miliseconds_temp = gt->microseconds_temp/1000;
gt->microseconds_temp -= miliseconds_temp*1000;
}
else
{
miliseconds_temp = 1;
gt->microseconds_temp -= 1000;
}
}
// gt->miliseconds = gt->microseconds / 1000;
gt->miliseconds += miliseconds_temp;
miliseconds_temp10 += miliseconds_temp;
gt->miliseconds = gt->microseconds / 1000;
if(gt->pwm_tics == gt->freq_pwm_hz)
{
gt->total_seconds++;
gt->total_seconds10 += 10;
gt->seconds++;
gt->pwm_tics = 0;
miliseconds_temp10 = 0;
if(gt->seconds == 60)
{
@ -71,9 +41,6 @@ void global_time_calc(GLOBAL_TIME_handle gt)
}
}
}
//gt->total_seconds10 += 10;
gt->total_seconds10full = gt->total_seconds10 + miliseconds_temp10/100;
}
@ -90,17 +57,9 @@ void init_timer_milisec(unsigned int *start_time)
int detect_pause_sec(unsigned int wait_pause, unsigned int *old_time)
{
unsigned long delta;
delta = (unsigned int)((unsigned int)global_time.total_seconds - *old_time);
if(global_time.total_seconds >= *old_time)
{
delta = (unsigned int)((unsigned int)global_time.total_seconds - *old_time);
}
else
{
delta = (unsigned int)((unsigned int)global_time.total_seconds + (0xFFFFUL - *old_time));
}
if (delta>=wait_pause)
if (delta>wait_pause)
{
*old_time = (unsigned int)global_time.total_seconds;
return 1;
@ -121,7 +80,7 @@ int detect_pause_milisec(unsigned int wait_pause, unsigned int *old_time)
delta = (unsigned int)((unsigned int)global_time.miliseconds + (0xFFFFUL - *old_time));
}
if (delta>=wait_pause)
if (delta>wait_pause)
{
*old_time = (unsigned int)global_time.miliseconds;
return 1;
@ -129,21 +88,3 @@ int detect_pause_milisec(unsigned int wait_pause, unsigned int *old_time)
else
return 0;
}
unsigned int get_delta_milisec(unsigned int *old_time, unsigned int upd)
{
unsigned long delta;
if(global_time.miliseconds >= *old_time)
{
delta = (unsigned int)((unsigned int)global_time.miliseconds - *old_time);
}
else
{
delta = (unsigned int)((unsigned int)global_time.miliseconds + (0xFFFFUL - *old_time));
}
if (upd)
*old_time = (unsigned int)global_time.miliseconds;
return delta;
}

View File

@ -3,13 +3,8 @@
typedef struct {
unsigned long total_seconds; //Âñåãî ñåêóíä ñ ìîìåíòà âêëþ÷åíèß
unsigned long total_seconds10; //Âñåãî ñåêóíä ñ ìîìåíòà âêëþ÷åíèß ñ äåñÿòûìè
unsigned long total_seconds10full; //Âñåãî ñåêóíä ñ ìîìåíòà âêëþ÷åíèß ñ äåñÿòûìè
unsigned long microseconds;
unsigned int microseconds_temp;
unsigned int miliseconds; //???
unsigned long miliseconds_long; //???
unsigned int pwm_tics;
unsigned int seconds;
unsigned int minuts;
@ -30,11 +25,7 @@ Default initalizer for the GLOBAL_TIME object.
#define GLOBAL_TIME_DEFAULTS { 0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
@ -53,6 +44,5 @@ void init_timer_sec(unsigned int *start_time); //
void init_timer_milisec(unsigned int *start_time); //Èíèöèàëèçèðóåò ïåðåìåííóþ, âðåìß ñòàðòà â ìèëèñåêóíäàõ
int detect_pause_sec(unsigned int wait_pause, unsigned int *old_time); //ïàóçà â ñåêóíäàõ
int detect_pause_milisec(unsigned int wait_pause, unsigned int *old_time); //Ïàóçà â ìèëèñåêóíäàõ (íå áîëåå 60000ìëñåê)
unsigned int get_delta_milisec(unsigned int *old_time, unsigned int upd); // âåðíóëè ñêîëüêî âðåìåíè ïðîøëî îò âðåìåíè old_time ; upd=1 - îáíîâèòü old_time - òåêóùèì
#endif //_GLOBAL_TIME

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,22 +0,0 @@
/*
* iq_values_norma.h
*
* Created on: 9 èþë. 2024 ã.
* Author: Evgeniy_Sokolov
*/
#ifndef _IQ_VALUES_N_H_
#define _IQ_VALUES_N_H_
#include "params_norma.h"
#if (NORMA_MZZ_INT==3000)
#endif
#endif /* _IQ_VALUES_NORMA_N_H_ */

View File

@ -1,149 +0,0 @@
#include "log_params.h"
#include "log_to_memory.h"
#include "MemoryFunctions.h"
//#pragma DATA_SECTION(log_params, ".fast_vars");
TYPE_LOG_PARAMS log_params = TYPE_LOG_PARAMS_DEFAULT;
void defineVarsErrSlowLogs(void)
{
//volatile static
unsigned long l1;
//fastlog
log_params.volume_of_fast_log = VOLUME_OF_FAST_LOG;
log_params.start_address_log = START_ADDRESS_LOG;
l1 = (unsigned long)(log_params.BlockSizeErr*VOLUME_OF_FAST_LOG);
// l1 = (unsigned long)(VOLUME_OF_FAST_LOG) * l1;
log_params.end_address_log = (unsigned long)log_params.start_address_log + (unsigned long)l1 - 1;
// âûðàâíèâàåì êîíåö áëîêà åñëè âûøåë çà ãðàíèöû
while (log_params.end_address_log >= START_ADDRESS_LOG_SLOW)
{
log_params.end_address_log -= log_params.BlockSizeErr;
log_params.volume_of_fast_log--;
}
l1 = (unsigned long)(log_params.volume_of_fast_log/3);
l1 = (unsigned long)(log_params.BlockSizeErr*l1);
log_params.end_address_log_level_1 = (unsigned long)log_params.start_address_log + (unsigned long)l1 - 1;
log_params.end_address_log_level_2 = log_params.end_address_log_level_1 + (unsigned long)l1 - 1;
//slow log
log_params.volume_of_slow_log = VOLUME_OF_SLOW_LOG;
log_params.start_address_log_slow = ((unsigned long)log_params.end_address_log + 0x1);
l1 = (unsigned long)VOLUME_OF_SLOW_LOG * (unsigned long)log_params.BlockSizeSlow;
log_params.end_address_log_slow = ((unsigned long)log_params.start_address_log_slow + l1 - 1);
// âûðàâíèâàåì êîíåö áëîêà åñëè âûøåë çà ãðàíèöû
while (log_params.end_address_log_slow >= END_ADDRESS_LOGS)
{
log_params.end_address_log_slow -= log_params.BlockSizeSlow;
log_params.volume_of_slow_log--;
}
l1 = (unsigned long)(log_params.volume_of_slow_log/3);
l1 = (unsigned long)(log_params.BlockSizeSlow*l1);
log_params.end_address_log_slow_level_1 = (unsigned long)log_params.start_address_log_slow + (unsigned long)l1 - 1;
log_params.end_address_log_slow_level_2 = log_params.end_address_log_slow_level_1 + (unsigned long)l1 - 1;
// log_params.start_address_save_log_memory = START_ADDRESS_SAVE_ON_ALARM;
// log_params.end_address_save_log_memory = END_ADDRESS_LOGS;
// log_params.end_address_log_slow_level_2 = log_params.end_address_save_log_memory - 0x2000;
// log_params.end_address_log_slow_level_3 = log_params.end_address_save_log_memory - 0x4000;
// èíäåêñû â íà÷àëî
log_params.addres_mem = log_params.start_address_log;
log_params.addres_mem_slow = log_params.start_address_log_slow;
}
void initLogSize(unsigned int c_fast, unsigned int c_slow)
{
log_params.size_slow_done = 0;
log_params.size_fast_done = 0;
log_params.init = 0;
if (c_fast>SIZE_LOGS_ARRAY)
c_fast = SIZE_LOGS_ARRAY;
if (c_slow>SIZE_LOGS_ARRAY)
c_slow = SIZE_LOGS_ARRAY;
logsdata.block_size_fast = c_fast;
logsdata.block_size_slow = c_slow;
getFastLogs(1);
getSlowLogs(1);
// log_params.BlockSizeErr = logpar.block_size_counter_fast;//block_size_counter_fast;
// log_params.BlockSizeSlow = logpar.block_size_counter_slow;
defineVarsErrSlowLogs();
log_params.init = 1;
clear_mem_all();
// clear_mem(FAST_LOG);
// clear_mem(SLOW_LOG);
// set_start_mem(FAST_LOG);
// getFastLogs();
// log_params.BlockSizeErr = block_size_counter_fast;
// set_start_mem(SLOW_LOG);
// getLogs();
// log_params.BlockSizeSlow = block_size_counter_slow;
}
//void initErrLog()
//{
//
// static unsigned long SizeLogErr = 0;
// static unsigned long SizeLogSlow = 0;
// unsigned int sizeHiword = 0;
// unsigned int sizeLoword = 0;
// unsigned int addrHiword = 0;
// unsigned int addrLoword = 0;
//
// set_start_mem(FAST_LOG);
//// set_start_mem(ALARM_SAVE_MEMORY);
// set_start_mem(INIT_LOG);
//// set_start_mem(ERR_LOG);
//
// clear_mem(INIT_LOG);
// clear_mem(FAST_LOG);
//// clear_mem(ALARM_SAVE_MEMORY);
//// clear_mem(ERR_LOG);
//
//// SizeLog = log_params.end_address_log - log_params.start_address_log; // END_ADDRESS_LOG - START_ADDRESS_LOG; //ERR_BLOCK_SIZE*600;
// SizeLogErr = log_params.end_address_err_log - log_params.start_address_err_log; // END_ADDRESS_ERR_LOG - START_ADDRESS_ERR_LOG;//(long)ERR_BLOCK_SIZE*(long)3000;
// SizeLogSlow = log_params.end_address_save_log_memory - log_params.start_address_save_log_memory; // END_ADDRESS_LOG_SLOW - START_ADDRESS_LOG_SLOW;
//
// sizeHiword = SizeLogErr >> 16;
// sizeLoword = SizeLogErr;
//
// WriteMemory(ADDR_SIZE_ERR_LOW, sizeLoword);
// WriteMemory(ADDR_SIZE_ERR_HIGH, sizeHiword);
//
// sizeHiword = SizeLogSlow >> 16;
// sizeLoword = SizeLogSlow;
// WriteMemory(ADDR_SIZE_SLOW_LOW, sizeLoword);
// WriteMemory(ADDR_SIZE_SLOW_HIGH, sizeHiword); //!!!
//
// WriteMemory(ADDR_ERR_BLOCK_SIZE, log_params.BlockSizeErr);
// WriteMemory(ADDR_SLOW_BLOCK_SIZE, log_params.BlockSizeSlow);
//
// addrHiword = log_params.start_address_err_log >> 16;
// addrLoword = log_params.start_address_err_log;
// WriteMemory(ADDR_START_ADDR_ERR_LOG_LOW, addrLoword);
// WriteMemory(ADDR_START_ADDR_ERR_LOG_HIGH, addrHiword);
//
// addrHiword = log_params.start_address_save_log_memory >> 16;
// addrLoword = log_params.start_address_save_log_memory;
// WriteMemory(ADDR_START_ADDR_SLOW_LOG_LOW, addrLoword);
// WriteMemory(ADDR_START_ADDR_SLOW_LOG_HIGH, addrHiword);
//}

View File

@ -1,109 +0,0 @@
#ifndef _LOG_PARAMS
#define _LOG_PARAMS
#define PERIOD_LOGS 3
#define START_ADDRESS_LOG 0xA0000 //0xa0000
#define START_ADDRESS_LOG_SLOW 0xC0000 //0xa0000
#define END_ADDRESS_LOGS 0x0dffff //0x0ef000
#define END_ADDRESS_LOGS_FINAL 0x0efff0 //0x0ef000
//#define COUNTER_ERR_WRITES 1
#define VOLUME_OF_FAST_LOG 2000L //0x800L // 0x1000 //0x3500
#define VOLUME_OF_SLOW_LOG 2000L //0x800L // 0x800 // 0x1000 //0x3500
//#define MAX_SUZE_LOG 0x20000
//#define END_ADDRESS_LOD_TEMP 0xC0000
//#define START_ADDRESS_SAVE_ON_ALARM 0xC0000
//#define LENGTH_HAZARD 100
#define COUNT_SAVE_LOG_OFF 50 //500
#define ADDR_SIZE_ERR_LOW 0xa0000
#define ADDR_SIZE_ERR_HIGH 0xa0001
#define ADDR_SIZE_SLOW_LOW 0xa0002
#define ADDR_SIZE_SLOW_HIGH 0xa0003
#define ADDR_ERR_BLOCK_SIZE 0xa0004
#define ADDR_SLOW_BLOCK_SIZE 0xa0005
#define ADDR_START_ADDR_ERR_LOG_LOW 0xa0006
#define ADDR_START_ADDR_ERR_LOG_HIGH 0xa0007
#define ADDR_START_ADDR_SLOW_LOG_LOW 0xa0008
#define ADDR_START_ADDR_SLOW_LOG_HIGH 0xa0009
#define START_ADDR_TIME_ERR_WRITE 0xa000a
#define END_ADDR_TIME_ERR_WRITE 0xa000e
#define LAST_WRITTEN_BLOCK 0xa000f
typedef struct
{
int stop_log_level_1;
int stop_log_level_2;
int stop_log_slow_level_1;
int stop_log_slow_level_2;
unsigned int init;
unsigned int BlockSizeErr;
unsigned int BlockSizeSlow;
unsigned long start_address_log;//START_ADDRESS_LOG
unsigned long end_address_log;//END_ADDRESS_LOG
unsigned long end_address_log_level_1;//END_ADDRESS_LOG_LEVEL_2
unsigned long end_address_log_level_2;
// unsigned long addr_size_err_low;//ADDR_SIZE_ERR_LOW
unsigned long start_address_log_slow;//START_ADDRESS_LOG_SLOW
unsigned long end_address_log_slow;
// unsigned long start_address_save_log_memory;
// unsigned long end_address_save_log_memory;
unsigned long end_address_log_slow_level_1;
unsigned long end_address_log_slow_level_2;
// unsigned long end_address_log_slow_level_3;
// unsigned long start_address_err_log;//START_ADDRESS_ERR_LOG
// unsigned long end_address_err_log;//END_ADDRESS_ERR_LOG
unsigned long addres_mem;//START_ADDRESS_LOG
unsigned long addres_mem_slow;//START_ADDRESS_LOG
unsigned int log_cycle_done;
unsigned int log_cycle_done_slow;
int no_write_slow;
int no_write_fast;
int size_slow_done;
int size_fast_done;
int stop_log_fast;
int stop_log_slow;
int log_saved_to_const_mem;
int copy_log_to_const_memory;
unsigned int volume_of_fast_log;
unsigned int volume_of_slow_log;
unsigned int cur_volume_of_fast_log;
unsigned int cur_volume_of_slow_log;
} TYPE_LOG_PARAMS;
#define TYPE_LOG_PARAMS_DEFAULT {0,0,0,0, 0,0,0,0, 0,0,0,0,0, 0,0,0,0, 0,0,0,0, 0,0,0,0, 0,0, 0,0, 0,0}
extern TYPE_LOG_PARAMS log_params;
void initErrLog(void);
void initLogSize(unsigned int c_fast, unsigned int c_slow);
#endif //_LOG_PARAMS

View File

@ -1,484 +0,0 @@
/****************************************************************/
/* TMS320C32 */
/* ====== BIOS, ÊËÀÈÍ, ÊËÂÑÏ ====== */
/* ÖÍÈÈ ÑÝÒ (ñ) 1998-2001ã. */
/****************************************************************/
/* log_to_mem.c
****************************************************************
* Çàïèñü ëîãîâ â ïàìyòü *
****************************************************************/
#include "log_to_memory.h"
#include "MemoryFunctions.h"
#include "log_params.h"
#include "global_time.h"
// ïåðåìåííûå èñïîëüçóåìûå òîëüêî â ýòîì ìîäóëå
// Ïåðåìåííûå èç ï/ï logs_data(), write_to_mem è clear_mem
// Íà÷àëüíûé àäðåñ ïàìyòè äëy çàïèñè ëîãîâ (ñì. ï/ï write_to_mem)
//#pragma DATA_SECTION(count_mem, ".fast_vars1");
//static unsigned long count_mem = START_ADDRESS_LOG; //static
//#pragma DATA_SECTION(count_mem_slow, ".fast_vars1");
//static unsigned long count_mem_slow; // = START_ADDRESS_LOG_SLOW;//START_ADDRESS_LOG_SLOW; //static
//#pragma DATA_SECTION(count_mem_err, ".fast_vars1");
//static unsigned long count_mem_err; // = START_ADDRESS_ERR_LOG;//START_ADDRESS_ERR_LOG; //static
//#pragma DATA_SECTION(count_mem_init, ".fast_vars1");
//static unsigned long count_mem_init = ADDR_SIZE_ERR_LOW;
// Îáyçàòåëüíîå íà÷àëüíîå çíà÷åíèå èíà÷å ïîðyäîê çàïèñè
// íàðóøàåòñy ïðè ïåðâîì çààïîëíåíèè áóôåðà
int hb_logs_data = 0;
//int stop_log = 0;
//int stop_log_slow = 0;
//int block_size_counter_slow = 0;
//int block_size_counter_fast = 0;
//#pragma DATA_SECTION(LOAG, ".fast_vars1");
//int LOAG[12];
#pragma DATA_SECTION(logsdata, ".fast_vars1");
LOGSDATA logsdata = LOGSDATA_DEFAULT;
//int no_write = 0; // Ôëàã, ÷òîáû íå ïèñàòü (åñëè ÷òî)
//int no_write_slow = 0; // Ôëàã, ÷òîáû íå ïèñàòü (åñëè ÷òî)
//int size_fast_done = 0;
//int size_slow_done = 0;
//#pragma CODE_SECTION(clear_logpar,".fast_run");
void clear_logpar(void)
{
int i;
for(i=0;i<SIZE_LOGS_ARRAY;i++)
logsdata.logs[i] = 0;
}
// Çàïèñü äâóõ ìëàäøèõ áàéòîâ àðãóìåíòà â ïàìyòü, ãäå ëîãè ëåæàò
#pragma CODE_SECTION(write_to_mem, ".fast_run2");
void write_to_mem(int tlog, int DataM)
{
// int DataT;
if (tlog == FAST_LOG)
{
if (!log_params.size_fast_done)
{
log_params.BlockSizeErr++;
return;
}
if (log_params.no_write_fast)
return;
// if (log_params.stop_log_level_1)
// return;
if (log_params.addres_mem >= log_params.end_address_log)
log_params.addres_mem = log_params.end_address_log;
WriteMemory(log_params.addres_mem, DataM);
// Fast_log_written = 1;
// if (one_block) block_size_counter++;
// *(int *)count_mem = ((DataM & 0xFFFF) );
log_params.addres_mem++;
return;
}
if (tlog == SLOW_LOG)
{
if (!log_params.size_slow_done)
{
log_params.BlockSizeSlow++;
return;
}
if (log_params.no_write_slow)
return;
// if (logpar.stop_log_level_1)
// return;
if (log_params.addres_mem_slow >= log_params.end_address_log_slow)
log_params.addres_mem_slow = log_params.end_address_log_slow;
WriteMemory(log_params.addres_mem_slow, DataM);
// Fast_log_written = 1;
// if (one_block) block_size_counter++;
// *(int *)count_mem = ((DataM & 0xFFFF) );
log_params.addres_mem_slow++;
return;
}
// if (tlog == ALARM_SAVE_MEMORY)
// {
//
// if (!size_slow_done)
// {
// block_size_counter_slow++;
// return;
// }
//
// if (no_write_slow)
// return;
//
// if (logpar.stop_log_slow_level_1)
// return;
//
// if (count_mem_slow >= log_params.end_address_save_log_memory)
// count_mem_slow = log_params.end_address_save_log_memory;
//
// WriteMemory(count_mem_slow, DataM);
// count_mem_slow++;
//
// return;
// }
/* if (tlog==ERR_LOG)
{
if (count_mem_err >= END_ADDRESS_ERR_LOG) count_mem_err = END_ADDRESS_ERR_LOG;
WriteMemory(count_mem_err,DataM);
count_mem_err++;
}
*/
}
#pragma CODE_SECTION(test_mem_limit, ".fast_run");
void test_mem_limit(int tlog, int ciclelog)
{
if (tlog == FAST_LOG)
{
// block_size_counter = 0;
if (log_params.addres_mem >= log_params.end_address_log)
{
log_params.log_cycle_done = 1;
if (ciclelog == 1)
{
log_params.stop_log_fast = 0;
// log_params.stop_log_level_1 = 0;
log_params.addres_mem = log_params.start_address_log;
}
else
{
log_params.stop_log_fast = 1;
// log_params.stop_log_level_1 = 1;
}
}
if (log_params.addres_mem >= (log_params.end_address_log_level_1))
{
log_params.stop_log_level_1 = 1;
}
else
{
log_params.stop_log_level_1 = 0;
}
if (log_params.addres_mem >= (log_params.end_address_log_level_2))
{
log_params.stop_log_level_2 = 1;
}
else
{
log_params.stop_log_level_2 = 0;
}
return;
}
if (tlog == SLOW_LOG)
{
// block_size_counter = 0;
if (log_params.addres_mem_slow >= log_params.end_address_log_slow)
{
log_params.log_cycle_done_slow = 1;
if (ciclelog == 1)
{
log_params.stop_log_slow = 0;
/// logpar.stop_log_level_1 = 0;
log_params.addres_mem_slow= log_params.start_address_log_slow;
}
else
{
log_params.stop_log_slow = 1;
// logpar.stop_log_level_1 = 1;
}
if (log_params.addres_mem_slow >= (log_params.end_address_log_slow_level_1))
{
log_params.stop_log_slow_level_1= 1;
}
else
{
log_params.stop_log_slow_level_1 = 0;
}
if (log_params.addres_mem_slow >= (log_params.end_address_log_slow_level_2))
{
log_params.stop_log_slow_level_2 = 1;
}
else
{
log_params.stop_log_slow_level_2 = 0;
}
}
return;
}
// if (tlog == ALARM_SAVE_MEMORY)
// {
// if (ciclelog == 1)
// {
// logpar.stop_log_slow_level_1 = 0;
// }
//
// if (count_mem_slow >= (log_params.end_address_save_log_memory - LENGTH_HAZARD))
// {
// if (ciclelog == 1)
// {
// stop_log_slow = 0;
// logpar.stop_log_slow_level_1 = 0;
// count_mem_slow = log_params.start_address_save_log_memory;
// }
// else
// {
// stop_log_slow = 1;
// logpar.stop_log_slow_level_1 = 1;
// }
// }
//
// if (count_mem_slow >= (log_params.end_address_log_slow_level_2))
// {
// logpar.stop_log_slow_level_2 = 1;
// }
// else
// {
// logpar.stop_log_slow_level_2 = 0;
// }
//
// if (count_mem_slow >= (log_params.end_address_log_slow_level_3))
// {
// logpar.stop_log_slow_level_3 = 1;
// }
// else
// {
// logpar.stop_log_slow_level_3 = 0;
// }
//
// return;
// }
}
// Î÷èùåíèå ïàìyòè, ãäå ëîãè ïèøóòñÿ
void clear_mem(int tlog)
{
if (tlog == FAST_LOG)
{
for (log_params.addres_mem = log_params.start_address_log; log_params.addres_mem < log_params.end_address_log; log_params.addres_mem++)
WriteMemory(log_params.addres_mem, 0x0);
log_params.addres_mem = log_params.start_address_log;
hb_logs_data = 0;
log_params.stop_log_fast = 0;
log_params.stop_log_level_1 = 0;
log_params.stop_log_level_2 = 0;
return;
}
if (tlog == SLOW_LOG)
{
for (log_params.addres_mem_slow = log_params.start_address_log_slow; log_params.addres_mem_slow < log_params.end_address_log_slow; log_params.addres_mem_slow++)
WriteMemory(log_params.addres_mem_slow, 0x0);
log_params.addres_mem_slow = log_params.start_address_log_slow;
hb_logs_data = 0;
log_params.stop_log_slow = 0;
log_params.stop_log_slow_level_1 = 0;
log_params.stop_log_slow_level_2 = 0;
return;
}
// if (tlog == ALARM_SAVE_MEMORY)
// {
//
// for (count_mem_slow = log_params.start_address_save_log_memory; count_mem_slow < log_params.end_address_save_log_memory; count_mem_slow++)
// WriteMemory(count_mem_slow, 0x0);
//
// count_mem_slow = log_params.start_address_save_log_memory;
// hb_logs_data = 0;
// stop_log_slow = 0;
//
// logpar.stop_log_slow_level_1 = 0;
// logpar.stop_log_slow_level_2 = 0;
// logpar.stop_log_slow_level_3 = 0;
//
// return;
// }
// if (tlog == ERR_LOG)
// {
//
// for (count_mem_err = log_params.start_address_err_log; count_mem_err < log_params.end_address_err_log; count_mem_err++)
// WriteMemory(count_mem_err, 0x0);
//
// count_mem_err = log_params.start_address_err_log;
// return;
// }
// if (tlog == INIT_LOG)
// {
// for (count_mem_init = ADDR_SIZE_ERR_LOW; count_mem_init <= END_ADDR_TIME_ERR_WRITE; count_mem_init++)
// WriteMemory(count_mem_init, 0x0);
//
// count_mem_init = ADDR_SIZE_ERR_LOW;
// return;
// }
}
//Î÷èùåíèå âñåé ïàìÿòè ñîõðàíåíèÿ ëîãîâ
void clear_mem_all() {
for (log_params.addres_mem = START_ADDRESS_LOG; log_params.addres_mem < END_ADDRESS_LOGS; log_params.addres_mem++) {
WriteMemory(log_params.addres_mem, 0x0);
}
log_params.addres_mem = log_params.start_address_log;
log_params.stop_log_fast = 0;
log_params.stop_log_level_1 = 0;
log_params.stop_log_level_2 = 0;
log_params.log_cycle_done = 0;
hb_logs_data = 0;
log_params.addres_mem_slow = log_params.start_address_log_slow;
log_params.stop_log_slow = 0;
log_params.stop_log_slow_level_1 = 0;
log_params.stop_log_slow_level_2 = 0;
}
// Âûñòàâëåíèå ïîçèöèè ëîãîâ â íà÷àëî
void set_start_mem(int tlog)
{
if (tlog == FAST_LOG)
{
log_params.addres_mem = log_params.start_address_log;
log_params.log_cycle_done = 0;
hb_logs_data = 0;
log_params.stop_log_fast = 0;
log_params.stop_log_level_1 = 0;
log_params.stop_log_level_2 = 0;
}
if (tlog == SLOW_LOG)
{
log_params.addres_mem_slow = log_params.start_address_log_slow;
log_params.log_cycle_done = 0;
hb_logs_data = 0;
log_params.stop_log_slow = 0;
log_params.stop_log_slow_level_1 = 0;
log_params.stop_log_slow_level_2 = 0;
}
// if (tlog == ALARM_SAVE_MEMORY)
// {
//
// count_mem_slow = log_params.start_address_save_log_memory;
// hb_logs_data = 0;
// stop_log_slow = 0;
//
// logpar.stop_log_slow_level_1 = 0;
// logpar.stop_log_slow_level_2 = 0;
// logpar.stop_log_slow_level_3 = 0;
// }
// if (tlog == ERR_LOG)
// {
//
// count_mem_err = log_params.start_address_err_log;
// hb_logs_data = 0;
// stop_log_slow = 0;
//
// logpar.stop_log_slow_level_1 = 0;
// logpar.stop_log_slow_level_2 = 0;
// logpar.stop_log_slow_level_3 = 0;
// }
// if (tlog == INIT_LOG)
// {
// count_mem_init = ADDR_SIZE_ERR_LOW;
// }
}
#pragma CODE_SECTION(getFastLogs, ".fast_run2");
void getFastLogs(int cicleLog)
{
int i_log;
if (log_params.size_fast_done)
test_mem_limit(FAST_LOG, cicleLog);
for (i_log=0;i_log<logsdata.block_size_fast;i_log++)
write_to_mem(FAST_LOG, (int) logsdata.logs[i_log]);
log_params.size_fast_done = 1;
}
#pragma CODE_SECTION(getSlowLogs, ".fast_run2");
void getSlowLogs(int cicleLog)
{
int i_log;
if (log_params.size_slow_done)
test_mem_limit(SLOW_LOG, cicleLog);
for (i_log=0;i_log<logsdata.block_size_slow;i_log++)
write_to_mem(SLOW_LOG, (int) logsdata.logs[i_log]);
if (log_params.cur_volume_of_slow_log>0)
log_params.cur_volume_of_slow_log--;
else
log_params.cur_volume_of_slow_log = log_params.volume_of_slow_log;
log_params.size_slow_done = 1;
}
//void copyLogsToSaveArea()
//{
// unsigned long from = START_ADDRESS_LOG;
// unsigned long to = START_ADDRESS_SAVE_ON_ALARM;
//
// for (;from <= log_params.end_address_log && to < END_ADDRESS_LOGS ;++from, ++to) {
// WriteMemory(to, ReadMemory(from));
// }
//}
//void copyLogsToSaveAreaUnrolled()
//{
// unsigned long from = log_params.log_cycle_done ? log_params.addres_mem : log_params.start_address_log;
// unsigned long to = START_ADDRESS_SAVE_ON_ALARM;
// unsigned long count = log_params.end_address_log - log_params.start_address_log;
//
// for (;count-- > 0 && to < END_ADDRESS_LOGS ;++from, ++to) {
// if (from >= log_params.end_address_log) {
// from = log_params.start_address_log;
// }
// WriteMemory(to, ReadMemory(from));
// }
//}

View File

@ -1,96 +0,0 @@
/****************************************************************/
/* TMS320C32 */
/* ====== BIOS, ÊËÀÈÍ, ÊËÂÑÏ ====== */
/* ÖÍÈÈ ÑÝÒ (ñ) 1998-2001ã. */
/****************************************************************/
/* log_to_mem.h
****************************************************************
* Çàïèñü ëîãîâ â ïàìyòü *
****************************************************************/
#ifndef _LOG_TO_MEM
#define _LOG_TO_MEM
#ifdef __cplusplus
extern "C" {
#endif
#define SIZE_LOGS_ARRAY 92
#define INIT_LOG 3
//#define ERR_LOG 2
//#define ALARM_SAVE_MEMORY 1
#define FAST_LOG 0
#define SLOW_LOG 4
#define ALL_LOG 5
typedef struct
{
// int copy_log_to_const_memory;
//
//// int start_write_fast_log; //Íà÷àëî çàïèñè ëîãà, äëÿ îïðåäåëåíèÿ count_log_params_fast_log
//// int count_log_params_fast_log; //Êîëè÷åñòâî çàïèñûâàåìûõ â ëîã ïàðàìåòðîâ
//
// int block_size_counter_fast;
// int block_size_counter_slow;
//
int block_size_fast;
int block_size_slow;
int logs[SIZE_LOGS_ARRAY];
} LOGSDATA;
//extern int LOAG[];
#define LOGSDATA_DEFAULT {0,0, {0} }
/* íå ïðîâîäèòü ðîòàöèþ ëîãîâ */
#define NO_ROTATE_LOG 0
//extern int no_write; // Ôëàã, ÷òîáû íå ïèñàòü (åñëè ÷òî)
//extern int stop_log; // Ëîãè îñòàíîâèëèñü
//extern int Fast_log_written; //FAST LOG çàïèñàí
//extern int block_size_counter_slow;
//extern int block_size_counter_fast;
//extern int block_size_counter;// ðàçìåð áëîêà
//extern int size_fast_done;
//extern int size_slow_done;
/* Çàïèñü äâóõ ìëàäøèõ áàéòîâ àðãóìåíòà â ïàìyòü, ãäå ëîãè ëåæàò */
void write_to_mem(int tlog,int DataM);
void write_to_mem_a(int DataM);
/* Ïðîâåðêà ãðàíèöû ïàìyòè äëy ëîãîâ */
void test_mem_limit(int tlog,int ciclelog);
void set_start_mem(int tlog);
/* Î÷èñòêà ïàìyòè (îáíóëåíèå) */
void clear_mem(int tlog);
void clear_mem_all(void);
void getFastLogs(int cicleLog);
void getSlowLogs(int cicleLog);
//Ñîõðàíåíèå ëîãîâ â íåçàòèðàåìóþ ïðè ðàáîòå ÷àñòü ïàìÿòè
void copyLogsToSaveArea(void);
//Ñîõðàíåíèå ñ ðàçâîðà÷èâàíèåì êîëüöà.
//Çàïèñü ïî âðåìåíè íà÷èíàåòñÿ â íà÷àëå ó÷àñòêà ïàìÿòè è çàêàí÷èâàåòñÿ â êîíöå.
void copyLogsToSaveAreaUnrolled(void);
void clear_logpar(void);
extern LOGSDATA logsdata;
#ifdef __cplusplus
}
#endif
#endif /* _LOG_TO_MEM */

View File

@ -12,23 +12,8 @@
#define CONST_SQRT3 29058990 //1.7320508075688772935274463415059 = sqrt(3)
#define CONST_SQRT3_2 14529495 //1.7320508075688772935274463415059/2=0.8660254 = sqrt(3)/2
#define CONST_IQ_1 16777216 //1
#define CONST_IQ_2 33554432 //2
#define CONST_IQ_01 1677721 //0.1
#define CONST_IQ_02 3355442 //0.2
#define CONST_IQ_03 5033163 //0.3
#define CONST_IQ_04 6710884 //0.4
#define CONST_IQ_05 8388608 //0.5
#define CONST_IQ_06 10066329 //0.6
#define CONST_IQ_07 11744051 //0.7
#define CONST_IQ_08 13421772 //0.8
#define CONST_IQ_09 15099494 //0.9
#define CONST_IQ_2 33554432 //2
#define CONST_IQ_PI6 8784530 //30
#define CONST_IQ_PI3 17569060 // 60

View File

@ -19,13 +19,13 @@
#include "DSP281x_Device.h" // DSP281x Headerfile Include File
#include "DSP281x_Examples.h" // DSP281x Examples Include File
#include <math.h>
#include "mathlib.h"
#include "params_norma.h"
#include "math_pi.h"
#include "params_pwm24.h"
#include <math.h>
#include "params_norma.h"
#include <params_norma.h>
_iq SQRT_32 = _IQ(0.8660254037844);
_iq CONST_23 = _IQ(2.0/3.0);
@ -36,38 +36,28 @@ _iq CONST_15 = _IQ(1.5);
#define real float
float my_satur_float(float Input, float Positive, float Negative, float DeadZone)
float my_satur_float(float Input, float Positive, float Negative)
{
if (fabs(DeadZone)>0.000001 && Input>-DeadZone && Input<DeadZone)
Input = 0;
else
if (Input>=Positive) Input=Positive;
else
if (Input<=Negative) Input=Negative;
return Input;
}
int my_satur_int(int Input, int Positive, int Negative, int DeadZone)
{
if (DeadZone!=0 && Input>-DeadZone && Input<DeadZone)
Input = 0;
else
if (Input>=Positive) Input=Positive;
else
if (Input<=Negative) Input=Negative;
return Input;
}
long my_satur_long(long Input, long Positive, long Negative, long DeadZone)
int my_satur_int(int Input, int Positive, int Negative)
{
if (Input>=Positive) Input=Positive;
if (Input<=Negative) Input=Negative;
return Input;
}
long my_satur_long(long Input, long Positive, long Negative)
{
if (DeadZone!=0 && Input>-DeadZone && Input<DeadZone)
Input = 0;
else
if (Input>=Positive) Input=Positive;
else
if (Input<=Negative) Input=Negative;
return Input;
@ -152,12 +142,9 @@ real exp_regul(real Tperiod_regul, real Texp_regul, real InpVarCurr, real InpVar
*/
float zad_intensiv(float StepP, float StepN, float InpVarCurr, float InpVarInstant)
real zad_intensiv(real StepP, real StepN, real InpVarCurr, real InpVarInstant)
{
float deltaVar, VarOut;
real deltaVar, VarOut;
deltaVar = InpVarInstant-InpVarCurr;
@ -173,7 +160,7 @@ float zad_intensiv(float StepP, float StepN, float InpVarCurr, float InpVarInsta
VarOut = InpVarCurr;
return VarOut;
}
*/
#pragma CODE_SECTION(zad_intensiv_q,".fast_run");
_iq zad_intensiv_q(_iq StepP, _iq StepN, _iq InpVarCurr, _iq InpVarInstant)
{
@ -350,88 +337,3 @@ float fast_round(float x)
}
float fast_round_with_delta(float prev, float x, float delta)
{
float d;
long i;
i = (long)x;
if (x<0)
{
d = i - x;
if (d>=0.5)
i = i - 1;
}
else
{
d = x - i;
if (d>=0.5)
i = i + 1;
}
if (fabs(prev-x)>=delta)
return (float)i;
else
return (float)prev;
}
float fast_round_with_limiter(float x, float lim)
{
float d;
long i;
if (fabs(x)<=lim)
return 0;
i = (long)x;
if (x<0)
{
d = i - x;
if (d>=0.5)
i = i - 1;
}
else
{
d = x - i;
if (d>=0.5)
i = i + 1;
}
return (float)i;
}
#pragma CODE_SECTION(calc_rms,".fast_run");
_iq calc_rms(_iq input, _iq input_prev, _iq freq_signal)
{
static _iq pi_pwm = _IQ(PI*NORMA_FROTOR/(FREQ_PWM/5.0));
_iq cosw, sinw, wdt, y2, z1, z2, z3, y;
wdt = _IQmpy(pi_pwm,freq_signal);
sinw = _IQsinPU(wdt);
cosw = _IQcosPU(wdt);
if (cosw==0)
return 0;
z1 = input_prev - _IQmpy(input,cosw);
// z2 = sinw;
z3 = _IQdiv(z1,sinw);
y2 = _IQmpy(input,input)+_IQmpy(z3,z3);
// cosw = _IQsin();
y = _IQsqrt(y2);
return y;
}

View File

@ -4,7 +4,6 @@
#include "IQmathLib.h"
/*
real pi_regul(real Kp_regul, real Tintegral_regul, real Tperiod_regul,
@ -12,7 +11,7 @@ real pi_regul(real Kp_regul, real Tintegral_regul, real Tperiod_regul,
real exp_regul(real Tperiod_regul, real Texp_regul, real InpVarCurr, real InpVarInstant);
real zad_intensiv(real StepP, real StepN, real InpVarCurr, real InpVarInstant);
real pid_regul2(real Kp_regul, real Tperiod_regul, real Minimum, real Maximum,
real yk, real *uk1, real *yk1, real *yk2, real *yzad,
@ -28,9 +27,7 @@ real pi_regul3(real Kp_regul, real ki_regul, real Tperiod_regul, real Minimum, r
real pi_regul4(real Kp_regul, real ki_regul, real Tperiod_regul, real Minimum, real Maximum,
real InpVar, real *InpVarPrev, real *OutVarPrev);
*/
float zad_intensiv(float StepP, float StepN, float InpVarCurr, float InpVarInstant);
*/
_iq zad_intensiv_q(_iq StepP, _iq StepN, _iq InpVarCurr, _iq InpVarInstant);
_iq im_calc( _iq ia, _iq ib, _iq ic);
@ -38,10 +35,9 @@ float exp_regul(float Tperiod_regul, float Texp_regul, float InpVarCurr, float I
float my_satur_float(float Input, float Positive, float Negative, float DeadZone);
int my_satur_int(int Input, int Positive, int Negative, int DeadZone);
long my_satur_long(long Input, long Positive, long Negative, long DeadZone);
float my_satur_float(float Input, float Positive, float Negative);
int my_satur_int(int Input, int Positive, int Negative);
long my_satur_long(long Input, long Positive, long Negative);
@ -72,10 +68,7 @@ typedef struct {
_iq calc_rms_array_var_period(RMS_CALC_ARRAY_THINNING *v);
_iq calc_rms_array_var_period_IQ15(RMS_CALC_ARRAY_THINNING *v);
float fast_round(float x);
float fast_round_with_limiter(float x, float lim);
float fast_round_with_delta(float prev, float x, float delta);
_iq calc_rms(_iq input, _iq input_prev, _iq freq_signal);
#endif

View File

@ -31,8 +31,6 @@ MODBUS_REG_STRUCT modbus_table_can_in[SIZE_MODBUS_TABLE];
#pragma DATA_SECTION(modbus_table_can_out,".logs");
MODBUS_REG_STRUCT modbus_table_can_out[SIZE_MODBUS_TABLE];
#pragma DATA_SECTION(modbus_table_can_out_temp,".logs");
MODBUS_REG_STRUCT modbus_table_can_out_temp[SIZE_MODBUS_TABLE];
@ -42,8 +40,8 @@ int i;
for (i=0;i<SIZE_MODBUS_TABLE;i++)
{
modbus_table_rs_in[i].all = 0;
modbus_table_can_in[i].all = 0;
modbus_table_rs_in[i].all=0;
modbus_table_can_in[i].all=0;
}
@ -55,9 +53,8 @@ void clear_modbus_table_out()
for (i=0;i<SIZE_MODBUS_TABLE;i++)
{
modbus_table_rs_out[i].all = 0;
modbus_table_can_out[i].all = 0;
modbus_table_can_out_temp[i].all = 0;
modbus_table_rs_out[i].all= 0;
modbus_table_can_out[i].all= 0;
}
}

View File

@ -24,7 +24,6 @@ extern MODBUS_REG_STRUCT modbus_table_rs_out[SIZE_MODBUS_TABLE];
extern MODBUS_REG_STRUCT modbus_table_rs_in[SIZE_MODBUS_TABLE];
extern MODBUS_REG_STRUCT modbus_table_can_out[SIZE_MODBUS_TABLE];
extern MODBUS_REG_STRUCT modbus_table_can_out_temp[SIZE_MODBUS_TABLE];
extern MODBUS_REG_STRUCT modbus_table_can_in[SIZE_MODBUS_TABLE];

File diff suppressed because it is too large Load Diff

View File

@ -1,626 +0,0 @@
/*
* adaptive_filters.c
*
* Created on: 24 ñåíò. 2023 ã.
* Author: user
*/
/*
Determining the appropriate values for the adaptive coefficients Ka and Kb in an adaptive PI
regulator requires a thorough understanding of your specific control system and motor dynamics.
The values of Ka and Kb are typically determined through a tuning process, which involves
experimentation and iteration to achieve the desired control performance.
Here's a general approach to tuning the adaptive coefficients Ka and Kb:
Start with small initial values: Begin with small values for Ka and Kb, such as 0.01 or 0.001.
Observe the system behavior: Run the control system with these initial values and observe the
response of the motor. Pay attention to the speed control performance, such as overshoot, settling
time, and steady-state error.
Adjust Ka and Kb based on the response: Increase or decrease the values of Ka and Kb based on
the observed system behavior. If the system response is slow or exhibits large overshoot,
consider increasing the values. If the system response is too aggressive or unstable,
consider decreasing the values.
Iterate the tuning process: Repeat steps 2 and 3, adjusting Ka and Kb iteratively until you
achieve the desired control performance. It may require several iterations to find suitable
values.
It's important to note that the tuning process is highly dependent on the specific motor
characteristics, the requirements of the control system, and the desired performance.
Therefore, it's recommended to consult motor control experts, refer to motor datasheets, or consider model-based control techniques for a more accurate tuning process.
Additionally, advanced control techniques such as adaptive control algorithms
(e.g., Model Reference Adaptive Control or Self-Tuning Regulators) can be explored for more
advanced and precise adaptation of control parameters.
Remember to thoroughly test and validate the tuned parameters under various operating
conditions to ensure stability and robust performance of the motor control system.
*/
// Constants for the PI regulator
#define Kp 0.5
#define Ki 0.2
// Constants for the adaptive part
#define Ka 0.05
#define Kb 0.02
// Function to calculate the adaptive PI control output
float adaptivePI(float setpoint, float measured_speed, float integral_error)
{
static float prev_error = 0.0;
static float prev_output = 0.0;
// Calculate the error
float error = setpoint - measured_speed;
// Calculate the integral error
integral_error += error;
// Calculate the adaptive part
float adaptive = Ka * error + Kb * (error - prev_error);
// Calculate the PI control output
float output = Kp * error + Ki * integral_error + adaptive;
// Store the current error and output for the next iteration
prev_error = error;
prev_output = output;
return output;
}
int main1()
{
float setpoint = 100.0; // Desired speed setpoint
float measured_speed = 85.0; // Measured speed of the motor
float integral_error = 0.0; // Integral error for the PI regulator
// Calculate the control output using the adaptive PI regulator
float control_output = adaptivePI(setpoint, measured_speed, integral_error);
printf("Control Output: %f\n", control_output);
return 0;
}
////////////////////////////
/*
In this simplified example, the mracControl function implements the MRAC algorithm for motor speed control.
The function takes the desired speed reference (reference_speed), the measured speed of the motor (measured_speed),
and the adaptation parameter (adaptation_param) as inputs. It returns the control output.
The MRAC algorithm calculates the error between the reference speed and the measured speed. It then multiplies
the error by the adaptation parameter, controller gain (Kc), and applies it as the control output.
The adaptation parameter is updated based on the derivative of the error and the adaptation rate (Lambda).
The main function demonstrates how to use the mracControl function by providing sample values for the reference
speed, measured speed, and adaptation parameter. It calculates the control output and prints it to the console.
Please note that this is a simplified example, and in a real-world scenario, you would need to consider
the specific motor dynamics, tuning of parameters, and implementation details based on the control
requirements of your motor system.
*/
// Constants for the MRAC algorithm
#define Kc 0.5 // Controller gain
#define Lambda 0.1 // Adaptation rate
// Reference model parameters
#define Km 0.5 // Model gain
#define Tm 1.0 // Model time constant
// Function to calculate the MRAC control output
float mracControl(float reference_speed, float measured_speed, float adaptation_param)
{
static float control_output = 0.0;
static float prev_error = 0.0;
// Calculate the error
float error = reference_speed - measured_speed;
// Calculate the control output
control_output = Kc * adaptation_param * error;
// Update the adaptation parameter
float derivative_error = (error - prev_error) / Tm;
adaptation_param += Lambda * derivative_error;
// Store the current error for the next iteration
prev_error = error;
return control_output;
}
int main2()
{
float reference_speed = 100.0; // Desired speed reference
float measured_speed = 85.0; // Measured speed of the motor
float adaptation_param = 1.0; // Initial value for the adaptation parameter
// Calculate the MRAC control output
float control_output = mracControl(reference_speed, measured_speed, adaptation_param);
printf("Control Output: %f\n", control_output);
return 0;
}
//////////////////////////////////////
/*
In this simplified example, the strControl function implements the STR algorithm for motor speed control.
It takes the desired speed reference (reference_speed), the measured speed of the motor (measured_speed),
and the adaptation parameter (adaptation_param) as inputs. It returns the control output.
The STR algorithm calculates the error between the reference speed and the measured speed.
It then multiplies the error by the adaptation parameter, controller gain (Kc), and applies it as the control output.
The updateAdaptationParam function updates the adaptation parameter based on the derivative of the error and the control output.
It calculates the derivative error by comparing the current control output and the previous control output, divided by
the difference in measured speed. The adaptation parameter is updated by adding the product of the derivative error and the adaptation rate (Lambda).
The main function demonstrates how to use the strControl function and the updateAdaptationParam function
by providing sample values for the reference speed, measured speed, and adaptation parameter.
It calculates the control output, updates the adaptation parameter, and prints the control output to the console.
Please note that this is a simplified example, and in a real-world scenario, you would need to consider the specific motor dynamics,
tuning of parameters, and implementation details based on the control requirements of your motor system.
*/
#include <stdio.h>
// Constants for the STR algorithm
#define Kc 0.5 // Initial controller gain
#define Lambda 0.1 // Adaptation rate
// Function to calculate the STR control output
float strControl(float reference_speed, float measured_speed, float adaptation_param)
{
static float control_output = 0.0;
// Calculate the error
float error = reference_speed - measured_speed;
// Calculate the control output
control_output = Kc * adaptation_param * error;
return control_output;
}
// Function to update the adaptation parameter
float updateAdaptationParam(float adaptation_param, float measured_speed, float control_output)
{
static float prev_error = 0.0;
static float prev_control_output = 0.0;
// Calculate the error derivative
float derivative_error = (control_output - prev_control_output) / (measured_speed - prev_error);
// Update the adaptation parameter
adaptation_param += Lambda * derivative_error;
// Store the current error and control output for the next iteration
prev_error = measured_speed;
prev_control_output = control_output;
return adaptation_param;
}
int main3()
{
float reference_speed = 100.0; // Desired speed reference
float measured_speed = 85.0; // Measured speed of the motor
float adaptation_param = 1.0; // Initial value for the adaptation parameter
// Calculate the STR control output
float control_output = strControl(reference_speed, measured_speed, adaptation_param);
// Update the adaptation parameter
adaptation_param = updateAdaptationParam(adaptation_param, measured_speed, control_output);
printf("Control Output: %f\n", control_output);
return 0;
}
///////////////////////
/*
In this example, the adaptivePIControl function calculates the adaptive PI control
output based on the reference speed, measured speed, and the current values of the
proportional gain (Kp) and integral gain (Ki). The function also updates the integral term.
The gradientDescentAdaptation function performs the gradient descent adaptation to
adjust the gains (Kp and Ki) based on the error between the reference speed and the
measured speed. It iteratively updates the gains using the gradients of the error
with respect to the gains.
The main function demonstrates the usage of the adaptive PI control and the gradient
descent adaptation. It initializes the gains, performs the adaptation, and calculates
the control output. The control output is then printed to the console.
Please note that this is a simplified example, and in a real-world scenario, you would
need to consider the specific motor dynamics, tuning of parameters, and implementation
details based on the control requirements of your motor system. Additionally, gradient
descent may not always be the most suitable adaptation algorithm for every situation,
and other algorithms may be more appropriate depending on the system characteristics
and control objectives.
*/
// Constants for the adaptive PI control
#define Kp_initial 1.0 // Initial proportional gain
#define Ki_initial 0.5 // Initial integral gain
#define Learning_rate 0.01 // Learning rate for adaptation
#define Max_iterations 1000 // Maximum number of iterations for adaptation
// Function to calculate the adaptive PI control output
float adaptivePIControl(float reference_speed, float measured_speed, float *Kp, float *Ki)
{
static float integral_term = 0.0;
float error = reference_speed - measured_speed;
// Update the integral term
integral_term += error;
// Calculate the control output
float control_output = (*Kp) * error + (*Ki) * integral_term;
return control_output;
}
// Function to perform gradient descent adaptation
void gradientDescentAdaptation(float reference_speed, float measured_speed, float *Kp, float *Ki)
{
int iteration;
float error;
float Kp_gradient, Ki_gradient;
for (iteration = 0; iteration < Max_iterations; iteration++)
{
// Calculate the error
error = reference_speed - measured_speed;
// Calculate the gradients
Kp_gradient = error;
Ki_gradient = error;
// Update the gains using gradient descent
*Kp += Learning_rate * Kp_gradient;
*Ki += Learning_rate * Ki_gradient;
}
}
int main4()
{
float reference_speed = 100.0; // Desired speed reference
float measured_speed = 85.0; // Measured speed of the motor
// Initialize the gains
float Kp = Kp_initial;
float Ki = Ki_initial;
// Perform gradient descent adaptation
gradientDescentAdaptation(reference_speed, measured_speed, &Kp, &Ki);
// Calculate the adaptive PI control output
float control_output = adaptivePIControl(reference_speed, measured_speed, &Kp, &Ki);
printf("Control Output: %f\n", control_output);
return 0;
}
/////////////////////////////////////////////////////
/*
In this example, the adaptivePIControl function calculates the adaptive PI control
output based on the reference speed, measured speed, and the current values of the
proportional gain (Kp) and integral gain (Ki). The function also updates the integral term.
The rlsAdaptation function performs the Recursive Least Squares (RLS) adaptation to
adjust the gains (Kp and Ki) based on the error between the reference speed and the
measured speed. It iteratively updates the estimates of the gains and the covariance
matrix using the RLS algorithm.
The main function demonstrates the usage of the adaptive PI control and the RLS adaptation.
It initializes the gains and covariance matrix, performs the adaptation, and calculates
the control output. The control output is then printed to the console.
Please note that this is a simplified example, and in a real-world scenario, you would
need to consider the specific motor dynamics, tuning of parameters, and implementation
details based on the control requirements of your motor system. Additionally, the RLS
algorithm may require additional considerations such as regularization techniques to
handle numerical stability and noise in the measurements.
*/
#include <stdio.h>
#include <math.h>
// Constants for the adaptive PI control and RLS algorithm
#define Lambda 0.9 // Forgetting factor
#define Initial_estimate 1.0 // Initial estimate for covariance matrix
#define Max_iterations 1000 // Maximum number of iterations for adaptation
// Function to calculate the adaptive PI control output
float adaptivePIControl(float reference_speed, float measured_speed, float Kp, float Ki)
{
static float integral_term = 0.0;
float error = reference_speed - measured_speed;
// Update the integral term
integral_term += error;
// Calculate the control output
float control_output = Kp * error + Ki * integral_term;
return control_output;
}
// Function to perform Recursive Least Squares (RLS) adaptation
void rlsAdaptation(float reference_speed, float measured_speed, float *Kp, float *Ki, float *P)
{
int iteration;
float error;
float integral_term = 0.0;
float Kp_estimate = *Kp;
float Ki_estimate = *Ki;
float P_estimate = *P;
for (iteration = 0; iteration < Max_iterations; iteration++)
{
// Calculate the error
error = reference_speed - measured_speed;
// Update the integral term
integral_term += error;
// Calculate the gain vector
float K_vector = P_estimate * integral_term / (Lambda + integral_term * P_estimate * integral_term);
// Update the estimates
Kp_estimate += K_vector * error;
Ki_estimate += K_vector * integral_term;
P_estimate = P_estimate / (Lambda + integral_term * P_estimate * integral_term);
// Update the gains
*Kp = Kp_estimate;
*Ki = Ki_estimate;
*P = P_estimate;
}
}
int main()
{
float reference_speed = 100.0; // Desired speed reference
float measured_speed = 85.0; // Measured speed of the motor
// Initialize the gains and covariance matrix
float Kp = 1.0;
float Ki = 0.5;
float P = Initial_estimate;
// Perform RLS adaptation
rlsAdaptation(reference_speed, measured_speed, &Kp, &Ki, &P);
// Calculate the adaptive PI control output
float control_output = adaptivePIControl(reference_speed, measured_speed, Kp, Ki);
printf("Control Output: %f\n", control_output);
return 0;
}
/////////////////////////////////////////////////////
/*
In this example, the adaptivePIControl function calculates the adaptive PI
control output based on the reference speed, measured speed, and the current
values of the proportional gain (Kp) and integral gain (Ki). The function also
updates the integral term.
The lmsAdaptation function performs the Least Mean Squares (LMS) adaptation to
adjust the gains (Kp and Ki) based on the error between the reference speed and
the measured speed. It iteratively updates the estimates of the gains using the
LMS algorithm.
The main function demonstrates the usage of the adaptive PI control and the
LMS adaptation. It initializes the gains, performs the adaptation, and calculates
the control output. The control output is then printed to the console.
Please note that this is a simplified example, and in a real-world scenario, you
would need to consider the specific motor dynamics, tuning of parameters, and
implementation details based on the control requirements of your motor system.
Additionally, the LMS algorithm may require additional considerations such as
step-size adaptation techniques or regularization to improve convergence and handle
noise in the measurements.
*/
// Constants for the adaptive PI control and LMS algorithm
#define Step_size 0.01 // Step size for adaptation
#define Max_iterations 1000 // Maximum number of iterations for adaptation
// Function to calculate the adaptive PI control output
float adaptivePIControl(float reference_speed, float measured_speed, float Kp, float Ki)
{
static float integral_term = 0.0;
float error = reference_speed - measured_speed;
// Update the integral term
integral_term += error;
// Calculate the control output
float control_output = Kp * error + Ki * integral_term;
return control_output;
}
// Function to perform Least Mean Squares (LMS) adaptation
void lmsAdaptation(float reference_speed, float measured_speed, float *Kp, float *Ki)
{
int iteration;
float error;
float integral_term = 0.0;
float Kp_estimate = *Kp;
float Ki_estimate = *Ki;
for (iteration = 0; iteration < Max_iterations; iteration++)
{
// Calculate the error
error = reference_speed - measured_speed;
// Update the integral term
integral_term += error;
// Update the estimates
Kp_estimate += Step_size * error;
Ki_estimate += Step_size * integral_term;
// Update the gains
*Kp = Kp_estimate;
*Ki = Ki_estimate;
}
}
int main()
{
float reference_speed = 100.0; // Desired speed reference
float measured_speed = 85.0; // Measured speed of the motor
// Initialize the gains
float Kp = 1.0;
float Ki = 0.5;
// Perform LMS adaptation
lmsAdaptation(reference_speed, measured_speed, &Kp, &Ki);
// Calculate the adaptive PI control output
float control_output = adaptivePIControl(reference_speed, measured_speed, Kp, Ki);
printf("Control Output: %f\n", control_output);
return 0;
}
//////////////////////////////////////////////
/*
In this example, the adaptiveControl function calculates the adaptive control
output based on the reference input and the measured output of the plant.
It also updates the state variable and adapts the plant parameters using the
MRAC algorithm.
The state variable represents the internal state of the plant model and is
updated using the plant gain and the difference between the reference input
and the current state variable multiplied by the adaptation rate.
The control output is calculated using the updated state variable.
The plant parameters, including the gain and time constant, are adapted using
the error between the measured output and the reference input, the state
variable, and the adaptation rate.
The main function demonstrates the usage of the adaptive control and the MRAC
algorithm. It initializes the plant parameters, performs the adaptation, and
calculates the control output. The control output is then printed to the console.
Please note that this is a simplified example, and in a real-world scenario,
you would need to consider the specific plant dynamics, tuning of parameters,
and implementation details based on the control requirements of your system.
Additionally, the MRAC algorithm may require additional considerations such as
stability analysis, anti-windup techniques, and robustness enhancements to handle
modeling uncertainties and external disturbances.
*/
// Constants for the model reference adaptive control (MRAC)
#define Adaptation_rate 0.01 // Adaptation rate for parameter updates
#define Reference_model_gain 1.0 // Gain of the reference model
#define Reference_model_time_constant 1.0 // Time constant of the reference model
// Function to calculate the adaptive control output
float adaptiveControl(float reference_input, float measured_output, float *plant_gain, float *plant_time_constant)
{
static float state_variable = 0.0;
float control_output;
// Update the state variable using the plant model
state_variable += (*plant_gain) * (reference_input - state_variable) * Adaptation_rate;
// Calculate the control output using the updated state variable
control_output = state_variable;
// Adapt the plant parameters using the error between the measured output and the reference input
float error = reference_input - measured_output;
*plant_gain += error * state_variable * Adaptation_rate;
*plant_time_constant += error * state_variable * state_variable * Adaptation_rate;
return control_output;
}
int main()
{
float reference_input = 1.0; // Desired reference input
float measured_output = 0.0; // Measured output of the plant
// Initialize the plant parameters
float plant_gain = 0.5;
float plant_time_constant = 0.75;
// Calculate the adaptive control output
float control_output = adaptiveControl(reference_input, measured_output, &plant_gain, &plant_time_constant);
printf("Control Output: %f\n", control_output);
return 0;
}
////////////////////////////////////////////
#include <stdio.h>
// Constants for the PID control
#define Kp 1.0 // Proportional gain
#define Ki 0.5 // Integral gain
#define Kd 0.2 // Derivative gain
// Function to calculate the PID control output
float PIDControl(float reference_value, float measured_value, float *previous_error, float *integral)
{
float error = reference_value - measured_value;
float derivative = error - (*previous_error);
// Update the integral term
*integral += error;
// Calculate the control output
float control_output = Kp * error + Ki * (*integral) + Kd * derivative;
// Update the previous error
*previous_error = error;
return control_output;
}
int main()
{
float reference_value = 10.0; // Desired reference value
float measured_value = 8.0; // Measured value
// Initialize variables for PID control
float previous_error = 0.0;
float integral = 0.0;
// Calculate the PID control output
float control_output = PIDControl(reference_value, measured_value, &previous_error, &integral);
printf("Control Output: %f\n", control_output);
return 0;
}

View File

@ -1,40 +0,0 @@
#include <stdio.h>
// Ïàðàìåòðû ðåãóëÿòîðà
double kp = 0.5; // Êîýôôèöèåíò ïðîïîðöèîíàëüíîé ñîñòàâëÿþùåé
double ki = 0.2; // Êîýôôèöèåíò èíòåãðàëüíîé ñîñòàâëÿþùåé
double e_prev = 0; // Ïðåäûäóùåå çíà÷åíèå îøèáêè
double i_term = 0; // Èíòåãðàëüíàÿ ñîñòàâëÿþùàÿ
// Ôóíêöèÿ, ðàññ÷èòûâàþùàÿ óïðàâëÿþùåå âîçäåéñòâèå
double calculate_control_action(double setpoint, double process_variable)
{
double error = setpoint - process_variable; // Âû÷èñëÿåì îøèáêó
// Âû÷èñëÿåì èíòåãðàëüíóþ ñîñòàâëÿþùóþ
i_term += ki * error;
// Àäàïòèâíûé êîýôôèöèåíò ïðîïîðöèîíàëüíîé ñîñòàâëÿþùåé
double adaptive_kp = kp / (1 + (i_term * i_term));
// Âû÷èñëÿåì óïðàâëÿþùåå âîçäåéñòâèå
double control_action = adaptive_kp * error + i_term;
// Ñîõðàíÿåì ïðåäûäóùåå çíà÷åíèå îøèáêè
e_prev = error;
return control_action;
}
int main()
{
double setpoint = 25.0; // Çàäàííîå çíà÷åíèå
double process_variable = 20.0; // Èçìåðåííîå çíà÷åíèå
// Ïå÷àòàåì óïðàâëÿþùåå âîçäåéñòâèå
printf("Control action: %f\n", calculate_control_action(setpoint, process_variable));
return 0;
}

View File

@ -1,193 +0,0 @@
/*=====================================================================================
File name: RMP3CNTL.C (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description: The ramp3 down control
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
-------------------------------------------------------------------------------------*/
#include "dmctype.h"
#include "IQmathLib.h" // Include header for IQmath library
#include "rmp_cntl_v2.h"
/*
* PosRampPlus
* PosRampMinus
* NegRampPlus
* NegRampMinus
*/
#pragma CODE_SECTION(rmp_cntl_v2_calc,".fast_run");
void rmp_cntl_v2_calc(RMP_V2 *v)
{
_iq tmp;
tmp = v->DesiredInput - v->Out;
if (v->Out>=0)
{
// äë˙ ďîëîćčňĺëüíîé ÷ŕńňč
if (v->Out >= v->RampHighLimit1)
{
// ěű íŕ âňîđîě óđîâíĺ
if (tmp > (_iq)v->PosRampPlus2)
{
v->Out += v->PosRampPlus2;
if (v->Out > v->RampHighLimit)
v->Out = v->RampHighLimit;
}
else
{
if (tmp < (_iq)v->PosRampMinus2)
{
v->Out += (_iq)v->PosRampMinus2;
if (v->Out < v->RampLowLimit)
v->Out = v->RampLowLimit;
}
else
{
v->Out = v->DesiredInput;
}
}
}
else
{
// ěű íŕ ďĺđâîě óđîâíĺ
if (tmp > (_iq)v->PosRampPlus1)
{
v->Out += v->PosRampPlus1;
if (v->Out > v->RampHighLimit)
v->Out = v->RampHighLimit;
}
else
{
if (tmp < (_iq)v->PosRampMinus1)
{
v->Out += (_iq)v->PosRampMinus1;
if (v->Out < v->RampLowLimit)
v->Out = v->RampLowLimit;
}
else
{
v->Out = v->DesiredInput;
}
}
}
// if (tmp > (_iq)v->PosRampPlus)
// {
// //v->RampDoneFlag = 0;
// v->Out += v->PosRampPlus;
// if (v->Out > v->RampHighLimit)
// v->Out = v->RampHighLimit;
// }
// else
// {
// if (tmp < (_iq)v->PosRampMinus)
// {
// //v->RampDoneFlag = 0;
// v->Out += (_iq)v->PosRampMinus;
// if (v->Out < v->RampLowLimit)
// v->Out = v->RampLowLimit;
// }
// else
// {
// v->Out = v->DesiredInput;
// //v->RampDoneFlag = 0x7FFFFFFF;
// }
// }
}
else
{
// äë˙ îňđčö. ÷ŕńňč
if (v->Out <= v->RampLowLimit1)
{
// ěű íŕ âňîđîě óđîâíĺ
if (tmp > (_iq)v->NegRampPlus2)
{
v->Out += v->NegRampPlus2;
if (v->Out > v->RampHighLimit)
v->Out = v->RampHighLimit;
}
else
{
if (tmp < (_iq)v->NegRampMinus2)
{
v->Out += (_iq)v->NegRampMinus2;
if (v->Out < v->RampLowLimit)
v->Out = v->RampLowLimit;
}
else
{
v->Out = v->DesiredInput;
}
}
}
else
{
// ěű íŕ ďĺđâîě óđîâíĺ
if (tmp > (_iq)v->NegRampPlus1)
{
v->Out += v->NegRampPlus1;
if (v->Out > v->RampHighLimit)
v->Out = v->RampHighLimit;
}
else
{
if (tmp < (_iq)v->NegRampMinus1)
{
v->Out += (_iq)v->NegRampMinus1;
if (v->Out < v->RampLowLimit)
v->Out = v->RampLowLimit;
}
else
{
v->Out = v->DesiredInput;
}
}
}
// if (tmp > (_iq)v->NegRampPlus)
// {
// //v->RampDoneFlag = 0;
// v->Out += v->NegRampPlus;
// if (v->Out > v->RampHighLimit)
// v->Out = v->RampHighLimit;
// }
// else
// {
// if (tmp < (_iq)v->NegRampMinus)
// {
// //v->RampDoneFlag = 0;
// v->Out += (_iq)v->NegRampMinus;
// if (v->Out < v->RampLowLimit)
// v->Out = v->RampLowLimit;
// }
// else
// {
// v->Out = v->DesiredInput;
// //v->RampDoneFlag = 0x7FFFFFFF;
// }
// }
}
}

View File

@ -1,69 +0,0 @@
/* =================================================================================
File name: RMP3CNTL.H (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description:
Header file containing constants, data type definitions, and
function prototypes for the RMP3 module.
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
------------------------------------------------------------------------------*/
#ifndef __RMP_CNTL_V2_H__
#define __RMP_CNTL_V2_H__
typedef struct { _iq DesiredInput; // Input: Desired ramp input (Q0) - independently with global Q
_iq PosRampPlus1; // Parameter: Ramp3 delay expressed in no of sampling period (Q0) - independently with global Q
_iq PosRampMinus1; // Variable: Counter for rmp3 delay (Q0) - independently with global Q
_iq PosRampPlus2; // Parameter: Ramp3 delay expressed in no of sampling period (Q0) - independently with global Q
_iq PosRampMinus2; // Variable: Counter for rmp3 delay (Q0) - independently with global Q
_iq NegRampPlus1; // Parameter: Ramp3 delay expressed in no of sampling period (Q0) - independently with global Q
_iq NegRampMinus1; // Variable: Counter for rmp3 delay (Q0) - independently with global Q
_iq NegRampPlus2; // Parameter: Ramp3 delay expressed in no of sampling period (Q0) - independently with global Q
_iq NegRampMinus2; // Variable: Counter for rmp3 delay (Q0) - independently with global Q
_iq Out; // Output: Ramp3 output (Q0) - independently with global Q
_iq RampLowLimit1; // Parameter: Minimum ramp output (Q0) - independently with global Q
_iq RampHighLimit1; // Parameter: Minimum ramp output (Q0) - independently with global Q
_iq RampLowLimit; // Parameter: Minimum ramp output (Q0) - independently with global Q
_iq RampHighLimit; // Parameter: Minimum ramp output (Q0) - independently with global Q
//Uint32 RampDoneFlag; // Output: Flag output (Q0) - independently with global Q
void (*calc)(); // Pointer to calculation function
} RMP_V2;
typedef RMP_V2 *RMP_V2_handle;
/*-----------------------------------------------------------------------------
Default initalizer for the RMP3 object.
-----------------------------------------------------------------------------*/
#define RMP_V2_DEFAULTS { 0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0x00000050, \
(void (*)())rmp_cntl_v2_calc }
/*------------------------------------------------------------------------------
Prototypes for the functions in RMP3CNTL.C
------------------------------------------------------------------------------*/
void rmp_cntl_v2_calc(RMP_V2_handle);
#endif // __RMP3_CNTL_H__

View File

@ -26,7 +26,6 @@
#include "svgen_dq.h"
#include "svgen_mf.h"
#include "dq_to_alphabeta_cos.h"
#include "params_norma.h"
@ -176,7 +175,6 @@ void uf_disbalance_uzpt(_iq Uzad_uf1, unsigned int disable_alg_u_disbalance, _iq
_iq pwm_t,delta_U,Uplus,Uminus;
volatile _iq Kplus;
static _iq u1=0,u2=0;
static _iq delta_U_minimal = _IQ (25.0/NORMA_ACP);
volatile _iq KplusMax;
@ -189,9 +187,6 @@ void uf_disbalance_uzpt(_iq Uzad_uf1, unsigned int disable_alg_u_disbalance, _iq
delta_U = Uplus - Uminus;
if (_IQabs(delta_U) < delta_U_minimal)
delta_U = 0;
if (disable_alg_u_disbalance==0)
{
if (kplus_u_disbalance!=0) // åñëè ìû çàäàëè èçâíå, òî åãî è èñïîëüçóåì, ýòî äëÿ òåñòà.
@ -355,15 +350,10 @@ void uf_const_f_24_Ing(_iq Fzad_uf1,_iq Fzad_uf2,_iq Uzad_uf1, _iq Uzad_uf2,
////////////////////////////////////////////////////////////
#pragma CODE_SECTION(test_calc_simple_dq_pwm24_Ing,".v_24pwm_run");
void test_calc_simple_dq_pwm24_Ing(_iq Fzad_uf1,
_iq Uzad_uf1,
unsigned int disable_alg_u_disbalance,
_iq kplus_u_disbalance,
_iq k_u_disbalance,
_iq U_1,
_iq U_2,
unsigned int flag_km_0,
//#pragma CODE_SECTION(test_calc_simple_dq_pwm24_Ing,".v_24pwm_run");
void test_calc_simple_dq_pwm24_Ing(_iq Fzad_uf1,_iq Uzad_uf1,
unsigned int disable_alg_u_disbalance, _iq kplus_u_disbalance, _iq k_u_disbalance,
_iq U_1, _iq U_2, unsigned int flag_km_0,
_iq Uzad_max,
_iq master_tetta,
_iq master_Uzad_uf1,
@ -611,14 +601,11 @@ void test_calc_vect_dq_pwm24_Ing(_iq Theta_zad,_iq Ud_zad, _iq Uq_zad,
////////////////////////////////////////
Umod = _IQsqrt(_IQmpy(Ud_zad, Ud_zad) + _IQmpy(Uq_zad, Uq_zad));
if (Umod > max_Km) {
Uq_zad = _IQsqrt(max_Km_square - _IQmpy(Ud_zad, Ud_zad));
Uq = _IQsqrt(max_Km_square - _IQmpy(Ud_zad, Ud_zad));
}
Umod = _IQsqrt(_IQmpy(Ud_zad, Ud_zad) + _IQmpy(Uq_zad, Uq_zad));
uf_disbalance_uzpt(Umod, disable_alg_u_disbalance, kplus_u_disbalance,
k_u_disbalance, U_1, U_2, Uzad_max, &Kplus);
*Kplus_out = Kplus;
*Uzad_out = Umod;
////////////////////////////////////////
////////////////////////////////////////

View File

@ -2,9 +2,9 @@
#include "alg_pll.h"
#include "params_pll.h"
#include "params_norma.h"
//#define NORMA_ACP 3000
#define NORMA_ACP 3000
//#define FREQ_PWM_VIPR 1975
//#define SIZE_PLL_AVG 50
@ -12,9 +12,8 @@
//_iq w_in_avg[SIZE_PLL_AVG];
//_iq w_out_avg[SIZE_PLL_AVG];
#define DETECT_PLL_D (2000.0/NORMA_ACP) // ampl
#define DETECT_PLL_Q (500.0/NORMA_ACP) // zero
#define DETECT_PLL_D (100.0/NORMA_ACP) // ampl
#define DETECT_PLL_Q (100.0/NORMA_ACP) // zero
_iq iqDetect_PLL_d=_IQ(DETECT_PLL_D);
_iq iqDetect_PLL_q=_IQ(DETECT_PLL_Q);
@ -105,7 +104,7 @@ void AB_BC_CA_To_ABC(_iq U_AB, _iq U_BC, _iq U_CA, _iq *Ua, _iq *Ub, _iq *Uc)
/////////////////////////////////////////////////
#pragma CODE_SECTION(PLLController,".fast_run");
//#pragma CODE_SECTION(PLLController,".fast_run");
/////////////////////////////////////////////////
void PLLController(PLL_REC *v)
{
@ -319,9 +318,9 @@ void PLLController(PLL_REC *v)
//////////////////////////////////////////////////
//////////////////////////////////////////////////
/////////////////////////////////////////////////
//#pragma CODE_SECTION(pll_get_freq,".fast_run");
#pragma CODE_SECTION(pll_get_freq,".fast_run");
/////////////////////////////////////////////////
void pll_get_freq_float(PLL_REC *v)
void pll_get_freq(PLL_REC *v)
{
if (v->output.flag_find_pll)
@ -337,22 +336,9 @@ void pll_get_freq_float(PLL_REC *v)
//////////////////////////////////////////////////
//////////////////////////////////////////////////
void pll_get_freq_iq(PLL_REC *v)
{
if (v->output.flag_find_pll)
{
v->output.iq_freq_net = v->vars.w_shtrih;//_IQtoF( v->vars.w_shtrih) * v->setup.freq_run_pll / PI * 50.00; // freq*100
}
else
{
v->output.iq_freq_net = 0;
}
}
//////////////////////////////////////////////////
//#pragma CODE_SECTION(detect_phase_count,".fast_run");
void detect_phase_count(PLL_REC *v)
{
static _iq prev_Ua = 0;

View File

@ -59,11 +59,10 @@ typedef struct { _iq Input_U_AB; //
typedef struct { int flag_find_pll;
int int_freq_net;
_iq iq_freq_net;
int status;
} PLL_OUTPUT;
#define PLL_OUTPUT_DEFAULT {0, 0, 0, STATUS_PLL_NOT_INITED}
#define PLL_OUTPUT_DEFAULT {0, 0, STATUS_PLL_NOT_INITED}
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
@ -140,8 +139,7 @@ typedef struct { PLL_INPUT input;
PLL_VARS vars;
void (*init)(); // Pointer to calculation function
void (*calc_pll)(); // Pointer to calculation function
void (*get_freq_float)(); // Pointer to calculation function
void (*get_freq_iq)();
void (*get_freq)(); // Pointer to calculation function
}PLL_REC;
typedef PLL_REC *PLL_REC_handle;
@ -153,14 +151,12 @@ typedef PLL_REC *PLL_REC_handle;
PLL_VARS_DEFAULT,\
(void (*)(unsigned long))pll_init,\
(void (*)(unsigned long))pll_calc,\
(void (*)(unsigned long))pll_get_freq_float,\
(void (*)(unsigned long))pll_get_freq_iq \
}
(void (*)(unsigned long))pll_get_freq\
}
void pll_init(PLL_REC_handle);
void pll_calc(PLL_REC_handle);
void pll_get_freq_float(PLL_REC_handle);
void pll_get_freq_iq(PLL_REC_handle);
void pll_get_freq(PLL_REC_handle);
void Find_zero_Uabc(PLL_REC_handle);
void PLLController(PLL_REC *v);

View File

@ -32,7 +32,7 @@ void init_teta_calc_struct()
tetta_calc.hz_to_angle = _IQ(2.0 * PI * NORMA_FROTOR / FREQ_PWM);
}
//#pragma CODE_SECTION(calc_teta_Id,".fast_run");
#pragma CODE_SECTION(calc_teta_Id,".fast_run");
void calc_teta_Id(_iq Frot, _iq Id, _iq Iq, _iq *theta_out, _iq *theta_to_slave, _iq *Fsl_out, _iq *Fstator_out,
unsigned int master, int reset) {
@ -56,10 +56,9 @@ void calc_teta_Id(_iq Frot, _iq Id, _iq Iq, _iq *theta_out, _iq *theta_to_slave,
} else {
Fsl = 0;
}
if (Fsl > MAX_Ud_Pid_Out_Id) { Fsl = MAX_Ud_Pid_Out_Id;}
if (Fsl < -MAX_Ud_Pid_Out_Id) { Fsl = -MAX_Ud_Pid_Out_Id;}
// if (Fsl < 0) { Fsl = 0;}
// if (Fsl < -MAX_Ud_Pid_Out_Id) { Fsl = -MAX_Ud_Pid_Out_Id;}
if (Fsl < 0) { Fsl = 0;}
Fst = Frot * POLUS + Fsl;
add_to_tic = _IQmpy(Fst, tetta_calc.hz_to_angle);

View File

@ -85,7 +85,7 @@ void vectorControlConstId (_iq Pzad, _iq Fzad, int direction, _iq Frot,
_iq P_measured = 0;
static _iq Ud_zad1 = 0, Uq_zad1 = 0, Ud_zad2 = 0, Uq_zad2 = 0;
// if(direction < 0) { Frot = -Frot; }
if(direction < 0) { Frot = -Frot; }
if (reset) {
Ud_zad1 = 0;
@ -134,13 +134,8 @@ void vectorControlConstId (_iq Pzad, _iq Fzad, int direction, _iq Frot,
vect_control.iqUqKm = Uq_zad1 + vect_control.iqUqCompensation;
}
vect_control.sqrtIdq1 = _IQsqrt(_IQmpy(vect_control.iqId1, vect_control.iqId1) + _IQmpy(vect_control.iqIq1, vect_control.iqIq1));
analog_Udq_calc(Ud_zad1, Uq_zad1, Ud_zad2, Uq_zad2);
*Iq_to_slave = Iq_zad;
vect_control.Iq_zad1 = Iq_zad;
vect_control.Id_zad1 = Id_zad;
}

View File

@ -49,22 +49,12 @@ typedef struct {
_iq koef_Ud_comp;
_iq koef_Uq_comp;
_iq koef_zero_Uzad;
_iq add_tetta;
_iq sqrtIdq1;
_iq sqrtIdq2;
_iq Iq_zad1;
_iq Id_zad1;
_iq add_bpsi;
} VECTOR_CONTROL;
#define VECTOR_CONTROL_DEFAULTS {PIDREG3_DEFAULTS, PIDREG3_DEFAULTS, \
PIDREG3_DEFAULTS, PIDREG3_DEFAULTS, \
0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
0,0,0,0,0,0,0,0,0,0,0}
void vectorControlConstId (_iq Pzad, _iq Fzad, int direction, _iq Frot,
int n_alg, unsigned int master, _iq mzz_zad,

View File

@ -73,9 +73,6 @@ typedef struct
CMD_DIGIT_BYTE_STRUCT Byte03;
CMD_DIGIT_BYTE_STRUCT Byte04;
CMD_DIGIT_BYTE_STRUCT Byte05;
CMD_DIGIT_BYTE_STRUCT Byte06;
} CMD_DIGIT_DATA_STRUCT;
typedef struct
@ -115,13 +112,6 @@ typedef struct
CHAR analog1_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog2_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog2_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog3_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog3_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog4_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog4_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog5_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog5_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
} CMD_ANALOG_DATA_TEST_ALL_STRUCT;
typedef struct
@ -221,19 +211,6 @@ typedef struct
CMD_DIGIT_BYTE_STRUCT byte49;
CMD_DIGIT_BYTE_STRUCT byte50;
CMD_DIGIT_BYTE_STRUCT byte51;
CMD_DIGIT_BYTE_STRUCT byte52;
CMD_DIGIT_BYTE_STRUCT byte53;
CMD_DIGIT_BYTE_STRUCT byte54;
CMD_DIGIT_BYTE_STRUCT byte55;
CMD_DIGIT_BYTE_STRUCT byte56;
CMD_DIGIT_BYTE_STRUCT byte57;
CMD_DIGIT_BYTE_STRUCT byte58;
CMD_DIGIT_BYTE_STRUCT byte59;
CMD_DIGIT_BYTE_STRUCT byte60;
} ANS_DIGIT_DATA_TO_TERMINAL_STRUCT; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè îò ÑÓ
@ -384,67 +361,6 @@ typedef struct
CHAR analog68_lo;
CHAR analog68_hi;
CHAR analog69_lo;
CHAR analog69_hi;
CHAR analog70_lo;
CHAR analog70_hi;
CHAR analog71_lo;
CHAR analog71_hi;
CHAR analog72_lo;
CHAR analog72_hi;
CHAR analog73_lo;
CHAR analog73_hi;
CHAR analog74_lo;
CHAR analog74_hi;
CHAR analog75_lo;
CHAR analog75_hi;
CHAR analog76_lo;
CHAR analog76_hi;
CHAR analog77_lo;
CHAR analog77_hi;
CHAR analog78_lo;
CHAR analog78_hi;
CHAR analog79_lo;
CHAR analog79_hi;
CHAR analog80_lo;
CHAR analog80_hi;
CHAR analog81_lo;
CHAR analog81_hi;
CHAR analog82_lo;
CHAR analog82_hi;
CHAR analog83_lo;
CHAR analog83_hi;
CHAR analog84_lo;
CHAR analog84_hi;
CHAR analog85_lo;
CHAR analog85_hi;
CHAR analog86_lo;
CHAR analog86_hi;
CHAR analog87_lo;
CHAR analog87_hi;
CHAR analog88_lo;
CHAR analog88_hi;
CHAR analog89_lo;
CHAR analog89_hi;
CHAR analog90_lo;
CHAR analog90_hi;
CHAR analog91_lo;
CHAR analog91_hi;
CHAR analog92_lo;
CHAR analog92_hi;
CHAR analog93_lo;
CHAR analog93_hi;
CHAR analog94_lo;
CHAR analog94_hi;
CHAR analog95_lo;
CHAR analog95_hi;
CHAR analog96_lo;
CHAR analog96_hi;
} TMS_ANALOG_DATA_STRUCT;
@ -498,17 +414,6 @@ typedef struct
CMD_DIGIT_BYTE_STRUCT byte23;
CMD_DIGIT_BYTE_STRUCT byte24;
CMD_DIGIT_BYTE_STRUCT byte25;
CMD_DIGIT_BYTE_STRUCT byte26;
CMD_DIGIT_BYTE_STRUCT byte27;
CMD_DIGIT_BYTE_STRUCT byte28;
CMD_DIGIT_BYTE_STRUCT byte29;
CMD_DIGIT_BYTE_STRUCT byte30;
CMD_DIGIT_BYTE_STRUCT byte31;
CMD_DIGIT_BYTE_STRUCT byte32;
CMD_DIGIT_BYTE_STRUCT byte33;
CMD_DIGIT_BYTE_STRUCT byte34;
} ANS_DIGIT_DATA_TO_TERMINAL_TEST_ALL_STRUCT;
typedef struct

View File

@ -1,5 +1,3 @@
#include "params.h"
#include "global_time.h"
#include "RS_Functions.h"
#include <project.h>
@ -18,9 +16,6 @@
#include "CRC_Functions.h"
#include "TuneUpPlane.h" //ñâåòîäèîäèê
#include "pwm_test_lines.h"
#include "profile_interrupt.h"
#define _ENABLE_INTERRUPT_RS232_LED2 0//1
@ -29,8 +24,8 @@
#define RS232_SPEED 57600//115200
#define COM_1 0 //1
#define COM_2 1 //2
#define COM_1 1
#define COM_2 2
//#define SIZE_MODBUS_TABLE 334
//#define ADR_MODBUS_TABLE 0x0001
@ -82,7 +77,8 @@
//#define SCIb_Wait4OK() while(!SCIb_OK())
#define SCIb_Send(a) ScibRegs.SCITXBUF = (unsigned char)a
#define EnableReceiveRS485() GpioDataRegs.GPBDAT.bit.GPIOB14 = 1
#define EnableSendRS485() GpioDataRegs.GPBDAT.bit.GPIOB14 = 0
#define SCIa_Get() SciaRegs.SCIRXBUF.bit.RXDT
@ -111,10 +107,10 @@ unsigned int RS_Len[RS_LEN_CMD] = {0};
char size_cmd15 = 1;
char size_cmd16 = 1;
//unsigned int enable_profile_led1_rsa = 1;
//unsigned int enable_profile_led1_rsb = 1;
//unsigned int enable_profile_led2_rsa = 0;
//unsigned int enable_profile_led2_rsb = 0;
unsigned int enable_profile_led1_rsa = 1;
unsigned int enable_profile_led1_rsb = 1;
unsigned int enable_profile_led2_rsa = 0;
unsigned int enable_profile_led2_rsb = 0;
@ -125,8 +121,6 @@ int ADDR_FOR_ALL = ADDR_FOR_ALL_DEF;
float KmodTerm = 0.0, freqTerm = 0.0;
int flag_special_mode_rs = 0;
int disable_flag_special_mode_rs = 0;
void RS_Wait4OK_TXRDY(char commnumber);
@ -147,27 +141,6 @@ void RS_LineToSend(char commnumber);
void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr);
//int RS232_BSend(RS_DATA_STRUCT *RS232_Arr,unsigned int *pBuf, unsigned long len);
void EnableReceiveRS485(void)
{
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_19_ON;
#endif
GpioDataRegs.GPBDAT.bit.GPIOB14 = 1;
}
void EnableSendRS485(void)
{
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_19_OFF;
#endif
GpioDataRegs.GPBDAT.bit.GPIOB14 = 0;
}
void T_Flash(RS_DATA_STRUCT *RS232_Arr)
{
volatile unsigned long Address1,Address2;
@ -338,12 +311,9 @@ void SCI_SwReset(char commnumber)
//////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////
//static int buf_fifo_rsa[17]={0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0};
//static int buf_fifo_rsb[17]={0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0};
static int buf_fifo_rsa[17]={0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0};
static int buf_fifo_rsb[17]={0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0};
static int buf_fifo_rs_ab[2][17]={ {0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0}, {0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0} };
#pragma CODE_SECTION(my_test_rs,".fast_run2");
int my_test_rs(int comn)
{
int cc=0;
@ -353,7 +323,7 @@ int my_test_rs(int comn)
{
while ((SciaRegs.SCIFFRX.bit.RXFIFST != 0) )
{
buf_fifo_rs_ab[comn][cc++] = SciaRegs.SCIRXBUF.bit.RXDT;
buf_fifo_rsa[cc++] = SciaRegs.SCIRXBUF.bit.RXDT;
if (cc>=17) cc = 0;
}
return cc;
@ -362,7 +332,7 @@ int my_test_rs(int comn)
{
while ((ScibRegs.SCIFFRX.bit.RXFIFST != 0) )
{
buf_fifo_rs_ab[comn][cc++] = ScibRegs.SCIRXBUF.bit.RXDT;
buf_fifo_rsb[cc++] = ScibRegs.SCIRXBUF.bit.RXDT;
if (cc>=17) cc = 0;
}
return cc;
@ -371,7 +341,6 @@ int my_test_rs(int comn)
}
///////////////
//#pragma CODE_SECTION(RS_RXA_Handler_fast,".fast_run2");
void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
{
char Rc;
@ -380,7 +349,6 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
//i_led2_on_off(1);
ClearTimerRS_Live(RS232_Arr);
cn = RS232_Arr->commnumber;
@ -393,7 +361,7 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
if (SciaRegs.SCIRXST.bit.RXERROR)
{
// Rc = SciaRegs.SCIRXBUF.all;
(RS232_Arr->count_recive_rxerror)++;
RS232_Arr->count_recive_rxerror++;
RS232_Arr->do_resetup_rs = 1;
}
if (SciaRegs.SCIRXST.bit.RXWAKE)
@ -407,7 +375,7 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
if (ScibRegs.SCIRXST.bit.RXERROR)
{
// Rc = SciaRegs.SCIRXBUF.all;
(RS232_Arr->count_recive_rxerror)++;
RS232_Arr->count_recive_rxerror++;
RS232_Arr->do_resetup_rs = 1;
}
if (ScibRegs.SCIRXST.bit.RXWAKE)
@ -435,14 +403,12 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
// continue;
// }
cc1--;
if (cn==COM_1)
Rc = buf_fifo_rsa[cc2++];//SciaRegs.SCIRXBUF.all;// SciaRegs.SCIRXBUF.bit.RXDT;//RS_Get(RS232_Arr->commnumber); // ×èòàåì ñèìâîë â ëþáîì ñëó÷àå
else
Rc = buf_fifo_rsb[cc2++];
// if (cn==COM_1)
Rc = buf_fifo_rs_ab[cn][cc2];//SciaRegs.SCIRXBUF.all;// SciaRegs.SCIRXBUF.bit.RXDT;//RS_Get(RS232_Arr->commnumber); // ×èòàåì ñèìâîë â ëþáîì ñëó÷àå
// else
// Rc = buf_fifo_rsb[cc2];
cc2++;
(RS232_Arr->count_recive_bytes_all)++;
RS232_Arr->count_recive_bytes_all++;
//i_led2_on_off(0);
if(RS232_Arr->RS_DataReady)
@ -462,7 +428,7 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
//i_led2_on_off(1);
if(RS232_Arr->RS_FlagSkiping)
{
(RS232_Arr->count_recive_bytes_skipped)++;
RS232_Arr->count_recive_bytes_skipped++;
continue; // Íå íàì
}
@ -482,10 +448,10 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
}
else
{
//i_led1_toggle();
i_led1_toggle();
RS232_Arr->RS_FlagSkiping = true; // Íå íàøåìó êîíòðîëëåðó
RS232_Arr->RS_FlagBegin = false; // îñòàëèñü â 9-áèò ðåæèìå
(RS232_Arr->count_recive_cmd_skipped)++;
RS232_Arr->count_recive_cmd_skipped++;
//i_led1_on_off(0);
}
//i_led2_on_off(1);
@ -524,7 +490,7 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
RS232_Arr->RS_FlagBegin = true;
RS232_Arr->RS_FlagSkiping = false;
RS232_Arr->RS_Cmd=0;
(RS232_Arr->count_recive_bad)++;
RS232_Arr->count_recive_bad++;
continue;
}
if(RS232_Arr->RS_Cmd == 4) {
@ -544,7 +510,7 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
RS232_Arr->RS_FlagSkiping = true;
RS232_Arr->RS_DataReady = true;
RS232_Arr->RS_Cmd=0;
(RS232_Arr->count_recive_dirty)++;
RS232_Arr->count_recive_dirty++;
}
//i_led2_on_off(1);
}
@ -559,14 +525,14 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
if(RS232_Arr->RS_PrevCmd != CMD_RS232_INITLOAD)
{
(RS232_Arr->count_recive_bad)++;
RS232_Arr->count_recive_bad++;
continue; // Ìû çäåñü îêàçàëèñü ïî êàêîé-òî ÷óäîâèùíîé îøèáêå
}
if(RS232_Arr->RS_DataReady) // Åñëè äàííûå â îñíîâíîì öèêëå íå çàáðàíû,
{ // òî ïðîïóñêàåì ñëåäóþùóþ ïîñûëêó
RS232_Arr->RS_FlagSkiping = true; // Èãíîðèðóåì äî ñëåäóþùåãî çàãîëîâêà
(RS232_Arr->count_recive_cmd_skipped)++;
RS232_Arr->count_recive_cmd_skipped++;
continue;
}
@ -580,7 +546,7 @@ void RS_RXA_Handler_fast(RS_DATA_STRUCT *RS232_Arr)
RS_SetBitMode(RS232_Arr,9); // Ïîëó÷èëè âñå äàííûå ïåðåñòðîèëèñü â 9-áèò äëß RS485?
RS232_Arr->RS_FlagSkiping = true; // Èãíîðèðóåì äî ñëåäóþùåãî çàãîëîâêà
RS232_Arr->RS_DataReady = true; // Ôëàã â îñíîâíîé öèêë - äàííûå ïîëó÷åíû
(RS232_Arr->count_recive_dirty)++;
RS232_Arr->count_recive_dirty++;
}
}
}
@ -603,20 +569,15 @@ int get_free_rs_fifo_tx(char commnumber)
void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr)
{
char RS232_BytePtr;
unsigned int final_flag=0, free_fifo;
unsigned int i;
int final_flag=0, free_fifo;
int i;
static unsigned int max_s_b = 1; // ïîñûëàåì ïî max_s_b øòóê
unsigned int final_free_fifo=0;
// if(RS232_Arr->RS_SendBlockMode == BM_CHAR32)
// {
free_fifo = get_free_rs_fifo_tx(RS232_Arr->commnumber);
ClearTimerRS_Live(RS232_Arr);
if (free_fifo>=max_s_b)
free_fifo=max_s_b; // ïîñûëàåì ïî max_s_b øòóê
for (i=0;i<free_fifo;i++)
{
@ -640,7 +601,7 @@ void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr)
else
SCI_Send(RS232_Arr->commnumber,*(RS232_Arr->pRS_SendPtr_stage1++));
(RS232_Arr->RS_SendLen)++;
RS232_Arr->RS_SendLen++;
break;
}
break;
@ -663,7 +624,7 @@ void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr)
else
SCI_Send(RS232_Arr->commnumber,*(RS232_Arr->pRS_SendPtr_stage2++));
(RS232_Arr->RS_SendLen)++;
RS232_Arr->RS_SendLen++;
break;
}
break;
@ -687,7 +648,7 @@ void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr)
else
SCI_Send(RS232_Arr->commnumber,*(RS232_Arr->pRS_SendPtr++));
(RS232_Arr->RS_SendLen)++;
RS232_Arr->RS_SendLen++;
}
break;
default :
@ -700,14 +661,10 @@ void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr)
if (final_flag)
{
final_free_fifo = get_free_rs_fifo_tx(RS232_Arr->commnumber);
if (final_free_fifo>=15) // âñå óåõàëè? áóôåð ÷èñò?
{
if(RS232_Arr->RS_SendBlockMode == BM_CHAR32)
{
// if (max_s_b>1)
// RS_Wait4OK(RS232_Arr->commnumber);
// RS_Wait4OK_TXRDY(RS232_Arr->commnumber);
RS_Wait4OK(RS232_Arr->commnumber);
RS_SetBitMode(RS232_Arr,9); /* Ïåðåäàëè âñå ïåðåñòðîèëèñü â 9-áèò äëß RS485?*/
RS_LineToReceive(RS232_Arr->commnumber); /* ðåæèì ïðèåìà RS485 */
@ -721,7 +678,6 @@ void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr)
EnableUART_Int_RX(RS232_Arr->commnumber); /* Çàïðåùàåì ïðåðûâàíèß ïî ïåðåäà÷å */
}
}
}
//
@ -731,7 +687,6 @@ void RS_TX_Handler(RS_DATA_STRUCT *RS232_Arr)
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
//#pragma CODE_SECTION(RSA_TX_Handler,".fast_run2");
interrupt void RSA_TX_Handler(void)
{
// Set interrupt priority:
@ -746,16 +701,14 @@ i_led2_on_off(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsa)
if (enable_profile_led1_rsa)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsa)
if (enable_profile_led2_rsa)
i_led2_on_off_special(1);
#endif
EINT;
@ -778,11 +731,11 @@ i_led2_on_off(1);
PieCtrlRegs.PIEIER9.all = TempPIEIER;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsa)
if (enable_profile_led1_rsa)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsa)
if (enable_profile_led2_rsa)
i_led2_on_off_special(0);
#endif
@ -791,13 +744,13 @@ i_led2_on_off(1);
i_led2_on_off(0);
#endif
}
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
//#pragma CODE_SECTION(RSB_TX_Handler,".fast_run2");
interrupt void RSB_TX_Handler(void)
{
// Set interrupt priority:
@ -807,20 +760,17 @@ interrupt void RSB_TX_Handler(void)
PieCtrlRegs.PIEIER9.all &= MG94; // Set "group" priority
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_16_ON;
#endif
#if (_ENABLE_INTERRUPT_RS232_LED2)
i_led2_on_off(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsb)
if (enable_profile_led1_rsb)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsb)
if (enable_profile_led2_rsb)
i_led2_on_off_special(1);
#endif
@ -846,11 +796,11 @@ i_led2_on_off(1);
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsb)
if (enable_profile_led1_rsb)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsb)
if (enable_profile_led2_rsb)
i_led2_on_off_special(0);
#endif
@ -858,17 +808,11 @@ i_led2_on_off(1);
i_led2_on_off(0);
#endif
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_16_OFF;
#endif
}
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
//#pragma CODE_SECTION(RSA_RX_Handler,".fast_run2");
interrupt void RSA_RX_Handler(void)
{
// Set interrupt priority:
@ -884,11 +828,11 @@ i_led2_on_off(1);
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsa)
if (enable_profile_led1_rsa)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsa)
if (enable_profile_led2_rsa)
i_led2_on_off_special(1);
#endif
@ -920,11 +864,11 @@ i_led2_on_off(1);
PieCtrlRegs.PIEIER9.all = TempPIEIER;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsa)
if (enable_profile_led1_rsa)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsa)
if (enable_profile_led2_rsa)
i_led2_on_off_special(0);
#endif
@ -938,7 +882,7 @@ i_led2_on_off(0);
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
//#pragma CODE_SECTION(RSB_RX_Handler,".fast_run2");
interrupt void RSB_RX_Handler(void)
{
// Set interrupt priority:
@ -948,23 +892,17 @@ interrupt void RSB_RX_Handler(void)
PieCtrlRegs.PIEIER9.all &= MG93; // Set "group" priority
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_17_ON;
#endif
#if (_ENABLE_INTERRUPT_RS232_LED2)
i_led2_on_off(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsb)
if (enable_profile_led1_rsb)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsb)
if (enable_profile_led2_rsb)
i_led2_on_off_special(1);
#endif
@ -987,11 +925,11 @@ i_led2_on_off(1);
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.rsb)
if (enable_profile_led1_rsb)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.rsb)
if (enable_profile_led2_rsb)
i_led2_on_off_special(0);
#endif
@ -999,9 +937,6 @@ i_led2_on_off(1);
i_led2_on_off(0);
#endif
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_17_OFF;
#endif
}
@ -1120,10 +1055,6 @@ float SciBaud;
//////////////////////////////////////////////////////
void EnableUART_Int_RX(char commnumber)
{
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_18_ON;
#endif
switch (commnumber)
{
case COM_1: //SciaRegs.SCICTL2.bit.RXBKINTENA = 0;//1; //enableUARTInt_A();
@ -1154,10 +1085,6 @@ void EnableUART_Int_RX(char commnumber)
void EnableUART_Int_TX(char commnumber)
{
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_18_OFF;
#endif
switch (commnumber)
{
case COM_1: rs_a.RS_OnTransmitedData = 1;
@ -1372,31 +1299,22 @@ int test_rs_live(RS_DATA_STRUCT *rs_arr)
void inc_RS_timeout_cicle(void)
{
unsigned int i, t_refresh;
static unsigned int old_time_rs = 0;
t_refresh = get_delta_milisec(&old_time_rs, 1);
if (t_refresh>1000)
t_refresh = 1000;
if (t_refresh<1)
t_refresh = 1;
if (rs_a.time_wait_rs_out<RS_TIME_OUT_MAX)
rs_a.time_wait_rs_out += t_refresh;
rs_a.time_wait_rs_out++;
if (rs_b.time_wait_rs_out<RS_TIME_OUT_MAX)
rs_b.time_wait_rs_out += t_refresh;
rs_b.time_wait_rs_out++;
if (rs_a.time_wait_rs_out_mpu<RS_TIME_OUT_MAX)
rs_a.time_wait_rs_out_mpu += t_refresh;
rs_a.time_wait_rs_out_mpu++;
if (rs_b.time_wait_rs_out_mpu<RS_TIME_OUT_MAX)
rs_b.time_wait_rs_out_mpu += t_refresh;
rs_b.time_wait_rs_out_mpu++;
if ((rs_a.RS_Flag9bit==0) || rs_a.do_resetup_rs || SCIa_RX_Error())
{
if (rs_a.time_wait_rs_lost<RS_TIME_OUT_LOST)
rs_a.time_wait_rs_lost += t_refresh;
rs_a.time_wait_rs_lost++;
// else
// resetup_mpu_rs(&rs_a);
}
@ -1404,7 +1322,7 @@ void inc_RS_timeout_cicle(void)
if ((rs_b.RS_Flag9bit==0) || rs_b.do_resetup_rs || SCIb_RX_Error())
{
if (rs_b.time_wait_rs_lost<RS_TIME_OUT_LOST)
rs_b.time_wait_rs_lost += t_refresh;
rs_b.time_wait_rs_lost++;
// else
// resetup_mpu_rs(&rs_b);
}
@ -1432,21 +1350,8 @@ void resetup_rs_on_timeout_lost(int rsp)
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
void clear_buffers_rs(RS_DATA_STRUCT *rs_arr)
{
unsigned int i;
for (i=0;i<MAX_RECEIVE_LENGTH;i++)
rs_arr->RS_Header[i] = 0;
for (i=0;i<MAX_SEND_LENGTH;i++)
rs_arr->buffer[i] = 0;
}
///////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////
#ifdef _USE_RS_FIFO
void SetupUART(char commnumber, unsigned long speed_baud)
@ -1535,7 +1440,6 @@ void SetupUART(char commnumber, unsigned long speed_baud)
EDIS;
SetupArrCmdLength();
clear_buffers_rs(&rs_a);
RS_SetControllerLeading(&rs_a,false);
@ -1549,7 +1453,66 @@ void SetupUART(char commnumber, unsigned long speed_baud)
resetup_mpu_rs(&rs_a);
///////
//
//// enable TX, RX, internal SCICLK,
//// Disable RX ERR, SLEEP, TXWAKE
// SciaRegs.SCIFFCT.bit.ABDCLR=1;
// SciaRegs.SCIFFCT.bit.CDC=0;
//
// SciaRegs.SCICTL1.bit.RXERRINTENA=0;
// SciaRegs.SCICTL1.bit.SWRESET=0;
// SciaRegs.SCICTL1.bit.TXWAKE=0;
// SciaRegs.SCICTL1.bit.SLEEP=0;
// SciaRegs.SCICTL1.bit.TXENA=1;
// SciaRegs.SCICTL1.bit.RXENA=1;
//
////
//// SciaRegs.SCIFFTX.all=0xC028;
// SciaRegs.SCIFFRX.all=0x0000;
//
// SciaRegs.SCIFFRX.bit.RXFFIL=2; //Äëèíà íàèìåíüøåé êîìàíäû
// SciaRegs.SCIFFRX.bit.RXFFIENA = 1;//Receive FIFO interrupt enable
// SciaRegs.SCIFFRX.bit.RXFFINTCLR = 1;//Write 1 to clear RXFFINT flag in bit 7
//
// SciaRegs.SCIFFCT.all=0x00;
//
//
//
//// SciaRegs.SCICTL1.all =0x0023; // Relinquish SCI from Reset
//// SciaRegs.SCIFFTX.bit.TXFIFOXRESET=1;
//
////
//
// SciaRegs.SCIFFTX.bit.SCIFFENA=0; // TX fifo off
//
// EALLOW;
// PieVectTable.RXAINT = &RSA_RX_Handler;
// PieVectTable.TXAINT = &RSA_TX_Handler;
// PieCtrlRegs.PIEIER9.bit.INTx1=1; // PIE Group 9, INT1
// PieCtrlRegs.PIEIER9.bit.INTx2=1; // PIE Group 9, INT2
// IER |= M_INT9; // Enable CPU INT
// EDIS;
//
// SetupArrCmdLength();
// RS_SetLineSpeed(commnumber,speed_baud); /* ñêîðîñòü ëèíèè */
// RS_SetControllerLeading(&rs_a,false);
//
// RS_LineToReceive(commnumber); // ðåæèì ïðèåìà RS485
// EnableUART_Int(commnumber); // ðàçðåøåíèå ïðåðûâàíèé UART
//
// RS_SetBitMode(&rs_a,9);
// rs_a.RS_PrevCmd = 0; // íå áûëî íèêàêèõ êîìàíä
// SCI_RX_IntClear(commnumber);
//
// SciaRegs.SCICTL1.bit.SWRESET=1; // Relinquish SCI from Reset
//// SciaRegs.SCIFFTX.bit.TXFIFOXRESET=1;
//// SciaRegs.SCIFFRX.bit.RXFIFORESET=1;
//
// SciaRegs.SCIFFRX.bit.RXFIFORESET=1; // Re-enable receive FIFO operation
//
//
}
@ -1635,8 +1598,6 @@ void SetupUART(char commnumber, unsigned long speed_baud)
EDIS;
SetupArrCmdLength();
clear_buffers_rs(&rs_b);
RS_SetControllerLeading(&rs_b,false);
@ -1653,7 +1614,64 @@ void SetupUART(char commnumber, unsigned long speed_baud)
}
/*
if(commnumber==COM_2)
{
// Initialize SCI-B:
// Note: Clocks were turned on to the SCIA peripheral
// in the InitSysCtrl() function
EALLOW;
GpioMuxRegs.GPGMUX.bit.SCIRXDB_GPIOG5=1;
GpioMuxRegs.GPGMUX.bit.SCITXDB_GPIOG4=1;
GpioMuxRegs.GPBMUX.bit.C5TRIP_GPIOB14=0;
GpioMuxRegs.GPBDIR.bit.GPIOB14=1;
EDIS;
RS_SetLineMode(commnumber,8,'N',1);
// enable TX, RX, internal SCICLK,
// Disable RX ERR, SLEEP, TXWAKE
ScibRegs.SCIFFCT.bit.CDC=0;
ScibRegs.SCIFFCT.bit.ABDCLR=1;
ScibRegs.SCICTL1.bit.RXERRINTENA=0;
ScibRegs.SCICTL1.bit.SWRESET=0;
ScibRegs.SCICTL1.bit.TXWAKE=0;
ScibRegs.SCICTL1.bit.SLEEP=0;
ScibRegs.SCICTL1.bit.TXENA=1;
ScibRegs.SCICTL1.bit.RXENA=1;
ScibRegs.SCIFFTX.bit.SCIFFENA=0; // fifo off
ScibRegs.SCIFFRX.bit.RXFFIL=1; //Äëèíà íàèìåíüøåé êîìàíäû
EALLOW;
PieVectTable.RXBINT = &RSB_RX_Handler;
PieVectTable.TXBINT = &RSB_TX_Handler;
PieCtrlRegs.PIEIER9.bit.INTx3=1; // PIE Group 9, INT3
PieCtrlRegs.PIEIER9.bit.INTx4=1; // PIE Group 9, INT4
IER |= M_INT9; // Enable CPU INT
EDIS;
SetupArrCmdLength();
RS_SetLineSpeed(commnumber,speed_baud); // ñêîðîñòü ëèíèè
RS_SetControllerLeading(&rs_b,false);
RS_LineToReceive(commnumber); // ðåæèì ïðèåìà RS485
EnableUART_Int(commnumber); // ðàçðåøåíèå ïðåðûâàíèé UART
RS_SetBitMode(&rs_b,9);
rs_b.RS_PrevCmd = 0; // íå áûëî íèêàêèõ êîìàíä
SCI_RX_IntClear(commnumber);
ScibRegs.SCICTL1.bit.SWRESET=1; // Relinquish SCI from Reset
// SciaRegs.SCIFFTX.bit.TXFIFOXRESET=1;
// SciaRegs.SCIFFRX.bit.RXFIFORESET=1;
}
*/
}
#else
@ -2000,7 +2018,7 @@ int GetCommand(RS_DATA_STRUCT *RS232_Arr)
// Ïðîâåðßåì äëèíó êîìàíäû äëß ñ÷èòûâàíèß CRC
if((RS_Len[cmd]<3) || (RS_Len[cmd]>MAX_RECEIVE_LENGTH))
{
(RS232_Arr->count_recive_bad)++;
RS232_Arr->count_recive_bad++;
RS_LineToReceive(RS232_Arr->commnumber); // ðåæèì ïðèåìà RS485
RS_SetBitMode(RS232_Arr,9);
@ -2029,7 +2047,7 @@ int GetCommand(RS_DATA_STRUCT *RS232_Arr)
if(crc == rcrc) // Ïðîâåðßåì crc
{
(RS232_Arr->count_recive_ok)++;
RS232_Arr->count_recive_ok++;
RS232_Arr->RS_PrevCmd = cmd;
if (RS232_Arr->RS_DataSended)
@ -2041,7 +2059,7 @@ int GetCommand(RS_DATA_STRUCT *RS232_Arr)
}
else
{
(RS232_Arr->count_recive_error_crc)++;
RS232_Arr->count_recive_error_crc++;
RS_SetAdrAnswerController(RS232_Arr,0);
RS_SetControllerLeading(RS232_Arr, false);
@ -2065,8 +2083,7 @@ void ExtendBios(RS_DATA_STRUCT *RS232_Arr)
unsigned long AdrOut1,AdrOut2,LengthOut;
unsigned int cerr, repl, count_ok, return_code, old_started;
volatile unsigned int go_to_reset = 0, go_to_set_baud = 0;
unsigned long set_baud;
volatile unsigned int go_to_reset = 0;
//int code_eeprom;
old_started = x_parallel_bus_project.flags.bit.started;
@ -2210,18 +2227,6 @@ void ExtendBios(RS_DATA_STRUCT *RS232_Arr)
break;
case 100:
go_to_set_baud = 1;
set_baud = Address1;
// SetLoad28_FromResetInternalFlash();
// SelectReset28();
//speed_baud = Address1;
break;
default: break;
}
@ -2276,23 +2281,6 @@ void ExtendBios(RS_DATA_STRUCT *RS232_Arr)
}
if (go_to_set_baud)
{
// for (i=0;i<2;i++)
DELAY_US(1000000);
// DRTM;
// DINT;
// for (i=0;i<2;i++)
// DELAY_US(1000000);
RS_SetLineSpeed(RS232_Arr->commnumber, set_baud); /* ñêîðîñòü ëèíèè */
go_to_set_baud = 0;
}
return;
}
@ -2321,7 +2309,7 @@ int RS_Send(RS_DATA_STRUCT *RS232_Arr,unsigned int *pBuf,unsigned long len)
if (RS232_Arr->RS_DataWillSend)
{
// RS232_Arr->RS_DataReadyAnswer = 0;
RS232_Arr->RS_DataReadyAnswer = 0;
RS232_Arr->RS_DataReadyAnswer = 0;
RS232_Arr->RS_DataSended = 0;
}
@ -2384,31 +2372,10 @@ void RS232_WorkingWith(unsigned int enable_rs_a, unsigned int enable_rs_b, unsig
switch (GetCommand(&rs_a))
{
case CMD_RS232_INIT: break;
case CMD_RS232_INITLOAD:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
InitLoad(&rs_a);
break;
case CMD_RS232_LOAD:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
Load(&rs_a);
break;
case CMD_RS232_INITLOAD: flag_special_mode_rs = 1; InitLoad(&rs_a); break;
case CMD_RS232_LOAD: flag_special_mode_rs = 1; Load(&rs_a); break;
case CMD_RS232_RUN: break;
case CMD_RS232_PEEK:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
Peek(&rs_a);
case CMD_RS232_PEEK: flag_special_mode_rs = 1; Peek(&rs_a);
//Led1_Toggle();
break;
@ -2429,47 +2396,16 @@ void RS232_WorkingWith(unsigned int enable_rs_a, unsigned int enable_rs_b, unsig
#if (USE_TEST_TERMINAL)
case CMD_RS232_STD:
rs_a.RS_DataReadyRequest = 1;
flag_special_mode_rs = 0;
ReceiveCommand(&rs_a);
break;
case CMD_RS232_TEST_ALL:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
ReceiveCommandTestAll(&rs_a);
break;
rs_a.RS_DataReadyRequest = 1;
flag_special_mode_rs = 0;
ReceiveCommand(&rs_a);
break;
case CMD_RS232_TEST_ALL: flag_special_mode_rs = 1; ReceiveCommandTestAll(&rs_a); break;
#endif
case CMD_RS232_POKE:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
Poke(&rs_a);
Led2_Toggle();
break;
case CMD_RS232_UPLOAD:
// flag_special_mode_rs = 1;
Upload(&rs_a);
break;
case CMD_RS232_TFLASH:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
T_Flash(&rs_a);
break;
case CMD_RS232_EXTEND:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
ExtendBios(&rs_a);
break;
case CMD_RS232_POKE: flag_special_mode_rs = 1; Poke(&rs_a); Led2_Toggle(); break;
case CMD_RS232_UPLOAD: flag_special_mode_rs = 1; Upload(&rs_a); break;
case CMD_RS232_TFLASH: flag_special_mode_rs = 1; T_Flash(&rs_a); break;
case CMD_RS232_EXTEND: flag_special_mode_rs = 1; ExtendBios(&rs_a); break;
default: break;
} // end switch
@ -2482,31 +2418,10 @@ void RS232_WorkingWith(unsigned int enable_rs_a, unsigned int enable_rs_b, unsig
switch (GetCommand(&rs_b))
{
case CMD_RS232_INIT: break;
case CMD_RS232_INITLOAD:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
InitLoad(&rs_b);
break;
case CMD_RS232_LOAD:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
Load(&rs_b);
break;
case CMD_RS232_INITLOAD: flag_special_mode_rs = 1; InitLoad(&rs_b); break;
case CMD_RS232_LOAD: flag_special_mode_rs = 1; Load(&rs_b); break;
case CMD_RS232_RUN: break;
case CMD_RS232_PEEK:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
Peek(&rs_b);
break;
case CMD_RS232_PEEK: flag_special_mode_rs = 1; Peek(&rs_b); break;
#if USE_MODBUS_TABLE_SVU
@ -2593,43 +2508,13 @@ void RS232_WorkingWith(unsigned int enable_rs_a, unsigned int enable_rs_b, unsig
#endif
#if (USE_TEST_TERMINAL)
case CMD_RS232_STD: flag_special_mode_rs = 0;
ReceiveCommand(&rs_b);
break;
case CMD_RS232_TEST_ALL:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
ReceiveCommandTestAll(&rs_b);
break;
case CMD_RS232_STD: flag_special_mode_rs = 0; ReceiveCommand(&rs_b); break;
case CMD_RS232_TEST_ALL: flag_special_mode_rs = 1; ReceiveCommandTestAll(&rs_b); break;
#endif
case CMD_RS232_POKE:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
Poke(&rs_b);
break;
case CMD_RS232_UPLOAD:
// flag_special_mode_rs = 1;
Upload(&rs_b);
break;
case CMD_RS232_TFLASH:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
T_Flash(&rs_b);
break;
case CMD_RS232_EXTEND:
if (disable_flag_special_mode_rs)
break;
flag_special_mode_rs = 1;
ExtendBios(&rs_b);
break;
case CMD_RS232_POKE: flag_special_mode_rs = 1; Poke(&rs_b); break;
case CMD_RS232_UPLOAD: flag_special_mode_rs = 1; Upload(&rs_b); break;
case CMD_RS232_TFLASH: flag_special_mode_rs = 1; T_Flash(&rs_b); break;
case CMD_RS232_EXTEND: flag_special_mode_rs = 1; ExtendBios(&rs_b); break;
default: break;
} // end switch

View File

@ -94,14 +94,13 @@ typedef struct {
unsigned int do_resetup_rs; // âûïîëíèòü ïåðåñáðîñ ïîðòà ïðè îøèáêàõ.
int RS_DataWillSend2; // флаг2, что мы подготовили свой запрос и сейчас начнем его передавать и мы мастер
} RS_DATA_STRUCT;
#define RS_DATA_STRUCT_DEFAULT {0,0,0,0,0,0,0,0,0,{0}, 0,0,0,{0},{0}, 0,0,0,0,0,0, 0,0, 0,0, 0,0,0,0, 0,0, 0,0,0, 0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0, 0,0}
#define RS_DATA_STRUCT_DEFAULT {0,0,0,0,0,0,0,0,0,{0}, 0,0,0,{0},{0}, 0,0,0,0,0,0, 0,0, 0,0, 0,0,0,0, 0,0, 0,0,0, 0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0, 0}
//////////////////////////////////////////////////////////
#define TMS_TO_TERMINAL_TEST_ALL_STRUCT_DEFAULT {{0}, {0}, {0}, 0, 0, 0}
@ -137,6 +136,6 @@ void SetCntrlAddr (int cntrl_addr,int cntrl_addr_for_all);
extern float KmodTerm, freqTerm;
extern unsigned int RS_Len[RS_LEN_CMD];
extern int flag_special_mode_rs, disable_flag_special_mode_rs;
extern int flag_special_mode_rs;
#endif

View File

@ -638,32 +638,6 @@ void xseeprom_delay(void)
pause_1000(10000);
}
void ResetNPeriphPlane(unsigned int np)
{
Controll.bit.line_P7_4_Is = np;
Controll.bit.OE_BUF_Is_ON = 1;
Controll.bit.line_Z_ER0_OUT_Is = 0;
Controll.bit.line_SET_MODE_Is = 1;
xControll_wr();
pause_1000(10000);
Controll.bit.line_P7_4_Is = 0x0;
Controll.bit.line_Z_ER0_OUT_Is = 1;
xControll_wr();
// Controll.bit.RemotePlane_Is_Reset = 1;
xControll_wr();
pause_1000(10000);
// Controll.bit.RemotePlane_Is_Reset = 0;
Controll.bit.line_P7_4_Is = 0x0;
}
void ResetPeriphPlane()
{
Controll.bit.line_P7_4_Is = 0xf;

View File

@ -257,8 +257,5 @@ int test_xilinx_live(void);
int enable_er0_control(void);
void ResetNPeriphPlane(unsigned int np);
#endif

View File

@ -134,7 +134,7 @@ void pause_1000(unsigned long t)
DSP28x_usDelay(40L);
}
}
//Xilinx Zone
void XintfZone0_Timing(void)
{
// Zone 0------------------------------------
@ -256,12 +256,12 @@ void XintfZone2_Timing(void)
// Lead must always be 1 or greater
// Zone write timing
XintfRegs.XTIMING2.bit.XWRLEAD = 3;//2;
XintfRegs.XTIMING2.bit.XWRACTIVE = 4;//2;
XintfRegs.XTIMING2.bit.XWRTRAIL = 2;//2;
XintfRegs.XTIMING2.bit.XWRACTIVE = 7;//2;
XintfRegs.XTIMING2.bit.XWRTRAIL = 3;//2;
// Zone read timing
XintfRegs.XTIMING2.bit.XRDLEAD = 2;
XintfRegs.XTIMING2.bit.XRDACTIVE = 3; //1;
XintfRegs.XTIMING2.bit.XRDTRAIL = 1;//2;//0;
XintfRegs.XTIMING2.bit.XRDLEAD = 3;
XintfRegs.XTIMING2.bit.XRDACTIVE = 7; //1;
XintfRegs.XTIMING2.bit.XRDTRAIL = 3;//2;//0;
// do not double all Zone read/write lead/active/trail timing
XintfRegs.XTIMING2.bit.X2TIMING = 0;

View File

@ -1,36 +0,0 @@
/*
* profile_interrupt.c
*
* Created on: 6 àâã. 2024 ã.
* Author: yura
*/
#include "profile_interrupt.h"
t_profile_interrupt profile_interrupt = T_PROFILE_INTERRUPT_DEFAULT;
void init_profile_interrupt(void)
{
profile_interrupt.for_led1.bits.timer1 = 1;
profile_interrupt.for_led1.bits.timer2 = 1;
profile_interrupt.for_led1.bits.timer3 = 1;
profile_interrupt.for_led1.bits.timer4 = 1;
profile_interrupt.for_led1.bits.can = 1;
profile_interrupt.for_led1.bits.pwm = 1;
profile_interrupt.for_led1.bits.rsa = 1;
profile_interrupt.for_led1.bits.rsb = 1;
profile_interrupt.for_led1.bits.sync = 1;
profile_interrupt.for_led2.bits.timer1 = 1;
profile_interrupt.for_led2.bits.timer2 = 1;
profile_interrupt.for_led2.bits.timer3 = 1;
profile_interrupt.for_led2.bits.timer4 = 1;
profile_interrupt.for_led2.bits.can = 1;
profile_interrupt.for_led2.bits.pwm = 1;
profile_interrupt.for_led2.bits.rsa = 1;
profile_interrupt.for_led2.bits.rsb = 1;
profile_interrupt.for_led2.bits.sync = 1;
}

View File

@ -1,48 +0,0 @@
/*
* profile_interrupt.h
*
* Created on: 6 àâã. 2024 ã.
* Author: yura
*/
#ifndef SRC_N12_XILINX_PROFILE_INTERRUPT_H_
#define SRC_N12_XILINX_PROFILE_INTERRUPT_H_
typedef union {
unsigned int all;
struct {
unsigned int timer1: 1;
unsigned int timer2: 1;
unsigned int timer3: 1;
unsigned int timer4: 1;
unsigned int sync: 1;
unsigned int can: 1;
unsigned int rsa: 1;
unsigned int rsb: 1;
unsigned int pwm: 1;
unsigned int reserv: 7;
} bits;
} t_enable_profile;
typedef struct
{
t_enable_profile for_led1;
t_enable_profile for_led2;
} t_profile_interrupt;
#define T_PROFILE_INTERRUPT_DEFAULT {0,0}
extern t_profile_interrupt profile_interrupt;
void init_profile_interrupt(void);
#endif /* SRC_N12_XILINX_PROFILE_INTERRUPT_H_ */

View File

@ -9,11 +9,7 @@
#include "MemoryFunctions.h"
#include "Spartan2E_Adr.h"
#include "TuneUpPlane.h"
#include "xp_write_xpwm_time.h"
#include "params.h"
#include "pwm_test_lines.h"
#include "sync_tools.h"
#include "profile_interrupt.h"
//Pointers to handler functions
void (*int13_handler)() = NULL;
@ -24,8 +20,8 @@ void (*int13_handler)() = NULL;
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//unsigned int enable_profile_led1_pwm = 1;
//unsigned int enable_profile_led2_pwm = 1;
unsigned int enable_profile_led1_pwm = 1;
unsigned int enable_profile_led2_pwm = 1;
@ -55,59 +51,21 @@ int InitXilinxSpartan2E(void (*int_handler)())
return err;
}
#pragma CODE_SECTION(XIntc_INT13_Handler,".fast_run2");
interrupt void XIntc_INT13_Handler(void)
{
static int l2;
IER &= MINT13; // Set "global" priority
if (xpwm_time.disable_sync_out==0)
{
if (xpwm_time.do_sync_out)
{
i_sync_pin_on();
#if(_ENABLE_PWM_LINES_FOR_TESTS_SYNC)
PWM_LINES_TK_17_ON;
#endif
}
else
{
i_sync_pin_off();
#if(_ENABLE_PWM_LINES_FOR_TESTS_SYNC)
PWM_LINES_TK_17_OFF;
#endif
}
}
if (xpwm_time.what_next_interrupt==PWM_LOW_LEVEL_INTERRUPT)
{
l2 = 1;
}
else
l2 = 0;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.pwm && l2)
if (enable_profile_led1_pwm)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.pwm && l2)
i_led2_on_off_special(1);
if (enable_profile_led2_pwm)
i_led2_on_off_special(1);
#endif
EINT;
// Insert ISR Code here.......
@ -157,13 +115,12 @@ interrupt void XIntc_INT13_Handler(void)
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.pwm)
if (enable_profile_led1_pwm)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.pwm)
if (l2)
i_led2_on_off_special(0);
if (enable_profile_led2_pwm)
i_led2_on_off_special(0);
#endif

View File

@ -116,7 +116,6 @@ extern X_PARALLEL_BUS x_parallel_bus_project;
// ver 2
#define read_pbus_value_v2(bit,adr,res) {if (bit) { res = i_ReadMemory(adr); i_WriteMemory(adr++,0x0); } else res = 0; }
#define read_pbus_value_full_v2(bit,adr,res) {res = i_ReadMemory(adr); i_WriteMemory(adr++,0x0); }
#define read_pbus_value_full_v3(bit,adr,res) {res = i_ReadMemory(adr++); }
#define read_pbus_adc_value_v2(bit,adr,res) {if (bit) { res = i_ReadMemory(adr) & 0xfff; i_WriteMemory(adr++,0x0);} else res = 0; }
#define read_pbus_adc_value_full_v2(bit,adr,res) {res = i_ReadMemory(adr) & 0xfff; i_WriteMemory(adr++,0x0); }

View File

@ -327,33 +327,123 @@ int cds_in_read_pbus(T_cds_in *v)
if (v->status & (component_Started | component_Ready | component_Error | component_ErrorSBus ))
{
adr_pbus = v->adr_pbus.adr_table[0] + ADR_FIRST_FREE;
adr_pbus = v->adr_pbus.adr_table[0] + ADR_FIRST_FREE;
if ((v->type_cds_xilinx == TYPE_CDS_XILINX_SP6) && (v->type_plate == cds_in_type_in_1))
{
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg0,adr_pbus, t);
v->read.pbus.data_in.all = (t & 0xff00) | ((~t) & 0x00ff);
}
else
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg0,adr_pbus,v->read.pbus.data_in.all);
if ((v->type_cds_xilinx == TYPE_CDS_XILINX_SP6) && (v->type_plate == cds_in_type_in_1))
{
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg0,adr_pbus, t);
v->read.pbus.data_in.all = (t & 0xff00) | ((~t) & 0x00ff);
}
else
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg0,adr_pbus,v->read.pbus.data_in.all);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg1,adr_pbus,v->read.pbus.ready_in.all);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg2,adr_pbus,v->read.pbus.direction_in.all);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg3,adr_pbus,v->read.pbus.SpeedS1_cnt);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg4,adr_pbus,v->read.pbus.SpeedS1_cnt90);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg5,adr_pbus,v->read.pbus.SpeedS2_cnt);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg6,adr_pbus,v->read.pbus.SpeedS2_cnt90);
if ((v->type_cds_xilinx == TYPE_CDS_XILINX_SP6))
{
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg7,adr_pbus,v->read.pbus.Time_since_zero_point_S1);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg8,adr_pbus,v->read.pbus.Impulses_since_zero_point_Rising_S1);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg9,adr_pbus,v->read.pbus.Impulses_since_zero_point_Falling_S1);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg10,adr_pbus,v->read.pbus.Time_since_zero_point_S2);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg11,adr_pbus,v->read.pbus.Impulses_since_zero_point_Rising_S2);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg12,adr_pbus,v->read.pbus.Impulses_since_zero_point_Falling_S2);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg13,adr_pbus,v->read.pbus.channel_alive.all);
}
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg1,adr_pbus,v->read.pbus.ready_in.all);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg2,adr_pbus,v->read.pbus.direction_in.all);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg3,adr_pbus,v->read.pbus.SpeedS1_cnt);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg4,adr_pbus,v->read.pbus.SpeedS1_cnt90);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg5,adr_pbus,v->read.pbus.SpeedS2_cnt);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg6,adr_pbus,v->read.pbus.SpeedS2_cnt90);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg7,adr_pbus,v->read.pbus.Time_since_zero_point_S1);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg8,adr_pbus,v->read.pbus.Impulses_since_zero_point_Rising_S1);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg9,adr_pbus,v->read.pbus.Impulses_since_zero_point_Falling_S1);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg10,adr_pbus,v->read.pbus.Time_since_zero_point_S2);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg11,adr_pbus,v->read.pbus.Impulses_since_zero_point_Rising_S2);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg12,adr_pbus,v->read.pbus.Impulses_since_zero_point_Falling_S2);
read_pbus_value(v->setup_pbus.use_reg_in_pbus.bit.reg13,adr_pbus,v->read.pbus.channel_alive.all);
/*
//0
if (v->setup_pbus.use_reg_in_pbus.bit.reg0)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[0];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.data_in.all = x_parallel_bus_project.data_table_read;
}
//1
if (v->setup_pbus.use_reg_in_pbus.bit.reg1)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[1];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.ready_in.all = x_parallel_bus_project.data_table_read;
}
//2
if (v->setup_pbus.use_reg_in_pbus.bit.reg2)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[2];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.direction_in.all = x_parallel_bus_project.data_table_read;
}
//3
if (v->setup_pbus.use_reg_in_pbus.bit.reg3)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[3];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.SpeedS1_cnt = x_parallel_bus_project.data_table_read;
}
//4
if (v->setup_pbus.use_reg_in_pbus.bit.reg4)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[4];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.SpeedS1_cnt90 = x_parallel_bus_project.data_table_read;
}
//5
if (v->setup_pbus.use_reg_in_pbus.bit.reg5)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[5];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.SpeedS2_cnt = x_parallel_bus_project.data_table_read;
}
//6
if (v->setup_pbus.use_reg_in_pbus.bit.reg6)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[6];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.SpeedS2_cnt90 = x_parallel_bus_project.data_table_read;
}
//7
if (v->setup_pbus.use_reg_in_pbus.bit.reg7)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[7];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.Time_since_zero_point_S1 = x_parallel_bus_project.data_table_read;
}
//8
if (v->setup_pbus.use_reg_in_pbus.bit.reg8)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[8];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.Time_since_zero_point_Rising_S1 = x_parallel_bus_project.data_table_read;
}
//9
if (v->setup_pbus.use_reg_in_pbus.bit.reg9)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[9];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.Time_since_zero_point_Falling_S1 = x_parallel_bus_project.data_table_read;
}
//10
if (v->setup_pbus.use_reg_in_pbus.bit.reg10)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[10];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.Time_since_zero_point_S2 = x_parallel_bus_project.data_table_read;
}
//11
if (v->setup_pbus.use_reg_in_pbus.bit.reg11)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[11];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.Time_since_zero_point_Rising_S2 = x_parallel_bus_project.data_table_read;
}
//12
if (v->setup_pbus.use_reg_in_pbus.bit.reg12)
{
x_parallel_bus_project.adr_table_read = v->adr_pbus.adr_table[12];
x_parallel_bus_project.read_one_data(&x_parallel_bus_project);
v->read.pbus.Time_since_zero_point_Falling_S2 = x_parallel_bus_project.data_table_read;
}
*/
}
else
{

View File

@ -64,12 +64,6 @@ int cds_tk_write_sbus_23550(T_cds_tk_23550 *v)
v->status_serial_bus.count_write_error++;
//10 time_after_err
x_serial_bus_project.reg_addr = 10; // adr memory in plate
x_serial_bus_project.write_data = v->write.sbus.time_after_err; // write data
if (x_serial_bus_project.write(&x_serial_bus_project)) // make write
v->status_serial_bus.count_write_error++;
@ -199,25 +193,6 @@ int cds_tk_read_sbus_23550(T_cds_tk_23550 *v)
else
v->status_serial_bus.count_read_error++;
//9 id_plate
x_serial_bus_project.reg_addr = 9; // adr memory in plate
x_serial_bus_project.read(&x_serial_bus_project); // read
if (x_serial_bus_project.flags.bit.read_error == 0) // check error
v->read.sbus.id_plate.all = x_serial_bus_project.read_data;
else
v->status_serial_bus.count_read_error++;
//10 time_after_err
x_serial_bus_project.reg_addr = 10; // adr memory in plate
x_serial_bus_project.read(&x_serial_bus_project); // read
if (x_serial_bus_project.flags.bit.read_error == 0) // check error
v->read.sbus.time_after_err = x_serial_bus_project.read_data;
else
v->status_serial_bus.count_read_error++;
//11 time_err_tk_all
x_serial_bus_project.reg_addr = 11; // adr memory in plate
x_serial_bus_project.read(&x_serial_bus_project); // read
@ -266,7 +241,7 @@ int cds_tk_read_pbus_23550(T_cds_tk_23550 *v)
{
unsigned long adr_pbus;
if (v->useit == 0 || v->setup_pbus.use_reg_in_pbus.all==0)
if (v->useit == 0)
return 0;
if (v->status & (component_Started | component_Ready | component_Error | component_ErrorSBus))
@ -275,12 +250,12 @@ int cds_tk_read_pbus_23550(T_cds_tk_23550 *v)
if (v->type_cds_xilinx == TYPE_CDS_XILINX_SP6)
{
adr_pbus = v->adr_pbus.adr_table[0] + ADR_FIRST_FREE;
read_pbus_value_full_v3(v->setup_pbus.use_reg_in_pbus.bit.reg0,adr_pbus,v->read.pbus.status1.all);
read_pbus_value_full_v3(v->setup_pbus.use_reg_in_pbus.bit.reg1,adr_pbus,v->read.pbus.DataReg0.all);
read_pbus_value_full_v3(v->setup_pbus.use_reg_in_pbus.bit.reg2,adr_pbus,v->read.pbus.DataReg1.all);
read_pbus_value_full_v3(v->setup_pbus.use_reg_in_pbus.bit.reg3,adr_pbus,v->read.pbus.DataReg2.all);
read_pbus_value_full_v3(v->setup_pbus.use_reg_in_pbus.bit.reg4,adr_pbus,v->read.pbus.DataReg3.all);
read_pbus_value_full_v3(v->setup_pbus.use_reg_in_pbus.bit.reg5,adr_pbus,v->read.pbus.status2.all);
read_pbus_value_full_v2(v->setup_pbus.use_reg_in_pbus.bit.reg0,adr_pbus,v->read.pbus.status1.all);
read_pbus_value_full_v2(v->setup_pbus.use_reg_in_pbus.bit.reg1,adr_pbus,v->read.pbus.DataReg0.all);
read_pbus_value_full_v2(v->setup_pbus.use_reg_in_pbus.bit.reg2,adr_pbus,v->read.pbus.DataReg1.all);
read_pbus_value_full_v2(v->setup_pbus.use_reg_in_pbus.bit.reg3,adr_pbus,v->read.pbus.DataReg2.all);
read_pbus_value_full_v2(v->setup_pbus.use_reg_in_pbus.bit.reg4,adr_pbus,v->read.pbus.DataReg3.all);
read_pbus_value_full_v2(v->setup_pbus.use_reg_in_pbus.bit.reg5,adr_pbus,v->read.pbus.status2.all);
}
}
else
@ -338,9 +313,8 @@ void cds_tk_optical_bus_check_error_read(T_cds_tk_23550 *v)
if ( v->optical_data_in.status_1.bit.id_sbus == v->optical_data_in.status_2.bit.id_sbus
&& v->optical_data_in.status_1.bit.id == v->optical_data_in.status_2.bit.id
// && (v->read.pbus.status1.bit.receiver_error==0)
// && (v->read.pbus.status2.bit.receiver_error==0)
)
&& (v->read.pbus.status1.bit.receiver_error==0)
&& (v->read.pbus.status2.bit.receiver_error==0) )
{
// åñëè âûñòàâèëñÿ ýòîò áèò, òî çíâ÷èò ïðèåìíèê â ïðèåìå äàííûõ, íî ò.ê. ýòè äàííûå ìû ïîëó÷àåì ïî PBUS ñ íåêîòîðûì ëàãîì
// ñìûñë ýòîãî áèòà òåðÿåò ñâîé ñìûñë, ïðîñòî êàê èíôîðìàöèÿ, äàííûå ìû ïîëó÷èì âñåãäà ïîñëåäíèå óäà÷íûå.
@ -352,17 +326,10 @@ void cds_tk_optical_bus_check_error_read(T_cds_tk_23550 *v)
// data old
v->optical_data_in.status_read.bit.old_data = 1;
v->optical_data_in.same_id_count += 1;
if (v->optical_data_in.same_id_count_between < v->optical_data_in.setup_count_error_between)
v->optical_data_in.same_id_count_between += 1;
else
// ÷èòàëè âñå âðåìÿ ñòàðûå äàííûå, ïåðåäàò÷èê óìåð íà òîé ñòîðîíå?
v->optical_data_in.ready = 0;
}
else
{
// î÷èñòêà îøèáîê
v->optical_data_in.same_id_count_between = 0;
v->optical_data_in.local_count_error = 0;
v->optical_data_in.raw_local_error = 0;
v->optical_data_in.ready = 1;

View File

@ -99,9 +99,7 @@ typedef struct {
UInt16 all;
struct
{
UInt16 reserv :8;
UInt16 detect_soft_disconnect :1;
UInt16 enable_soft_disconnect :1;
UInt16 reserv :10;
UInt16 enable_line_err :1;
UInt16 disable_err_mintime :1;
UInt16 disable_err_hwp :1;
@ -113,8 +111,7 @@ typedef struct {
//7
UInt16 cmd_reset_error;
//10
UInt16 time_after_err; //time_after_err = 4000<-DEC * 0.02 = 80mc
//
} T_cds_tk_write_sbus_23550;
@ -198,9 +195,7 @@ typedef struct {
UInt16 all;
struct
{
UInt16 reserv :8;
UInt16 detect_soft_disconnect :1;
UInt16 enable_soft_disconnect :1;
UInt16 reserv :10;
UInt16 enable_line_err :1;
UInt16 disable_err_mintime :1;
UInt16 disable_err_hwp :1;
@ -266,9 +261,7 @@ typedef struct {
UInt16 all;
struct
{
UInt16 reserv :5;
UInt16 ErrorSoftShutdownForbidComb :1;
UInt16 ErrorSoftShutdownFromErr0 :1;
UInt16 reserv :7;
UInt16 line_err_keys_3210 :1;
UInt16 line_err_keys_7654 :1;
UInt16 mintime_err_keys_3210 :1;
@ -306,22 +299,6 @@ typedef struct {
} bit;
} status_protect_current_ack;
//9
union
{
UInt16 all;
struct
{
UInt16 revision :5;
UInt16 version :6;
T_plate_type plate_type :5;
} bit;
} id_plate;
//10
UInt16 time_after_err;
//11
union
@ -503,14 +480,12 @@ typedef union {
//////////////////////////////////////////////////////////////
typedef struct {
UInt16 setup_count_error; // ñêîëüêî æäåì äî ïàäåíèÿ øèíû
UInt16 setup_count_error_between; // ñêîëüêî æäåì äî ïàäåíèÿ øèíû ïðè ÷òåíèè ñòàðûõ çíà÷åíèé
UInt16 full_count_error; // âñåãî îøèáîê
UInt16 local_count_error; // òåêóùèé ñ÷åò÷èê îøèáîê, èäåò äî setup_count_error è ñíèìàåòñÿ ready, ïðè óäà÷íîì ÷òåíèè îáíóëÿåòñÿ
UInt16 count_ok; // ñêîëüêî óäà÷íûõ ÷òåíèé
UInt16 count_lost; // ñêîëüêî ïîòåðü äàííûõ (ïî id_sbus)
UInt16 ready; // øèíà ðàáîòàåò, îøèáêè íå ïðåâûñèëè setup_count_error
UInt16 same_id_count; // ñêîëüêî âñåãî ïîâòîðíûõ ÷òåíèé òåõæå äàííûõ, ò.å. ïåðåäàò÷èê â äð.Ï× íå ïðèñëàë íè÷åãî íîâîãî
UInt16 same_id_count_between; // ìåæäó óäà÷íûìè ÷òåíèÿìè, ñêîëüêî ïîâòîðíûõ ÷òåíèé òåõæå äàííûõ, ò.å. ïåðåäàò÷èê â äð.Ï× íå ïðèñëàë íè÷åãî íîâîãî
UInt16 same_id_count; // сколько повторных чтений техже данных, т.е. передатчик в др.ПЧ не прислал ничего нового
UInt16 error_not_ready_count; // ñêîëüêî îøèáîê íå ãîòîâíîñòè øèíû ready
UInt16 raw_local_error; // åñòü îøèáêà ïðè ÷òåíèè, íî øèíà íå óïàëà åùå
UInt16 buf[4]; // äàííûå
@ -521,7 +496,7 @@ typedef struct {
STATUS_DATA_READ_OPT_BUS prev_status_read;// ñòàòóñ ïîñëå ÷òåíèÿ è àíàëèçà äàííûõ
} T_cds_optical_bus_data_in;
#define T_CDS_OPTICAL_BUS_DATA_IN_DEFAULTS {15,50,0,0,0,0,0,0,0,0,0,{0,0,0,0},0,0,0,0,0}
#define T_CDS_OPTICAL_BUS_DATA_IN_DEFAULTS {15,0,0,0,0,0,0,0,0,{0,0,0,0},0,0,0,0,0}
/////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////

View File

@ -183,18 +183,15 @@ void hwp_init(T_hwp *v)
#if (HWP_SPEED_VERSION_DEFINE==MODE_HWP_SPEED_NORMAL)
// v->low_setup.dac_config.bit.HWP_Speed = MODE_HWP_SPEED_NORMAL;//HWP_SPEED_VERSION_DEFINE; // new version hwp with low speed serial hwp
v->write.HWP_Speed = MODE_HWP_SPEED_NORMAL;
v->low_setup.dac_config.bit.HWP_Speed = MODE_HWP_SPEED_NORMAL;//HWP_SPEED_VERSION_DEFINE; // new version hwp with low speed serial hwp
#endif
#if (HWP_SPEED_VERSION_DEFINE==MODE_HWP_SPEED_SLOW)
// v->low_setup.dac_config.bit.HWP_Speed = MODE_HWP_SPEED_SLOW;//HWP_SPEED_VERSION_DEFINE; // new version hwp with low speed serial hwp
v->write.HWP_Speed = MODE_HWP_SPEED_SLOW;
v->low_setup.dac_config.bit.HWP_Speed = MODE_HWP_SPEED_SLOW;//HWP_SPEED_VERSION_DEFINE; // new version hwp with low speed serial hwp
#endif
#if (HWP_SPEED_VERSION_DEFINE==MODE_HWP_SPEED_AUTO)
// v->low_setup.dac_config.bit.HWP_Speed = MODE_HWP_SPEED_AUTO;//HWP_SPEED_VERSION_DEFINE; // new version hwp with low speed serial hwp
v->write.HWP_Speed = MODE_HWP_SPEED_AUTO;
v->low_setup.dac_config.bit.HWP_Speed = MODE_HWP_SPEED_AUTO;//HWP_SPEED_VERSION_DEFINE; // new version hwp with low speed serial hwp
#endif
}
@ -1270,7 +1267,7 @@ int hwp_write_all_dacs(T_hwp *v)
int hwp_write_all(T_hwp *v)
{
int err = 0, err_ready = 0;
int err = 0;
if (v->useit == 0)
return 0;
@ -1315,8 +1312,6 @@ int hwp_write_all(T_hwp *v)
else
v->status = component_Ready;
err_ready = check_cds_ready_hwpbus( err, ITS_WRITE_BUS, &v->status_hwp_bus);
return 0;

View File

@ -23,7 +23,6 @@ static void write_command_reg(T_inc_sensor *inc_s);
static void tune_sampling_time(T_inc_sensor *inc_s);
static void wait_for_registers_updated(T_inc_sensor *inc_s);
static void read_direction_in_plane(T_inc_sensor *inc_s);
static void detect_break_sensor_1_2(T_inc_sensor *inc_s);
void sensor_set(T_inc_sensor *inc_s)
{
@ -81,8 +80,6 @@ void inc_sensor_read(T_inc_sensor *inc_s)
inc_s->read_sensor2(inc_s);
}
detect_break_sensor_1_2(inc_s);
#ifdef AUTO_CHANGE_SAMPLING_TIME
tune_sampling_time(inc_s);
#endif
@ -90,8 +87,7 @@ void inc_sensor_read(T_inc_sensor *inc_s)
////////////////////////////////////////////////////////
////////////////////////////////////////////////////////
#define MAX_COUNT_OVERFULL_DISCRET_3 150
#pragma CODE_SECTION(inc_sensor_read1,".fast_run");
void inc_sensor_read1(T_inc_sensor *inc_s)
{
read_in_sensor_line1(inc_s);
@ -111,47 +107,8 @@ void inc_sensor_read1(T_inc_sensor *inc_s)
//#endif
//inc_s->data.CountZero1 = inc_s->pm67regs.zero_time_line1;
if (inc_s->pm67regs.zero_time_line1==0)
{
if (inc_s->data.countCountZero1==MAX_COUNT_OVERFULL_DISCRET_3)
{
inc_s->data.prev_CountZero1 = inc_s->data.CountZero1 = 0;
}
else
{
inc_s->data.CountZero1 = inc_s->data.prev_CountZero1;
inc_s->data.countCountZero1++;
}
}
else
{
inc_s->data.countCountZero1 = 0;
inc_s->data.CountZero1 = inc_s->pm67regs.zero_time_line1;
inc_s->data.prev_CountZero1 = inc_s->pm67regs.zero_time_line1;
}
// inc_s->data.CountOne1 = inc_s->pm67regs.one_time_line1;
if (inc_s->pm67regs.one_time_line1==0)
{
if (inc_s->data.countCountOne1==MAX_COUNT_OVERFULL_DISCRET_3)
{
inc_s->data.prev_CountOne1 = inc_s->data.CountOne1 = 0;
}
else
{
inc_s->data.CountOne1 = inc_s->data.prev_CountOne1;
inc_s->data.countCountOne1++;
}
}
else
{
inc_s->data.countCountOne1 = 0;
inc_s->data.CountOne1 = inc_s->pm67regs.one_time_line1;
inc_s->data.prev_CountOne1 = inc_s->pm67regs.one_time_line1;
}
inc_s->data.CountZero1 = inc_s->pm67regs.zero_time_line1;
inc_s->data.CountOne1 = inc_s->pm67regs.one_time_line1;
inc_s->data.counter_freq1 = inc_s->pm67regs.read_comand_reg.bit.sampling_time1;
@ -160,7 +117,7 @@ void inc_sensor_read1(T_inc_sensor *inc_s)
////////////////////////////////////////////////////////
////////////////////////////////////////////////////////
#pragma CODE_SECTION(inc_sensor_read2,".fast_run");
void inc_sensor_read2(T_inc_sensor *inc_s)
{
read_in_sensor_line2(inc_s);
@ -179,46 +136,8 @@ void inc_sensor_read2(T_inc_sensor *inc_s)
inc_s->data.TimeCalcFromImpulses2 = 0;
//#endif
//inc_s->data.CountZero1 = inc_s->pm67regs.zero_time_line1;
if (inc_s->pm67regs.zero_time_line2==0)
{
if (inc_s->data.countCountZero2==MAX_COUNT_OVERFULL_DISCRET_3)
{
inc_s->data.prev_CountZero2 = inc_s->data.CountZero2 = 0;
}
else
{
inc_s->data.CountZero2 = inc_s->data.prev_CountZero2;
inc_s->data.countCountZero2++;
}
}
else
{
inc_s->data.countCountZero2 = 0;
inc_s->data.CountZero2 = inc_s->pm67regs.zero_time_line2;
inc_s->data.prev_CountZero2 = inc_s->pm67regs.zero_time_line2;
}
// inc_s->data.CountOne1 = inc_s->pm67regs.one_time_line1;
if (inc_s->pm67regs.one_time_line2==0)
{
if (inc_s->data.countCountOne2==MAX_COUNT_OVERFULL_DISCRET_3)
{
inc_s->data.prev_CountOne2 = inc_s->data.CountOne2 = 0;
}
else
{
inc_s->data.CountOne2 = inc_s->data.prev_CountOne2;
inc_s->data.countCountOne2++;
}
}
else
{
inc_s->data.countCountOne2 = 0;
inc_s->data.CountOne2 = inc_s->pm67regs.one_time_line2;
inc_s->data.prev_CountOne2 = inc_s->pm67regs.one_time_line2;
}
inc_s->data.CountZero2 = inc_s->pm67regs.zero_time_line2;
inc_s->data.CountOne2 = inc_s->pm67regs.one_time_line2;
inc_s->data.counter_freq2 = inc_s->pm67regs.read_comand_reg.bit.sampling_time2;
@ -332,32 +251,6 @@ void wait_for_registers_updated(T_inc_sensor *inc_s)
}
////////////////////////////////////////////////////////
void detect_break_sensor_1_2(T_inc_sensor *inc_s)
{
unsigned int f1 = (inc_s->data.CountOne1 || inc_s->data.CountZero1);
unsigned int f2 = (inc_s->data.CountOne2 || inc_s->data.CountZero2);
if (f1 && f2==0)
{
inc_s->break_sensor1 = 0;
inc_s->break_sensor2 = 1;
}
if (f1==0 && f2)
{
inc_s->break_sensor1 = 1;
inc_s->break_sensor2 = 0;
}
if ((f1==0 && f2==0) || (f1 && f2))
{
inc_s->break_sensor1 = 0;
inc_s->break_sensor2 = 0;
}
}
////////////////////////////////////////////////////////
@ -366,20 +259,16 @@ void tune_sampling_time(T_inc_sensor *inc_s)
// ñíà÷àëà ïðîâåðßåì íà ìàêñèìóì, ò.ê. åñëè äàò÷èê îòâàëèëñß, òî îí ïîêàæåò = 0.
if(
(inc_s->use_sensor1 && inc_s->break_sensor1==0 && (inc_s->data.CountOne1 > LEVEL_SWITCH_MICROSEC) && (inc_s->data.CountZero1 > LEVEL_SWITCH_MICROSEC) )
|| (inc_s->use_sensor2 && inc_s->break_sensor2==0 && (inc_s->data.CountOne2 > LEVEL_SWITCH_MICROSEC) && (inc_s->data.CountZero2 > LEVEL_SWITCH_MICROSEC) )
)
if((inc_s->use_sensor1 && (inc_s->pm67regs.zero_time_line1 > LEVEL_SWITCH_MICROSEC))
|| (inc_s->use_sensor2 && (inc_s->pm67regs.zero_time_line2 > LEVEL_SWITCH_MICROSEC)))
{
inc_s->pm67regs.write_comand_reg.bit.set_sampling_time = SAMPLING_TIME_MS;
return;
}
// ïðîâåðêà íà ìèíèìóì
if(
(inc_s->use_sensor1 && inc_s->break_sensor1==0 && (inc_s->data.CountOne1 < LEVEL_SWITCH_NANOSEC) && (inc_s->data.CountZero1 < LEVEL_SWITCH_NANOSEC) )
|| (inc_s->use_sensor2 && inc_s->break_sensor2==0 && (inc_s->data.CountOne2 < LEVEL_SWITCH_NANOSEC) && (inc_s->data.CountZero2 < LEVEL_SWITCH_NANOSEC) )
)
if((inc_s->use_sensor1 && (inc_s->pm67regs.zero_time_line1 < LEVEL_SWITCH_NANOSEC))
|| (inc_s->use_sensor2 && (inc_s->pm67regs.zero_time_line2 < LEVEL_SWITCH_NANOSEC)))
{
inc_s->pm67regs.write_comand_reg.bit.set_sampling_time = SAMPLING_TIME_NS;
}

View File

@ -67,10 +67,6 @@ typedef struct {
unsigned int error_update;
unsigned int use_sensor1;
unsigned int use_sensor2;
unsigned int break_sensor1;
unsigned int break_sensor2;
unsigned int break_direction;
struct {
@ -78,10 +74,6 @@ typedef struct {
unsigned int Impulses1; // Quantity of full impulses during survey time
unsigned int CountZero1; // Value of the zero-half-period counter
unsigned int CountOne1; // Value of the one-half-period counter
unsigned int prev_CountZero1; // Value of the prev zero-half-period counter
unsigned int prev_CountOne1; // Value of the prev one-half-period counter
unsigned int countCountZero1; // Value of the zero-half-period counter
unsigned int countCountOne1; // Value of the one-half-period counter
unsigned int counter_freq1; // 1 - 60MHz; 0 - 600KHz
unsigned long TimeCalcFromImpulses1; // Ïåðåñ÷åò âðåìåíè èìïóëüñà èç êîëè÷åñòâà Impulses1 è âðåìåíè Time1
int direction1; // 1 - direct; 0 - reverse
@ -90,10 +82,6 @@ typedef struct {
unsigned int Impulses2; // Quantity of full impulses during survey time
unsigned int CountZero2; // Value of the zero-half-period counter
unsigned int CountOne2; // Value of the one-half-period counter
unsigned int prev_CountZero2; // Value of the prev zero-half-period counter
unsigned int prev_CountOne2; // Value of the prev one-half-period counter
unsigned int countCountZero2; // Value of the zero-half-period counter
unsigned int countCountOne2; // Value of the one-half-period counter
unsigned int counter_freq2; // 1 - 60MHz; 0 - 600KHz
unsigned long TimeCalcFromImpulses2; // Ïåðåñ÷åò âðåìåíè èìïóëüñà èç êîëè÷åñòâà Impulses1 è âðåìåíè Time1
int direction2; // 1 - direct; 0 - reverse
@ -110,14 +98,7 @@ typedef struct {
} T_inc_sensor;
#define T_INC_SENSOR_DEFAULT {0, 0, 0, 0, 0, 0, 0, {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,0,0,0, 0,0,0,0}, \
T_INC_SENSOR_REGS_DEFAULTS, \
inc_sensor_set,\
update_sensors_data_s, \
inc_sensor_read, \
inc_sensor_read1, \
inc_sensor_read2 \
}
#define T_INC_SENSOR_DEFAULT {0, 0, 0, 0, {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, T_INC_SENSOR_REGS_DEFAULTS, inc_sensor_set, update_sensors_data_s, inc_sensor_read, inc_sensor_read1, inc_sensor_read2}
//////////////////////////////////////////////////////////////////////////////////
////

View File

@ -1229,8 +1229,6 @@ void project_autospeed_all_hwp(void)
#define PAUSE_WAIT_SBUS 10000
#define MAX_COUNT_ERR_READ_SBUS 1100 //2000 çàïàñ ïî âðåìåíè 2õ îòíîñèòåëüíî íîðìàëüíîãî ïåðèîäà çàãðóçêè âñåé êîðçèíû
#define MAX_COUNT_ERR_READ_SBUS_2 600 //2000 çàïàñ ïî âðåìåíè 2õ îòíîñèòåëüíî íîðìàëüíîãî ïåðèîäà çàãðóçêè âñåé êîðçèíû
#define MAX_COUNT_OR_READ_SBUS 20//200
@ -1245,8 +1243,6 @@ unsigned int project_wait_load_all_cds(int flag_reset)
unsigned int counterOk = 0, err;
unsigned int i,count_find_plat;
unsigned int old_status_max_read_error = 0;
unsigned int prev_count_one_find_plat = 0, count_one_find_plat = 0;
unsigned int max_count_err_read_sbus = MAX_COUNT_ERR_READ_SBUS;
// unsigned int erReg, rd;
/*
for (i=0;i<C_adc_number;i++)
@ -1281,7 +1277,6 @@ unsigned int project_wait_load_all_cds(int flag_reset)
{
counterOk++;
project.adc[i].status = component_Started;
count_one_find_plat++;
}
project.adc[i].status_serial_bus.max_read_error = old_status_max_read_error;
@ -1312,7 +1307,6 @@ unsigned int project_wait_load_all_cds(int flag_reset)
{
counterOk++;
project.cds_tk[i].status = component_Started;
count_one_find_plat++;
}
project.cds_tk[i].status_serial_bus.max_read_error = old_status_max_read_error;
@ -1343,7 +1337,6 @@ unsigned int project_wait_load_all_cds(int flag_reset)
{
counterOk++;
project.cds_in[i].status = component_Started;
count_one_find_plat++;
}
project.cds_in[i].status_serial_bus.max_read_error = old_status_max_read_error;
@ -1374,8 +1367,6 @@ unsigned int project_wait_load_all_cds(int flag_reset)
{
counterOk++;
project.cds_out[i].status = component_Started;
count_one_find_plat++;
}
project.cds_out[i].status_serial_bus.max_read_error = old_status_max_read_error;
@ -1406,8 +1397,6 @@ unsigned int project_wait_load_all_cds(int flag_reset)
{
counterOk++;
project.cds_rs[i].status = component_Started;
count_one_find_plat++;
}
project.cds_rs[i].status_serial_bus.max_read_error = old_status_max_read_error;
@ -1438,8 +1427,6 @@ unsigned int project_wait_load_all_cds(int flag_reset)
{
counterOk++;
project.hwp[i].status = component_Started;
count_one_find_plat++;
}
project.hwp[i].status_hwp_bus.max_read_error = old_status_max_read_error;
@ -1448,16 +1435,8 @@ unsigned int project_wait_load_all_cds(int flag_reset)
}
#endif
///////////////////////////////////////
if (count_one_find_plat && prev_count_one_find_plat==0)
{
// ÷åòî íàøëè â ïåðâûé ðàç?
counterErr = 0;// ñáðîñèëè ñ÷åò÷èê, æäåì ïî íîâîé îñòàâøèåñÿ
max_count_err_read_sbus = MAX_COUNT_ERR_READ_SBUS_2;
}
prev_count_one_find_plat = count_one_find_plat;
// test error - timeout?
if (counterErr >= max_count_err_read_sbus)
if (counterErr >= MAX_COUNT_ERR_READ_SBUS)
{
if (flag_reset == 0)
xerror(xserial_bus_er_ID(2), (void *)0);

View File

@ -188,11 +188,11 @@ void wait_for_registers_updated(T_cds_in_rotation_sensor *rs)
while(rs->read.regs.comand_reg.bit.update_registers)
{
read_command_reg(rs);
(rs->count_wait_for_update_registers)++;
rs->count_wait_for_update_registers++;
counter_in_while++;
if(counter_in_while > 1000)
{
(rs->error_update)++;
rs->error_update++;
break;
}
}

View File

@ -341,6 +341,6 @@ void in_sensor_read1(T_cds_in_rotation_sensor *rs);
void in_sensor_read2(T_cds_in_rotation_sensor *rs);
//extern T_rotation_sensor rotation_sensor;
extern T_rotation_sensor rotation_sensor;
#endif //XP_ROT_SENS_H

View File

@ -123,7 +123,6 @@ typedef struct
unsigned int Tclosed_high;
// unsigned int Tclosed_1;
unsigned int pwm_tics;
unsigned int half_pwm_tics;
unsigned int inited;
unsigned int freq_pwm;
unsigned int Tclosed_saw_direct_0;
@ -132,16 +131,13 @@ typedef struct
unsigned int where_interrupt;
unsigned int mode_reload;
unsigned int one_or_two_interrupts_run;
unsigned int what_next_interrupt;
unsigned int do_sync_out;
unsigned int disable_sync_out;
WORD_UINT2BITS_STRUCT saw_direct;
void (*write_1_2_winding_break_times)();
void (*write_zero_winding_break_times)();
void (*init)();
} XPWM_TIME;
#define DEFAULT_XPWM_TIME {0,0,0,0,0,0, 0,0,0,0,0,0,0, 0,0,0,0,0, 0,0,0, 0, 0, 0, 0, 0,0,0, 0,0, {0}, \
#define DEFAULT_XPWM_TIME {0,0,0,0,0,0, 0,0,0,0,0,0, 0,0,0,0, 0,0,0, 0, 0, 0, 0, 0,0,0, {0}, \
xpwm_write_1_2_winding_break_times_16_lines, \
xpwm_write_zero_winding_break_times_16_lines, \
initXpwmTimeStructure \

View File

@ -43,7 +43,6 @@
#include <f281xbmsk.h>
#include "TuneUpPlane.h"
#include "profile_interrupt.h"
// Prototype statements for functions found within this file.
interrupt void eva_timer1_isr(void);
@ -58,15 +57,15 @@ Uint32 EvaTimer2InterruptCount = 0;
Uint32 EvbTimer3InterruptCount = 0;
Uint32 EvbTimer4InterruptCount = 0;
//unsigned int enable_profile_led1_Timer1 = 1;
//unsigned int enable_profile_led1_Timer2 = 1;
//unsigned int enable_profile_led1_Timer3 = 1;
//unsigned int enable_profile_led1_Timer4 = 1;
//
//unsigned int enable_profile_led2_Timer1 = 0;
//unsigned int enable_profile_led2_Timer2 = 0;
//unsigned int enable_profile_led2_Timer3 = 0;
//unsigned int enable_profile_led2_Timer4 = 0;
unsigned int enable_profile_led1_Timer1 = 1;
unsigned int enable_profile_led1_Timer2 = 1;
unsigned int enable_profile_led1_Timer3 = 1;
unsigned int enable_profile_led1_Timer4 = 1;
unsigned int enable_profile_led2_Timer1 = 0;
unsigned int enable_profile_led2_Timer2 = 0;
unsigned int enable_profile_led2_Timer3 = 0;
unsigned int enable_profile_led2_Timer4 = 0;
//Pointers to handler functions
void (*timer1_handler)() = NULL;
@ -333,11 +332,11 @@ interrupt void eva_timer1_isr(void)
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer1)
if (enable_profile_led1_Timer1)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer1)
if (enable_profile_led2_Timer1)
i_led2_on_off_special(1);
#endif
EINT;
@ -355,11 +354,11 @@ interrupt void eva_timer1_isr(void)
DINT;
PieCtrlRegs.PIEIER2.all = TempPIEIER;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer1)
if (enable_profile_led1_Timer1)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer1)
if (enable_profile_led2_Timer1)
i_led2_on_off_special(0);
#endif
@ -405,11 +404,11 @@ interrupt void eva_timer2_isr(void)
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer2)
if (enable_profile_led1_Timer2)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer2)
if (enable_profile_led2_Timer2)
i_led2_on_off_special(1);
#endif
@ -429,11 +428,11 @@ interrupt void eva_timer2_isr(void)
PieCtrlRegs.PIEIER3.all = TempPIEIER;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer2)
if (enable_profile_led1_Timer2)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer2)
if (enable_profile_led2_Timer2)
i_led2_on_off_special(0);
#endif
@ -485,11 +484,11 @@ interrupt void evb_timer3_isr(void)
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer3)
if (enable_profile_led1_Timer3)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer3)
if (enable_profile_led2_Timer3)
i_led2_on_off_special(1);
#endif
@ -512,11 +511,11 @@ interrupt void evb_timer3_isr(void)
PieCtrlRegs.PIEIER4.all = TempPIEIER;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer3)
if (enable_profile_led1_Timer3)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer3)
if (enable_profile_led2_Timer3)
i_led2_on_off_special(0);
#endif
@ -567,11 +566,11 @@ interrupt void evb_timer4_isr(void)
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer4)
if (enable_profile_led1_Timer4)
i_led1_on_off_special(1);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer4)
if (enable_profile_led2_Timer4)
i_led2_on_off_special(1);
#endif
@ -591,11 +590,11 @@ interrupt void evb_timer4_isr(void)
PieCtrlRegs.PIEIER5.all = TempPIEIER;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.timer4)
if (enable_profile_led1_Timer4)
i_led1_on_off_special(0);
#endif
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
if (profile_interrupt.for_led2.bits.timer4)
if (enable_profile_led2_Timer4)
i_led2_on_off_special(0);
#endif

View File

@ -8,9 +8,6 @@
#ifndef SRC_MAIN_CAN_PROJECT_H_
#define SRC_MAIN_CAN_PROJECT_H_
#include "can_protocol_ukss.h"
//////////////////////////////////////////////////////////////////
// íàñòðîéêà áàçîâûõ àäðåñîâ CAN
// PCH_1 èëè PCH_2 âûáèðàåòñÿ äæàìïåðîâ íà ÏÌ67
@ -31,21 +28,23 @@
//#define CAN_PROTOCOL_VERSION 1
#define CAN_PROTOCOL_VERSION 2
#define CAN_SPEED_BITS 125000
//#define CAN_SPEED_BITS 250000
#define CAN_SPEED_BITS 250000
//#define CAN_SPEED_BITS 500000
#define ENABLE_CAN_SEND_TO_UKSS_FROM_MAIN 1
#define ENABLE_CAN_SEND_TO_MPU_FROM_MAIN 1
#define ENABLE_CAN_SEND_TO_TERMINAL_FROM_MAIN 0//1
#define ENABLE_CAN_SEND_TO_TERMINAL_FROM_MAIN 1
#define ENABLE_CAN_SEND_TO_TERMINAL_OSCIL 0//1
#define ENABLE_CAN_SEND_TO_ANOTHER_BSU_FROM_MAIN 1
//////////////////////////////////////////////////////
#ifndef ENABLE_CAN_SEND_TO_UKSS_FROM_MAIN
#define ENABLE_CAN_SEND_TO_UKSS_FROM_MAIN 0
#endif

View File

@ -14,9 +14,9 @@ void main()
// This example function is found in the DSP281x_SysCtrl.c file.
InitSysCtrl();
XintfZone0_Timing();//Xilinx Zone
XintfZone6_And7_Timing();//Flash Zone
XintfZone2_Timing();//External RAM Zone
XintfZone0_Timing();
XintfZone6_And7_Timing();
XintfZone2_Timing();
// Step 2. Initalize GPIO:
// This example function is found in the DSP281x_Gpio.c file and

File diff suppressed because it is too large Load Diff

View File

@ -11,8 +11,7 @@
void InitPWM(void);
void PWM_interrupt(void);
void PWM_interrupt_main(void);
void InitPWM_Variables(void);
void stop_wdog(void);
@ -22,20 +21,11 @@ void start_wdog(void);
void global_time_interrupt(void);
void optical_bus_read_write_interrupt(void);
void pwm_analog_ext_interrupt(void);
void pwm_inc_interrupt(void);
void fix_pwm_freq_synchro_ain(void);
void async_pwm_ext_interrupt(void);
void calc_rotors(int flag);
void detect_work_revers(int direction, _iq fzad, _iq frot);
void calc_power_full(void);
//////////////////////////////////////////////////
//////////////////////////////////////////////////

View File

@ -132,8 +132,6 @@ ERR_ADC_PROTECT err_adc_protect[COUNT_ARR_ADC_BUF],mask_err_adc_protect[COUNT_AR
_iq koef_Im_filter=0;
_iq koef_Power_filter=0;
_iq koef_Power_filter2=0;
#pragma DATA_SECTION(k_norm_ADC,".slow_vars")
_iq19 k_norm_ADC[COUNT_ARR_ADC_BUF][16];
@ -167,8 +165,8 @@ _iq koef_Uin_filter=0;
void fast_detect_protect_ACP();
//void fast_read_all_adc_one(int cc);
//void fast_read_all_adc_more(void);
void fast_read_all_adc_one(int cc);
void fast_read_all_adc_more(void);
#if (USE_INTERNAL_ADC==1)
@ -576,7 +574,7 @@ void Init_Adc_Variables(void)
}
for (i=0;i<COUNT_ARR_ADC_BUF;i++)
for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
{
if (project.adc[i].status >= component_Ready)
detect_zero_analog(i);
@ -592,7 +590,7 @@ void Init_Adc_Variables(void)
#if (COUNT_ARR_ADC_BUF>1)
zero_ADC[1][1]=zero_ADC[1][15];
zero_ADC[1][2]=zero_ADC[1][15];
zero_ADC[1][3]=zero_ADC[1][15];
@ -607,12 +605,12 @@ void Init_Adc_Variables(void)
zero_ADC[1][12]=zero_ADC[1][15];
zero_ADC[1][13]=zero_ADC[1][15];
zero_ADC[1][14]=zero_ADC[1][15];
#endif
for (k=0;k<16;k++)
{
for (i=0;i<COUNT_ARR_ADC_BUF;i++)
for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
{
if ((zero_ADC[i][k]>2200) || (zero_ADC[i][k]<1900))
zero_ADC[i][k] = DEFAULT_ZERO_ADC;
@ -623,7 +621,7 @@ void Init_Adc_Variables(void)
for (k=0;k<16;k++)
{
for (i=0;i<COUNT_ARR_ADC_BUF;i++)
for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
{
iq19_zero_ADC[i][k]=_IQ19(zero_ADC[i][k]);//_IQ19(1770);
}
@ -638,8 +636,6 @@ void Init_Adc_Variables(void)
// koef_Im_filter = _IQ(0.001/0.006);
koef_Im_filter = _IQ(0.001/0.065);
koef_Power_filter = _IQ(0.001/0.065);
koef_Power_filter2 = _IQ(0.001/0.2);
// koef_Iabc_filter = _IQ(0.001/0.006);
@ -672,7 +668,7 @@ void Init_Adc_Variables(void)
// filter.iqUin_m2 = 0;
for (i=0;i<COUNT_ARR_ADC_BUF;i++)
for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
{
mask_err_adc_protect[i].plus.all=0;
mask_err_adc_protect[i].minus.all=0x0;
@ -759,7 +755,7 @@ void read_error_ACP()
// pr = project.controller.fpga.cds_fpga_parallel_bus.pread;
for (i=0;i<COUNT_ARR_ADC_BUF;i++)
for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
{
if (project.adc[i].status == component_Ready)
for (k=0;k<16;k++)
@ -851,181 +847,181 @@ _iq norma_adc_internal_sf(int l)
/////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////
//
//#pragma CODE_SECTION(fast_read_all_adc_one,".fast_run");
//void fast_read_all_adc_one(int cc)
//{
// int i,k;
// int t;
//
// i_led1_on_off(1);
//
// project.adc[0].read_pbus(&project.adc[0]);
//
// for (k=0;k<16;k++)
// {
// t = project.adc[0].read.pbus.adc_value[k];
// ADC_fast[0][k][cc] = t;
//
// // save max values
// if (t>ADC_fast[0][k][1] || cc==3)
// ADC_fast[0][k][1] = t;
// // save min values
// if (t<ADC_fast[0][k][2] || cc==3)
// ADC_fast[0][k][2] = t;
// }
//
//
//
//
//
////i_led2_off();
// i_led1_on_off(0);
//
//}
//#pragma CODE_SECTION(fast_read_all_adc_two,".fast_run");
//void fast_read_all_adc_two(void)
//{
// int i,k;
// int t;
//
//// i_led2_on_off(1);
//
// project.adc[1].read_pbus(&project.adc[1]);
//
// for (k=0;k<16;k++)
// {
// t = project.adc[1].read.pbus.adc_value[k];
// ADC_fast[1][k][0] = t;
// }
//
//// i_led2_on_off(0);
//
//}
#pragma CODE_SECTION(fast_read_all_adc_one,".fast_run");
void fast_read_all_adc_one(int cc)
{
int i,k;
int t;
i_led1_on_off(1);
project.adc[0].read_pbus(&project.adc[0]);
for (k=0;k<16;k++)
{
t = project.adc[0].read.pbus.adc_value[k];
ADC_fast[0][k][cc] = t;
// save max values
if (t>ADC_fast[0][k][1] || cc==3)
ADC_fast[0][k][1] = t;
// save min values
if (t<ADC_fast[0][k][2] || cc==3)
ADC_fast[0][k][2] = t;
}
//i_led2_off();
i_led1_on_off(0);
}
#pragma CODE_SECTION(fast_read_all_adc_two,".fast_run");
void fast_read_all_adc_two(void)
{
int i,k;
int t;
// i_led2_on_off(1);
project.adc[1].read_pbus(&project.adc[1]);
for (k=0;k<16;k++)
{
t = project.adc[1].read.pbus.adc_value[k];
ADC_fast[1][k][0] = t;
}
// i_led2_on_off(0);
}
/////////////////////////////////////////////////////////
//#define PAUSE_BETWEEN_ADC_FAST 5
//#pragma CODE_SECTION(fast_read_all_adc_more,".fast_run");
//void fast_read_all_adc_more(void)
//{
// int i,k;
// static int p = PAUSE_BETWEEN_ADC_FAST;
//
// project.read_errors_controller();
//
// if (project.adc[0].status == component_Ready
// && project.controller.read.errors.bit.error_pbus == 0
// && project.controller.read.errors_buses.bit.slave_addr_error==0
// && project.x_parallel_bus->flags.bit.error==0 )
// {
//
//
//
// fast_read_all_adc_one(3);
// pause_1000(p);
// fast_read_all_adc_one(4);
// pause_1000(p);
// fast_read_all_adc_one(5);
// pause_1000(p);
// fast_read_all_adc_one(6);
// pause_1000(p);
// fast_read_all_adc_one(7);
// pause_1000(p);
// fast_read_all_adc_one(8);
//
//
//
// for (k=0;k<16;k++)
// {
// ADC_fast[0][k][0] = (-ADC_fast[0][k][1] - ADC_fast[0][k][2] + ADC_fast[0][k][3] + ADC_fast[0][k][4]
// +ADC_fast[0][k][5] + ADC_fast[0][k][6] + ADC_fast[0][k][7] + ADC_fast[0][k][8]) >> 2; // ñóììó äåëèì íà 4
// }
//
// }
// else
// {
// for (k=0;k<16;k++)
// {
// ADC_fast[0][k][0] = 5000; // error
// }
// }
//
//
// if (project.adc[1].status == component_Ready
// && project.controller.read.errors.bit.error_pbus == 0
// && project.controller.read.errors_buses.bit.slave_addr_error==0
// && project.x_parallel_bus->flags.bit.error==0 )
// {
//
// fast_read_all_adc_two();
// }
// else
// {
// for (k=0;k<16;k++)
// {
// ADC_fast[1][k][0] = 5000; // error
// }
// }
//
//}
#define PAUSE_BETWEEN_ADC_FAST 5
#pragma CODE_SECTION(fast_read_all_adc_more,".fast_run");
void fast_read_all_adc_more(void)
{
int i,k;
static int p = PAUSE_BETWEEN_ADC_FAST;
/////////////////////////////////////////////////////////
//
//#pragma CODE_SECTION(norma_fast_adc,".fast_run");
//void norma_fast_adc(void)
//{
// int i,k;
//// int bb;
//
//#ifdef LOG_ACP_TO_BUF
// static int c_log=0;
// static int n_log_acp_p=0;
// static int n_log_acp_c=2;
// static int n_log_acp_p_2=0;
// static int n_log_acp_c_2=2;
//
//#endif
//
// for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
// {
//
// if ( project.adc[i].status == component_Ready
// && project.controller.read.errors.bit.error_pbus == 0
// && project.controller.read.errors_buses.bit.slave_addr_error==0
// && project.x_parallel_bus->flags.bit.error==0 )
// {
// for (k=0;k<16;k++)
// {
// iq_norm_ADC[i][k] = _IQ19toIQ(_IQ19mpy((-iq19_zero_ADC[i][k] + ((long)ADC_fast[i][k][0]<<19) ),iq19_k_norm_ADC[i][k]));
// }
// }
// else
// {
// for (k=0;k<16;k++)
// {
// iq_norm_ADC[i][k] = 0;
// }
//
// }
//
// }
//
//#ifdef LOG_ACP_TO_BUF
// if (c_log>=SIZE_BUF_LOG_ACP)
// c_log=0;
// BUF_ADC[c_log]=ADC_fast[n_log_acp_p][n_log_acp_c][0];
// BUF_ADC_2[c_log]=ADC_fast[n_log_acp_p_2][n_log_acp_c_2][3];
// c_log++;
//#endif
//
////i_led2_off();
//}
project.read_errors_controller();
if (project.adc[0].status == component_Ready
&& project.controller.read.errors.bit.error_pbus == 0
&& project.controller.read.errors_buses.bit.slave_addr_error==0
&& project.x_parallel_bus->flags.bit.error==0 )
{
fast_read_all_adc_one(3);
pause_1000(p);
fast_read_all_adc_one(4);
pause_1000(p);
fast_read_all_adc_one(5);
pause_1000(p);
fast_read_all_adc_one(6);
pause_1000(p);
fast_read_all_adc_one(7);
pause_1000(p);
fast_read_all_adc_one(8);
for (k=0;k<16;k++)
{
ADC_fast[0][k][0] = (-ADC_fast[0][k][1] - ADC_fast[0][k][2] + ADC_fast[0][k][3] + ADC_fast[0][k][4]
+ADC_fast[0][k][5] + ADC_fast[0][k][6] + ADC_fast[0][k][7] + ADC_fast[0][k][8]) >> 2; // ñóììó äåëèì íà 4
}
}
else
{
for (k=0;k<16;k++)
{
ADC_fast[0][k][0] = 5000; // error
}
}
if (project.adc[1].status == component_Ready
&& project.controller.read.errors.bit.error_pbus == 0
&& project.controller.read.errors_buses.bit.slave_addr_error==0
&& project.x_parallel_bus->flags.bit.error==0 )
{
fast_read_all_adc_two();
}
else
{
for (k=0;k<16;k++)
{
ADC_fast[1][k][0] = 5000; // error
}
}
}
/////////////////////////////////////////////////////////
/*
#pragma CODE_SECTION(norma_fast_adc,".fast_run");
void norma_fast_adc(void)
{
int i,k;
// int bb;
#ifdef LOG_ACP_TO_BUF
static int c_log=0;
static int n_log_acp_p=0;
static int n_log_acp_c=2;
static int n_log_acp_p_2=0;
static int n_log_acp_c_2=2;
#endif
for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
{
if ( project.adc[i].status == component_Ready
&& project.controller.read.errors.bit.error_pbus == 0
&& project.controller.read.errors_buses.bit.slave_addr_error==0
&& project.x_parallel_bus->flags.bit.error==0 )
{
for (k=0;k<16;k++)
{
iq_norm_ADC[i][k] = _IQ19toIQ(_IQ19mpy((-iq19_zero_ADC[i][k] + ((long)ADC_fast[i][k][0]<<19) ),iq19_k_norm_ADC[i][k]));
}
}
else
{
for (k=0;k<16;k++)
{
iq_norm_ADC[i][k] = 0;
}
}
}
#ifdef LOG_ACP_TO_BUF
if (c_log>=SIZE_BUF_LOG_ACP)
c_log=0;
BUF_ADC[c_log]=ADC_fast[n_log_acp_p][n_log_acp_c][0];
BUF_ADC_2[c_log]=ADC_fast[n_log_acp_p_2][n_log_acp_c_2][3];
c_log++;
#endif
//i_led2_off();
}
/////////////////////////////////////////////////////////
#pragma CODE_SECTION(norma_all_adc,".fast_run");
void norma_all_adc(void)
{
@ -1040,7 +1036,76 @@ void norma_all_adc(void)
#endif
for (i=0;i<COUNT_ARR_ADC_BUF;i++)
//i_led2_on();
// T_cds_paralle_bus_read_all* pr;
// pr = project.controller.fpga.cds_fpga_parallel_bus.pread;
// (int)pr->data.adc[nadc].acc_short[ncan];
///
/*
iq_norm_ADC[0][0] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][0] - ((long)ADC_f[0][0]<<19) ),iq19_k_norm_ADC[0][0]));
iq_norm_ADC[0][1] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][1] - ((long)ADC_f[0][1]<<19) ),iq19_k_norm_ADC[0][1]));
iq_norm_ADC[0][2] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][2] - ((long)ADC_f[0][2]<<19) ),iq19_k_norm_ADC[0][2]));
iq_norm_ADC[0][3] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][3] - ((long)ADC_f[0][3]<<19) ),iq19_k_norm_ADC[0][3]));
iq_norm_ADC[0][4] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][4] - ((long)ADC_f[0][4]<<19) ),iq19_k_norm_ADC[0][4]));
iq_norm_ADC[0][5] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][5] - ((long)ADC_f[0][5]<<19) ),iq19_k_norm_ADC[0][5]));
iq_norm_ADC[0][6] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][6] - ((long)ADC_f[0][6]<<19) ),iq19_k_norm_ADC[0][6]));
iq_norm_ADC[0][7] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][7] - ((long)ADC_f[0][7]<<19) ),iq19_k_norm_ADC[0][7]));
//i1 second mes
// ADC_f[0][8] = (int)pr->data.adc[0].acc_short[2];
// ADC_f[0][9] = (int)pr->data.adc[0].acc_short[3];
// ADC_f[0][10] = (int)pr->data.adc[0].acc_short[4];
// ADC_f[0][11] = (int)pr->data.adc[0].acc_short[5];
// ADC_f[0][12] = (int)pr->data.adc[0].acc_short[6];
// ADC_f[0][13] = (int)pr->data.adc[0].acc_short[7];
iq_norm_ADC[0][8] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][8] - ((long)ADC_f[0][8]<<19) ),iq19_k_norm_ADC[0][8]));
iq_norm_ADC[0][9] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][9] - ((long)ADC_f[0][9]<<19) ),iq19_k_norm_ADC[0][9]));
iq_norm_ADC[0][10] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][10] - ((long)ADC_f[0][10]<<19) ),iq19_k_norm_ADC[0][10]));
iq_norm_ADC[0][11] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][11] - ((long)ADC_f[0][11]<<19) ),iq19_k_norm_ADC[0][11]));
iq_norm_ADC[0][12] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][12] - ((long)ADC_f[0][12]<<19) ),iq19_k_norm_ADC[0][12]));
iq_norm_ADC[0][13] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][13] - ((long)ADC_f[0][13]<<19) ),iq19_k_norm_ADC[0][13]));
// iq_norm_ADC[0][14] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][14] - ((long)ADC_f[0][14]<<19) ),iq19_k_norm_ADC[0][14]));
// iq_norm_ADC[0][15] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[0][15] - ((long)ADC_f[0][15]<<19) ),iq19_k_norm_ADC[0][15]));
///
// iq_norm_ADC[1][0] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][0] - ((long)ADC_f[1][0]<<19) ),iq19_k_norm_ADC[1][0]));
// iq_norm_ADC[1][1] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][1] - ((long)ADC_f[1][1]<<19) ),iq19_k_norm_ADC[1][1]));
iq_norm_ADC[1][2] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][2] - ((long)ADC_f[1][2]<<19) ),iq19_k_norm_ADC[1][2]));
iq_norm_ADC[1][3] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][3] - ((long)ADC_f[1][3]<<19) ),iq19_k_norm_ADC[1][3]));
iq_norm_ADC[1][4] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][4] - ((long)ADC_f[1][4]<<19) ),iq19_k_norm_ADC[1][4]));
// iq_norm_ADC[1][5] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][5] - ((long)ADC_f[1][5]<<19) ),iq19_k_norm_ADC[1][5]));
// iq_norm_ADC[1][6] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][6] - ((long)ADC_f[1][6]<<19) ),iq19_k_norm_ADC[1][6]));
// iq_norm_ADC[1][7] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][7] - ((long)ADC_f[1][7]<<19) ),iq19_k_norm_ADC[1][7]));
iq_norm_ADC[1][8] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][8] - ((long)ADC_f[1][8]<<19) ),iq19_k_norm_ADC[1][8]));
iq_norm_ADC[1][9] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][9] - ((long)ADC_f[1][9]<<19) ),iq19_k_norm_ADC[1][9]));
iq_norm_ADC[1][10] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][10] - ((long)ADC_f[1][10]<<19) ),iq19_k_norm_ADC[1][10]));
iq_norm_ADC[1][11] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][11] - ((long)ADC_f[1][11]<<19) ),iq19_k_norm_ADC[1][11]));
iq_norm_ADC[1][12] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][12] - ((long)ADC_f[1][12]<<19) ),iq19_k_norm_ADC[1][12]));
iq_norm_ADC[1][13] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][13] - ((long)ADC_f[1][13]<<19) ),iq19_k_norm_ADC[1][13]));
iq_norm_ADC[1][14] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][14] - ((long)ADC_f[1][14]<<19) ),iq19_k_norm_ADC[1][14]));
iq_norm_ADC[1][15] = _IQ19toIQ(_IQ19mpy((iq19_zero_ADC[1][15] - ((long)ADC_f[1][15]<<19) ),iq19_k_norm_ADC[1][15]));
*/
for (i=0;i<COUNT_ARR_ADC_BUF_EXTERNAL;i++)
{
project.read_errors_controller();
project.adc[i].read_pbus(&project.adc[i]);
@ -1096,56 +1161,72 @@ void norma_all_adc(void)
#endif
//i_led2_off();
}
*/
////////////////////////////////////////////////////////////////////
#pragma CODE_SECTION(norma_adc_nc,".fast_run");
void norma_adc_nc(int nc)
{
int k;
// int bb;
project.read_errors_controller();
project.adc[nc].read_pbus(&project.adc[nc]);
if ( project.adc[nc].status == component_Ready
&& project.controller.read.errors.bit.error_pbus == 0
&& project.controller.read.errors_buses.bit.slave_addr_error==0
&& project.x_parallel_bus->flags.bit.error==0 )
{
for (k=0;k<16;k++)
{
ADC_f[nc][k] = project.adc[nc].read.pbus.adc_value[k];
ADC_sf[nc][k] += (((int)(ADC_f[nc][k] - ADC_sf[nc][k]))>>SDVIG_K_FILTER_S);
iq_norm_ADC[nc][k] = _IQ19toIQ(_IQ19mpy((-iq19_zero_ADC[nc][k] + ((long)ADC_f[nc][k]<<19) ),iq19_k_norm_ADC[nc][k]));
}
}
else
{
for (k=0;k<16;k++)
{
ADC_f[nc][k] = 5000;//DEFAULT_ZERO_ADC;
ADC_sf[nc][k] = 5000;//DEFAULT_ZERO_ADC;
iq_norm_ADC[nc][k] = 0;
}
}
}
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
#pragma CODE_SECTION(calc_norm_ADC_1,".fast_run");
void calc_norm_ADC_1(int run_norma)
#pragma CODE_SECTION(calc_norm_ADC,".fast_run");
void calc_norm_ADC(int fast)
{
_iq a1,a2,a3;
// _iq19 t1;
// int k;
#if (USE_ADC_1)
//i_led1_on_off(0);
if (run_norma)
norma_adc_nc(1);
//i_led1_on_off(1);
// return;
//if (fast)
//{
// fast_read_all_adc_more();
// norma_fast_adc();
//}
//else
// norma_all_adc();
analog.iqU_1 = iq_norm_ADC[0][0] - analog_zero.iqU_1;
analog.iqU_2 = iq_norm_ADC[0][1] - analog_zero.iqU_2;
analog.iqIu_1 = iq_norm_ADC[0][2];
analog.iqIv_1 = iq_norm_ADC[0][3];
analog.iqIw_1 = iq_norm_ADC[0][4];
analog.iqIu_2 = iq_norm_ADC[0][5];
analog.iqIv_2 = iq_norm_ADC[0][6];
analog.iqIw_2 = iq_norm_ADC[0][7];
analog.iqIin_1 = -iq_norm_ADC[0][9]; // äàò÷èê ïåðåâåðíóò
analog.iqIin_2 = -iq_norm_ADC[0][9]; // äàò÷èê ïåðåâåðíóò
analog.iqUin_A1B1 = iq_norm_ADC[0][10];
// äâà âàðèàíòà ïîäêëþ÷åíèÿ äàò÷èêîâ 23550.1 áîëåå ïðàâèëüíûé - ïî ñõåìå
// 23550.1
analog.iqUin_B1C1 = iq_norm_ADC[0][11]; // 23550.1
analog.iqUin_A2B2 = iq_norm_ADC[0][12]; // 23550.1
// 23550.3 bs1 bs2
// analog.iqUin_B1C1 = iq_norm_ADC[0][12]; // 23550.3
// analog.iqUin_A2B2 = iq_norm_ADC[0][11]; // 23550.3
//
analog.iqUin_C1A1 = -(analog.iqUin_A1B1 + analog.iqUin_B1C1);
analog.iqUin_B2C2 = iq_norm_ADC[0][13];
analog.iqUin_C2A2 = -(analog.iqUin_A2B2 + analog.iqUin_B2C2);
analog.iqIbreak_1 = iq_norm_ADC[0][14];
analog.iqIbreak_2 = iq_norm_ADC[0][15];
#if (_FLOOR6==1)
@ -1186,86 +1267,9 @@ void calc_norm_ADC_1(int run_norma)
#endif
#else
// analog.iqI_vozbud = iq_norm_ADC[1][13];
analog.T_U01 =
analog.T_U02 =
analog.T_U03 =
analog.T_U04 =
analog.T_U05 =
analog.T_U06 =
analog.T_U07 =
analog.T_Water_external =
analog.T_Water_internal =
analog.P_Water_internal =
analog.T_Air_01 =
analog.T_Air_02 =
analog.T_Air_03 =
analog.T_Air_04 = 0;
#endif
// analog.iqI_vozbud = iq_norm_ADC[1][13];
}
////////////////////////////////////////////////////////////////////
#pragma CODE_SECTION(calc_norm_ADC_0,".fast_run");
void calc_norm_ADC_0(int run_norma)
{
_iq a1,a2,a3;
#if (USE_ADC_0)
if (run_norma)
norma_adc_nc(0);
#if (_FLOOR6)
analog.iqU_1 = iq_norm_ADC[0][0] - analog_zero.iqU_1 + analog.iqU_1_imit;
analog.iqU_2 = iq_norm_ADC[0][1] - analog_zero.iqU_2 + analog.iqU_1_imit;
#else
analog.iqU_1 = iq_norm_ADC[0][0] - analog_zero.iqU_1;
analog.iqU_2 = iq_norm_ADC[0][1] - analog_zero.iqU_2;
#endif
analog.iqIu_1 = iq_norm_ADC[0][2];
analog.iqIv_1 = iq_norm_ADC[0][3];
analog.iqIw_1 = iq_norm_ADC[0][4];
analog.iqIu_2 = iq_norm_ADC[0][5];
analog.iqIv_2 = iq_norm_ADC[0][6];
analog.iqIw_2 = iq_norm_ADC[0][7];
analog.iqIin_1 = -iq_norm_ADC[0][9]; // äàò÷èê ïåðåâåðíóò
analog.iqIin_2 = -iq_norm_ADC[0][9]; // äàò÷èê ïåðåâåðíóò
analog.iqUin_A1B1 = iq_norm_ADC[0][10];
// äâà âàðèàíòà ïîäêëþ÷åíèÿ äàò÷èêîâ 23550.1 áîëåå ïðàâèëüíûé - ïî ñõåìå
// 23550.1
analog.iqUin_B1C1 = iq_norm_ADC[0][11]; // 23550.1
analog.iqUin_A2B2 = iq_norm_ADC[0][12]; // 23550.1
// 23550.3 bs1 bs2
// analog.iqUin_B1C1 = iq_norm_ADC[0][12]; // 23550.3
// analog.iqUin_A2B2 = iq_norm_ADC[0][11]; // 23550.3
//
analog.iqUin_B2C2 = iq_norm_ADC[0][13];
analog.iqIbreak_1 = iq_norm_ADC[0][14];
analog.iqIbreak_2 = iq_norm_ADC[0][15];
#else
analog.iqU_1 = analog.iqIu_1 = analog.iqIu_2 = analog.iqIv_1 = analog.iqIv_2 =
analog.iqIw_1 = analog.iqIw_2 = analog.iqIin_1 = analog.iqIin_2 = analog.iqUin_A1B1 =
analog.iqUin_B1C1 = analog.iqUin_A2B2 = analog.iqUin_B2C2 = analog.iqIbreak_1 = analog.iqIbreak_2
= 0;
#endif
analog.iqUin_C1A1 = -(analog.iqUin_A1B1 + analog.iqUin_B1C1);
analog.iqUin_C2A2 = -(analog.iqUin_A2B2 + analog.iqUin_B2C2);
@ -1335,8 +1339,11 @@ void calc_norm_ADC_0(int run_norma)
a3 = _IQmpy(a1,a2);
analog.PowerScalar = a3;
// filter.Power = analog.iqU_1+analog.iqU_2;
filter.PowerScalar = exp_regul_iq(koef_Power_filter, filter.PowerScalar, analog.PowerScalar);
filter.PowerScalarFilter2 = exp_regul_iq(koef_Power_filter2, filter.PowerScalarFilter2, filter.PowerScalar);
filter.PowerScalar = exp_regul_iq(koef_Im_filter, filter.PowerScalar, analog.PowerScalar);
//i_led1_on_off(0);
//i_led1_on_off(1);
}
@ -1367,10 +1374,7 @@ void detect_zero_analog(int nc)
for (i=0; i<COUNT_DETECT_ZERO; i++)
{
// norma_all_adc();
norma_adc_nc(nc);
// norma_adc_nc(1);
norma_all_adc();
for (k=0;k<16;k++)
{

View File

@ -5,17 +5,39 @@
#include "IQmathLib.h"
#include "xp_project.h"
#include "params_norma.h"
#define COUNT_DETECT_ZERO 3000
#define COUNT_ARR_ADC_BUF_FAST_POINT 10
#define NORMA_ACP 3000.0
#define NORMA_ACP_TEMPER_MILL_AMP 100.0 //
#ifndef PROJECT_SHIP
#error Íå óñòàíîâëåí PROJECT_SHIP â predifine Name
#else
#if (PROJECT_SHIP == 1)
#define NORMA_ACP_TEMPER 100.0 // äëÿ 23550.1
#endif
#if (PROJECT_SHIP == 2)
#define NORMA_ACP_TEMPER 200.0 // äëÿ 23550.3
#endif
#if (PROJECT_SHIP== 3)
#define NORMA_ACP_TEMPER 200.0 // äëÿ 23550.3
#endif
#endif
#define DELTA_ACP_TEMPER 0.0 // äàò÷èêè áëîêè pt100 äàåþò ïîñòîÿííîå ñìåùåíèå 0.0 ãðàäóñîâ, òàê íàñòðîåí áëîê SG3013
#define NORMA_ACP_P 100.0
#define ADC_READ_FROM_PARALLEL_BUS 1
#define DEFAULT_ZERO_ADC 2048
@ -235,7 +257,7 @@ typedef struct
_iq iqUin_m2;
_iq iqIbreak_1;
_iq iqIbreak_2; //39
_iq iqIbreak_2;
_iq T_U01;
_iq T_U02;
@ -253,7 +275,7 @@ typedef struct
_iq T_Air_03;
_iq T_Air_04;
_iq P_Water_internal; //53
_iq P_Water_internal;
_iq iqI_vozbud;
@ -269,11 +291,8 @@ typedef struct
_iq iqM;
_iq PowerScalar;
_iq PowerScalarFilter2;
_iq PowerFOC;
_iq iqU_1_imit; //63
/*
_iq iqUzpt_1_2; //uzpt1 bs2
@ -341,7 +360,7 @@ typedef struct
#define ANALOG_VALUE_DEFAULT {0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0, 0,0, 0}
0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0, 0}
/* Ãëîáàëüíày ñòðóêòóðà çíà÷åíèé òîêîâ è íàïðyæåíèé ÀÈÍ */
@ -369,12 +388,8 @@ extern ANALOG_VALUE analog;
extern ANALOG_VALUE filter;
extern ANALOG_VALUE analog_zero;
//void calc_norm_ADC(int fast);
void calc_norm_ADC_0(int run_norma);
void calc_norm_ADC_1(int run_norma);
void calc_norm_ADC(int fast);
void Init_Adc_Variables(void);
void norma_adc_nc(int nc);
extern int ADC_f[COUNT_ARR_ADC_BUF][16];
@ -386,8 +401,8 @@ extern unsigned int R_ADC[COUNT_ARR_ADC_BUF][16];
extern unsigned int K_LEM_ADC[COUNT_ARR_ADC_BUF][16];
extern float K_NORMA_ADC[COUNT_ARR_ADC_BUF][16];
//void norma_all_adc(void);
extern _iq koef_Uzpt_long_filter, koef_Uzpt_fast_filter, koef_Uin_filter, koef_Im_filter, koef_Power_filter, koef_Power_filter2;
void norma_all_adc(void);
void detect_zero_analog(int nc);

View File

@ -1,196 +0,0 @@
/*
* alarm_log.c
*
* Created on: 11 ñåíò. 2024 ã.
* Author: yura
*/
#include "edrk_main.h"
#include "alarm_log_can.h"
#include "alarm_log.h"
#include "log_params.h"
#include "logs_hmi.h"
#include "global_time.h"
#define PAUSE_AUTO_SAVE_ALARM_LOG_SECONDS 20 // 20 sec
#define PAUSE_AUTO_STOP_ALARM_LOG_SECONDS 5 // 5 sec
void send_alarm_log_pult(void)
{
static int prev_imit_send_alarm_log_pult = 0;
int to_store = 0;
static int flag_wait_alarm = 0, prev_Ready2 = 0, flag_store_log = 0, flag_store_log_prepare = 0, flag_auto_logs = 0, flag_stop_alarm = 0;
static unsigned int pause_store_logs = 0, pause_stop_logs = 0;
// èìèòàöèÿ ñ òåðìèíàëêè
if (edrk.imit_send_alarm_log_pult && prev_imit_send_alarm_log_pult == 0)
flag_store_log = 1;
prev_imit_send_alarm_log_pult = edrk.imit_send_alarm_log_pult;
// àâòî ëîããèðîâàíèå àâàðèéíûõ ëîãîâ íà ïóëüò
// ñõåìà ñîáðàëàñü? çíà÷èò ëîâèì àâàðèþ
if (prev_Ready2==0 && edrk.Status_Ready.bits.ready_final)
{
flag_wait_alarm = 1;
flag_stop_alarm = 0;
}
if (prev_Ready2==1 && edrk.Status_Ready.bits.ready_final==0)
{
// äàåì ïàóçó, æäåì îøèáêè
init_timer_sec(&pause_stop_logs);
flag_stop_alarm = 1;
}
prev_Ready2 = edrk.Status_Ready.bits.ready_final;
//ñõåìà áûëà ñîáðàíà è ïîÿâèëàñü àâàðèÿ
if (flag_wait_alarm && edrk.summ_errors)
{
// ìîæíî ñîõðàíèòüñÿ
flag_store_log_prepare = 1;
flag_wait_alarm = 0;
flag_stop_alarm = 0;
init_timer_sec(&pause_store_logs);
}
// //ñõåìà áûëà ðàçîáðàíà, íî îøèáîê ìîæåò è íå áûòü
// if (flag_stop_alarm)
// {
//
//
// }
// îøèáîê íå ïîÿâèëîñü, ïðåêðàùàåì æäàòü
if (flag_stop_alarm && detect_pause_sec(PAUSE_AUTO_STOP_ALARM_LOG_SECONDS, &pause_stop_logs))
{
flag_stop_alarm = 0;
flag_wait_alarm = 0;
}
if (flag_store_log_prepare)
{
flag_auto_logs = detect_pause_sec(PAUSE_AUTO_SAVE_ALARM_LOG_SECONDS, &pause_store_logs);
}
if (flag_auto_logs)
{
flag_store_log_prepare = 0;
flag_auto_logs = 0;
// ñîõðàíÿåì
flag_store_log = 1;
flag_wait_alarm = 0;
flag_stop_alarm = 0;
}
// ïðîèçâîäèì ñáðîñ ëîãîâ íà ïóëüò
if (flag_store_log)
{
if (edrk.pult_cmd.log_what_memory >= 2)
to_store = 2;
else
if (edrk.pult_cmd.log_what_memory >= 1)
to_store = 1;
else
to_store = 0;
log_to_HMI.sdusb = to_store;
// åñëè åñòü íîñèòåëè òî ñîõðàíÿåì
if (log_to_HMI.sdusb)
{
log_to_HMI.send_log = 3;
}
flag_store_log = 0;
}
}
void test_send_alarm_log(int alarm_cmd)
{
static unsigned int points_alarm_log = 1000;
// static unsigned int nchannel_alarm_log = 30;
static int prev_alarm_cmd = 0;
static int local_alarm_cmd = 0;
if (alarm_cmd && prev_alarm_cmd==0 && alarm_log_can.stage==0)
{
// i_led2_on();
alarm_log_can.post_points = COUNT_SAVE_LOG_OFF;//100; // êîëè÷åñòâî ïîñòàâàðèéíûéõ çàïèñåé
alarm_log_can.oscills = log_params.BlockSizeErr;//nchannel_alarm_log; // êîëè÷åñòâî êîëîíîê
alarm_log_can.global_enable = 1;
alarm_log_can.start_adr_temp = (int *)0xc0000; // àäðåñ äëÿ âðåìåííîãî ðàçìåùåíèÿ êîïèè ëîãà, ëîã ñêîïèðóåòñÿ èç öèêëè÷åñêîãî áóôåðà â ýòîò ðàçâåðíóâøèñü.
// alarm_log_can.finish_adr_temp = (int *)0xa0000; // àäðåñ äëÿ âðåìåííîãî ðàçìåùåíèÿ êîïèè ëîãà, ëîã ñêîïèðóåòñÿ èç öèêëè÷åñêîãî áóôåðà â ýòîò ðàçâåðíóâøèñü.
alarm_log_can.start_adr_real_logs = (int *)log_params.start_address_log;//(int *)START_ADDRESS_LOG; // àäðåñ íà÷àëà ðåàëüíûõ ëîãîâ â öèêëè÷åñêîì áóôåðå
alarm_log_can.finish_adr_real_log = (int *)log_params.end_address_log;//(int *)logpar.; // êîíåö ëîãîâ â öèêëè÷åñêîì áóôåðå
alarm_log_can.current_adr_real_log = (int *)log_params.addres_mem;
alarm_log_can.temp_points = points_alarm_log; // ðåàëüíûé ðàçìåð öèêëè÷åñêãî áóôåðà â òî÷êàõ.
// alarm_log_can.real_points = 1000; // íóæíûé êóñîê äëÿ êîïèè, äàííîå êîëè÷åñòâî ñêîïèðóåòñÿ èç öèêëè÷åñêîãî áóôåðà âî âðåìåííûé ëîã.
alarm_log_can.step = 450; // mks
local_alarm_cmd = alarm_cmd;
// alarm_log_can.status_alarm = alarm_cmd;//cmd_alarm_log; // êîä àâàðèè
alarm_log_can.start = 0x1;
alarm_log_can.stop = 0x1;
alarm_log_can.copy2temp = 0x1;
alarm_log_can.clear(&alarm_log_can);
// alarm_log_can.send(&alarm_log_can);
// i_led2_off();
}
else
local_alarm_cmd = 0;
alarm_log_can.status_alarm = local_alarm_cmd;//cmd_alarm_log; // êîä àâàðèè
alarm_log_can.send(&alarm_log_can);
if (alarm_log_can.stage)
{
// i_led2_on_off(1);
}
else
{
// i_led2_on_off(0);
}
prev_alarm_cmd = alarm_cmd;
}
////////////////////////////////////////////////////////////

View File

@ -1,16 +0,0 @@
/*
* alarm_log.h
*
* Created on: 11 ñåíò. 2024 ã.
* Author: yura
*/
#ifndef SRC_MAIN_ALARM_LOG_H_
#define SRC_MAIN_ALARM_LOG_H_
void test_send_alarm_log(int alarm_cmd);
void send_alarm_log_pult(void);
#endif /* SRC_MAIN_ALARM_LOG_H_ */

View File

@ -8,39 +8,36 @@
#include <alg_simple_scalar.h>
#include <edrk_main.h>
//#include <log_to_mem.h>
#include <log_to_mem.h>
#include <master_slave.h>
#include <math.h>
#include <params_alg.h>
#include <params_norma.h>
#include <project.h>
//#include "log_to_mem.h"
#include "log_to_mem.h"
#include "IQmathLib.h"
#include "math_pi.h"
#include "mathlib.h"
#include "params_pwm24.h"
#include "filter_v1.h"
#include "log_to_memory.h"
#pragma DATA_SECTION(simple_scalar1,".slow_vars");
ALG_SIMPLE_SCALAR simple_scalar1 = ALG_SIMPLE_SCALAR_DEFAULT;
_iq koefBpsi = _IQ(0.05); //0.05
void init_simple_scalar(void)
{
simple_scalar1.mzz_add_1 = _IQ(MZZ_ADD_1/NORMA_MZZ);
simple_scalar1.mzz_add_2 = _IQ(MZZ_ADD_2/NORMA_MZZ);
simple_scalar1.mzz_add_3 = _IQ(MZZ_ADD_3/NORMA_MZZ);
simple_scalar1.poluses = _IQ(POLUS);
simple_scalar1.iq_mzz_max_for_fzad = _IQ(1000.0/NORMA_MZZ);
simple_scalar1.powerzad_add = _IQ(POWERZAD_ADD_MAX);
simple_scalar1.powerzad_dec = _IQ(POWERZAD_DEC);
// simple_scalar1.k_freq_for_pid = _IQ(1.0);
simple_scalar1.k_freq_for_pid = _IQ(1.0);
simple_scalar1.k_freq_for_pid = _IQ(450.0/FREQ_PWM);
simple_scalar1.iq_add_kp_df = _IQ(ADD_KP_DF);
@ -63,7 +60,7 @@ void init_simple_scalar(void)
simple_scalar1.pidIm1.OutMax=_IQ(K_STATOR_MAX);
simple_scalar1.pidIm1.OutMin=_IQ(K_STATOR_MIN);
simple_scalar1.pidIm1.OutMin=_IQ(0);
//////////////
@ -100,8 +97,7 @@ void init_simple_scalar(void)
// ìèí. ñêîëüæåíèå
simple_scalar1.min_bpsi = _IQ(BPSI_MINIMAL/NORMA_FROTOR);
simple_scalar1.max_bpsi = _IQ(BPSI_MAXIMAL/NORMA_FROTOR);
simple_scalar1.min_bpsi = _IQ(0.05/NORMA_FROTOR);
}
@ -122,32 +118,14 @@ void init_simple_scalar(void)
Èäåò ğàñ÷åò íàïğyæåíèy ÷åğåç ìîäóëü òîêà ïî îäíîé èç 3-õ ôàçíîé ñòîåê.
Çàìûêàåòñy îáğàòíày ñâyçü ïî îáîğîòàì */
/****************************************************************/
//#pragma CODE_SECTION(simple_scalar,".fast_run");
void simple_scalar(int n_alg,
int n_wind_pump,
int direction,
_iq Frot_pid,
_iq Frot,
_iq fzad,
void simple_scalar(int n_alg, int n_wind_pump,
_iq Frot_pid,_iq Frot, _iq fzad,
_iq iqKoefOgran,
_iq mzz_zad,
_iq bpsi_const,
_iq iqIm,
_iq iqUin,
_iq Iin,
_iq powerzad,
_iq power_pid,
_iq power_limit,
int mode_oborots_power,
_iq Izad_from_master,
int master,
int count_bs_work,
_iq *Fz,
_iq *Uz1,
_iq *Uz2,
_iq *Izad_out)
_iq mzz_zad, _iq bpsi_const,
_iq iqIm, _iq iqUin, _iq Iin, _iq powerzad, _iq power_pid,
_iq Izad_from_master, int master,
_iq *Fz, _iq *Uz1, _iq *Uz2, _iq *Izad_out)
{
_iq mzz, dF, dI1, Izad, Uz_t1, Kpred_Ip, pred_Ip;//, znak_moment;
@ -157,7 +135,6 @@ void simple_scalar(int n_alg,
_iq Im_regul=0;
static _iq bpsi=0;
// static _iq IQ_POLUS=0;
@ -191,7 +168,7 @@ void simple_scalar(int n_alg,
static _iq fzad_add=0; //fzad_dec
_iq halfIm1, halfIm2;
static _iq powerzad_int=0, powerzad_add_max=0, pidFOutMax = 0, pidFOutMin = 0 ;
static _iq powerzad_int=0, powerzad_add_max=0 ;
//powerzad_dec powerzad_add
// static _iq koef_bpsi=0;
// static _iq min_bpsi=0;
@ -206,217 +183,15 @@ void simple_scalar(int n_alg,
// static _iq iq_spad_k=1;
static _iq myq_temp=0;
static _iq bpsi_filter=0;
static _iq _iq_koef_im_on_tormog = _IQ(KOEF_IM_ON_TORMOG);
static _iq _iq_koef_im_on_tormog_max_temper_break = _IQ(KOEF_IM_ON_TORMOG_WITH_MAX_TEMPER_BREAK);
static _iq n_iq_koef_im_on_tormog = CONST_IQ_1, t_iq_koef_im_on_tormog = CONST_IQ_1;
static _iq _iq_koef_im_on_tormog_add =_IQ(0.0005), _iq_koef_im_on_tormog_dec = _IQ(0.01);
// static _iq F_revers_level00= _IQ(70.0/60.0/NORMA_FROTOR);
static _iq F_revers_level0 = _IQ(90.0/60.0/NORMA_FROTOR);
static _iq F_revers_level1 = _IQ(100.0/60.0/NORMA_FROTOR);
static _iq F_revers_level2 = _IQ(110.0/60.0/NORMA_FROTOR);
static _iq F_revers_level3 = _IQ(120.0/60.0/NORMA_FROTOR);
static _iq F_revers_level4 = _IQ(130.0/60.0/NORMA_FROTOR);
static _iq F_revers_level5 = _IQ(140.0/60.0/NORMA_FROTOR);
static _iq F_revers_level6 = _IQ(150.0/60.0/NORMA_FROTOR);
static _iq F_revers_level7 = _IQ(160.0/60.0/NORMA_FROTOR);
static _iq F_revers_level8 = _IQ(170.0/60.0/NORMA_FROTOR);
static _iq F_revers_level9 = _IQ(180.0/60.0/NORMA_FROTOR);
static _iq F_revers_level10 = _IQ(190.0/60.0/NORMA_FROTOR);
static _iq F_revers_level11 = _IQ(200.0/60.0/NORMA_FROTOR);
static _iq F_revers_level12 = _IQ(210.0/60.0/NORMA_FROTOR);
static _iq F_revers_level13 = _IQ(220.0/60.0/NORMA_FROTOR);
static _iq kF_revers_level00 = _IQ(0.65);
static _iq kF_revers_level0 = _IQ(0.70);
static _iq kF_revers_level1 = _IQ(0.75);
static _iq kF_revers_level2 = _IQ(0.78);
static _iq kF_revers_level3 = _IQ(0.80);
static _iq kF_revers_level4 = _IQ(0.82);
static _iq kF_revers_level5 = _IQ(0.84);
static _iq kF_revers_level6 = _IQ(0.86);
static _iq kF_revers_level7 = _IQ(0.88);
static _iq kF_revers_level8 = _IQ(0.90);
static _iq kF_revers_level9 = _IQ(0.91);
static _iq kF_revers_level10 = _IQ(0.92);
static _iq kF_revers_level11 = _IQ(0.93);
static _iq kF_revers_level12 = _IQ(0.94);
static _iq kF_revers_level13 = _IQ(0.96);
static _iq P_level0 = _IQ(70.0/60.0/NORMA_FROTOR);
static _iq P_level1 = _IQ(150.0/60.0/NORMA_FROTOR);
static _iq P_level2 = _IQ(160.0/60.0/NORMA_FROTOR);
static _iq P_level3 = _IQ(170.0/60.0/NORMA_FROTOR);
static _iq P_level4 = _IQ(180.0/60.0/NORMA_FROTOR);
static _iq P_level5 = _IQ(190.0/60.0/NORMA_FROTOR);
static _iq P_level6 = _IQ(200.0/60.0/NORMA_FROTOR);
static _iq P_level7 = _IQ(210.0/60.0/NORMA_FROTOR);
static _iq P_level8 = _IQ(220.0/60.0/NORMA_FROTOR);
static _iq P_level9 = _IQ(230.0/60.0/NORMA_FROTOR);
// static _iq P_level9 = _IQ(300.0/60.0/NORMA_FROTOR);
static _iq kP_level0 = _IQ(0.9);
static _iq kP_level1 = _IQ(0.9);
static _iq kP_level2 = _IQ(0.9);
static _iq kP_level3 = _IQ(0.85);
static _iq kP_level4 = _IQ(0.8);
static _iq kP_level5 = _IQ(0.75);
static _iq kP_level6 = _IQ(0.7);
static _iq kP_level7 = _IQ(0.65);
static _iq kP_level8 = _IQ(0.6);
static _iq kP_level9 = _IQ(0.55);
static _iq pid_kp_power = _IQ(PID_KP_POWER);
static _iq add_mzz_outmax_pidp = _IQ(100.0/NORMA_MZZ);
_iq new_pidP_OutMax = 0;
_iq k_ogr_p_koef_1 = 0;
_iq k_ogr_p_koef_2 = 0;
_iq k_ogr_n = 0;
_iq Frot_pid_abs;
_iq d_m=0;
_iq iq_decr_mzz_power;
_iq level1_power_ain_decr_mzz, level2_power_ain_decr_mzz;
_iq new_power_limit = 0;
static _iq koef_Power_filter2 = _IQ(1.0/(FREQ_PWM*EXP_FILTER_KOEF_OGRAN_POWER_LIMIT));//2.2 ñåê //30000;// 0,0012//16777;//0,001//13981;
Frot_pid_abs = _IQabs(Frot_pid);
// ïîïûòêà ïåðåñ÷èòàòü pidPower.Kp íà ëåòó
//
// if (Frot_pid_abs>=P_level0)
// {
// k_ogr_p_koef_1 = CONST_IQ_1 - _IQdiv( (Frot_pid_abs-P_level0) , (P_level9-P_level0) );
// if (k_ogr_p_koef_1<0) k_ogr_p_koef_1 = 0;
// }
// else
// k_ogr_p_koef_1 = CONST_IQ_1;
//
// //k_ogr_p_koef_1 ìåíÿåòñÿ îò 1 äî 0 ñ
//
// k_ogr_p_koef_2 = CONST_IQ_01 + _IQmpy(CONST_IQ_09, k_ogr_p_koef_1);
// simple_scalar1.pidPower.Kp = _IQmpy (pid_kp_power, k_ogr_p_koef_2);// _IQ(PID_KP_POWER)
simple_scalar1.pidPower.Kp = pid_kp_power;//_IQmpy (pid_kp_power, k_ogr_p_koef_2);// _IQ(PID_KP_POWER)
if (mode_oborots_power == ALG_MODE_SCALAR_OBOROTS)
{
if (simple_scalar1.cmd_new_calc_p_limit)
{
simple_scalar1.flag_decr_mzz_power = 0;
simple_scalar1.iq_decr_mzz_power_filter = CONST_IQ_1;
simple_scalar1.iq_decr_mzz_power = CONST_IQ_1;
new_power_limit = power_limit;
}
else
{
// ðàñ÷åò êîýô îãðàíè÷åíèÿ ìîùíîñòè ïî ïðåâûøåíèþ çàïàñà, âûøå ëèìèòà
// åñëè òåê ìîùíîñòü ïðèáëèæàåòñÿ ê ëèìèòó òî íà÷èíàåì ïðîïîðóöèîíàëüíî óìåíüøàòü òîê ÷åðåç êîýô.
// simple_scalar1.iq_decr_mzz_power_filter êîòîðûé èäåò îò 1.0 - íåò îãðàíè÷åíèÿ,
// äî 1-MAX_KOEF_OGRAN_POWER_LIMIT - ïîëíîå îãðàíè÷åíèå
new_power_limit = power_limit - simple_scalar1.sdvig_power_limit;
if (new_power_limit<MIN_DELTA_LEVEL_POWER_AIN_DECR_MZZ_DEF)
new_power_limit = MIN_DELTA_LEVEL_POWER_AIN_DECR_MZZ_DEF;
// ïåðâûé óðîâåíü
level1_power_ain_decr_mzz = new_power_limit - DELTA_LEVEL_POWER_AIN_DECR_MZZ_DEF - simple_scalar1.add_power_limit;
if (level1_power_ain_decr_mzz<0)
level1_power_ain_decr_mzz = 0;
// âòîðîé óðîâåíü
level2_power_ain_decr_mzz = level1_power_ain_decr_mzz + DELTA_LEVEL_POWER_AIN_DECR_MZZ_DEF + simple_scalar1.add_power_limit;
// ñìåñòèëè óðîâíè íà SMEWENIE_LEVEL_POWER_AIN_DECR_MZZ_DEF ââåðõ
level1_power_ain_decr_mzz = level1_power_ain_decr_mzz + SMEWENIE_LEVEL_POWER_AIN_DECR_MZZ_DEF;
level2_power_ain_decr_mzz = level2_power_ain_decr_mzz + SMEWENIE_LEVEL_POWER_AIN_DECR_MZZ_DEF;
d_m = power_pid - level1_power_ain_decr_mzz;
if (d_m<0)
d_m=0; // âñå â íîðìå
else
{
// ïîðà îãðàíè÷èâàòü ìîìåíò
if (d_m>=(level2_power_ain_decr_mzz-level1_power_ain_decr_mzz))
d_m = CONST_IQ_1;
else
d_m = _IQdiv(d_m,(level2_power_ain_decr_mzz - level1_power_ain_decr_mzz));
}
if (d_m<0)
d_m=0; // âñå â íîðìå
if (d_m>CONST_IQ_1)
d_m=CONST_IQ_1; // ïîëíîå îãðàíè÷åíèå
// ïåðåâåëè óðîâåíü îò 1.0 äî 0.0 â óðîâåíü îò MAX_KOEF_OGRAN_POWER_LIMIT äî 0.0
d_m = _IQmpy(d_m, MAX_KOEF_OGRAN_POWER_LIMIT); //
simple_scalar1.iq_decr_mzz_power = CONST_IQ_1 - d_m;// òåïåðü êîýô ìåíÿåòñÿ îò 1.0 - íåò îãðàí. äî MAX_KOEF_OGRAN_POWER_LIMIT ìàêñ. îãðàíè÷.
if (simple_scalar1.iq_decr_mzz_power<0)
simple_scalar1.iq_decr_mzz_power=0;
simple_scalar1.iq_decr_mzz_power_filter = exp_regul_iq(koef_Power_filter2,
simple_scalar1.iq_decr_mzz_power_filter,
simple_scalar1.iq_decr_mzz_power);
if (simple_scalar1.iq_decr_mzz_power_filter<0)
simple_scalar1.iq_decr_mzz_power_filter = 0;
if (d_m>0)
simple_scalar1.flag_decr_mzz_power = 1;
else
simple_scalar1.flag_decr_mzz_power=0;
}
}
else
{
simple_scalar1.flag_decr_mzz_power = 0;
simple_scalar1.iq_decr_mzz_power_filter = CONST_IQ_1;
simple_scalar1.iq_decr_mzz_power = CONST_IQ_1;
new_power_limit = power_limit;
}
#if (ENABLE_DECR_MZZ_POWER_IZAD)
if (simple_scalar1.disable_KoefOgranIzad==0)
simple_scalar1.iqKoefOgranIzad = _IQmpy(iqKoefOgran,simple_scalar1.iq_decr_mzz_power_filter);
else
simple_scalar1.iqKoefOgranIzad = iqKoefOgran;
#else
simple_scalar1.iqKoefOgranIzad = iqKoefOgran;
#endif
//static _iq _iq_1 = _IQ(1.0);
// static _iq mzz_int_level1_on_F=0;
// mzz = _IQsat(mzz,mzz_zad_int,0);
simple_scalar1.mzz_zad_in1 = mzz_zad;
simple_scalar1.mzz_zad = mzz_zad;
simple_scalar1.Izad_from_master = Izad_from_master;
iqKoefOgran = _IQsat(iqKoefOgran,CONST_IQ_1,0);
/* óñòàíàâëèâàåì íà÷àëüíûå óñëîâèy âñåõ ğåãóëyòîğîâ */
if ( (Frot==0) && (fzad==0) )
@ -424,16 +199,11 @@ void simple_scalar(int n_alg,
mzzi = 0;
fzad_int = 0;
powerzad_int = 0;
bpsi_filter = 0;
pidFOutMax = pidFOutMin = 0;
n_iq_koef_im_on_tormog = CONST_IQ_1;//_IQ(1.0);
simple_scalar1.iq_decr_mzz_power_filter = CONST_IQ_1;
}
if (mzz_zad==0)
{
bpsi_filter = 0;
mzz=0;
I1_i=0;
mzzi=0;
@ -505,88 +275,6 @@ void simple_scalar(int n_alg,
}
// îãðàíè÷åíèå ïðè ðåêóïåðàöèè
if (direction==0)
{
// ñòîèì
n_iq_koef_im_on_tormog = CONST_IQ_1;//_IQ(1.0);
}
else
if (direction==-1 && fzad <= 0)
{
// åäåì íàçàä, çàäàíèå ñîâïàäàåò ñ íàïðàâëåíèåì âðàùåíèÿ
if (Frot_pid<-F_revers_level13)
n_iq_koef_im_on_tormog = kF_revers_level13;
else
if (Frot_pid<-F_revers_level12)
n_iq_koef_im_on_tormog = kF_revers_level12;
else
if (Frot_pid<-F_revers_level11)
n_iq_koef_im_on_tormog = kF_revers_level11;
else
if (Frot_pid<-F_revers_level10)
n_iq_koef_im_on_tormog = kF_revers_level10;
else
if (Frot_pid<-F_revers_level9)
n_iq_koef_im_on_tormog = kF_revers_level9;
else
if (Frot_pid<-F_revers_level8)
n_iq_koef_im_on_tormog = kF_revers_level8;
else
if (Frot_pid<-F_revers_level7)
n_iq_koef_im_on_tormog = kF_revers_level7;
else
if (Frot_pid<-F_revers_level6)
n_iq_koef_im_on_tormog = kF_revers_level6;
else
if (Frot_pid<-F_revers_level5)
n_iq_koef_im_on_tormog = kF_revers_level5;
else
if (Frot_pid<-F_revers_level4)
n_iq_koef_im_on_tormog = kF_revers_level4;
else
if (Frot_pid<-F_revers_level3)
n_iq_koef_im_on_tormog = kF_revers_level3;
else
if (Frot_pid<-F_revers_level2)
n_iq_koef_im_on_tormog = kF_revers_level2;
else
if (Frot_pid<-F_revers_level1)
n_iq_koef_im_on_tormog = kF_revers_level1;
if (Frot_pid<-F_revers_level0)
n_iq_koef_im_on_tormog = kF_revers_level0;
else
n_iq_koef_im_on_tormog = kF_revers_level00;
}
else
if (direction==1 && fzad>=0)
{
// åäåì âïåðåä, çàäàíèå ñîâïàäàåò ñ íàïðàâëåíèåì âðàùåíèÿ
n_iq_koef_im_on_tormog = CONST_IQ_1;//_IQ(1.0);
}
else
{
// åñëè ðåêóïåðàöèÿ òî óìåíüøèì òîê â _iq_koef_im_on_tormog ðàç ìåíüøå îò çàäàííîãî
// mzz_zad = _IQmpy(mzz_zad, _iq_koef_im_on_tormog);
if (edrk.warnings.e9.bits.BREAK_TEMPER_ALARM == 1)
// åñòü ïåðåãðåâ àâàðèéíûé, ñíèæàåì ìîùíîñòü
n_iq_koef_im_on_tormog = _iq_koef_im_on_tormog_max_temper_break;
else
n_iq_koef_im_on_tormog = _iq_koef_im_on_tormog;
}
t_iq_koef_im_on_tormog = zad_intensiv_q(_iq_koef_im_on_tormog_add,
_iq_koef_im_on_tormog_dec,
t_iq_koef_im_on_tormog,
n_iq_koef_im_on_tormog);
mzz_zad = _IQmpy(mzz_zad, t_iq_koef_im_on_tormog);
simple_scalar1.mzz_zad_in2 = mzz_zad;
/* çàäàò÷èê èíòåíñèâíîñòè ìîìåíòà */
if (n_alg==1)
{
@ -604,14 +292,14 @@ void simple_scalar(int n_alg,
if (n_alg==2)
mzz_zad_int = zad_intensiv_q(simple_scalar1.mzz_add_2, simple_scalar1.mzz_add_2, mzz_zad_int, mzz_zad);
// myq_temp = _IQdiv(mzz_zad, simple_scalar1.iq_mzz_max_for_fzad);
// myq_temp = _IQmpy( myq_temp, fzad_add_max);
// fzad_add = myq_temp;
fzad_int = zad_intensiv_q(fzad_add, fzad_add, fzad_int, fzad );
myq_temp = _IQdiv(mzz_zad, simple_scalar1.iq_mzz_max_for_fzad);
myq_temp = _IQsat( myq_temp, simple_scalar1.fzad_add_max, 0);
fzad_add = myq_temp;
fzad_int = zad_intensiv_q(fzad_add, fzad_add, fzad_int, fzad);
powerzad_int = zad_intensiv_q(simple_scalar1.powerzad_add, simple_scalar1.powerzad_add, powerzad_int, powerzad);
@ -620,31 +308,11 @@ void simple_scalar(int n_alg,
/* ğåãóëyòîğ ñêîğîñòè */
if (mzz_zad_int>=0)
{
dF = fzad_int - Frot_pid;//*direction;
dF = fzad_int - Frot_pid;
////////// Power PI //////////////
//if (_IQabs(simple_scalar1.pidF.Out))
k_ogr_n = (_IQabs(power_pid) - _IQabs(powerzad_int));
// if (k_ogr_n<0) k_ogr_n = 0;
k_ogr_n = CONST_IQ_1 - _IQdiv(k_ogr_n, _IQabs(powerzad_int));
simple_scalar1.k_ogr_n = _IQsat(k_ogr_n,CONST_IQ_1,-CONST_IQ_1);
// íîâîå îãðàíè÷åíèÿ äëÿ pidP OutMax
new_pidP_OutMax = _IQabs(simple_scalar1.pidF.Out)+add_mzz_outmax_pidp;
new_pidP_OutMax = _IQsat(new_pidP_OutMax, mzz_zad_int, add_mzz_outmax_pidp ); // îò 100 äî ðåçóëüòàòà âûõîäà ðåãóëÿòîðà simple_scalar1.pidF.Out
// ñòàðûé âàðèàíò îãðàíè÷åíèÿ
// new_pidP_OutMax = mzz_zad_int;
simple_scalar1.pidPower.OutMax = new_pidP_OutMax;
simple_scalar1.pidPower.OutMin = 0;
simple_scalar1.pidPower.OutMax=mzz_zad;
// pidPower.Kp = _IQmpy( _IQdiv(iq_add_kp_dpower, _IQsat(mzz_zad,mzz_zad,MIN_MZZ_FOR_DPOWER)), pidPower_Kp);
// pidPower.Ki = _IQmpy( _IQdiv(iq_add_ki_dpower, _IQsat(mzz_zad,mzz_zad,MIN_MZZ_FOR_DPOWER)), pidPower_Ki);
@ -652,9 +320,9 @@ void simple_scalar(int n_alg,
// simple_scalar1.pidPower.Ki = _IQmpy(simple_scalar1.pidPower.Ki, simple_scalar1.k_freq_for_pid);
simple_scalar1.pidPower.Ref = _IQabs(powerzad_int); // òóò òîëüêî ïîëîæèòåëüíàÿ ìîùíîñòü
simple_scalar1.pidPower.Ref = powerzad_int;
simple_scalar1.pidPower.Fdb = _IQabs(power_pid);
simple_scalar1.pidPower.Fdb = power_pid;
simple_scalar1.pidPower.calc(&simple_scalar1.pidPower);
@ -674,56 +342,12 @@ void simple_scalar(int n_alg,
// pidF.OutMax=mzz_zad_int;
// èëè òàê
pidFOutMax = zad_intensiv_q(simple_scalar1.mzz_add_3, simple_scalar1.mzz_add_1, pidFOutMax, simple_scalar1.pidPower.Out);
pidFOutMin = zad_intensiv_q(simple_scalar1.mzz_add_3, simple_scalar1.mzz_add_1, pidFOutMin, simple_scalar1.pidPower.Out);
// fzad
if (direction==-1 && fzad <= 0)
{
pidFOutMax = 0;
simple_scalar1.pidF.OutMax = 0;//simple_scalar1.pidPower.Out;
simple_scalar1.pidF.OutMin = -pidFOutMin;//-simple_scalar1.pidPower.Out;
}
else
if (direction==1 && fzad>=0)
{
pidFOutMin = 0;
simple_scalar1.pidF.OutMax = pidFOutMax;//simple_scalar1.pidPower.Out;
simple_scalar1.pidF.OutMin = 0;//-simple_scalar1.pidPower.Out;
}
else
{
simple_scalar1.pidF.OutMax = pidFOutMax;//simple_scalar1.pidPower.Out;
simple_scalar1.pidF.OutMin = -pidFOutMin;//-simple_scalar1.pidPower.Out;
}
/*
// pzad
if (direction==-1 && powerzad <= 0)
{
}
else
if (direction==1 && powerzad>=0)
{
}
else
{
}
*/
simple_scalar1.pidF.OutMax = simple_scalar1.pidPower.Out;
// pidF.OutMax = mzz_zad;
if (count_bs_work==2)
simple_scalar1.pidF.Kp = simple_scalar1.pidF_Kp;//_IQmpy( _IQdiv(simple_scalar1.iq_add_kp_df, _IQsat(mzz_zad,mzz_zad,simple_scalar1.min_mzz_for_df)), simple_scalar1.pidF_Kp);
else
simple_scalar1.pidF.Kp = _IQmpy2(simple_scalar1.pidF_Kp);
simple_scalar1.pidF.Ki = simple_scalar1.pidF_Ki;//_IQmpy( _IQdiv(simple_scalar1.iq_add_ki_df, _IQsat(mzz_zad,mzz_zad,simple_scalar1.min_mzz_for_df)), simple_scalar1.pidF_Ki);
simple_scalar1.pidF.Kp = _IQmpy( _IQdiv(simple_scalar1.iq_add_kp_df, _IQsat(mzz_zad,mzz_zad,simple_scalar1.min_mzz_for_df)), simple_scalar1.pidF_Kp);
simple_scalar1.pidF.Ki = _IQmpy( _IQdiv(simple_scalar1.iq_add_ki_df, _IQsat(mzz_zad,mzz_zad,simple_scalar1.min_mzz_for_df)), simple_scalar1.pidF_Ki);
simple_scalar1.pidF.Ki = _IQmpy(simple_scalar1.pidF.Ki,simple_scalar1.k_freq_for_pid);
@ -742,10 +366,9 @@ void simple_scalar(int n_alg,
//////////////////////////////////
// áåç êîğğåêöèé dF
//fzad_int =
simple_scalar1.pidF.Ref = _IQmpy(fzad_int, iqKoefOgran);
simple_scalar1.pidF.Ref = fzad_int;
simple_scalar1.pidF.Fdb = Frot_pid;//*direction;
simple_scalar1.pidF.Fdb = Frot_pid;
simple_scalar1.pidF.calc(&simple_scalar1.pidF);
@ -757,7 +380,7 @@ void simple_scalar(int n_alg,
simple_scalar1.pidF.Ui = simple_scalar1.pidF.OutMin;
/////////////////////////////////////
mzz = _IQabs(simple_scalar1.pidF.Out); // òóò ìîäóëü!!!
mzz = simple_scalar1.pidF.Out;
///////////////////////////////////////
@ -818,8 +441,8 @@ void simple_scalar(int n_alg,
*/
Izad = _IQmpy(mzz, simple_scalar1.iqKoefOgranIzad);
iqKoefOgran = _IQsat(iqKoefOgran,CONST_IQ_1,0);
Izad = _IQmpy(mzz, iqKoefOgran);
// if ((n_alg==1) || (n_alg==2))
// {
@ -901,7 +524,7 @@ void simple_scalar(int n_alg,
Uze_t1 = Uz_t1;
}
Uze_t1 = _IQsat(Uze_t1,simple_scalar1.pidIm1.OutMax, simple_scalar1.pidIm1.OutMin);
Uze_t1 = _IQsat(Uze_t1,simple_scalar1.pidIm1.OutMax,0);
// }
@ -911,13 +534,15 @@ void simple_scalar(int n_alg,
*Uz2 = Uze_t1;
bpsi = bpsi_const + simple_scalar1.add_bpsi;
bpsi = bpsi_const;
// ñêîëüæ. ~ ìîìåíòó
// bpsi = _IQmpy(koef_bpsi,mzz);
bpsi = _IQsat(bpsi,simple_scalar1.max_bpsi, simple_scalar1.min_bpsi);
bpsi = _IQsat(bpsi,bpsi_const, simple_scalar1.min_bpsi);
#ifdef BAN_ROTOR_REVERS_DIRECT
// èñïîëüçóåì çàùèòó îò íåïğàâèëüíîãî âğàùåíèß
@ -930,35 +555,12 @@ void simple_scalar(int n_alg,
#else
if (simple_scalar1.pidF.Out < 0)
{
bpsi_filter = exp_regul_iq(koefBpsi, bpsi_filter, -bpsi);
}
else
if (simple_scalar1.pidF.Out > 0)
{
bpsi_filter = exp_regul_iq(koefBpsi, bpsi_filter, bpsi);
}
else
bpsi_filter = exp_regul_iq(koefBpsi, bpsi_filter, 0);
// *Fz = _IQmpy(Frot*direction,simple_scalar1.poluses) + bpsi_filter;
*Fz = _IQmpy(Frot, simple_scalar1.poluses) + bpsi_filter;
simple_scalar1.bpsi_curent = bpsi_filter;
*Fz = _IQmpy(Frot,simple_scalar1.poluses) + bpsi; /* bpsi - ñêîëüæåíèå, áåðåì ïîêà
êîíñòàíòîé õîòy òîæå äîëæåí ðåãóëèðîâàòüñy */
#endif
simple_scalar1.mzz_zad_int = mzz_zad_int;
simple_scalar1.Uze_t1 = Uze_t1;
simple_scalar1.iqKoefOgran = iqKoefOgran;
simple_scalar1.Fz = *Fz;
simple_scalar1.direction = direction;
simple_scalar1.fzad_int = fzad_int;
// if (n_alg==2)
@ -970,6 +572,20 @@ void simple_scalar(int n_alg,
// }
// logpar.log1 = (int16)(_IQtoIQ15(Izad));
// logpar.log2 = (int16)(_IQtoIQ15(mzz_zad));//(int16)(_IQtoIQ15(Uze_t1));
// logpar.log3 = (int16)(_IQtoIQ15(fzad_int));
// logpar.log4 = (int16)(_IQtoIQ15(simple_scalar1.pidF.Ui));
// logpar.log5 = (int16)(_IQtoIQ14(simple_scalar1.pidF.Up));
// logpar.log6 = (int16)(_IQtoIQ14(simple_scalar1.pidF.SatErr));
// logpar.log7 = (int16)(_IQtoIQ15(mzz_zad_int));
// logpar.log8 = (int16)(_IQtoIQ15(simple_scalar1.pidIm1.Ref));
// logpar.log9 = (int16)(_IQtoIQ15(simple_scalar1.pidIm1.Fdb));
// logpar.log10 = (int16)(_IQtoIQ15(simple_scalar1.pidIm1.Ui));
// logpar.log11 = (int16)(_IQtoIQ15(simple_scalar1.pidIm1.Up));
}

View File

@ -39,38 +39,11 @@ typedef struct { PIDREG3 pidIm1;
int UpravIm2;
_iq pidIm_Ki;
_iq mzz_zad_in1;
_iq mzz_zad_in2;
_iq mzz_zad;
_iq mzz_zad_int;
_iq Im_regul;
_iq Izad;
_iq Izad_from_master;
_iq bpsi_curent;
_iq Uze_t1;
_iq iqKoefOgran;
_iq Fz;
int direction;
_iq fzad_int;
_iq add_bpsi;
_iq max_bpsi;
_iq mzz_add_3;
_iq k_ogr_n;
_iq iq_decr_mzz_power;
_iq iq_decr_mzz_power_filter;
int flag_decr_mzz_power;
_iq iqKoefOgranIzad;
int disable_KoefOgranIzad;
_iq add_power_limit;
_iq sdvig_power_limit;
int cmd_new_calc_p_limit;
} ALG_SIMPLE_SCALAR;
@ -79,8 +52,7 @@ typedef struct { PIDREG3 pidIm1;
0,0,0,0,0,\
0,0,0,0,0,\
0,0,0,0,0,\
0,0,0,0,0,0,0, \
0,0, 0,0,0, 0,0, 0, 0, 0,0,0,0,0,0, 0,0 \
0,0,0,0,0 \
}
@ -88,12 +60,10 @@ extern ALG_SIMPLE_SCALAR simple_scalar1;
void simple_scalar(int n_alg, int n_wind_pump, int direction,
_iq Frot_pid, _iq Frot,_iq fzad,_iq mzz_zad, _iq bpsi_const,
void simple_scalar(int n_alg, int n_wind_pump, _iq Frot_pid, _iq Frot,_iq fzad,_iq mzz_zad, _iq bpsi_const,
_iq iqKoefOgran,
_iq iqIm, _iq iqUin, _iq Iin, _iq powerzad, _iq power_pid,
_iq power_limit, int mode_oborots_power,
_iq Izad_from_master, int master, int count_bs_work,
_iq Izad_from_master, int master,
_iq *Fz, _iq *Uz1, _iq *Uz2, _iq *Izad);
void init_simple_scalar(void);

View File

@ -1,458 +0,0 @@
/*
* another_bs.c
*
* Created on: 13 íîÿá. 2024 ã.
* Author: Evgeniy_Sokolov
*/
#include <edrk_main.h>
#include <params.h>
#include <params_alg.h>
#include <params_norma.h>
#include <params_pwm24.h>
#include <params_temper_p.h>
#include <project.h>
#include "IQmathLib.h"
#include "mathlib.h"
#include <optical_bus.h>
#include "adc_tools.h"
#include "CAN_project.h"
#include "CAN_Setup.h"
#include "global_time.h"
#include "v_rotor.h"
#include "ukss_tools.h"
#include "another_bs.h"
#include "control_station_project.h"
#include "control_station.h"
#include "can_bs2bs.h"
#include "sync_tools.h"
#include "vector_control.h"
#include "master_slave.h"
#include "digital_filters.h"
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
void read_data_from_bs(void)
{
int g;
if (control_station.alive_control_station[CONTROL_STATION_ANOTHER_BS])
{
g = Unites[ANOTHER_BSU1_CAN_DEVICE][5];
edrk.int_koef_ogran_power_another_bs = g;
edrk.iq_koef_ogran_power_another_bs = ((float)edrk.int_koef_ogran_power_another_bs);
g = Unites[ANOTHER_BSU1_CAN_DEVICE][6];
edrk.power_kw_another_bs = g;
edrk.iq_power_kw_another_bs = _IQ(((float)edrk.power_kw_another_bs * 1000.0)/NORMA_ACP/NORMA_ACP);
g = Unites[ANOTHER_BSU1_CAN_DEVICE][7];
edrk.active_post_upravl_another_bs = g;
g = Unites[ANOTHER_BSU1_CAN_DEVICE][9];
edrk.Ready1_another_bs = g;
g = Unites[ANOTHER_BSU1_CAN_DEVICE][10];
edrk.Ready2_another_bs = g;
g = Unites[ANOTHER_BSU1_CAN_DEVICE][11];
edrk.MasterSlave_another_bs = g;
g = Unites[ANOTHER_BSU1_CAN_DEVICE][3] & 0x1;
edrk.ump_cmd_another_bs = g;
g = (Unites[ANOTHER_BSU1_CAN_DEVICE][3] & 0x2) >> 1;
edrk.qtv_cmd_another_bs = g;
g = Unites[ANOTHER_BSU1_CAN_DEVICE][13];
edrk.errors_another_bs_from_can = g;
}
else
{
edrk.errors_another_bs_from_can = 0;
}
}
//////////////////////////////////////////////////////////
unsigned int read_cmd_sbor_from_bs(void)
{
unsigned int g;
g = Unites[ANOTHER_BSU1_CAN_DEVICE][4];
return g;
}
void UpdateTableSecondBS(void)
{
int cmd;
int i,k;
static unsigned int counter_sum_errors = 0;
Unites2SecondBS[0]++;
Unites2SecondBS[1] = global_time.miliseconds;
Unites2SecondBS[2] = edrk.flag_second_PCH;
Unites2SecondBS[3] = (edrk.to_shema.bits.QTV_ON_OFF << 1) | (edrk.to_shema.bits.UMP_ON_OFF);
Unites2SecondBS[4] = edrk.SumSbor;
Unites2SecondBS[5] = edrk.int_koef_ogran_power;
Unites2SecondBS[6] = (int)edrk.power_kw;
Unites2SecondBS[7] = (int)edrk.active_post_upravl;
Unites2SecondBS[8] = (int)edrk.power_kw;
Unites2SecondBS[9] = edrk.Status_Ready.bits.ready1;
Unites2SecondBS[10] = edrk.Status_Ready.bits.ready_final;
Unites2SecondBS[11] = edrk.MasterSlave;
Unites2SecondBS[12] = _IQtoF(vect_control.iqId_min) * NORMA_ACP;
Unites2SecondBS[13] = pause_detect_error(&counter_sum_errors, 10, edrk.summ_errors);
for (i=0;i<CONTROL_STATION_CMD_LAST;i++)
{
if ((POS_STATION_CMD_ANOTHER_BSU1+i)<SIZE_ARR_CAN_UNITES_BS2BS)
Unites2SecondBS[POS_STATION_CMD_ANOTHER_BSU1+i] = control_station.active_array_cmd[i];
}
// Unites2SecondBS[3] = _IQtoIQ15(edrk.zadanie.iq_fzad);
// Unites2SecondBS[4] = _IQtoIQ15(edrk.zadanie.iq_kzad);
// Unites2SecondBS[5] = _IQtoIQ15(edrk.zadanie.iq_Izad);
// Unites2SecondBS[6] = (edrk.zadanie.oborots_zad);
// Unites2SecondBS[7] = _IQtoIQ15(edrk.zadanie.iq_power_zad);
if (edrk.flag_second_PCH==0)
{
// Unites2SecondBS[5] = Unites[ANOTHER_BSU1_CAN_DEVICE][8];
// Unites2SecondBS[8] = 0xaa;
//
// max_count_send_to_can2second_bs = 10;
}
else
{
// Unites2SecondBS[5] = Unites[ANOTHER_BSU1_CAN_DEVICE][8];
// Unites2SecondBS[8] = 0x55;
//
// max_count_send_to_can2second_bs = 10;
}
}
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
void detect_error_from_another_bs(void)
{
if (edrk.errors_another_bs_from_can)
edrk.errors.e7.bits.ANOTHER_BS_ALARM |= 1;
}
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
#define MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS 30 //20
#define MAX_WAIT_READY1_DETECT_ALIVE_ANOTHER_BS 100
#define MAX_WAIT_READY2_DETECT_ALIVE_ANOTHER_BS 70 //30 // äîëæåí áûòü áîëüøå ÷åì MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
void detect_alive_another_bs(void)
{
// static unsigned int count_wait_ready = 0;
static unsigned int prev_another_bs_maybe_on = 0;
static unsigned int prev_another_bs_maybe_on_after_ready1 = 0,
prev_alive_can_to_another_bs = 0;
int real_box;
real_box = get_real_in_mbox(UNITS_TYPE_BOX,ANOTHER_BSU1_CAN_DEVICE);
if (real_box != -1)
{
edrk.ms.err_signals.alive_can_to_another_bs = CAN_timeout[real_box];
if (edrk.ms.err_signals.alive_can_to_another_bs == 1
&& prev_alive_can_to_another_bs == 0)
{
// reinit CAN
InitCanSoft();
}
prev_alive_can_to_another_bs = edrk.ms.err_signals.alive_can_to_another_bs;
}
#if (USE_TK_3)
edrk.ms.err_signals.alive_opt_bus_read = !project.cds_tk[3].optical_data_in.ready;
edrk.ms.err_signals.alive_opt_bus_write = !project.cds_tk[3].optical_data_out.ready;
#else
edrk.ms.err_signals.alive_opt_bus_read = 1;
edrk.ms.err_signals.alive_opt_bus_write = 1;
#endif
edrk.ms.err_signals.alive_sync_line = !sync_data.global_flag_sync_1_2;
edrk.ms.err_signals.alive_sync_line_local = !sync_data.local_flag_sync_1_2;
// edrk.ms.err_signals.input_alarm_another_bs = edrk.from_ing1.bits.
// òóò ïîêà îòêëþ÷åí êàíàë.
// edrk.ms.err_signals.fast_optical_alarm = 0;//!project.cds_tk[3].read.sbus.status_tk_40pin.bit.tk5_ack;
edrk.ms.err_signals.another_rascepitel = edrk.from_second_pch.bits.RASCEPITEL;
if (edrk.ms.err_signals.alive_can_to_another_bs
&& (edrk.ms.err_signals.alive_opt_bus_read
|| edrk.ms.err_signals.alive_opt_bus_write)
&& edrk.ms.err_signals.alive_sync_line
// && edrk.ms.err_signals.fast_optical_alarm
)
{
edrk.ms.another_bs_maybe_off = 1;
edrk.ms.another_bs_maybe_on = 0;
}
else
{
edrk.ms.another_bs_maybe_off = 0;
edrk.ms.another_bs_maybe_on = 1;
}
// åñëè ñâÿçü âîññòàíîâèëàñü, òî îïÿòü æäåì íåêîòîðîå âðåìÿ ïîêà çàïóñòÿòñÿ âñå îñòàëüíûå êàíàëû ñâÿçè.
if (prev_another_bs_maybe_on!=edrk.ms.another_bs_maybe_on && edrk.ms.another_bs_maybe_on)
{
// edrk.ms.count_time_wait_ready1 = 0;
edrk.ms.count_time_wait_ready2 = 0;
prev_another_bs_maybe_on_after_ready1 = 0;
clear_errors_master_slave();
}
//
// âûñòàâëÿåì ôëàã òîëüêî ÷åðåç âðåìÿ MAX_WAIT_READY_DETECT_ALIVE_ANOTHER_BS
//
edrk.ms.ready1 = filter_err_count(&edrk.ms.count_time_wait_ready1,
MAX_WAIT_READY1_DETECT_ALIVE_ANOTHER_BS,
1,
0);
if (edrk.Status_Ready.bits.ready5)
{
edrk.ms.ready2 = filter_err_count(&edrk.ms.count_time_wait_ready2,
MAX_WAIT_READY2_DETECT_ALIVE_ANOTHER_BS,
1,
0);
}
else
{
edrk.ms.count_time_wait_ready2 = 0;
edrk.ms.ready2 = 0;
}
// edrk.ms.ready2 = edrk.Status_Ready.bits.ready5 && filter_err_count(&edrk.ms.count_time_wait_ready2,
// MAX_WAIT_READY2_DETECT_ALIVE_ANOTHER_BS,
// 1,
// 0);
prev_another_bs_maybe_on = edrk.ms.another_bs_maybe_on;
// æäåì ïîêà ïðîéäåò íåêîòîðîå âðåìÿ
if (edrk.ms.ready1==0)
{
edrk.ms.status = 1;
return;
}
// åñëè ñâÿçü áûëà ïîñëå edrk.ms.ready1==1, íî âñÿ ïðîïàëà, äàåì îøèáêó
if (prev_another_bs_maybe_on_after_ready1!=edrk.ms.another_bs_maybe_on && edrk.ms.another_bs_maybe_on==0)
{
edrk.errors.e4.bits.ANOTHER_BS_POWER_OFF |= 1;
}
prev_another_bs_maybe_on_after_ready1 = edrk.ms.another_bs_maybe_on;
edrk.ms.err_lock_signals.alive_can_to_another_bs |= filter_err_count(&edrk.ms.errors_count.alive_can_to_another_bs,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.alive_can_to_another_bs,
0);
edrk.ms.err_lock_signals.alive_opt_bus_read |= filter_err_count(&edrk.ms.errors_count.alive_opt_bus_read,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.alive_opt_bus_read,
0);
edrk.ms.err_lock_signals.alive_opt_bus_write |= filter_err_count(&edrk.ms.errors_count.alive_opt_bus_write,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.alive_opt_bus_write,
0);
edrk.ms.err_lock_signals.alive_sync_line = filter_err_count(&edrk.ms.errors_count.alive_sync_line,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.alive_sync_line,
0);
edrk.ms.err_lock_signals.alive_sync_line_local = filter_err_count(&edrk.ms.errors_count.alive_sync_line_local,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.alive_sync_line_local,
0);
edrk.ms.err_lock_signals.fast_optical_alarm |= filter_err_count(&edrk.ms.errors_count.fast_optical_alarm,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.fast_optical_alarm,
0);
edrk.ms.err_lock_signals.input_alarm_another_bs |= filter_err_count(&edrk.ms.errors_count.input_alarm_another_bs,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.input_alarm_another_bs,
0);
edrk.ms.err_lock_signals.another_rascepitel |= filter_err_count(&edrk.ms.errors_count.another_rascepitel,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.another_rascepitel,
0);
edrk.ms.err_lock_signals.input_master_slave |= filter_err_count(&edrk.ms.errors_count.input_master_slave,
MAX_ERRORS_DETECT_ALIVE_ANOTHER_BS,
edrk.ms.err_signals.input_master_slave,
0);
if (edrk.ms.err_signals.alive_can_to_another_bs
&& (edrk.ms.err_signals.alive_opt_bus_read
|| edrk.ms.err_signals.alive_opt_bus_write)
&& edrk.ms.err_signals.alive_sync_line
// && edrk.ms.err_signals.fast_optical_alarm
// && edrk.ms.err_signals.input_alarm_another_bs &&
// && edrk.ms.err_signals.another_rascepitel == 0
// && edrk.ms.err_signals.input_master_slave
)
{
if (edrk.ms.err_signals.another_rascepitel)
edrk.errors.e7.bits.ANOTHER_RASCEPITEL_ON |= 1;
// edrk.ms.another_bs_maybe_off = 1;
// edrk.ms.another_bs_maybe_on = 0;
edrk.warnings.e4.bits.ANOTHER_BS_POWER_OFF = 1;
// edrk.warnings.e4.bits.FAST_OPTICAL_ALARM = 1;
edrk.warnings.e7.bits.MASTER_SLAVE_SYNC = 1;
edrk.warnings.e7.bits.READ_OPTBUS = edrk.ms.err_signals.alive_opt_bus_read;
edrk.warnings.e7.bits.WRITE_OPTBUS = edrk.ms.err_signals.alive_opt_bus_write;
edrk.warnings.e7.bits.CAN2CAN_BS = 1;
edrk.ms.status = 2;
}
else
{
edrk.warnings.e4.bits.ANOTHER_BS_POWER_OFF = 0;
//
if (edrk.ms.err_lock_signals.alive_can_to_another_bs)
edrk.errors.e7.bits.CAN2CAN_BS |= 1;
else
edrk.warnings.e7.bits.CAN2CAN_BS = 0;
//
if (edrk.ms.err_lock_signals.alive_opt_bus_read)
edrk.errors.e7.bits.READ_OPTBUS |= 1;
else
edrk.warnings.e7.bits.READ_OPTBUS = 0;
//
if (edrk.ms.err_lock_signals.alive_opt_bus_write)
edrk.errors.e7.bits.WRITE_OPTBUS |= 1;
else
edrk.warnings.e7.bits.WRITE_OPTBUS = 0;
//
if (edrk.ms.err_lock_signals.alive_sync_line)
edrk.warnings.e7.bits.MASTER_SLAVE_SYNC = 1;
else
edrk.warnings.e7.bits.MASTER_SLAVE_SYNC = 0;
//
// if (edrk.ms.err_lock_signals.fast_optical_alarm)
// edrk.errors.e4.bits.FAST_OPTICAL_ALARM |= 1;
// else
// edrk.warnings.e4.bits.FAST_OPTICAL_ALARM = 0;
// edrk.ms.another_bs_maybe_on = 1;
// edrk.ms.another_bs_maybe_off = 0;
if (edrk.ms.err_signals.alive_can_to_another_bs
|| edrk.ms.err_signals.alive_opt_bus_read
|| edrk.ms.err_signals.alive_opt_bus_write
|| edrk.ms.err_signals.alive_sync_line
|| edrk.ms.err_signals.fast_optical_alarm
)
edrk.ms.status = 3;
else
edrk.ms.status = 4;
}
}
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
// îáíîâëßåì äðóãîé ÁÑÓ ïî CAN
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
void update_bsu_can(unsigned int pause)
{
int real_mbox;
int t1;
// if (edrk.flag_second_PCH==0)
// t1 = 125;
// if (edrk.flag_second_PCH==1)
// t1 = 150;
SendAll2SecondBS(pause);
}
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
// ñïåö íàñòðîéêè äëÿ ìåæáëî÷íîãî îáìåíà ÁÑ1 ÁÑ2 ïî CAN
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
void init_can_box_between_bs1_bs2(void)
{
// âêëþ÷àåì ðåâåðñ àäðåñîâ òîëüêî äëÿ îäíîãî ÁÑ
// èìèòèðóåì ÿùèê Unites êàêáû
//
if (edrk.flag_second_PCH==0)
{
unites_can_setup.revers_box[ANOTHER_BSU1_CAN_DEVICE] = 1;
}
unites_can_setup.adr_detect_refresh[ZADATCHIK_CAN] = 16;
}

View File

@ -1,21 +0,0 @@
/*
* another_bs.h
*
* Created on: 13 íîÿá. 2024 ã.
* Author: Evgeniy_Sokolov
*/
#ifndef SRC_MAIN_ANOTHER_BS_H_
#define SRC_MAIN_ANOTHER_BS_H_
void update_bsu_can(unsigned int pause);
void init_can_box_between_bs1_bs2(void);
void detect_alive_another_bs(void);
void detect_error_from_another_bs(void);
void UpdateTableSecondBS(void);
unsigned int read_cmd_sbor_from_bs(void);
void read_data_from_bs(void);
#endif /* SRC_MAIN_ANOTHER_BS_H_ */

View File

@ -64,34 +64,25 @@ void break_resistor_managment_calc()
{
static unsigned int break_counter = 0;//MAX_BREAK_IMPULSE + 1;
if(edrk.Discharge && edrk.from_shema_filter.bits.QTV_ON_OFF==0
&& edrk.from_shema_filter.bits.UMP_ON_OFF==0)// && edrk.to_shema.bits.QTV_ON == 0)
if(edrk.Discharge && edrk.from_shema.bits.QTV_ON_OFF==0 && edrk.from_shema.bits.UMP_ON_OFF==0)
{
if (break_counter < MAX_BREAK_IMPULSE)
{
break_counter++;
if ((filter.iqU_1_fast > BREAK_INSENSITIVE_LEVEL_MIN)
|| edrk.ManualDischarge || edrk.NoDetectUZeroDischarge)
if ((filter.iqU_1_fast > BREAK_INSENSITIVE_LEVEL_MIN) || edrk.ManualDischarge || edrk.NoDetectUZeroDischarge)
{
if (edrk.Obmotka1 == 0)
break_result_1 = 300;
else
break_result_1 = 0;
break_result_1 = 300;
}
else
{
break_result_1 = 0;
}
if ((filter.iqU_2_fast > BREAK_INSENSITIVE_LEVEL_MIN)
|| edrk.ManualDischarge || edrk.NoDetectUZeroDischarge )
if ((filter.iqU_2_fast > BREAK_INSENSITIVE_LEVEL_MIN) || edrk.ManualDischarge || edrk.NoDetectUZeroDischarge )
{
if (edrk.Obmotka2 == 0)
break_result_2 = 300;
else
break_result_2 = 0;
break_result_2 = 300;
}
else
{
@ -158,8 +149,7 @@ void break_resistor_recup_calc(_iq Uzpt_nominal)
{
_iq Uzpt_start_recup = Uzpt_nominal + IQ_DELTA_U_START_RECUP;
_iq Uzpt_max_open_break_keys = Uzpt_nominal + IQ_DELTA_U_MAX_OPEN_BREAK_KEYS;
if (/*edrk.Go &&*/ (edrk.SborFinishOk || edrk.Status_Ready.bits.ImitationReady2) )
if (edrk.Go && edrk.SborFinishOk)
{
break_result_1 = calc_recup(filter.iqU_1_fast, Uzpt_start_recup, Uzpt_max_open_break_keys);
break_result_2 = calc_recup(filter.iqU_2_fast, Uzpt_start_recup, Uzpt_max_open_break_keys);

View File

@ -19,8 +19,6 @@ int calc_max_temper_acdrive_winding(void);
int calc_max_temper_edrk_u(void);
int calc_max_temper_edrk_water(void);
int calc_max_temper_edrk_air(void);
int calc_min_temper_edrk_air(void);
@ -96,19 +94,6 @@ int calc_max_temper_edrk_air(void)
return max_t;
}
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
int calc_min_temper_edrk_air(void)
{
int i, min_t=1000;
for (i=0;i<4;i++)
if (edrk.temper_edrk.real_int_temper_air[i]<min_t)
min_t = edrk.temper_edrk.real_int_temper_air[i];
return min_t;
}
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
@ -272,8 +257,6 @@ void calc_temper_edrk(void)
edrk.temper_edrk.real_int_temper_air[i] = edrk.temper_edrk.real_temper_air[i]*K_TEMPER_TO_SVU;
edrk.temper_edrk.max_real_int_temper_air = calc_max_temper_edrk_air();
edrk.temper_edrk.min_real_int_temper_air = calc_min_temper_edrk_air();
}

View File

@ -20,7 +20,6 @@
#include "DSP281x_SWPrioritizedIsrLevels.h" // DSP281x Examples Include File
#include "DSP281x_Device.h"
#include "xp_project.h"
#include "another_bs.h"
@ -28,11 +27,10 @@
#pragma DATA_SECTION(Unites2SecondBS, ".slow_vars")
int Unites2SecondBS[SIZE_ARR_CAN_UNITES_BS2BS]={0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0\
int Unites2SecondBS[SIZE_ARR_CAN_UNITES_BS2BS]={0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0\
};

View File

@ -8,7 +8,7 @@
#ifndef SRC_MAIN_CAN_BS2BS_H_
#define SRC_MAIN_CAN_BS2BS_H_
#define SIZE_ARR_CAN_UNITES_BS2BS 50 //100
#define SIZE_ARR_CAN_UNITES_BS2BS 100
extern int Unites2SecondBS[SIZE_ARR_CAN_UNITES_BS2BS];

View File

@ -1,63 +0,0 @@
/*
* can_protocol_ukss.h
*
* Created on: 23 àâã. 2024 ã.
* Author: yura
*/
#ifndef SRC_MAIN_CAN_PROTOCOL_UKSS_H_
#define SRC_MAIN_CAN_PROTOCOL_UKSS_H_
#define CAN_PROTOCOL_UKSS 2 // 2
#ifndef CAN_PROTOCOL_UKSS
#define CAN_PROTOCOL_UKSS 1
#endif
#if (CAN_PROTOCOL_UKSS == 2)
#define ADR_CYCLES_TIMER_MAIN 96 //Ïåðèîä îñíîâí. ïîñûëîê CAN, * 10 mñåê
#define ADR_CYCLES_TIMER_ADD 97 //Ïåðèîä äîïîëí. ïîñûëîê CAN, * 10 mñåê
#define ADR_CYCLES_PAUSE_MAIN 98 //Ïàóçà îñíîâí. ïîñûëîê CAN, * 10 mñåê
#define ADR_CYCLES_PAUSE_ADD 99 //Ïàóçà äîïîëí. ïîñûëîê CAN, * 10 mñåê
#define ADR_CYCLES_REPEATE_MAIN 100 //Ïîâòîð îñíîâí. ïîñûëîê CAN, * 10 mñåê
#define ADR_CYCLES_REPEATE_ADD 101 //Ïîâòîð äîïîëí. ïîñûëîê CAN, * 10 mñåê
#define ADR_CYCLES_REPEATE_DIGIO 102 //Ïîâòîðÿòü ïîñûëêó äèñêð. âõîäîâ, ðàç
#define ADR_LIGHT_LED_1 104 //ßðêîñòü ëàìïû 1
#define ADR_LIGHT_LED_2 105 //ßðêîñòü ëàìïû 2
#define ADR_LIGHT_LED_3 106 //ßðêîñòü ëàìïû 3
#define ADR_LIGHT_LED_4 107 //ßðêîñòü ëàìïû 4
#define ADR_LIGHT_LED_5 108 //ßðêîñòü ëàìïû 5
#define ADR_LIGHT_LED_6 109 //ßðêîñòü ëàìïû 6
#define ADR_LIGHT_LED_7 110 //ßðêîñòü ëàìïû 7
#define ADR_COUNT_CYCLES_MAIN 120 //Êîëè÷åñòâî öèêëîâ îñíîâí. ïîñûëîê CAN
#define ADR_COUNT_CYCLES_ADD 121 //Êîëè÷åñòâî öèêëîâ äîïîëí. ïîñûëîê CAN
#define ADR_COUNT_FULL_CYCLES_MAIN 122 //Êîë-âî ïîëíûõ öèêëîâ îñíîâí. ïîñûëîê CAN
#define ADR_COUNT_FULL_CYCLES_ADD 123 //Êîë-âî ïîëíûõ öèêëîâ äîïîëí. ïîñûëîê CAN
#define ADR_PROTOCOL_VERSION 125 //Âåðñèÿ ïðîòîêîëà
#define ADR_UKSS_NUMBER 126 //Àäðåñ óñòðîéñòâà
#endif
#endif /* SRC_MAIN_CAN_PROTOCOL_UKSS_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -76,14 +76,13 @@ enum
CONTROL_STATION_CMD_DISABLE_ON_QTV,
CONTROL_STATION_CMD_MANUAL_DISCHARGE,
CONTROL_STATION_CMD_DISABLE_ON_UMP,
CONTROL_STATION_CMD_WDOG_OFF,
CONTROL_STATION_CMD_CROSS_STEND_AUTOMATS,
CONTROL_STATION_CMD_SET_LIMIT_POWER,// çàïàñ ìîùíîñòü îò ïîñòà
CONTROL_STATION_CMD_BLOCK_BS, // áëîêèðîâêà ñ âåðõíåãî óðîâíÿ
CONTROL_STATION_CMD_DISABLE_INTERRUPT_SYNC,
CONTROL_STATION_CMD_DISABLE_INTERRUPT_TIMER2,
CONTROL_STATION_CMD_DISABLE_RASCEPITEL, // íå óïðàâëÿòü ðàñöåïèòåëåì, åñëè îí ñâåäåí è íå ðàáîòàåò ìîòîð ðàñöåïèòåëÿ
CONTROL_STATION_CMD_PWM_TEST_LINES, // øèì ëèíèè íà 96ïèí øèíå êàê òåñòîâûå, òîëüêî äëÿ òåñòà!!!
CONTROL_STATION_CMD_STOP_LOGS, // ñòîï ëîãîâ
CONTROL_STATION_CMD_LAST // ïîñëåäíèé êîä â ñïèñêå, âñåãäà äîëæåí áûòü, íå óäàëÿòü åãî, èñïîëüçóåì äëÿ ðàçìåðíîñòè ìàññèâà.
};

View File

@ -162,6 +162,6 @@ int detect_system_asymmetry_rms(DETECT_PROTECT_3_PHASE *v) {
_iq d3 = _IQabs(v->iqVal_U - v->iqVal_W);
return d1 > v->setup.levels.iqAsymmetry_delta ||
d2 > v->setup.levels.iqAsymmetry_delta ||
d3 > v->setup.levels.iqAsymmetry_delta ? 1 : 0;
d2 > v->setup.levels.iqAsymmetry_delta ? 1 : 0;
}

View File

@ -118,7 +118,7 @@ typedef struct {
//Setup
SETUP_3_PHASE_PROTECT setup;
int (*calc_detect_error_3_phase)();
int (*calc)();
} DETECT_PROTECT_3_PHASE;

View File

@ -15,14 +15,9 @@
#include <protect_levels.h>
#include <sync_tools.h>
#include <vector.h>
#include "v_rotor.h"
#include "control_station.h"
#include "DSP281x_Device.h"
#include "master_slave.h"
#include "another_bs.h"
#include "digital_filters.h"
void detect_error_from_knopka_avaria(void);
@ -64,17 +59,10 @@ void detect_error_acdrive_winding(void);
int get_common_state_warning(void);
int get_common_state_overheat(void);
void detect_error_sensor_rotor(void);
#pragma DATA_SECTION(protect_levels,".slow_vars");
PROTECT_LEVELS protect_levels = PROTECT_LEVELS_DEFAULTS;
///////////////////////////////////////////////
int get_status_temper_acdrive_winding(int nc)
{
@ -212,54 +200,6 @@ int get_status_p_water_min(int pump_on_off)
}
///////////////////////////////////////////////
///////////////////////////////////////////////
void detect_error_sensor_rotor(void)
{
static unsigned int count_err1 = 0, count_err2 = 0, count_err3 = 0, count_err4 = 0;
if (edrk.Go)
{
// ñòîèì íà ìåñòå?
if (edrk.iq_f_rotor_hz==0)
{
// äîëãî ñòîèì!
if (pause_detect_error(&count_err3,TIME_WAIT_SENSOR_ROTOR_BREAK_ALL,1))
{
edrk.warnings.e9.bits.SENSOR_ROTOR_1_BREAK = 1;
edrk.warnings.e9.bits.SENSOR_ROTOR_2_BREAK = 1;
//edrk.errors.e9.bits.SENSOR_ROTOR_1_2_BREAK |= 1; // ïîêà óáåðåì!
}
else
{
// edrk.warnings.e9.bits.SENSOR_ROTOR_1_BREAK = 0;
// edrk.warnings.e9.bits.SENSOR_ROTOR_2_BREAK = 0;
edrk.warnings.e9.bits.SENSOR_ROTOR_1_BREAK = pause_detect_error(&count_err1,TIME_WAIT_SENSOR_ROTOR_BREAK_ONE_SENSOR,
inc_sensor.break_sensor1);
edrk.warnings.e9.bits.SENSOR_ROTOR_2_BREAK = pause_detect_error(&count_err2,TIME_WAIT_SENSOR_ROTOR_BREAK_ONE_SENSOR,
inc_sensor.break_sensor2);
}
}
else
{
count_err3 = 0;
// edrk.warnings.e9.bits.SENSOR_ROTOR_1_BREAK = 0;
// edrk.warnings.e9.bits.SENSOR_ROTOR_2_BREAK = 0;
edrk.warnings.e9.bits.SENSOR_ROTOR_1_BREAK |= pause_detect_error(&count_err1,TIME_WAIT_ERROR,inc_sensor.break_sensor1);
edrk.warnings.e9.bits.SENSOR_ROTOR_2_BREAK |= pause_detect_error(&count_err2,TIME_WAIT_ERROR,inc_sensor.break_sensor2);
}
}
else
{
count_err1 = count_err2 = 0;
count_err3 = 0;
edrk.warnings.e9.bits.SENSOR_ROTOR_1_BREAK = 0;
edrk.warnings.e9.bits.SENSOR_ROTOR_2_BREAK = 0;
}
}
///////////////////////////////////////////////
#define TIME_WAIT_T_WATER 30
void detect_error_t_water(void)
@ -513,7 +453,7 @@ void detect_error_acdrive_bear(void)
static unsigned int count_run = 0, count_run_static = 0;
int status,i;
// status = 0;
status = 0;
status = get_status_temper_acdrive_bear_with_limits(0, protect_levels.alarm_temper_acdrive_bear_DNE,
protect_levels.abnormal_temper_acdrive_bear_DNE);
@ -616,7 +556,7 @@ void detect_error_ground(void)
}
if ((edrk.from_ing1.bits.ZAZEML_OFF == 1) && (edrk.from_ing1.bits.ZAZEML_ON == 0))
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
}
@ -632,7 +572,7 @@ void detect_error_nagrev(void)
edrk.errors.e5.bits.ERROR_HEAT |= 1;
}
else
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
}
@ -675,11 +615,10 @@ void detect_error_block_izol(void)
if (edrk.from_ing1.bits.BLOCK_IZOL_AVARIA == 0 && edrk.from_ing1.bits.BLOCK_IZOL_NORMA == 1 )
{
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR_IZOL,0);
}
if (edrk.cmd_imit_low_isolation)
edrk.errors.e5.bits.ERROR_ISOLATE |= 1;
}
@ -700,7 +639,7 @@ void detect_error_pre_charge(void)
if (edrk.from_ing1.bits.ZARYAD_ON == 0 && edrk.to_ing.bits.ZARYAD_ON == 0)
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR_CHARGE_ANSWER,0);
// edrk.errors.e6.bits.ERROR_PRE_CHARGE_ANSWER |= 1;
@ -715,7 +654,7 @@ void detect_error_qtv(void)
// íåò êîìàíäû íà âûêë, íî ñóõîé êîíòàêò ïðèøåë
if (edrk.from_shema_filter.bits.QTV_ON_OFF == 1 && edrk.cmd_to_qtv == 0)
if (edrk.from_shema.bits.QTV_ON_OFF == 1 && edrk.cmd_to_qtv == 0)
{
if (pause_detect_error(&count_err_off,TIME_WAIT_ERROR_QTV,1))
edrk.errors.e6.bits.QTV_ERROR_NOT_ANSWER |= 1;
@ -726,7 +665,7 @@ void detect_error_qtv(void)
}
// áûëà êîìàíäà íà âêë, íî ñóõîé êîíòàêò íå ïðèøåë
if (edrk.from_shema_filter.bits.QTV_ON_OFF == 0 && edrk.cmd_to_qtv == 1)
if (edrk.from_shema.bits.QTV_ON_OFF == 0 && edrk.cmd_to_qtv == 1)
{
if (pause_detect_error(&count_err_on,TIME_WAIT_ERROR_QTV,1))
edrk.errors.e6.bits.QTV_ERROR_NOT_ANSWER |= 1;
@ -757,77 +696,20 @@ void detect_error_predohr_vipr(void)
edrk.errors.e5.bits.ERROR_PRED_VIPR |= 1;
if (edrk.from_ing1.bits.VIPR_PREDOHR_NORMA == 1)
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
}
///////////////////////////////////////////////
#define TIME_WAIT_ERROR_UMP_READY 1200 //120 ñåê //750 // æäåì 75 ñåê ò.ê. âîçìîæíî óìð çàíÿò íà ñáîð âòîðîãî áñ
#define TIME_WAIT_WARNING_UMP_READY 10
void detect_error_ump(void)
{
static unsigned int count_err = 0;
static unsigned int count_err2 = 0;
static unsigned int prev_SumSbor = 0;
static unsigned int StageUMP = 0;
static unsigned int count_UMP_NOT_READY = 0;
int local_warning_ump = 0;
if (edrk.from_shema.bits.READY_UMP == 0)
if (pause_detect_error(&count_err,TIME_WAIT_ERROR,1))
edrk.errors.e7.bits.UMP_NOT_READY |= 1;
if (edrk.SumSbor==1)
{
switch (StageUMP) {
case 0: if (edrk.from_shema_filter.bits.UMP_ON_OFF == 1)
StageUMP++;
break;
case 1: if (edrk.from_shema_filter.bits.UMP_ON_OFF == 0)
StageUMP++;
break;
case 2:
break;
case 3:
break;
default: break;
}
if ((edrk.from_shema_filter.bits.READY_UMP == 0) && (StageUMP==0) && control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_UMP]==0)
{
if (pause_detect_error(&count_err,TIME_WAIT_ERROR_UMP_READY,1))
edrk.errors.e7.bits.UMP_NOT_READY |= 1;
}
if (edrk.from_shema_filter.bits.READY_UMP == 1)
count_err = 0;
}
else
{
count_err= 0;
// ÓÌÏ âêëþ÷åí, à íå äîëæåí!
if (edrk.from_shema_filter.bits.UMP_ON_OFF==1)
if (pause_detect_error(&count_err2,TIME_WAIT_ERROR,1))
edrk.errors.e11.bits.ERROR_UMP_NOT_OFF |= 1;
if (edrk.from_shema_filter.bits.UMP_ON_OFF == 0)
count_err2 = 0;
// íåò ãîòîâíîñòè
if (edrk.ump_cmd_another_bs==0) // äðóãîé ÁÑ íå çàíÿë ÓÌÏ
local_warning_ump = !edrk.from_shema_filter.bits.READY_UMP;
// edrk.warnings.e7.bits.UMP_NOT_READY = !edrk.from_shema_filter.bits.READY_UMP;
StageUMP = 0;
}
edrk.warnings.e7.bits.UMP_NOT_READY = filter_digital_input( edrk.warnings.e7.bits.UMP_NOT_READY,
&count_UMP_NOT_READY,
TIME_WAIT_WARNING_UMP_READY,
local_warning_ump);
prev_SumSbor = edrk.SumSbor;
if (edrk.from_ing1.bits.VIPR_PREDOHR_NORMA == 1)
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
}
@ -839,14 +721,8 @@ void detect_error_block_qtv_from_svu(void)
if (edrk.from_shema.bits.SVU_BLOCK_QTV == 1 || control_station.active_array_cmd[CONTROL_STATION_CMD_BLOCK_BS])
{
if (pause_detect_error(&count_err,TIME_WAIT_BLOCK_QTV_FROM_SVU,1))
edrk.errors.e7.bits.SVU_BLOCK_ON_QTV |= 1;
}
else
{
count_err = 0;
}
}
@ -864,7 +740,7 @@ void detect_error_fan(void)
edrk.errors.e5.bits.FAN |= 1;
if (edrk.from_ing1.bits.VENTIL_ON == 0 && (edrk.to_ing.bits.NASOS_1_ON == 0 && edrk.to_ing.bits.NASOS_2_ON == 0))
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR_FAN,0);
}
@ -884,7 +760,7 @@ void detect_error_pre_ready_pump(void)
if (edrk.from_ing1.bits.NASOS_NORMA == 1)
{
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
edrk.warnings.e5.bits.PRE_READY_PUMP = 0;
}
}
@ -913,13 +789,13 @@ void detect_error_pump_1(void)
if (edrk.from_ing1.bits.NASOS_ON == 0 && edrk.to_ing.bits.NASOS_1_ON==0 && edrk.SelectPump1_2==1)
{
// òóò âñå îê
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR_PUMP,0);
}
if (edrk.from_ing1.bits.NASOS_ON == 1 && edrk.to_ing.bits.NASOS_1_ON==1 && edrk.SelectPump1_2==1)
{
// òóò âñå îê
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR_PUMP,0);
edrk.warnings.e5.bits.PUMP_1 = 0;
}
@ -948,13 +824,13 @@ void detect_error_pump_2(void)
if (edrk.from_ing1.bits.NASOS_ON == 0 && edrk.to_ing.bits.NASOS_2_ON==0 && edrk.SelectPump1_2==2)
{
// òóò âñå îê
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR_PUMP,0);
}
if (edrk.from_ing1.bits.NASOS_ON == 1 && edrk.to_ing.bits.NASOS_2_ON==1 && edrk.SelectPump1_2==2)
{
// òóò âñå îê
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR_PUMP,0);
edrk.warnings.e5.bits.PUMP_2 = 0;
}
}
@ -970,7 +846,7 @@ void detect_error_op_pit(void)
edrk.errors.e5.bits.OP_PIT |= 1;
if (edrk.from_ing1.bits.OP_PIT_NORMA == 1 )
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
}
///////////////////////////////////////////////
void detect_error_power_upc(void)
@ -982,7 +858,7 @@ void detect_error_power_upc(void)
edrk.errors.e5.bits.POWER_UPC |= 1;
if (edrk.from_ing1.bits.UPC_24V_NORMA == 1 )
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
}
///////////////////////////////////////////////
void detect_error_t_vipr(void)
@ -1007,7 +883,7 @@ void detect_error_ute4ka_water(void)
if (edrk.from_ing1.bits.OHLAD_UTE4KA_WATER == 0 )
count_err = 0;
pause_detect_error(&count_err,TIME_WAIT_ERROR,0);
}
///////////////////////////////////////////////
@ -1055,55 +931,14 @@ void detect_error_sync_bus(void)
// ó ýòîãî ÁÑ ñèíõðîñèãíàëà íåò, è ó âòîðîãî òîæå íåò, òîãäà àâàðèÿ
if (sync_data.timeout_sync_signal && optical_read_data.data.cmd.bit.sync_line_detect==0
&& edrk.ms.another_bs_maybe_on && optical_read_data.status==1)
{
if (pause_detect_error(&count_err,TIME_WAIT_SYNC_SIGNAL,1))
edrk.errors.e1.bits.NO_INPUT_SYNC_SIGNAL |= 1;
}
else
count_err = 0;
}
///////////////////////////////////////////////
#pragma CODE_SECTION(detect_error_u_zpt_fast,".fast_run");
int detect_error_u_zpt_fast(void)
{
int err;
err = 0;
if (analog.iqU_1>=edrk.iqMAX_U_ZPT_Global)
edrk.errors.e0.bits.U_1_MAX |= 1;
if (analog.iqU_2>=edrk.iqMAX_U_ZPT_Global)
edrk.errors.e0.bits.U_2_MAX |= 1;
if (analog.iqU_1>=edrk.iqMAX_U_ZPT)
edrk.errors.e0.bits.U_1_MAX |= 1;
if (analog.iqU_2>=edrk.iqMAX_U_ZPT)
edrk.errors.e0.bits.U_2_MAX |= 1;
if (edrk.from_shema_filter.bits.QTV_ON_OFF == 1
// && edrk.to_shema.bits.QTV_ON
)
{
if (analog.iqU_1<=edrk.iqMIN_U_ZPT)
edrk.errors.e0.bits.U_1_MIN |= 1;
if (analog.iqU_2<=edrk.iqMIN_U_ZPT)
edrk.errors.e0.bits.U_2_MIN |= 1;
}
err = (edrk.errors.e0.bits.U_1_MAX || edrk.errors.e0.bits.U_2_MAX || edrk.errors.e0.bits.U_1_MIN || edrk.errors.e0.bits.U_2_MIN);
return err;
}
///////////////////////////////////////////////
///////////////////////////////////////////////
int detect_error_u_zpt(void)
{
@ -1121,9 +956,7 @@ int detect_error_u_zpt(void)
}
if (edrk.iqMAX_U_ZPT>MINIMAL_LEVEL_ZAD_U && edrk.from_shema_filter.bits.QTV_ON_OFF == 1
// && edrk.to_shema.bits.QTV_ON
)
if (edrk.iqMAX_U_ZPT>MINIMAL_LEVEL_ZAD_U && edrk.from_shema.bits.QTV_ON_OFF == 1)
{
if (analog.iqU_1>=edrk.iqMAX_U_ZPT)
edrk.errors.e0.bits.U_1_MAX |= 1;
@ -1133,9 +966,7 @@ int detect_error_u_zpt(void)
edrk.errors.e0.bits.U_2_MAX |= 1;
}
if (edrk.from_shema_filter.bits.QTV_ON_OFF == 1
//&& edrk.to_shema.bits.QTV_ON
)
if (edrk.from_shema.bits.QTV_ON_OFF == 1)
{
if (analog.iqU_1<=edrk.iqMIN_U_ZPT)
edrk.errors.e0.bits.U_1_MIN |= 1;
@ -1172,7 +1003,6 @@ int detect_error_u_zpt_on_predzaryad(void)
}
///////////////////////////////////////////////
#pragma CODE_SECTION(detect_error_u_in,".fast_run");
int detect_error_u_in(void)
{
int err;
@ -1190,9 +1020,7 @@ int detect_error_u_in(void)
edrk.errors.e0.bits.U_IN_MAX |= 1;
}
if (edrk.from_shema_filter.bits.QTV_ON_OFF == 1 && edrk.SumSbor
// && edrk.to_shema.bits.QTV_ON
)
if (edrk.from_shema.bits.QTV_ON_OFF == 1 && edrk.SumSbor)
{
if (control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_QTV]==1)
{
@ -1233,7 +1061,7 @@ int detect_error_u_in(void)
}
///////////////////////////////////////////////
#define MAX_WAIT_AFTER_KVITIR 100//50
#define MAX_WAIT_AFTER_KVITIR 50
void detect_error_all(void)
{
unsigned int pause_after_kvitir=0;
@ -1272,13 +1100,9 @@ void detect_error_all(void)
detect_error_ground();
detect_error_ump();
// äëÿ àâàðèè â äðóãîé Ï× èñêëþ÷àåì àâàðèþ èç ýòîãîæå Ï×, èíà÷å ïîëó÷àåì êîëüöî. Àâàðèè çàìûêàþòñÿ!
if (pause_after_kvitir)
{
detect_error_from_knopka_avaria();
detect_error_from_another_bs();
}
#if (_FLOOR6==1)
@ -1305,7 +1129,6 @@ void detect_error_all(void)
edrk.warnings.e10.bits.WARNING_I_OUT_OVER_1_6_NOMINAL = out_I_over_1_6.overload_detected;
// edrk.errors.e7.bits.ANOTHER_BS_ALARM |= optical_read_data.data.cmd.bit.alarm;
detect_error_sensor_rotor();
}
@ -1366,7 +1189,7 @@ void read_plane_errors(void)
if (project.controller.read.errors.bit.pwm_wdog)
edrk.errors.e9.bits.ERR_PWM_WDOG |= 1;
#if USE_TK_0
#ifdef USE_TK_0
//af1
if (project.cds_tk[0].read.sbus.status_protect_current_ack.bit.tk0_ack ||
project.cds_tk[0].read.sbus.status_protect_current_ack.bit.tk0_current ||
@ -1393,7 +1216,7 @@ void read_plane_errors(void)
edrk.errors.e6.bits.UO3_KEYS |= 1;
#endif
#if USE_TK_1
#ifdef USE_TK_1
//af3
if (project.cds_tk[1].read.sbus.status_protect_current_ack.bit.tk0_ack ||
project.cds_tk[1].read.sbus.status_protect_current_ack.bit.tk0_current ||
@ -1420,7 +1243,7 @@ void read_plane_errors(void)
edrk.errors.e6.bits.UO5_KEYS |= 1;
#endif
#if USE_TK_2
#ifdef USE_TK_2
//af5
if (project.cds_tk[2].read.sbus.status_protect_current_ack.bit.tk0_ack ||
project.cds_tk[2].read.sbus.status_protect_current_ack.bit.tk0_current ||
@ -1449,7 +1272,7 @@ void read_plane_errors(void)
#endif
#if USE_TK_3
#ifdef USE_TK_3
if (project.cds_tk[3].read.sbus.status_protect_current_ack.bit.tk0_ack ||
project.cds_tk[3].read.sbus.status_protect_current_ack.bit.tk0_current ||
@ -1566,7 +1389,7 @@ void read_plane_errors(void)
if (project.all_status_plates.in0 != component_Ready)
edrk.errors.e3.bits.NOT_READY_IN_0 |= 1;
#endif
#if USE_IN_1
#if USE_IN_0
if (project.all_status_plates.in1 != component_Ready)
edrk.errors.e3.bits.NOT_READY_IN_1 |= 1;
#endif
@ -1603,4 +1426,3 @@ int get_common_state_overheat() {
edrk.errors.e2.bits.T_UO7_MAX | edrk.errors.e2.bits.T_WATER_EXT_MAX |
edrk.errors.e2.bits.T_WATER_INT_MAX;
}

View File

@ -10,17 +10,12 @@
#define TIME_WAIT_ERROR 20 // 2 sec
#define TIME_WAIT_ERROR_QTV 100 // 10 sec
#define TIME_WAIT_ERROR_CHARGE_ANSWER 60 // 6 sec
#define TIME_WAIT_ERROR_IZOL 50 //5 sec //200 // 20 sec
#define TIME_WAIT_ERROR_PUMP 100 // 10 sec
#define TIME_WAIT_ERROR_FAN 300 // 30 sec
#define TIME_WAIT_SENSOR_ROTOR_BREAK_ALL 200 // 20 sec
#define TIME_WAIT_SENSOR_ROTOR_BREAK_DIRECTION 10 // 1 sec
#define TIME_WAIT_SENSOR_ROTOR_BREAK_ONE_SENSOR 20 // 2 sec
#define TIME_WAIT_ERROR 20 // 2 sec
#define TIME_WAIT_ERROR_QTV 100 // 10 sec
#define TIME_WAIT_ERROR_CHARGE_ANSWER 60 // 6 sec
#define TIME_WAIT_ERROR_IZOL 200 // 20 sec
#define TIME_WAIT_ERROR_PUMP 100 // 10 sec
#define TIME_WAIT_ERROR_FAN 300 // 30 sec
#define MINIMAL_LEVEL_ZAD_U 27962 // 10 V
@ -31,50 +26,5 @@ void detect_error_all(void);
void read_plane_errors(void);
int detect_error_u_zpt_on_predzaryad(void);
int detect_error_u_in(void);
int detect_error_u_zpt_fast(void);
void detect_error_from_knopka_avaria(void);
void detect_error_ute4ka_water(void);
void detect_error_t_vipr(void);
void detect_error_power_upc(void);
void detect_error_op_pit(void);
void detect_error_p_water(void);
void detect_error_pump_2(void);
void detect_error_pump_1(void);
void detect_error_pre_ready_pump(void);
void detect_error_fan(void);
void detect_error_block_qtv_from_svu(void);
void detect_error_predohr_vipr(void);
void detect_error_qtv(void);
void detect_error_pre_charge(void);
void detect_error_block_izol(void);
void detect_error_nagrev(void);
void detect_error_ground(void);
void detect_error_block_door(void);
void detect_error_optical_bus(void);
void detect_error_sync_bus(void);
int get_status_temper_acdrive_winding(int nc);
int get_status_temper_acdrive_winding_with_limits(int nc, int alarm, int abnormal);
int get_status_temper_acdrive_bear(int nc);
int get_status_temper_acdrive_bear_with_limits(int nc, int alarm, int abnormal);
int get_status_temper_air(int nc);
int get_status_temper_air_with_limits(int nc, int alarm, int abnormal);
int get_status_temper_u(int nc);
int get_status_temper_u_with_limits(int nc, int alarm, int abnormal);
int get_status_temper_water(int nc);
int get_status_p_water_max(void);
int get_status_p_water_min(int pump_on_off);
void detect_error_t_water(void);
void detect_error_t_air(void);
void detect_error_t_u(void);
void detect_error_acdrive_winding(void);
int get_common_state_warning(void);
int get_common_state_overheat(void);
void detect_error_sensor_rotor(void);
#endif /* SRC_MYLIBS_DETECT_ERRORS_H_ */

View File

@ -11,22 +11,18 @@
#include <edrk_main.h>
#include <params_protect_adc.h>
#include <protect_levels.h>
#include "digital_filters.h"
#include "IQmathLib.h"
//ANALOG_PROTECT_LEVELS analog_protect_levels = ANALOG_PROTECT_LEVELS_DEFAULTS;
//#pragma DATA_SECTION(analog_protect,".fast_vars");
#pragma DATA_SECTION(analog_protect,".slow_vars");
#pragma DATA_SECTION(analog_protect,".fast_vars");
ANALOG_ADC_PROTECT analog_protect = ANALOG_ADC_PROTECT_DEFAULTS;
//#pragma DATA_SECTION(break_Iout_1_state,".fast_vars");
#pragma DATA_SECTION(break_Iout_1_state,".slow_vars");
#pragma DATA_SECTION(break_Iout_1_state,".fast_vars");
BREAK_PHASE_I break_Iout_1_state = BREAK_PHASE_I_DEFAULTS;
//#pragma DATA_SECTION(break_Iout_2_state,".fast_vars");
#pragma DATA_SECTION(break_Iout_2_state,".slow_vars");
#pragma DATA_SECTION(break_Iout_2_state,".fast_vars");
BREAK_PHASE_I break_Iout_2_state = BREAK_PHASE_I_DEFAULTS;
int detect_error_Izpt();
@ -38,9 +34,7 @@ void init_analog_protect_levels(void) {
}
#define AMPL_TO_RMS 0.709
//#define LEVEL_I_1_2_DIBALANCE 1118481 // 200 A
#define LEVEL_I_1_2_DIBALANCE 1677721 // 300 A
#define LEVEL_I_1_2_DIBALANCE 1118481
void init_protect_3_phase(void) {
analog_protect.in_voltage[0].setup.levels.iqVal_module_max = edrk.iqMAX_U_IN;
@ -202,14 +196,13 @@ void detect_protect_adc(_iq teta_ch1, _iq teta_ch2) {
edrk.errors.e0.bits.U_B2C2_MAX |= analog_protect.in_voltage[1].errors.bits.phase_V_max;
edrk.errors.e0.bits.U_IN_MAX |= analog_protect.in_voltage[1].errors.bits.module_max;
edrk.warnings.e8.bits.U_IN_20_PROCENTS_HIGH = analog_protect.in_voltage[0].over_limit.bits.module_20_percent_hi || analog_protect.in_voltage[1].over_limit.bits.module_20_percent_hi;
edrk.warnings.e8.bits.U_IN_20_PROCENTS_HIGH = analog_protect.in_voltage[0].over_limit.bits.module_20_percent_hi;
edrk.errors.e8.bits.U_IN_20_PROCENTS_HIGH |= analog_protect.in_voltage[0].errors.bits.module_20_percent_hi;
edrk.warnings.e8.bits.U_IN_20_PROCENTS_HIGH = analog_protect.in_voltage[1].over_limit.bits.module_20_percent_hi;
edrk.errors.e8.bits.U_IN_20_PROCENTS_HIGH |= analog_protect.in_voltage[1].errors.bits.module_20_percent_hi;
if (edrk.from_shema_filter.bits.QTV_ON_OFF == 1
// && edrk.to_shema.bits.QTV_ON
)
{
if (edrk.from_shema.bits.QTV_ON_OFF == 1) {
// êîíòðîëü íàïðÿæåíèé òîëüêî ïðè âêëþ÷åííîì ñèëîâîì àâòîìàòå
edrk.errors.e8.bits.U_IN_10_PROCENTS_LOW |= analog_protect.in_voltage[0].errors.bits.module_10_percent_low;
@ -218,21 +211,11 @@ void detect_protect_adc(_iq teta_ch1, _iq teta_ch2) {
edrk.errors.e8.bits.U_IN_10_PROCENTS_LOW |= analog_protect.in_voltage[1].errors.bits.module_10_percent_low;
edrk.errors.e8.bits.U_IN_20_PROCENTS_LOW |= analog_protect.in_voltage[1].errors.bits.module_20_percent_low;
edrk.warnings.e8.bits.U_IN_10_PROCENTS_LOW = pause_detect_error(&counter_in1_minus10,
TIME_DETECT_WARNING_U_PREDELS,
analog_protect.in_voltage[0].over_limit.bits.module_10_percent_low);
edrk.warnings.e8.bits.U_IN_10_PROCENTS_LOW = pause_detect_error(&counter_in1_minus10, TIME_DETECT_WARNING_U_PREDELS, analog_protect.in_voltage[0].over_limit.bits.module_10_percent_low);
edrk.warnings.e8.bits.U_IN_10_PROCENTS_LOW |= pause_detect_error(&counter_in2_minus10, TIME_DETECT_WARNING_U_PREDELS, analog_protect.in_voltage[1].over_limit.bits.module_10_percent_low);
edrk.warnings.e8.bits.U_IN_10_PROCENTS_LOW = pause_detect_error(&counter_in2_minus10,
TIME_DETECT_WARNING_U_PREDELS,
analog_protect.in_voltage[1].over_limit.bits.module_10_percent_low);
edrk.warnings.e8.bits.U_IN_20_PROCENTS_LOW = pause_detect_error(&counter_in1_minus20,
TIME_DETECT_WARNING_U_PREDELS,
analog_protect.in_voltage[0].over_limit.bits.module_20_percent_low);
edrk.warnings.e8.bits.U_IN_20_PROCENTS_LOW = pause_detect_error(&counter_in2_minus20,
TIME_DETECT_WARNING_U_PREDELS,
analog_protect.in_voltage[1].over_limit.bits.module_20_percent_low);
edrk.warnings.e8.bits.U_IN_20_PROCENTS_LOW = pause_detect_error(&counter_in1_minus20, TIME_DETECT_WARNING_U_PREDELS, analog_protect.in_voltage[0].over_limit.bits.module_20_percent_low);
edrk.warnings.e8.bits.U_IN_20_PROCENTS_LOW |= pause_detect_error(&counter_in2_minus20, TIME_DETECT_WARNING_U_PREDELS, analog_protect.in_voltage[1].over_limit.bits.module_20_percent_low);
edrk.errors.e9.bits.DISBALANCE_Uin_1 |= analog_protect.in_voltage[0].errors.bits.system_asymmetry;
edrk.errors.e9.bits.DISBALANCE_Uin_2 |= analog_protect.in_voltage[1].errors.bits.system_asymmetry;

View File

@ -33,8 +33,7 @@ typedef struct {
#define ANALOG_ADC_PROTECT_DEFAULTS { \
{DETECT_PROTECT_3_PHASE_DEFAULTS,DETECT_PROTECT_3_PHASE_DEFAULTS},\
{DETECT_PROTECT_3_PHASE_DEFAULTS,DETECT_PROTECT_3_PHASE_DEFAULTS},\
0,0 }
{DETECT_PROTECT_3_PHASE_DEFAULTS,DETECT_PROTECT_3_PHASE_DEFAULTS}}
void init_analog_protect_levels(void);
void detect_protect_adc (_iq teta_ch1, _iq teta_ch2);

View File

@ -9,7 +9,6 @@
#include <edrk_main.h>
#include <params_motor.h>
#include <params_pwm24.h>
#include "alg_simple_scalar.h"
#include "IQmathLib.h"
@ -44,49 +43,32 @@ int calc_detect_overload(DETECT_OVERLOAD *v) {
return v->overload_detected;
}
#define LIMIT_DETECT_LEVEL 16273899 // 0.97 //15938355 //95%
#define LIMIT_DETECT_LEVEL 15938355 //95%
void check_all_power_limits() {
_iq level_I_nominal = 0;
//edrk.power_limit.bits.limit_by_temper = edrk.temper_limit_koeffs.code_status;
edrk.power_limit.bits.limit_by_temper = edrk.temper_limit_koeffs.code_status;
if (edrk.Go)
{
level_I_nominal = _IQmpy(LIMIT_DETECT_LEVEL, edrk.zadanie.iq_Izad_rmp);
if ((filter.iqIm > level_I_nominal) ||
out_I_over_1_6.overload_detected)
{
edrk.power_limit.bits.limit_Iout = 1;
} else
{
edrk.power_limit.bits.limit_Iout = 0;
}
}
else
level_I_nominal = _IQmpy(LIMIT_DETECT_LEVEL, edrk.zadanie.iq_Izad_rmp);
if ((filter.iqIm_1 > level_I_nominal) || (filter.iqIm_1 > level_I_nominal) ||
out_I_over_1_6.overload_detected) {
edrk.power_limit.bits.limit_Iout = 1;
} else {
edrk.power_limit.bits.limit_Iout = 0;
// if (edrk.from_uom.code>1)
// edrk.power_limit.bits.limit_UOM = 1;
// else
// edrk.power_limit.bits.limit_UOM = 0;
//filter.PowerScalar + edrk.iq_power_kw_another_bs
if ( (edrk.iq_power_kw_full_filter_abs > _IQmpy(LIMIT_DETECT_LEVEL, edrk.zadanie.iq_limit_power_zad_rmp))
|| simple_scalar1.flag_decr_mzz_power
// Äàííûé ñïîñîá äëÿ ñêàëÿðíîãî óïðàâëåíèÿ, äëÿ FOC, âîçìîæíî, íóæíà âåêòîðíàÿ ìîùíîñòü.
)
{
edrk.power_limit.bits.limit_from_SVU = 1;
}
else
{
// edrk.power_limit.bits.limit_UOM =
if ((filter.PowerScalar + edrk.iq_power_kw_another_bs) >
_IQmpy(LIMIT_DETECT_LEVEL, edrk.zadanie.iq_limit_power_zad_rmp)
// Äàííûé ñïîñîá äëÿ ñêàëÿðíîãî óïðàâëåíèÿ, äëÿ FOC, âîçìîæíî, íóæíà âåêòîðíàÿ ìîùíîñòü.
) {
edrk.power_limit.bits.limit_from_SVU = 1;
} else {
edrk.power_limit.bits.limit_from_SVU = 0;
}
}

View File

@ -1,103 +0,0 @@
/*
* digital_filters.c
*
* Created on: 13 íîÿá. 2024 ã.
* Author: Evgeniy_Sokolov
*/
////////////////////////////////////////////////////////////////////
unsigned int filter_digital_input(unsigned int prev_valus, unsigned int *c_plus, unsigned int max_wait, unsigned int flag)
{
if (flag)
{
if ((*c_plus)>=max_wait)
{
return 1;
}
else
{
(*c_plus)++;
return (prev_valus);
}
}
else
{
if ((*c_plus)==0)
{
return 0;
}
else
{
(*c_plus)--;
return (prev_valus);
}
}
}
///////////////////////////////////////////////////////////////////
//TODO: may be move to detect_errors.c
unsigned int pause_detect_error(unsigned int *c_err, unsigned int max_wait,unsigned int flag)
{
if (flag)
{
if ((*c_err)>=max_wait)
{
return 1;
}
else
{
(*c_err)++;
return 0;
}
}
else
{
(*c_err) = 0;
return 0;
}
}
//////////////////////////////////////////////////////////
unsigned int filter_err_count(unsigned int *counter, unsigned int max_errors, unsigned int err, unsigned int cmd)
{
if (cmd==1)
{
(*counter) = 0;
return 0;
}
if (err)
{
if ((*counter)>=max_errors)
return 1;
else
(*counter)++;
return 0;
}
if (err==0)
{
if ((*counter)==0)
return 0;
else
(*counter)--;
return 0;
}
return 0;
}

View File

@ -1,19 +0,0 @@
/*
* digital_filters.h
*
* Created on: 13 íîÿá. 2024 ã.
* Author: Evgeniy_Sokolov
*/
#ifndef SRC_MAIN_DIGITAL_FILTERS_H_
#define SRC_MAIN_DIGITAL_FILTERS_H_
unsigned int filter_digital_input(unsigned int prev_valus, unsigned int *c_plus, unsigned int max_wait, unsigned int flag);
unsigned int pause_detect_error(unsigned int *c_err, unsigned int max_wait,unsigned int flag);
unsigned int filter_err_count(unsigned int *counter, unsigned int max_errors, unsigned int err, unsigned int cmd);
#endif /* SRC_MAIN_DIGITAL_FILTERS_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -5,25 +5,16 @@
#include "IQmathLib.h"
#include "rmp_cntl_v1.h"
#include "rmp_cntl_v2.h"
#include "alg_pll.h"
#define TIME_PAUSE_MODBUS_CAN_BS2BS 500 //900 //500
#define TIME_PAUSE_MODBUS_CAN_ZADATCHIK_VPU 250 //100//100
#define TIME_PAUSE_MODBUS_CAN_UKSS_SETUP 2500 //
#define TIME_PAUSE_MODBUS_CAN_MPU 1100 //500
#define TIME_PAUSE_MODBUS_CAN_TERMINALS 2000 //1000
#define TIME_PAUSE_MODBUS_CAN_BS2BS 500
#define TIME_PAUSE_MODBUS_CAN_ZADATCHIK_VPU 100
#define TIME_PAUSE_MODBUS_CAN_UKSS_SETUP 5000
#define TIME_PAUSE_MODBUS_CAN_MPU 500
#define TIME_PAUSE_MODBUS_CAN_TERMINALS 1000
#define TIME_PAUSE_MODBUS_CAN_OSCIL 5000
//#define TIME_PAUSE_MODBUS_CAN_BS2BS 100//20//500
//#define TIME_PAUSE_MODBUS_CAN_ZADATCHIK_VPU 250//20//100
//#define TIME_PAUSE_MODBUS_CAN_UKSS_SETUP 5000
//#define TIME_PAUSE_MODBUS_CAN_MPU 500//20//500
//#define TIME_PAUSE_MODBUS_CAN_TERMINALS 1000
//#define TIME_PAUSE_MODBUS_CAN_OSCIL 5000
//#define TIME_PAUSE_MODBUS_CAN_TMS2TMS_VIPR 75 //500
@ -143,22 +134,6 @@ enum
};
enum
{
STAGE_SBOR_STATUS_NO_STATUS = 0,
STAGE_SBOR_STATUS_FIRST,
STAGE_SBOR_STATUS_PUMP,
STAGE_SBOR_STATUS_ZARYAD,
STAGE_SBOR_STATUS_UMP_ON,
STAGE_SBOR_STATUS_QTV,
STAGE_SBOR_STATUS_UMP_OFF,
STAGE_SBOR_STATUS_RASCEPITEL_1,
STAGE_SBOR_STATUS_RASCEPITEL_2,
STAGE_SBOR_STATUS_RASCEPITEL_3,
STAGE_SBOR_STATUS_RASCEPITEL_4,
STAGE_SBOR_STATUS_WAIT_READY_ANOTHER,
STAGE_SBOR_STATUS_FINISH
};
/*
@ -213,7 +188,6 @@ typedef struct
float real_temper_air[4];
int real_int_temper_air[4];
int max_real_int_temper_air;
int min_real_int_temper_air;
@ -221,7 +195,7 @@ typedef struct
} TEMPER_EDRK;
#define TEMPER_EDRK_DEFAULT {{0,0,0,0,0,0,0},{0,0,0,0,0,0,0},{0,0,0,0,0,0,0},0,\
{0,0},{0,0},{0,0},0,\
{0,0,0,0},{0,0,0,0},{0,0,0,0},0,0\
{0,0,0,0},{0,0,0,0},{0,0,0,0},0\
}
@ -540,15 +514,8 @@ typedef struct
unsigned int ERR_PWM_WDOG :1;
unsigned int ERR_INT_PWM_VERY_LONG : 1;
unsigned int SENSOR_ROTOR_1_BREAK : 1;
unsigned int SENSOR_ROTOR_2_BREAK : 1;
unsigned int SENSOR_ROTOR_1_2_BREAK : 1;
unsigned int SENSOR_ROTOR_BREAK_DIRECTION : 1;
unsigned int BREAK_TEMPER_WARNING : 1;
unsigned int BREAK_TEMPER_ALARM : 1;
unsigned int BREAKER_GED_ON : 1;
unsigned int res: 7;
} bits;
} e9;
@ -718,8 +685,8 @@ typedef union {
} bits;
} AUTO_MASTER_SLAVE_DATA;
////////////////////////////////////////////////////////
typedef union {
unsigned int all;
@ -737,10 +704,11 @@ typedef union {
unsigned int Batt: 1;
unsigned int ImitationReady2: 1;
unsigned int MasterSlaveActive: 1; // âûñòàâèì åñëè åñòü master èëè slave
unsigned int preImitationReady2: 1;
unsigned int res:4;
unsigned int MasterSlaveActive: 1; // âûñòàâèì åñëè åñòü master èëè slave
// unsigned int res:6;
} bits;
} STATUS_READY;
////////////////////////////////////////////////////////
@ -865,14 +833,8 @@ typedef union {
unsigned int PLUS: 1;
unsigned int MINUS : 1;
unsigned int PROVOROT :1 ;
unsigned int UOM_READY_ACTIVE : 1;
unsigned int UOM_LIMIT_3 : 1;
unsigned int UOM_LIMIT_2 : 1;
unsigned int UOM_LIMIT_1 : 1;
unsigned int res:8;
unsigned int ACTIVE : 1;
unsigned int res:11;
} bits;
} FROM_ZADAT4IK;
////////////////////////////////////////////////////////
@ -913,14 +875,14 @@ typedef union {
union {
unsigned int all;
struct {
unsigned int GOTOV1 : 1;
unsigned int GOTOV2 : 1;
unsigned int EMKOST : 1; //For 23550.3 and AVARIA moved up
unsigned int NEISPRAVNOST : 1;
unsigned int GOTOV1: 1;
unsigned int GOTOV2: 1;
// unsigned int EMKOST : 1; //For 23550.3 and AVARIA moved up
unsigned int AVARIA:1;
unsigned int NEISPRAVNOST :1 ;
unsigned int PEREGREV : 1;
unsigned int OGRAN_POWER : 1;
unsigned int AVARIA : 1;
unsigned int res:9;
unsigned int res:10;
} bits;
} BIG_LAMS;
@ -961,10 +923,6 @@ typedef union {
} APL_LAMS_PCH;
} TO_ZADAT4IK;
#define TO_ZADAT4IK_DEFAULT {0,0,0,0,0}
////////////////////////////////////////////////////////
typedef struct {
@ -989,18 +947,12 @@ typedef union {
} BIG_LAMS;
} TO_VPU;
#define TO_VPU_DEFAULT {0,0,0}
////////////////////////////////////////////////////////
typedef struct {
unsigned int level_value;
unsigned int ready;
unsigned int error;
unsigned int code;
_iq iq_level_value;
_iq iq_level_value_kwt;
@ -1068,17 +1020,12 @@ typedef struct {
RMP_V1 rmp_k_u_disbalance;
RMP_V1 rmp_kplus_u_disbalance;
RMP_V1 rmp_Izad;
RMP_V2 rmp_powers_zad;
RMP_V2 rmp_limit_powers_zad;
RMP_V1 rmp_powers_zad;
RMP_V1 rmp_limit_powers_zad;
RMP_V1 rmp_kzad;
RMP_V1 rmp_oborots_zad_hz;
RMP_V2 rmp_oborots_zad_hz;
RMP_V1 rmp_oborots_imitation;
_iq rmp_oborots_imitation_rmp;
float ZadanieU_Charge;
@ -1086,7 +1033,6 @@ typedef struct {
_iq iq_ZadanieU_Charge_rmp;
float oborots_zad;
float oborots_zad_hz;
_iq iq_oborots_zad_hz;
_iq iq_oborots_zad_hz_rmp;
@ -1119,154 +1065,37 @@ typedef struct {
_iq iq_limit_power_zad;
_iq iq_limit_power_zad_rmp;
_iq iq_set_break_level;
float oborots_zad_no_dead_zone;
} ZADANIE;
#define ZADANIE_DEFAULT { RMP_V1_DEFAULTS, RMP_V1_DEFAULTS,RMP_V1_DEFAULTS,\
RMP_V1_DEFAULTS,RMP_V1_DEFAULTS,\
RMP_V2_DEFAULTS,\
RMP_V2_DEFAULTS,RMP_V1_DEFAULTS,\
RMP_V2_DEFAULTS,\
RMP_V1_DEFAULTS,\
0, 0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0 , 0,0,0, 0,0}
RMP_V1_DEFAULTS,RMP_V1_DEFAULTS,RMP_V1_DEFAULTS,RMP_V1_DEFAULTS,RMP_V1_DEFAULTS,RMP_V1_DEFAULTS,\
0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0 , 0,0,0}
typedef union {
struct {
unsigned int limit_by_temper:1;
unsigned int limit_Iout:1;
unsigned int limit_UOM:1; //Óñòðîéñòâî îãðàíè÷åíèÿ ìîùíîñòè
unsigned int limit_from_SVU:1;
unsigned int limit_from_freq:1;
unsigned int limit_from_uom_fast:1;
unsigned int limit_moment:1;
unsigned int res:9;
unsigned int limit_by_temper;
unsigned int limit_Iout;
unsigned int limit_UOM; //Óñòðîéñòâî îãðàíè÷åíèÿ ìîùíîñòè
unsigned int limit_from_SVU;
} bits;
unsigned int all;
} POWER_LIMIT;
#define POWER_LIMIT_DEFAULTS {0}
#define POWER_LIMIT_DEFAULTS {0,0,0,0}
typedef struct {
_iq temper_limit;
_iq power_limit;
_iq moment_limit;
_iq uin_freq_limit;
_iq uom_limit;
_iq local_temper_limit;
_iq local_power_limit;
_iq local_moment_limit;
_iq local_uin_freq_limit;
_iq local_uom_limit;
_iq sum_limit;
_iq local_sum_limit;
int code_status;
} ALL_LIMIT_KOEFFS;
#define ALL_LIMIT_KOEFFS_DEFAULTS {0,0,0,0,0, 0,0,0,0,0, 0,0,0}
typedef struct {
_iq power_units;
_iq area;
_iq water_int;
_iq water_ext;
_iq acdrive_windings;
_iq acdrive_bears;
_iq sum_limit;
int code_status;
} TEMPERATURE_LIMIT_KOEFFS;
#define TEMPERATURE_LIMIT_KOEFFS_DEFAULTS {0,0,0,0,0, 0,CONST_IQ_1,0}
#define COUNT_MOTO_PULT 18
typedef struct
{
int nPCH;
int TimeToChangePump;
int count_revers; // êîë-âî ðåâåðñîâ
int count_build; // êîë-âî ñáîðîê ñõåì
int LastWorkPump; // êàêîé áûë ïîñëåäíèé çàïóùåííûé íàñîñ
int moto[COUNT_MOTO_PULT];
} t_params_pult_ing_one;
#define PARAMS_PULT_ING_ONE_DEFAULTS {-1,-1, -1,-1, 0, \
{-1,-1,-1,-1,-1, -1,-1,-1,-1,-1, -1,-1,-1,-1,-1, -1,-1,-1 } }
#define PARAMS_PULT_ING_TWO_DEFAULTS {0,0, 0,0, 0, \
{0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 0,0,0 } }
typedef struct
{
int flagSaveDataPCH;
int flagSaveDataMoto;
int flagSaveSlowLogs;
int flagSaveParamLogs;
int logger_params[28];
t_params_pult_ing_one data;
t_params_pult_ing_one data_from_pult;
t_params_pult_ing_one data_to_pult;
// int nPCH_from_pult;
// int nPCH_to_pult;
// int nPCH;
//
// int TimeToChangePump_from_pult;
// int TimeToChangePump_to_pult;
// int TimeToChangePump;
//
// int moto_from_pult[COUNT_MOTO_PULT];
// int mot_to_pult[COUNT_MOTO_PULT];
// int moto[COUNT_MOTO_PULT];
//
// int count_revers_from_pult;
// int count_revers_to_pult;
} t_params_pult_ing;
#define PARAMS_PULT_ING_DEFAULTS {0,0,0,0, \
{0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 0,0,0}, \
PARAMS_PULT_ING_TWO_DEFAULTS, \
PARAMS_PULT_ING_ONE_DEFAULTS, \
PARAMS_PULT_ING_ONE_DEFAULTS \
}
typedef struct
{
int log_what_memory; // Çíà÷åíèå 0 - íåò íè ôëåøêè, íè êàðòû;
//Çíà÷åíèå 1 - íåò ôëåøêè, åñòü êàðòà;
//Çíà÷åíèå 2 - åñòü ôëåøêà, íåò êàðòû;
//Çíà÷åíèå 3 - åñòü è ôëåøêà è êàðòà;
int kvitir; //
int sbor;
int send_log;
int pump_mode;
int sdusb;// 0 - sd, 1 usb
} t_pult_cmd_ing;
#define PULT_CMD_ING_DEFAULTS 0,0,0,0,0,0
#define TEMPERATURE_LIMIT_KOEFFS_DEFAULTS {0,0,0,0,0,0,0}
////////////////////////////////////////////////////////
typedef struct
@ -1281,7 +1110,6 @@ typedef struct
POWER_LIMIT power_limit;
TEMPERATURE_LIMIT_KOEFFS temper_limit_koeffs;
ALL_LIMIT_KOEFFS all_limit_koeffs;
MASTER_SLAVE_COM ms;
@ -1314,7 +1142,6 @@ typedef struct
TO_SHEMA to_shema;//1
FROM_SHEMA from_shema;//1
FROM_SHEMA from_shema_filter;//1
FROM_ZADAT4IK from_zadat4ik;//1
@ -1336,7 +1163,7 @@ typedef struct
TO_VPU to_vpu;//3
FROM_UOM from_uom;//7
FROM_UOM from_uom;//4
///////////////////////////////////////////////
unsigned int Discharge;
@ -1359,7 +1186,6 @@ typedef struct
unsigned int prevGo;
unsigned int Go;
unsigned int GoBreak;
unsigned int GoWait;
@ -1367,8 +1193,6 @@ typedef struct
int flag_block_zadanie;
int StartGEDfromControl;
int StartGEDfromZadanie;
int prevStartGEDfromZadanie;
int StartGED;
int test_mode;
int cmd_to_qtv;//20
@ -1443,8 +1267,7 @@ typedef struct
_iq iq_f_rotor_hz;
float f_rotor_hz;
int oborots;
int rotor_direction;
int power_kw;
float power_kw;
// _iq iq_oborots;
_iq Izad_out;
@ -1476,7 +1299,7 @@ typedef struct
int warning;
int overheat;
unsigned int MasterSlave;
unsigned MasterSlave;
_iq master_theta;
_iq master_Uzad;
@ -1508,14 +1331,10 @@ typedef struct
int Ready1_another_bs;
int Ready2_another_bs;
int ump_cmd_another_bs;
int qtv_cmd_another_bs;
int active_post_upravl;
int active_post_upravl_another_bs;
int MasterSlave_another_bs;
int freq_50hz_1;
int freq_50hz_2;
int freq_50hz;
_iq test_rms_Iu;
_iq test_rms_Ua;
@ -1537,168 +1356,62 @@ typedef struct
int disable_rascepitel_work;
int enable_pwm_test_lines;
int count_bs_work;
unsigned int run_to_pwm_async;
int power_kw_full;
int stop_logs_rs232;
int sbor_wait_ump1;
int sbor_wait_ump2;
int flag_enable_on_ump;
int local_ump_on_off;
int local_ump_on_off_count;
int local_ready_ump;
int local_ready_ump_count;
t_params_pult_ing pult_data;
int logs_rotor;
int stop_slow_log;
int t_slow_log;
int disable_limit_power_from_svu;
int disable_uom;
int disable_break_work;
int flag_another_bs_first_ready12;
int flag_this_bs_first_ready12;
int enter_to_pump_stage;
int buildYear;
int buildMonth;
int buildDay;
int errors_another_bs_from_can;
unsigned int count_sbor;
unsigned int count_revers;
unsigned int count_run;
int flag_slow_in_main;
t_pult_cmd_ing pult_cmd;
int get_new_data_from_hmi2;
_iq iq_freq_50hz;
int imit_limit_freq;
int imit_limit_uom;
int set_limit_uom_50;
_iq iq_power_kw_full_znak;
_iq iq_power_kw_one_znak;
_iq iq_power_kw_full_filter_znak;
_iq iq_power_kw_one_filter_znak;
_iq iq_power_kw_full_abs;
_iq iq_power_kw_one_abs;
_iq iq_power_kw_full_filter_abs;
_iq iq_power_kw_one_filter_abs;
unsigned int sum_count_err_read_opt_bus;
int imit_save_slow_logs;
int imit_send_alarm_log_pult;
int current_active_control;
// int data_to_message2[100];
//101
unsigned long canes_reg;
unsigned long cantec_reg; // Transmit Error Counter
unsigned long canrec_reg; // Receive Error Counter
int cmd_clear_can_error;
int cmd_very_slow_start;
int cmd_imit_low_isolation;
int breaker_on;
int break_tempers[4];
int cmd_disable_calc_km_on_slave;
} EDRK;
#define EDRK_DEFAULT { \
ZADANIE_DEFAULT,\
ZADANIE_FROM_ANOTHER_BS_DEFAULT,\
TEMPER_EDRK_DEFAULT, \
P_WATER_EDRK_DEFAULT, \
ERRORS_EDRK_DEFAULT, \
ERRORS_EDRK_DEFAULT, \
TEMPER_ACDRIVE_DEFAULT, \
POWER_LIMIT_DEFAULTS, \
TEMPERATURE_LIMIT_KOEFFS_DEFAULTS, \
ALL_LIMIT_KOEFFS_DEFAULTS, \
MASTER_SLAVE_COM_DEFAULT, \
0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0, \
0,0,0,0, \
0,0,0, \
0,0,0,0,0,0,0, \
\
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0,0,0, 0,0, \
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, \
0,0,0,0, \
PARAMS_PULT_ING_DEFAULTS, \
0,0,0,0,0,0,0,0, \
ZADANIE_DEFAULT,\
ZADANIE_FROM_ANOTHER_BS_DEFAULT,\
TEMPER_EDRK_DEFAULT, P_WATER_EDRK_DEFAULT, \
ERRORS_EDRK_DEFAULT, ERRORS_EDRK_DEFAULT,\
TEMPER_ACDRIVE_DEFAULT,\
POWER_LIMIT_DEFAULTS,\
TEMPERATURE_LIMIT_KOEFFS_DEFAULTS,\
MASTER_SLAVE_COM_DEFAULT,\
0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,\
0,0,0,0,\
0,0,0,\
0, 0,0,0, 0, \
PULT_CMD_ING_DEFAULTS, 0,0, 0,0,0, 0,0,0,0, 0,0,0,0, \
0, 0,0, 0, 0, \
0,0,0, 0, 0, 0, \
0, {0,0,0,0}, \
0 \
}
0,0,0,0,\
\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0,0,0,\
0,0,0,0,0,0,0,0,0,0, 0,0,\
0,0,0,0,0,0,0,0,0,0,0,0 \
}
extern EDRK edrk;
extern PLL_REC pll1;
//float get_sensor_ing(void);
//float get_i_vozbud(void);
//float get_zad_vozbud(void);
float get_sensor_ing(void);
float get_i_vozbud(void);
float get_zad_vozbud(void);
//unsigned int convert_w_to_mA(float inp);
unsigned int convert_w_to_mA(float inp);
void edrk_init(void);
void update_input_edrk(void);
void update_output_edrk(void);
float get_amper_vozbud(void);
//float get_amper_vozbud(void);
//void set_amper_vozbud(float set_curr, float cur_curr);
void set_amper_vozbud(float set_curr, float cur_curr);
//void write_dac(int ndac, int Value);
void write_dac(int ndac, int Value);
void run_edrk(void);
@ -1707,52 +1420,63 @@ void run_edrk(void);
void set_oborots_from_zadat4ik(void);
void get_where_oborots(void);
//void update_errors(void);
void update_errors(void);
void calc_p_water_edrk(void);
unsigned int pause_detect_error(unsigned int *c_err, unsigned int max_wait,unsigned int flag);
//unsigned int zaryad_on_off(unsigned int flag);
void nagrev_auto_on_off(void);
unsigned int zaryad_on_off(unsigned int flag);
void update_lamp_alarm(void);
void auto_block_key_on_off(void);
void nagrev_auto_on_off(void);
//int get_status_temper_acdrive_winding(int nc);
//int get_status_temper_acdrive_bear(int nc);
//int get_status_temper_air(int nc);
//int get_status_temper_u(int nc);
//int get_status_temper_water(int nc);
//int get_status_p_water_max(void);
//int get_status_p_water_min(int pump_on_off);
int get_status_temper_acdrive_winding(int nc);
int get_status_temper_acdrive_bear(int nc);
int get_status_temper_air(int nc);
int get_status_temper_u(int nc);
int get_status_temper_water(int nc);
int get_status_p_water_max(void);
int get_status_p_water_min(int pump_on_off);
void detect_kvitir_from_all(void);
//void set_status_pump_fan(void);
void set_status_pump_fan(void);
int qtv_on_off(unsigned int flag);
///int detect_error_u_zpt(void);
//int detect_error_u_zpt_on_predzaryad(void);
int detect_error_u_zpt(void);
int detect_error_u_zpt_on_predzaryad(void);
void set_zadanie_u_charge(void);
void update_ukss_can(unsigned int pause);
void update_ukss_setup(unsigned int pause);
void update_bsu_can(unsigned int pause);
void init_can_box_between_bs1_bs2(void);
unsigned int filter_err_count(unsigned int *counter, unsigned int max_errors, unsigned int err, unsigned int cmd);
void detect_alive_another_bs(void);
void auto_select_master_slave(void);
void clear_errors_master_slave(void);
void who_select_sync_signal(void);
void clear_wait_synhro_optical_bus(void);
unsigned int wait_synhro_optical_bus(void);
void edrk_init_variables(void);
@ -1762,53 +1486,41 @@ void edrk_go_main(void);
int get_start_ged_from_zadanie(void);
void ramp_all_zadanie(int flag_set_zero);
void init_ramp_all_zadanie(void);
//void UpdateTableSecondBS(void);
void UpdateTableSecondBS(void);
unsigned int get_ready_1(void);
//int detect_zaryad_ump(void);
int detect_zaryad_ump(void);
void cross_stend_automats(void);
void update_zadat4ik(void);
void get_sumsbor_command(void);
//unsigned int read_cmd_sbor_from_bs(void);
unsigned int read_cmd_sbor_from_bs(void);
//void read_data_from_bs(void);
void read_data_from_bs(void);
void check_change_post_upravl(void);
int get_code_active_post_upravl(void);
void get_freq_50hz(void);
void calc_pll_50hz(void);
void init_50hz_input_net50hz(void);
void auto_detect_zero_u_zpt(void);
void run_can_from_mpu(void);
void set_new_level_i_protect(int n_af, int level);
void update_maz_level_i_af(int n_af, unsigned int new_maz_level);
void calc_count_build_revers(void);
int calc_auto_moto_pump(void);
void prepare_logger_pult(void);
void read_can_error(void);
void clear_can_error(void);
void cmd_clear_can_error(void);
void check_temper_break(void);
void check_breaker_ged(void);
_iq calc_rms(_iq input, _iq input_prev, _iq freq_signal);
//extern int ccc[40];
void reinit_before_sbor(void);
unsigned int toggle_status_lamp(unsigned int bb1, unsigned int flag);
#endif

View File

@ -1,50 +0,0 @@
/*
* limit_lib.c
*
* Created on: 15 àâã. 2024 ã.
* Author: yura
*/
#include "IQmathLib.h"
#include "math_pi.h"
_iq linear_decrease(float current, int alarm_level, int warnig_level) {
float delta = current - warnig_level;
float max_delta = alarm_level - warnig_level;
if (delta <= 0 || max_delta <= 0) {
return CONST_IQ_1;
} else {
if (delta>max_delta)
return 0;
else
return CONST_IQ_1 - _IQ(delta / max_delta);
}
}
_iq linear_decrease_iq(_iq current, _iq alarm_level, _iq warnig_level)
{
_iq delta = current - warnig_level;
_iq max_delta = alarm_level - warnig_level;
if (delta <= 0 || max_delta <= 0) {
return CONST_IQ_1;
} else {
if (delta>=max_delta)
return 0;
else
return CONST_IQ_1 - _IQdiv(delta, max_delta);
}
}

View File

@ -1,15 +0,0 @@
/*
* limit_lib.h
*
* Created on: 15 àâã. 2024 ã.
* Author: yura
*/
#ifndef SRC_MAIN_LIMIT_LIB_H_
#define SRC_MAIN_LIMIT_LIB_H_
_iq linear_decrease(float current, int alarm_level, int warnig_level);
_iq linear_decrease_iq(_iq current, _iq alarm_level, _iq warnig_level);
#endif /* SRC_MAIN_LIMIT_LIB_H_ */

View File

@ -1,237 +0,0 @@
/*
* limit_power.c
*
* Created on: 15 àâã. 2024 ã.
* Author: yura
*/
#include "IQmathLib.h"
#include <adc_tools.h>
#include <detect_overload.h>
#include <edrk_main.h>
#include <params_motor.h>
#include <params_pwm24.h>
#include "mathlib.h"
#include "math_pi.h"
#include "limit_power.h"
#include "limit_lib.h"
#include "pll_tools.h"
#include "uom_tools.h"
#define KOEF_50HZ (FREQ_PWM*2.0*50.0/PI)
#define LEVEL_01HZ_IQ _IQ(10.0/KOEF_50HZ) // 0.1 HZ
_iq level_50hz = _IQmpyI32(LEVEL_01HZ_IQ, 500);
_iq level_minimal_level_work_hz = _IQmpyI32(LEVEL_01HZ_IQ, 350);
_iq delta_freq_test = 0;
//_iq level_01hz = _IQ(LEVEL_01HZ);
//#define LEVEL_50HZ (5000.0/KOEF_50HZ) // 50 HZ
//#define LEVEL_05HZ (50.0/KOEF_50HZ) // 50 HZ
//
//#define LEVEL_3HZ (300.0/KOEF_50HZ) // 50 HZ
//#define LEVEL_2HZ (200.0/KOEF_50HZ) // 50 HZ
//#define LEVEL_1HZ (100.0/KOEF_50HZ) // 50 HZ
#define LEVEL1_FREQ_DECR 10 // 1.5 Hz îò 49.0
#define LEVEL2_FREQ_DECR 100 // 10 Hz äî 40
//#define LEVEL1_FREQ_DECR 15 // 1.5 Hz îò 48.5
//#define LEVEL2_FREQ_DECR 100 // 10 Hz äî 40
#define PLUS_LIMIT_KOEFFS 0.0001
#define MINUS_LIMIT_KOEFFS 0.05
#define MAX_COUNT_GO_UOM (FREQ_PWM*5) // 5 sec
#define SET_LIMIT_UOM 0.5
void calc_all_limit_koeffs(void)
{
_iq sum_limit, delta_freq;
static unsigned int prev_uom = 0;
static int flag_enable_go_uom = 0;
static _iq level1_freq_decr = _IQmpyI32(LEVEL_01HZ_IQ, LEVEL1_FREQ_DECR);
static _iq level2_freq_decr = _IQmpyI32(LEVEL_01HZ_IQ, LEVEL2_FREQ_DECR);
static _iq iq_set_limit_uom = _IQ(SET_LIMIT_UOM);
static unsigned int count_go_uom = 0;
static _iq iq_plus_limit_koeffs = _IQ(PLUS_LIMIT_KOEFFS);
static _iq iq_minus_limit_koeffs = _IQ(MINUS_LIMIT_KOEFFS);
static long freq_test = 30;
//*LEVEL_01HZ_IQ;
static _iq minus_delta_freq_test = _IQdiv32(LEVEL_01HZ_IQ); // 0.1/32
static int uom_test = 50;
static int prev_imit_limit_freq = 0, prev_imit_limit_uom = 0;
static _iq iq_new_uom_level_kwt = 0;
update_uom();
// temper
edrk.all_limit_koeffs.local_temper_limit = edrk.temper_limit_koeffs.sum_limit;
// uin_freq
if (edrk.Status_Ready.bits.ready_final) //|| edrk.imit_limit_freq
{
get_freq_50hz_iq();
// freq = LEVEL_50HZ - edrk.iq_freq_50hz;
if (edrk.imit_limit_freq && prev_imit_limit_freq == 0)
delta_freq_test = _IQmpyI32(LEVEL_01HZ_IQ, freq_test);
if (delta_freq_test>0)
{
if (delta_freq_test>0)
delta_freq_test -= minus_delta_freq_test;
if (delta_freq_test<0)
delta_freq_test = 0;
}
if (edrk.iq_freq_50hz>level_minimal_level_work_hz)
{
edrk.all_limit_koeffs.local_uin_freq_limit = linear_decrease_iq( (level_50hz - edrk.iq_freq_50hz),
level2_freq_decr, level1_freq_decr);
}
else
edrk.all_limit_koeffs.local_uin_freq_limit = CONST_IQ_1;
}
else
{
edrk.all_limit_koeffs.local_uin_freq_limit = CONST_IQ_1;
}
prev_imit_limit_freq = edrk.imit_limit_freq;
//
/// UOM
//
if (edrk.from_uom.ready || edrk.set_limit_uom_50)
{
if (edrk.set_limit_uom_50)
{
edrk.from_uom.level_value = uom_test;
}
if (edrk.imit_limit_uom && prev_imit_limit_uom == 0)
edrk.from_uom.level_value++;
if (prev_uom!=edrk.from_uom.level_value && edrk.from_uom.level_value > prev_uom)
{
if (edrk.iq_power_kw_full_filter_abs > edrk.from_uom.iq_level_value_kwt)
flag_enable_go_uom = 1;
}
else
flag_enable_go_uom = 0;
if (flag_enable_go_uom)
{
count_go_uom = MAX_COUNT_GO_UOM;
edrk.all_limit_koeffs.local_uom_limit = iq_set_limit_uom; // äàåì ñáðîñ
}
if (count_go_uom)
{
// äåðæèì ñáðîñ
count_go_uom--;
}
else
edrk.all_limit_koeffs.local_uom_limit = CONST_IQ_1; // âîçâðàùàåìñÿ
prev_uom = edrk.from_uom.level_value;
}
else
{
edrk.power_limit.bits.limit_from_uom_fast = 0;
edrk.all_limit_koeffs.uom_limit = CONST_IQ_1;
prev_uom = 0;
}
prev_imit_limit_uom = edrk.imit_limit_uom;
// if ()
//// temper
edrk.all_limit_koeffs.temper_limit = zad_intensiv_q(iq_plus_limit_koeffs, iq_minus_limit_koeffs,
edrk.all_limit_koeffs.temper_limit,
edrk.all_limit_koeffs.local_temper_limit);
edrk.power_limit.bits.limit_by_temper = (edrk.all_limit_koeffs.temper_limit<CONST_IQ_1) ? 1 : 0;
////// freq
edrk.all_limit_koeffs.uin_freq_limit = zad_intensiv_q(iq_plus_limit_koeffs, iq_minus_limit_koeffs,
edrk.all_limit_koeffs.uin_freq_limit,
edrk.all_limit_koeffs.local_uin_freq_limit);
edrk.power_limit.bits.limit_from_freq = (edrk.all_limit_koeffs.uin_freq_limit<CONST_IQ_1) ? 1 : 0;
///// uom
edrk.all_limit_koeffs.uom_limit = zad_intensiv_q(iq_plus_limit_koeffs, iq_minus_limit_koeffs,
edrk.all_limit_koeffs.uom_limit,
edrk.all_limit_koeffs.local_uom_limit);
edrk.power_limit.bits.limit_from_uom_fast = (edrk.all_limit_koeffs.uom_limit<CONST_IQ_1) ? 1 : 0;
// sum_limit
sum_limit = edrk.all_limit_koeffs.temper_limit;
sum_limit = _IQmpy(sum_limit, edrk.all_limit_koeffs.moment_limit );
sum_limit = _IQmpy(sum_limit, edrk.all_limit_koeffs.power_limit );
sum_limit = _IQmpy(sum_limit, edrk.all_limit_koeffs.uin_freq_limit );
sum_limit = _IQmpy(sum_limit, edrk.all_limit_koeffs.uom_limit );
edrk.all_limit_koeffs.sum_limit = sum_limit;
}
void init_all_limit_koeffs(void)
{
edrk.all_limit_koeffs.moment_limit = CONST_IQ_1;
edrk.all_limit_koeffs.power_limit = CONST_IQ_1;
edrk.all_limit_koeffs.temper_limit = CONST_IQ_1;
edrk.all_limit_koeffs.uin_freq_limit = CONST_IQ_1;
edrk.all_limit_koeffs.uom_limit = CONST_IQ_1;
edrk.all_limit_koeffs.sum_limit = CONST_IQ_1;
edrk.all_limit_koeffs.local_moment_limit = CONST_IQ_1;
edrk.all_limit_koeffs.local_power_limit = CONST_IQ_1;
edrk.all_limit_koeffs.local_temper_limit = CONST_IQ_1;
edrk.all_limit_koeffs.local_uin_freq_limit = CONST_IQ_1;
edrk.all_limit_koeffs.local_uom_limit = CONST_IQ_1;
edrk.all_limit_koeffs.local_sum_limit = CONST_IQ_1;
}

View File

@ -1,21 +0,0 @@
/*
* limit_power.h
*
* Created on: 15 àâã. 2024 ã.
* Author: yura
*/
#ifndef SRC_MAIN_LIMIT_POWER_H_
#define SRC_MAIN_LIMIT_POWER_H_
void calc_all_limit_koeffs(void);
void init_all_limit_koeffs(void);
extern _iq level_50hz, delta_freq_test;
#endif /* SRC_MAIN_LIMIT_POWER_H_ */

View File

@ -40,11 +40,27 @@ int no_write = 0; //
int no_write_slow = 0; // Флаг, чтобы не писать (если что)
#pragma CODE_SECTION(clear_logpar,".fast_run");
void clear_logpar()
{
int i;
for(i=0;i<SIZE_LOGS_ARRAY;i++)
logpar.logs[i] = 0;
void clear_logpar() {
logpar.log1 = 0;
logpar.log2 = 0;
logpar.log3 = 0;
logpar.log4 = 0;
logpar.log5 = 0;
logpar.log6 = 0;
logpar.log7 = 0;
logpar.log8 = 0;
logpar.log9 = 0;
logpar.log10 = 0;
logpar.log11 = 0;
logpar.log12 = 0;
logpar.log13 = 0;
logpar.log14 = 0;
logpar.log15 = 0;
logpar.log16 = 0;
logpar.log17 = 0;
logpar.log18 = 0;
logpar.log19 = 0;
logpar.log20 = 0;
}
// Запись двух младших байтов аргумента в памyть, где логи лежат

View File

@ -15,7 +15,6 @@
#define SLOW_LOG 1
#define FAST_LOG 0
#define SIZE_LOGS_ARRAY 90
#ifdef __cplusplus
extern "C" {
@ -26,122 +25,41 @@ typedef struct
int stop_log_level_1;
int stop_log_level_2;
int stop_log_level_3;
int stop_log_slow_level_1;
int stop_log_slow_level_2;
int stop_log_slow_level_3;
int log1;
int log2;
int log3;
int log4;
int log5;
int log6;
int log7;
int log8;
int log9;
int log10;
int log11;
int log12;
int log13;
int log14;
int log15;
int log16;
int log17;
int log18;
int log19;
int log20;
int logs[SIZE_LOGS_ARRAY];
long addres_mem; //Àäðåñ ïàìyòè äëy çàïèñè ëîãîâ
// int log1;
// int log2;
// int log3;
// int log4;
// int log5;
// int log6;
// int log7;
// int log8;
// int log9;
// int log10;
// int log11;
// int log12;
// int log13;
// int log14;
// int log15;
// int log16;
// int log17;
// int log18;
// int log19;
// int log20;
//
// int log21;
// int log22;
// int log23;
// int log24;
// int log25;
// int log26;
// int log27;
// int log28;
// int log29;
// int log30;
//
// int log31;
// int log32;
// int log33;
// int log34;
// int log35;
// int log36;
// int log37;
// int log38;
// int log39;
// int log40;
//
// int log41;
// int log42;
// int log43;
// int log44;
// int log45;
// int log46;
// int log47;
// int log48;
// int log49;
// int log50;
//
// int log51;
// int log52;
// int log53;
// int log54;
// int log55;
// int log56;
// int log57;
// int log58;
// int log59;
// int log60;
//
// int log61;
// int log62;
// int log63;
// int log64;
// int log65;
// int log66;
// int log67;
// int log68;
// int log69;
// int log70;
//
// int log71;
// int log72;
// int log73;
// int log74;
// int log75;
//
// int log76;
// int log77;
// int log78;
// int log79;
// int log80;
// int log81;
// int log82;
// int log83;
// int log84;
// int log85;
//
// int log86;
// int log87;
// int log88;
// int log89;
// int log90;
// long addres_mem; //Àäðåñ ïàìyòè äëy çàïèñè ëîãîâ
//
// int count_log_params_fast_log; //Êîëè÷åñòâî çàïèñûâàåìûõ â ëîã ïàðàìåòðîâ
// int start_write_fast_log; //Íà÷àëî çàïèñè ëîãà, äëÿ îïðåäåëåíèÿ count_log_params_fast_log
// long real_finish_addres_mem; //Àäðåñ ïàìyòè äëy çàïèñè ëîãîâ
int count_log_params_fast_log; //Êîëè÷åñòâî çàïèñûâàåìûõ â ëîã ïàðàìåòðîâ
int start_write_fast_log; //Íà÷àëî çàïèñè ëîãà, äëÿ îïðåäåëåíèÿ count_log_params_fast_log
long real_finish_addres_mem; //Àäðåñ ïàìyòè äëy çàïèñè ëîãîâ
} LOGSPARAMS;
#define LOGSPARAMS_DEFAULTS { 0,0,0, 0,0,0, \
{0} \
}
#define LOGSPARAMS_DEFAULTS { 0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0, \
0,0,0,0,0,0,0,0, \
0,0,0,0,0,0 }

File diff suppressed because it is too large Load Diff

View File

@ -1,86 +0,0 @@
/*
* logs_hmi.h
*
* Created on: 28 àâã. 2024 ã.
* Author: Evgeniy_Sokolov
*/
#ifndef SRC_MAIN_LOGS_HMI_H_
#define SRC_MAIN_LOGS_HMI_H_
#define _LOG_HMI_SMALL_TEST 0//1
#define PLACE_STORE_LOG_PULT_SD 1 //SD
#define PLACE_STORE_LOG_PULT_USB 2 //USB Flash
typedef struct {
int send_log;
// int new_send_log_checked;
unsigned long log_size_sent;
// int flag_data_received;
// unsigned int number_of_log;
unsigned long count_write_to_modbus;
// unsigned long current_address;
unsigned long start_log_address;
// int log_address_step;
int step;
int progress_bar;
int enable_progress_bar;
int cleanLogs;
int tick_step;
// int tick_finish;
int flag_log_array_sended;
int flag_start_log_array_sent;
int flag_log_array_sent_process;
int count_data_in_buf;
unsigned long count_sended_to_pult;
unsigned long max_size_logs_hmi;
int tick_step2;
int tick_step3;
int tick_step4;
int tick_step5;
int n_log_array_sended;
unsigned long max_size_logs_hmi_small;
unsigned long max_size_logs_hmi_full;
int saveLogsToSDCard;
int ReportLogOut;
int sdusb;
} t_Logs_with_modbus;
#define LOGS_WITH_MODBUS_DEFAULTS {0,0,0,0,0, 0,0,0,0, 0,0,0,0,0, 0, 0,0,0,0,0, 0,0, 0,0,0}
extern t_Logs_with_modbus log_to_HMI;
#define LOG_START_ADRES 0xA0000UL
#define LOG_END_ADRES 0xF0000UL
#define LOG_BUFFER_SIZE 0x50000UL //0x100UL
void fillLogArea(); //TODO for testing only
int alarm_log_get_data(unsigned long pos, int type_log);
int writeLogsArray(int flag_next);
static void prepareWriteLogsArray(void);
static int fillAnalogDataArrayForLogSend(void);
int sendLogToHMI(int status_ok);
void run_store_slow_logs(void);
#endif /* SRC_MAIN_LOGS_HMI_H_ */

View File

@ -1,586 +0,0 @@
/*
* master_slave.c
*
* Created on: 13 íîÿá. 2024 ã.
* Author: Evgeniy_Sokolov
*/
#include <edrk_main.h>
#include <params.h>
#include <params_alg.h>
#include <params_norma.h>
#include <params_pwm24.h>
#include <params_temper_p.h>
#include <project.h>
#include "IQmathLib.h"
#include "mathlib.h"
#include <optical_bus.h>
#include "synhro_tools.h"
#include "master_slave.h"
//////////////////////////////////////////////////////////
#pragma DATA_SECTION(buf_log_master_slave_status,".slow_vars");
unsigned int buf_log_master_slave_status[SIZE_LOG_MASTER_SLAVE_STATUS] = {0};
//AUTO_MASTER_SLAVE_DATA buf2[SIZE_BUF1] = {0};
//AUTO_MASTER_SLAVE_DATA buf3[SIZE_BUF1] = {0};
//OPTICAL_BUS_DATA_LOW_CMD buf4[SIZE_BUF1] = {0};
//OPTICAL_BUS_DATA_LOW_CMD buf5[SIZE_BUF1] = {0};
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
void auto_select_master_slave(void)
{
static unsigned int count_try_master = 0;
static unsigned int count_wait_answer_confirm_mode = 0;
static unsigned int count_wait_slave_try_master = 0;
unsigned int err_confirm_mode = 0; // îøèáêà ïîäòâåðæäåíèÿ ðåæèìà äðóãèì Ï×
static unsigned int c_buf_log_master_slave_status = 0, prev_status = 0;
// logs master_slave_status
if (edrk.auto_master_slave.status != prev_status)
{
c_buf_log_master_slave_status++;
if (c_buf_log_master_slave_status>=SIZE_LOG_MASTER_SLAVE_STATUS)
c_buf_log_master_slave_status = 0;
buf_log_master_slave_status[c_buf_log_master_slave_status] = edrk.auto_master_slave.status;
}
prev_status = edrk.auto_master_slave.status;
//end logs master_slave_status
if (edrk.ms.ready2==0 && edrk.errors.e7.bits.AUTO_SET_MASTER==0)
{
edrk.auto_master_slave.remoute.all = 0;
edrk.auto_master_slave.local.all = 0;
edrk.auto_master_slave.prev_remoute.all = edrk.auto_master_slave.remoute.all;
edrk.auto_master_slave.prev_local.all = edrk.auto_master_slave.local.all;
edrk.auto_master_slave.status = 1;
// if (prev_ready!=edrk.ms.ready2)
// for (c_buf=0;c_buf<SIZE_BUF1;c_buf++)
// {
// buf2[c_buf].all = buf3[c_buf].all = buf1[c_buf] = buf4[c_buf].all = buf5[c_buf].all =0;
// }
//
// c_buf = 0;
//
// prev_ready = edrk.ms.ready2;
clear_wait_synhro_optical_bus();
return;
}
// else
// prev_ready = edrk.ms.ready2;
if (edrk.errors.e7.bits.AUTO_SET_MASTER)
{
edrk.to_second_pch.bits.MASTER = edrk.auto_master_slave.local.bits.master;
edrk.auto_master_slave.local.bits.master = 0;
edrk.auto_master_slave.local.bits.slave = 0;
edrk.auto_master_slave.local.bits.try_master = 0;
edrk.auto_master_slave.local.bits.try_slave = 0;
edrk.auto_master_slave.local.bits.nothing = 1;
// edrk.auto_master_slave.prev_remoute.all = edrk.auto_master_slave.remoute.all;
// edrk.auto_master_slave.prev_local.all = edrk.auto_master_slave.local.all;
// edrk.auto_master_slave.status = 10;
return;
}
edrk.auto_master_slave.prev_status = edrk.auto_master_slave.status;
// c_buf++;
// if (c_buf>=SIZE_BUF1)
// c_buf = 0;
//
// buf1[c_buf] = edrk.auto_master_slave.status;
// buf2[c_buf].all = edrk.auto_master_slave.local.all;
// buf3[c_buf].all = edrk.auto_master_slave.remoute.all;
// buf4[c_buf].all = optical_read_data.data.cmd.all;
// buf5[c_buf].all = optical_write_data.data.cmd.all;
//
// ñáðîñèì ñ÷åò÷èê âðåìåíè ïåðåõîäà íà ìàñòåð
if (edrk.auto_master_slave.local.bits.try_master==0 ||
(edrk.auto_master_slave.prev_local.bits.try_master != edrk.auto_master_slave.local.bits.try_master && edrk.auto_master_slave.local.bits.try_master==1))
count_try_master = 0;
// åñëè øèíà OPTICAL_BUS ñäîõëà, âûõîäèì
if (edrk.errors.e7.bits.WRITE_OPTBUS==1 || edrk.errors.e7.bits.READ_OPTBUS==1 ||
edrk.warnings.e7.bits.WRITE_OPTBUS==1 || edrk.warnings.e7.bits.READ_OPTBUS==1)
{
if (edrk.errors.e7.bits.WRITE_OPTBUS==1 || edrk.errors.e7.bits.READ_OPTBUS==1)
{
// øèíà íå ðàáîòàåò, è òîò Ï× âêëþ÷åí
// çíà÷èò ÷òî-òî ñëó÷èëîñü - âûêëþ÷àåìñÿ
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.remoute.bits.nothing = 1;
edrk.auto_master_slave.remoute.bits.master = 0;
edrk.auto_master_slave.remoute.bits.slave = 0;
edrk.auto_master_slave.remoute.bits.try_master = 0;
edrk.auto_master_slave.remoute.bits.try_slave = 0;
edrk.auto_master_slave.local.bits.master = 0;
edrk.auto_master_slave.local.bits.slave = 0;
edrk.auto_master_slave.local.bits.try_master = 0;
edrk.auto_master_slave.local.bits.try_slave = 0;
edrk.auto_master_slave.local.bits.nothing = 1;
edrk.auto_master_slave.status = 10;
}
else
{
// øèíà íå ðàáîòàåò, è òîò Ï× âûêëþ÷åí
// çíà÷èò ìû ñðàçó ìàñòåð
edrk.warnings.e7.bits.AUTO_SET_MASTER = 1;
edrk.auto_master_slave.remoute.bits.nothing = 1;
edrk.auto_master_slave.remoute.bits.master = 0;
edrk.auto_master_slave.remoute.bits.slave = 0;
edrk.auto_master_slave.remoute.bits.try_master = 0;
edrk.auto_master_slave.remoute.bits.try_slave = 0;
edrk.auto_master_slave.local.bits.master = 1;
edrk.auto_master_slave.local.bits.slave = 0;
edrk.auto_master_slave.local.bits.try_master = 0;
edrk.auto_master_slave.local.bits.try_slave = 0;
edrk.auto_master_slave.local.bits.nothing = 1;
edrk.auto_master_slave.status = 2;
}
edrk.auto_master_slave.remoute.bits.sync_line_detect = 0;
edrk.auto_master_slave.remoute.bits.bus_off = 1;
edrk.auto_master_slave.remoute.bits.sync1_2 = 0;
}
else
{
edrk.warnings.e7.bits.AUTO_SET_MASTER = 0;
edrk.auto_master_slave.remoute.bits.bus_off = 0;
// ñèíõðîíèçèðóåì ñâîè ïðîãðàììû ÷åðåç OPTICAL_BUS
if (wait_synhro_optical_bus()==1)
{
edrk.auto_master_slave.status = 50; // wait synhro
}
else
{
edrk.auto_master_slave.remoute.bits.master = optical_read_data.data.cmd.bit.master;
edrk.auto_master_slave.remoute.bits.slave = optical_read_data.data.cmd.bit.slave;
edrk.auto_master_slave.remoute.bits.try_master = optical_read_data.data.cmd.bit.maybe_master;
edrk.auto_master_slave.remoute.bits.sync1_2 = optical_read_data.data.cmd.bit.sync_1_2;
edrk.auto_master_slave.remoute.bits.sync_line_detect = optical_read_data.data.cmd.bit.sync_line_detect;
edrk.auto_master_slave.remoute.bits.tick = optical_read_data.data.cmd.bit.wdog_tick;
if (optical_read_data.data.cmd.bit.master==0 && optical_read_data.data.cmd.bit.slave==0)
edrk.auto_master_slave.remoute.bits.nothing = 1;
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 1
// òîò Ï× óæå ìàñòåð
if (edrk.auto_master_slave.remoute.bits.master)
{
// è ýòîò Ï× ìàñòåð ïî÷åìó-òî?
if (edrk.auto_master_slave.local.bits.master)
{
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 3;
}
else
{
// ýòîò Ï× åùå íå îïðåäåëèëñÿ, ïîýòîìó ïåðåõîä íà slave
if (edrk.auto_master_slave.local.bits.master==0 && edrk.auto_master_slave.local.bits.slave==0)
{
// edrk.auto_master_slave.local.bits.try_slave = 1;
// ñòàëè slave
edrk.auto_master_slave.local.bits.slave = 1;
// ñíÿëè ñâîé çàïðîñ íà ìàñòåðà åñëè îí áûë
edrk.auto_master_slave.local.bits.try_master = 0;
edrk.auto_master_slave.status = 4;
}
else
{
edrk.auto_master_slave.status = 21;
}
}
}
else
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 2
// òîò Ï× óæå slave
if (edrk.auto_master_slave.remoute.bits.slave)
{
// è ýòîò Ï× slave ïî÷åìó-òî?
if (edrk.auto_master_slave.local.bits.slave)
{
// áûë ïåðåõîä èç ìàñòåð â slave
if (edrk.auto_master_slave.prev_remoute.bits.slave==0)
{
if (edrk.Go)
{
// çàïóùåí ØÈÌ
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 5;
}
else
{
// ïðîáóåì ïåðåõâàòèòü master
edrk.auto_master_slave.local.bits.try_master = 1;
edrk.auto_master_slave.status = 6;
}
}
else
{
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 7;
}
}
else
{
// ýòîò Ï× åùå íå îïðåäåëèëñÿ, ïîýòîìó çàïðàøèâàåò íà master
if (edrk.auto_master_slave.local.bits.master==0 && edrk.auto_master_slave.local.bits.slave==0 && edrk.auto_master_slave.local.bits.try_master==0)
{
if (edrk.flag_second_PCH==0)
edrk.auto_master_slave.local.bits.try_master = 1;
if (edrk.flag_second_PCH==1)
edrk.auto_master_slave.local.bits.try_master = 1;
edrk.auto_master_slave.status = 8;
// edrk.auto_master_slave.local.bits.slave = 1;
}
else
// ýòîò Ï× óæå â çàïðîñå íà ìàñòåð, à òîò Ï× ïîäòâåðäèë â slave ÷òî îí íå ïðîòèâ.
if (edrk.auto_master_slave.local.bits.master==0 && edrk.auto_master_slave.local.bits.slave==0 && edrk.auto_master_slave.local.bits.try_master==1)
{
// ñòàëè ìàñòåðîì
edrk.auto_master_slave.local.bits.master = 1;
edrk.auto_master_slave.local.bits.try_master = 0;
edrk.auto_master_slave.status = 9;
// edrk.auto_master_slave.local.bits.slave = 1;
}
else
{
edrk.auto_master_slave.status = 22;
}
}
}
else
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 3
// òîò Ï× çàïðàøèâàåò ïåðåõîä íà ìàñòåð
if (edrk.auto_master_slave.remoute.bits.master==0
&& edrk.auto_master_slave.remoute.bits.slave==0
&& edrk.auto_master_slave.remoute.bits.try_master)
{
// à ýòîò Ï× slave
if (edrk.auto_master_slave.local.bits.slave)
{
// âðîäå íå íîðì, îñòàåìñÿ slave
// òóò íàäî ïîäîæäàòü íåêîòðîå âðåìÿ, ïîêà òîò Ï× íå ïîéìåò ÷òî ìû ñòàëè ñëåéâîì è ïåðåéäåò èç try_master â ìàñòåð
if (count_wait_slave_try_master<MAX_COUNT_WAIT_SLAVE_TRY_MASTER)
count_wait_slave_try_master++;
else
{
edrk.auto_master_slave.status = 10;
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
}
}
else
// à ýòîò Ï× master
if (edrk.auto_master_slave.local.bits.master)
{
// òóò ìû äîëæíû ïðèíÿòü ðåøåíèå îòäàâàòü ëè ñâîé ìàñòåð äðóãîìó Ï×?
// ïîêà âûñòàâèì îøèáêó
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 11;
}
else
// ýòîò Ï× íå ìàñòåð è íå ñëåéâ è íåò çàïðîñîâ îò íåãî íà ìàñòåð
if (edrk.auto_master_slave.local.bits.master==0 && edrk.auto_master_slave.local.bits.slave==0 && edrk.auto_master_slave.local.bits.try_master==0)
{
// ñòàíîâèìñÿ slave
edrk.auto_master_slave.local.bits.slave = 1;
edrk.auto_master_slave.status = 12;
count_wait_slave_try_master = 0; // îáíóëèì ñ÷åò÷èê, ò.ê. íàñ íàäî ÷òîá òîò Ï× ïîíÿë ÷òî ìû ñòàëè slave
}
else
// ýòîò Ï× íå ìàñòåð è íå ñëåéâ è åñòü çàïðîñ îò íåãî íà ìàñòåð, ò.å. îáà Ï× õîòÿò áûòü ìàñòåðàìè
if (edrk.auto_master_slave.local.bits.master==0 && edrk.auto_master_slave.local.bits.slave==0 && edrk.auto_master_slave.local.bits.try_master==1)
{
// ñòàíîâèìñÿ master ÷åðåç íåêîòîðîå âðåìÿ (äëÿ êàæäîãî Ï× âðåìÿ ðàçíîå)
if (edrk.flag_second_PCH==0)
{
//îáà õîòÿò, íî ïðèîòðèòåò äàåì âñåãäà ïåðâîìó
edrk.auto_master_slave.local.bits.master = 1;
edrk.auto_master_slave.local.bits.try_master = 0;
// if (count_try_master<MAX_COUNT_TRY_MASTER_BS1)
// count_try_master++;
// else
// edrk.auto_master_slave.local.bits.master = 1;
}
if (edrk.flag_second_PCH==1)
{
//îáà õîòÿò, íî ïðèîòðèòåò äàåì âñåãäà ïåðâîìó
edrk.auto_master_slave.local.bits.slave = 1;
edrk.auto_master_slave.local.bits.try_master = 0;
// if (count_try_master<MAX_COUNT_TRY_MASTER_BS2)
// count_try_master++;
// else
// edrk.auto_master_slave.local.bits.master = 1;
}
edrk.auto_master_slave.status = 13;
}
else
{
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 100;
}
}
else
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 4
// ýòîò Ï× çàïðàøèâàåò ïåðåõîä íà ìàñòåð
if (edrk.auto_master_slave.local.bits.master==0
&& edrk.auto_master_slave.local.bits.slave==0
&& edrk.auto_master_slave.local.bits.try_master)
{
// ñòàíîâèìñÿ master ÷åðåç íåêîòîðîå âðåìÿ (äëÿ êàæäîãî Ï× âðåìÿ ðàçíîå)
if (edrk.flag_second_PCH==0)
{
if (count_try_master<MAX_COUNT_TRY_MASTER_BS1)
{
count_try_master++;
edrk.auto_master_slave.status = 14;
}
else
{
edrk.auto_master_slave.local.bits.master = 1;
edrk.auto_master_slave.local.bits.try_master = 0;
edrk.auto_master_slave.status = 15;
}
}
if (edrk.flag_second_PCH==1)
{
if (count_try_master<MAX_COUNT_TRY_MASTER_BS2)
{
count_try_master++;
edrk.auto_master_slave.status = 14;
}
else
{
edrk.auto_master_slave.local.bits.master = 1;
edrk.auto_master_slave.local.bits.try_master = 0;
edrk.auto_master_slave.status = 15;
}
}
}
else
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 5
// òîò Ï× íè÷åãî íå äåëàåò
if (edrk.auto_master_slave.remoute.bits.master==0 && edrk.auto_master_slave.remoute.bits.slave==0 && edrk.auto_master_slave.remoute.bits.try_master==0)
{
// à ýòîò Ï× slave
if (edrk.auto_master_slave.local.bits.slave)
{
// áûëè â ñëåéâå, à òîò Ï× ïî÷åìó-òî ïîòåðÿë ðåæèì - îøèáêà èëè ïîïûòêà çàõâàòà ìàñòåðà!
if (edrk.auto_master_slave.prev_remoute.bits.master)
{
if (edrk.Go) // ïðè ØÈÌå âûðóáàåìñÿ.
{
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 24;
}
else
{
// à òóò âñå îê.
edrk.auto_master_slave.local.bits.slave = 0;
edrk.auto_master_slave.local.bits.master = 1;
edrk.auto_master_slave.status = 23;
}
}
else
{
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 16;
}
}
else
// à ýòîò Ï× master
if (edrk.auto_master_slave.local.bits.master)
{
// òóò ìû îñòåìñÿ ìàñòåðîì âðîäå?
// íî òîò Ï× íå ïîäòâåðäèë ïåðåõîä, îí äîëæåí ñòàòü ìàñòåðîì èëè ñëåéâîì
err_confirm_mode = 0;
// filter_err_count(&count_wait_answer_confirm_mode,
// MAX_COUNT_WAIT_ANSWER_CONFIRM_MODE,
// 1,
// 0);
if (err_confirm_mode)
{
// ìû ìàñòåð, íî òîò Ï× òàê è íå ïîíÿë ýòî
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 20;
}
else
edrk.auto_master_slave.status = 17;
}
else
{
// òóò ïûòàåìñÿ çàõâàòèòü ìàñòåð
if (edrk.flag_second_PCH==0)
edrk.auto_master_slave.local.bits.try_master = 1;
if (edrk.flag_second_PCH==1)
edrk.auto_master_slave.local.bits.try_master = 1;
edrk.auto_master_slave.status = 18;
}
}
else
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 5
//
{
// ÷òî-òî ïîøëî íå òàê
edrk.errors.e7.bits.AUTO_SET_MASTER |= 1;
edrk.auto_master_slave.status = 19;
}
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 6
//
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 7
//
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// 8
//
}
}
// optical_write_data.cmd.bit. = edrk.auto_master_slave.local.bits.slave;
edrk.to_second_pch.bits.MASTER = edrk.auto_master_slave.local.bits.master;
edrk.auto_master_slave.prev_remoute.all = edrk.auto_master_slave.remoute.all;
edrk.auto_master_slave.prev_local.all = edrk.auto_master_slave.local.all;
}
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////
void clear_errors_master_slave(void)
{
// if (edrk.errors.e7.bits.AUTO_SET_MASTER)
{
// if (edrk.errors.e7.bits.MASTER_SLAVE_SYNC
// || edrk.errors.e1.bits.NO_INPUT_SYNC_SIGNAL)
// edrk.ms.count_time_wait_ready1 = 0;
edrk.ms.count_time_wait_ready2 = 0;
edrk.ms.errors_count.alive_can_to_another_bs = 0;
edrk.ms.errors_count.alive_opt_bus_read = 0;
edrk.ms.errors_count.alive_opt_bus_write = 0;
edrk.ms.errors_count.alive_sync_line = 0;
edrk.ms.errors_count.alive_sync_line_local = 0;
edrk.ms.errors_count.another_rascepitel = 0;
edrk.ms.errors_count.fast_optical_alarm = 0;
edrk.ms.errors_count.input_alarm_another_bs = 0;
edrk.ms.errors_count.input_master_slave = 0;
edrk.ms.err_lock_signals.alive_can_to_another_bs = 0;
edrk.ms.err_lock_signals.alive_opt_bus_read = 0;
edrk.ms.err_lock_signals.alive_opt_bus_write = 0;
edrk.ms.err_lock_signals.alive_sync_line = 0;
edrk.ms.err_lock_signals.alive_sync_line_local = 0;
edrk.ms.err_lock_signals.another_rascepitel = 0;
edrk.ms.err_lock_signals.fast_optical_alarm = 0;
edrk.ms.err_lock_signals.input_alarm_another_bs = 0;
edrk.ms.err_lock_signals.input_master_slave = 0;
}
}
//////////////////////////////////////////////////////////

View File

@ -17,18 +17,5 @@ MODE_SLAVE
};
//////////////////////////////////////////////////////////
#define MAX_COUNT_TRY_MASTER_BS1 200//40 //15 //5
#define MAX_COUNT_TRY_MASTER_BS2 100//40 //15 //40 //20
#define MAX_COUNT_WAIT_ANSWER_CONFIRM_MODE 20
#define MAX_COUNT_WAIT_SLAVE_TRY_MASTER 100
#define SIZE_LOG_MASTER_SLAVE_STATUS 50
void auto_select_master_slave(void);
void clear_errors_master_slave(void);
#endif /* SRC_MASTER_SLAVE_H_ */

View File

@ -22,13 +22,7 @@
#include "xp_hwp.h"
#include "xp_project.h"
#include "modbus_table_v2.h"
#include "filter_v1.h"
#include "v_rotor_22220.h"
#include "log_params.h"
#include "break_regul.h"
#include "logs_hmi.h"
#include "CAN_Setup.h"
#include "params_temper_p.h"
void func_unpack_answer_from_TMS_RS232(CMD_TO_TMS_STRUCT *pcommand)
@ -107,8 +101,8 @@ void func_pack_answer_to_TMS(TMS_TO_TERMINAL_STRUCT *reply_a)
/* const óêàçàòåëü íà ñòðóêòóðó ñòàíäàðòíîé êîìàíäû
íàñòðîèëè íà áóôåð ïðèåìà */
// edrk.data_to_message2[1] = _IQtoF(filter.iqU_1_long)*NORMA_ACP;
// edrk.data_to_message2[2] = _IQtoF(filter.iqU_2_long)*NORMA_ACP;
//For instance
@ -153,6 +147,7 @@ void func_pack_answer_to_TMS(TMS_TO_TERMINAL_STRUCT *reply_a)
reply_a->analog_data.analog7_hi = HIBYTE(Data);
Data = _IQtoF(filter.iqIm_2)*NORMA_ACP;//project.adc[0].read.pbus.adc_value[3];
reply_a->analog_data.analog8_lo = LOBYTE(Data);
reply_a->analog_data.analog8_hi = HIBYTE(Data);
@ -168,31 +163,31 @@ void func_pack_answer_to_TMS(TMS_TO_TERMINAL_STRUCT *reply_a)
reply_a->analog_data.analog11_lo = LOBYTE(Data);
reply_a->analog_data.analog11_hi = HIBYTE(Data);
Data = (int) (edrk.temper_edrk.max_real_int_temper_air);//_IQtoF(edrk.f_stator)*F_STATOR_MAX;//
Data = (int) (edrk.temper_edrk.max_real_int_temper_air);//_IQtoF(edrk.f_stator)*F_STATOR_MAX;//
reply_a->analog_data.analog12_lo = LOBYTE(Data);
reply_a->analog_data.analog12_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.zadanie.iq_ZadanieU_Charge_rmp)*NORMA_ACP);//edrk.I_zad_vozbud;//
Data = fast_round(_IQtoF(edrk.zadanie.iq_ZadanieU_Charge_rmp)*NORMA_ACP);//edrk.I_zad_vozbud;//
reply_a->analog_data.analog13_lo = LOBYTE(Data);
reply_a->analog_data.analog13_hi = HIBYTE(Data);
Data = edrk.zadanie.oborots_zad;//edrk.I_zad_vozbud_exp;//
Data = edrk.zadanie.oborots_zad;//edrk.I_zad_vozbud_exp;//
reply_a->analog_data.analog14_lo = LOBYTE(Data);
reply_a->analog_data.analog14_hi = HIBYTE(Data);
Data = edrk.zadanie.power_zad;//edrk.I_cur_vozbud;//
Data = edrk.zadanie.power_zad;//edrk.I_cur_vozbud;//
reply_a->analog_data.analog15_lo = LOBYTE(Data);
reply_a->analog_data.analog15_hi = HIBYTE(Data);
Data = edrk.zadanie.Izad;//edrk.I_cur_vozbud_exp;//
Data = edrk.zadanie.Izad;//edrk.I_cur_vozbud_exp;//
reply_a->analog_data.analog16_lo = LOBYTE(Data);
reply_a->analog_data.analog16_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.Kplus)*1000.0);//edrk.W_zad_mA;//
Data = fast_round(_IQtoF(edrk.Kplus)*1000.0);//edrk.W_zad_mA;//
reply_a->analog_data.analog17_lo = LOBYTE(Data);
reply_a->analog_data.analog17_hi = HIBYTE(Data);
Data = fast_round(edrk.freq_50hz_1/10.0);//edrk.Zadanie2VozbudING;//
Data = fast_round(edrk.freq_50hz/10.0);//edrk.Zadanie2VozbudING;//
reply_a->analog_data.analog18_lo = LOBYTE(Data);
reply_a->analog_data.analog18_hi = HIBYTE(Data);
@ -204,16 +199,15 @@ Data = fast_round(_IQtoF(edrk.k_stator1)*10000.0);// edrk.W_from_all;
reply_a->analog_data.analog20_lo = LOBYTE(Data);
reply_a->analog_data.analog20_hi = HIBYTE(Data);
Data = _IQtoF(vect_control.iqId1)*NORMA_ACP;//0;//_IQtoF(edrk.test_rms_Iu)*NORMA_ACP; //fast_round(_IQtoF(WRotor.iqWRotorImpulses1)*NORMA_FROTOR*1000.0);// edrk.W_from_DISPLAY;
Data =_IQtoF(edrk.test_rms_Iu)*NORMA_ACP; //fast_round(_IQtoF(WRotor.iqWRotorImpulses1)*NORMA_FROTOR*1000.0);// edrk.W_from_DISPLAY;
reply_a->analog_data.analog21_lo = LOBYTE(Data);
reply_a->analog_data.analog21_hi = HIBYTE(Data);
Data = _IQtoF(vect_control.iqIq1)*NORMA_ACP;// 0;//_IQtoF(edrk.test_rms_Ua)*NORMA_ACP;// fast_round(_IQtoF(WRotor.iqWRotorImpulses2)*NORMA_FROTOR*1000.0);//600.0*1000000000.0/WRotor.iqWRotorImpulses1;//edrk.W_from_SVU;
Data =_IQtoF(edrk.test_rms_Ua)*NORMA_ACP;// fast_round(_IQtoF(WRotor.iqWRotorImpulses2)*NORMA_FROTOR*1000.0);//600.0*1000000000.0/WRotor.iqWRotorImpulses1;//edrk.W_from_SVU;
reply_a->analog_data.analog22_lo = LOBYTE(Data);
reply_a->analog_data.analog22_hi = HIBYTE(Data);
//Data = fast_round(_IQtoF(WRotor.iqWRotorSumFilter3)*NORMA_FROTOR*100.0*60.0);//edrk.oborots;//fast_round(_IQtoF(WRotorPBus.iqAngle1F)*360.0);//600.0*1000000000.0/WRotor.iqWRotorImpulses2;//edrk.W_from_ZADAT4IK;
Data = _IQtoF(WRotor.iqWRotorSumFilter) * NORMA_FROTOR*600.0;//edrk.oborots;
Data = edrk.oborots;//fast_round(_IQtoF(WRotorPBus.iqAngle1F)*360.0);//600.0*1000000000.0/WRotor.iqWRotorImpulses2;//edrk.W_from_ZADAT4IK;
reply_a->analog_data.analog23_lo = LOBYTE(Data);
reply_a->analog_data.analog23_hi = HIBYTE(Data);
@ -222,12 +216,11 @@ Data = fast_round(edrk.f_rotor_hz*100.0);//fast_round(_IQtoF(WRotorPBus.iqAngle2
reply_a->analog_data.analog24_hi = HIBYTE(Data);
//Data = _IQtoF(edrk.k_stator1)*10000;//;
Data = edrk.period_calc_pwm_int2;//fast_round(_IQtoF(rotor_22220.iqFdirty)*NORMA_FROTOR*1000.0);
Data = fast_round(_IQtoF(WRotor.iqWRotorCalcBeforeRegul1)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog25_lo = LOBYTE(Data);
reply_a->analog_data.analog25_hi = HIBYTE(Data);
Data = edrk.power_kw_full; //Ìîùíîñòü äâèãàòåëÿ òåêóùàÿ êÂò
//fast_round(_IQtoF(WRotor.iqWRotorCalcBeforeRegul2)*NORMA_FROTOR*1000.0);
Data = fast_round(_IQtoF(WRotor.iqWRotorCalcBeforeRegul2)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog26_lo = LOBYTE(Data);
reply_a->analog_data.analog26_hi = HIBYTE(Data);
@ -247,59 +240,56 @@ Data = edrk.period_calc_pwm_int1;
reply_a->analog_data.analog30_lo = LOBYTE(Data);
reply_a->analog_data.analog30_hi = HIBYTE(Data);
Data = (int)edrk.temper_acdrive.winding.max_real_int_temper;
reply_a->analog_data.analog31_lo = LOBYTE(Data);
reply_a->analog_data.analog31_hi = HIBYTE(Data);
Data = (int)edrk.temper_acdrive.bear.max_real_int_temper;
reply_a->analog_data.analog32_lo = LOBYTE(Data);
reply_a->analog_data.analog32_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[0]);
reply_a->analog_data.analog33_lo = LOBYTE(Data);
reply_a->analog_data.analog33_hi = HIBYTE(Data);
reply_a->analog_data.analog31_lo = LOBYTE(Data);
reply_a->analog_data.analog31_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[1]);
reply_a->analog_data.analog32_lo = LOBYTE(Data);
reply_a->analog_data.analog32_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[2]);
reply_a->analog_data.analog33_lo = LOBYTE(Data);
reply_a->analog_data.analog33_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[3]);
reply_a->analog_data.analog34_lo = LOBYTE(Data);
reply_a->analog_data.analog34_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[2]);
Data = (int)(edrk.temper_edrk.real_int_temper_u[4]);
reply_a->analog_data.analog35_lo = LOBYTE(Data);
reply_a->analog_data.analog35_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[3]);
Data = (int)(edrk.temper_edrk.real_int_temper_u[5]);
reply_a->analog_data.analog36_lo = LOBYTE(Data);
reply_a->analog_data.analog36_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[4]);
Data = (int)(edrk.temper_edrk.real_int_temper_u[6]);
reply_a->analog_data.analog37_lo = LOBYTE(Data);
reply_a->analog_data.analog37_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[5]);
Data = (int)(edrk.temper_edrk.real_int_temper_air[0]);
reply_a->analog_data.analog38_lo = LOBYTE(Data);
reply_a->analog_data.analog38_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_u[6]);
Data = (int)(edrk.temper_edrk.real_int_temper_air[1]);
reply_a->analog_data.analog39_lo = LOBYTE(Data);
reply_a->analog_data.analog39_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_air[0]);
Data = (int)(edrk.temper_edrk.real_int_temper_air[2]);
reply_a->analog_data.analog40_lo = LOBYTE(Data);
reply_a->analog_data.analog40_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_air[1]);
reply_a->analog_data.analog41_lo = LOBYTE(Data);
reply_a->analog_data.analog41_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_air[2]);
reply_a->analog_data.analog42_lo = LOBYTE(Data);
reply_a->analog_data.analog42_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_air[3]);
reply_a->analog_data.analog41_lo = LOBYTE(Data);
reply_a->analog_data.analog41_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_water[0]); // external
reply_a->analog_data.analog42_lo = LOBYTE(Data);
reply_a->analog_data.analog42_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_water[1]); // internal
reply_a->analog_data.analog43_lo = LOBYTE(Data);
reply_a->analog_data.analog43_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_water[0]); // external
Data = (int)edrk.temper_acdrive.winding.max_real_int_temper;
reply_a->analog_data.analog44_lo = LOBYTE(Data);
reply_a->analog_data.analog44_hi = HIBYTE(Data);
Data = (int)(edrk.temper_edrk.real_int_temper_water[1]); // internal
Data = (int)edrk.temper_acdrive.bear.max_real_int_temper;
reply_a->analog_data.analog45_lo = LOBYTE(Data);
reply_a->analog_data.analog45_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidF.OutMax)*NORMA_ACP);//edrk.auto_master_slave.prev_status;//fast_round(_IQtoF(edrk.zadanie.iq_ZadanieU_Charge_rmp)*NORMA_ACP);
Data = edrk.auto_master_slave.prev_status;//fast_round(_IQtoF(edrk.zadanie.iq_ZadanieU_Charge_rmp)*NORMA_ACP);
reply_a->analog_data.analog46_lo = LOBYTE(Data);
reply_a->analog_data.analog46_hi = HIBYTE(Data);
@ -321,14 +311,15 @@ Data = edrk.period_calc_pwm_int1;
reply_a->analog_data.analog51_lo = LOBYTE(Data);
reply_a->analog_data.analog51_hi = HIBYTE(Data);
Data = _IQtoF(vect_control.iqId2)*NORMA_ACP;//0;//fast_round( _IQtoF(edrk.zadanie.iq_k_u_disbalance_rmp)*100.0);
Data = fast_round( _IQtoF(edrk.zadanie.iq_k_u_disbalance_rmp)*100.0);
reply_a->analog_data.analog52_lo = LOBYTE(Data);
reply_a->analog_data.analog52_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.zadanie.iq_limit_power_zad_rmp)*NORMA_ACP*NORMA_ACP/1000.0);
Data = edrk.auto_master_slave.status;//fast_round(_IQtoF(edrk.zadanie.iq_kplus_u_disbalance_rmp)*1000.0);
reply_a->analog_data.analog53_lo = LOBYTE(Data);
reply_a->analog_data.analog53_hi = HIBYTE(Data);
if (edrk.Mode_ScalarVectorUFConst == ALG_MODE_FOC_OBOROTS || edrk.Mode_ScalarVectorUFConst == ALG_MODE_FOC_POWER) {
Data = fast_round(_IQtoF(turns.pidFvect.Out)*NORMA_ACP);
reply_a->analog_data.analog54_lo = LOBYTE(Data);
@ -344,7 +335,7 @@ Data = edrk.period_calc_pwm_int1;
Data = fast_round(_IQtoF(simple_scalar1.pidF.Out)*NORMA_ACP);
reply_a->analog_data.analog54_lo = LOBYTE(Data);
reply_a->analog_data.analog54_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidF.OutMin)*NORMA_ACP);
Data = fast_round(_IQtoF(simple_scalar1.pidF.OutMax)*NORMA_ACP);
reply_a->analog_data.analog55_lo = LOBYTE(Data);
reply_a->analog_data.analog55_hi = HIBYTE(Data);
Data =fast_round(_IQtoF(simple_scalar1.pidPower.Out)*NORMA_ACP);
@ -355,18 +346,13 @@ Data = edrk.period_calc_pwm_int1;
reply_a->analog_data.analog57_lo = LOBYTE(Data);
reply_a->analog_data.analog57_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.Izad)*NORMA_ACP);
reply_a->analog_data.analog58_lo = LOBYTE(Data);
reply_a->analog_data.analog58_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.master_Iq)*NORMA_ACP);
reply_a->analog_data.analog59_lo = LOBYTE(Data);
reply_a->analog_data.analog59_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.mzz_zad_in2)*NORMA_ACP);//count_transmited++;
Data = fast_round(_IQtoF(simple_scalar1.mzz_zad)*NORMA_ACP);//count_transmited++;
reply_a->analog_data.analog60_lo = LOBYTE(Data);
reply_a->analog_data.analog60_hi = HIBYTE(Data);
//
@ -386,153 +372,25 @@ Data = edrk.period_calc_pwm_int1;
reply_a->analog_data.analog64_lo = LOBYTE(Data);
reply_a->analog_data.analog64_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidPower.SatErr)*NORMA_ACP);//project.cds_tk[3].optical_data_in.local_count_error;
Data = project.cds_tk[3].optical_data_in.local_count_error;
reply_a->analog_data.analog65_lo = LOBYTE(Data);
reply_a->analog_data.analog65_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidPower.Fdb)*NORMA_ACP*NORMA_ACP/1000.0);//project.cds_tk[3].optical_data_out.local_count_error;
Data = project.cds_tk[3].optical_data_out.local_count_error;
reply_a->analog_data.analog66_lo = LOBYTE(Data);
reply_a->analog_data.analog66_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidPower.Ref)*NORMA_ACP*NORMA_ACP/1000.0);//////optical_read_data.count_error_wdog;
Data = optical_read_data.count_error_wdog;
reply_a->analog_data.analog67_lo = LOBYTE(Data);
reply_a->analog_data.analog67_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidPower.Up)*NORMA_ACP);//edrk.auto_master_slave.status;//fast_round(_IQtoF(edrk.zadanie.iq_kplus_u_disbalance_rmp)*1000.0);
Data = edrk.period_calc_pwm_int2;
reply_a->analog_data.analog68_lo = LOBYTE(Data);
reply_a->analog_data.analog68_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(pll1.vars.pll_Uq)*NORMA_ACP);
reply_a->analog_data.analog69_lo = LOBYTE(Data);
reply_a->analog_data.analog69_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(pll1.vars.pll_Ud)*NORMA_ACP);
reply_a->analog_data.analog70_lo = LOBYTE(Data);
reply_a->analog_data.analog70_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.bpsi_curent)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog71_lo = LOBYTE(Data);
reply_a->analog_data.analog71_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(WRotor.iqWRotorSumFilter2)*NORMA_FROTOR*1000.0); //iqFlong
reply_a->analog_data.analog72_lo = LOBYTE(Data);
reply_a->analog_data.analog72_hi = HIBYTE(Data);
//Data = fast_round(_IQtoF(WRotor.iqWRotorCalc1)*NORMA_FROTOR*1000.0);
Data = fast_round(_IQtoF(edrk.from_uom.iq_level_value_kwt)*NORMA_ACP*NORMA_ACP/1000.0);// ;//edrk.from_uom.level_value;//fast_round(_IQtoF(rotor_22220.iqFdirty)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog73_lo = LOBYTE(Data);
reply_a->analog_data.analog73_hi = HIBYTE(Data);
//Data = fast_round(_IQtoF(WRotor.iqWRotorCalc2)*NORMA_FROTOR*1000.0);
Data = _IQtoF(vect_control.iqIq2)*NORMA_ACP;//0;//fast_round(_IQtoF(rotor_22220.iqF)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog74_lo = LOBYTE(Data);
reply_a->analog_data.analog74_hi = HIBYTE(Data);
//Data = fast_round(_IQtoF(WRotor.iqWRotorImpulsesBeforeRegul1)*NORMA_FROTOR*1000.0);// edrk.W_from_DISPLAY;
Data = fast_round(_IQtoF(WRotor.iqWRotorSumFilter)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog75_lo = LOBYTE(Data);
reply_a->analog_data.analog75_hi = HIBYTE(Data);
//Data = fast_round(_IQtoF(WRotor.iqWRotorImpulsesBeforeRegul2)*NORMA_FROTOR*1000.0);//600.0*1000000000.0/WRotor.iqWRotorImpulses1;//edrk.W_from_SVU;
Data = fast_round(_IQtoF(simple_scalar1.mzz_zad_int)*NORMA_ACP);//;//0;//fast_round(_IQtoF(rotor_22220.iqFlong)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog76_lo = LOBYTE(Data);
reply_a->analog_data.analog76_hi = HIBYTE(Data);
//Data = fast_round(_IQtoF(WRotor.iqWRotorImpulses1)*NORMA_FROTOR*1000.0);// edrk.W_from_DISPLAY;
Data = _IQtoF(simple_scalar1.Izad)*NORMA_ACP_RMS;// 0;//fast_round(_IQtoF(WRotor.iqWRotorSumRamp)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog77_lo = LOBYTE(Data);
reply_a->analog_data.analog77_hi = HIBYTE(Data);
//Data = fast_round(_IQtoF(WRotor.iqWRotorImpulses2)*NORMA_FROTOR*1000.0);//600.0*1000000000.0/WRotor.iqWRotorImpulses1;//edrk.W_from_SVU;
Data = WRotor.RotorDirectionSlow;
reply_a->analog_data.analog78_lo = LOBYTE(Data);
reply_a->analog_data.analog78_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.iqKoefOgran)*1000.0);//0;//fast_round(_IQtoF(WRotor.iqWRotorSum)*NORMA_FROTOR*1000.0);// edrk.W_from_DISPLAY;
reply_a->analog_data.analog79_lo = LOBYTE(Data);
reply_a->analog_data.analog79_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.iqKoefOgranIzad)*1000.0);//0;//fast_round(_IQtoF(WRotor.iqWRotorSumFilter)*NORMA_FROTOR*1000.0);//600.0*1000000000.0/WRotor.iqWRotorImpulses1;//edrk.W_from_SVU;
reply_a->analog_data.analog80_lo = LOBYTE(Data);
reply_a->analog_data.analog80_hi = HIBYTE(Data);
Data = log_params.cur_volume_of_slow_log;//edrk.power_kw_full; //Ìîùíîñòü äâèãàòåëÿ òåêóùàÿ êÂò
// Data = (_IQtoF((analog.Power) * 9000.0)); //Ìîùíîñòü äâèãàòåëÿ òåêóùàÿ êÂò
//_IQtoF(analog.iqIin_1)*NORMA_ACP;//project.adc[0].read.pbus.adc_value[0];
reply_a->analog_data.analog81_lo = LOBYTE(Data);
reply_a->analog_data.analog81_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.zadanie.iq_limit_power_zad)*NORMA_ACP*NORMA_ACP/1000.0);
reply_a->analog_data.analog82_lo = LOBYTE(Data);
reply_a->analog_data.analog82_hi = HIBYTE(Data);
Data = break_result_1;//fast_round(_IQtoF(WRotor.iqWRotorSumFilter3)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog83_lo = LOBYTE(Data);
reply_a->analog_data.analog83_hi = HIBYTE(Data);
Data = break_result_2;//WRotorPBus.RotorDirectionInstant;
reply_a->analog_data.analog84_lo = LOBYTE(Data);
reply_a->analog_data.analog84_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.all_limit_koeffs.sum_limit)*1000.0);//WRotorPBus.RotorDirectionCount;
reply_a->analog_data.analog85_lo = LOBYTE(Data);
reply_a->analog_data.analog85_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.all_limit_koeffs.uom_limit)*1000.0);//WRotorPBus.RotorDirectionSlow2;
reply_a->analog_data.analog86_lo = LOBYTE(Data);
reply_a->analog_data.analog86_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(edrk.all_limit_koeffs.uin_freq_limit)*1000.0);//fast_round(_IQtoF(WRotor.iqWRotorSumRamp)*NORMA_FROTOR*1000.0);
reply_a->analog_data.analog87_lo = LOBYTE(Data);
reply_a->analog_data.analog87_hi = HIBYTE(Data);
Data = _IQtoF(simple_scalar1.Im_regul)*NORMA_ACP_RMS;//(edrk.cantec_reg & 0xff);//edrk.pult_data.TimeToChangePump_from_pult;//0;//fast_round(_IQtoF(WRotor.iqWRotorCalc1Ramp)*NORMA_FROTOR*1000.0);;//WRotor.iqWRotorCalc1Ramp
reply_a->analog_data.analog88_lo = LOBYTE(Data);
reply_a->analog_data.analog88_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidPower.Ui)*NORMA_ACP);//(edrk.canrec_reg & 0xff);;//edrk.pult_data.nPCH_from_pult;//0;//fast_round(_IQtoF(WRotor.iqWRotorCalc2Ramp)*NORMA_FROTOR*1000.0);;
reply_a->analog_data.analog89_lo = LOBYTE(Data);
reply_a->analog_data.analog89_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidF.Fdb)*NORMA_FROTOR*1000.0);//(((unsigned long)edrk.canes_reg>>16) & 0x01ff);
reply_a->analog_data.analog90_lo = LOBYTE(Data);
reply_a->analog_data.analog90_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidF.Ref)*NORMA_FROTOR*1000.0);//(((unsigned long)edrk.canes_reg) & 0x3f);
reply_a->analog_data.analog91_lo = LOBYTE(Data);
reply_a->analog_data.analog91_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidF.SatErr)*NORMA_ACP);//CanBusOffError;//0;
reply_a->analog_data.analog92_lo = LOBYTE(Data);
reply_a->analog_data.analog92_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidF.Ui)*NORMA_ACP);//CanTimeOutErrorTR;//0;
reply_a->analog_data.analog93_lo = LOBYTE(Data);
reply_a->analog_data.analog93_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.pidF.Up)*NORMA_ACP);//0;
reply_a->analog_data.analog94_lo = LOBYTE(Data);
reply_a->analog_data.analog94_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.iq_decr_mzz_power)*1000.0);//0;//simple_scalar1.k_ogr_n
reply_a->analog_data.analog95_lo = LOBYTE(Data);
reply_a->analog_data.analog95_hi = HIBYTE(Data);
Data = fast_round(_IQtoF(simple_scalar1.iq_decr_mzz_power_filter)*1000.0);//fast_round(_IQtoF(edrk.zadanie.rmp_oborots_zad_hz.PosRampPlus1)*NORMA_FROTOR*60.0*450.0*1000.0);
reply_a->analog_data.analog96_lo = LOBYTE(Data);
reply_a->analog_data.analog96_hi = HIBYTE(Data);
// Data = 0;
// reply_a->analog_data.analog97_lo = LOBYTE(Data);
// reply_a->analog_data.analog97_hi = HIBYTE(Data);
pByte = &reply_a->digit_data.byte01.byte_data;
for (i = 0; i < 59; i++) //zero all dig data
pByte = &reply_a->digit_data.byte01.byte_data;
for (i = 0; i < 44; i++) //zero all dig data
{
*(pByte + i) = 0;
}
@ -573,11 +431,6 @@ Data = fast_round(_IQtoF(simple_scalar1.iqKoefOgranIzad)*1000.0);//0;//fast_roun
reply_a->digit_data.byte13.bit_data.bit2 = edrk.from_second_pch.bits.MASTER;
reply_a->digit_data.byte13.bit_data.bit3 = edrk.from_second_pch.bits.RASCEPITEL;
reply_a->digit_data.byte13.bit_data.bit4 = edrk.warning;
reply_a->digit_data.byte13.bit_data.bit5 = edrk.overheat;
reply_a->digit_data.byte13.bit_data.bit6 = edrk.summ_errors;
reply_a->digit_data.byte13.bit_data.bit7 = edrk.Status_Ready.bits.ready_final;
// reply_a->digit_data.byte13.byte_data = edrk.errors.e6.all & 0xff;
// reply->digit_data.byte14.byte_data = (edrk.errors.e6.all >> 8) & 0xff;
@ -717,12 +570,8 @@ Data = fast_round(_IQtoF(simple_scalar1.iqKoefOgranIzad)*1000.0);//0;//fast_roun
reply_a->digit_data.byte36.bit_data.bit1 = edrk.ms.ready1;
reply_a->digit_data.byte36.bit_data.bit2 = edrk.ms.ready2;
reply_a->digit_data.byte36.bit_data.bit3 = edrk.flag_wait_both_ready2;
reply_a->digit_data.byte36.bit_data.bit4 = edrk.Ready1_another_bs;
reply_a->digit_data.byte36.bit_data.bit5 = edrk.Ready2_another_bs;
reply_a->digit_data.byte36.bit_data.bit6 = edrk.flag_another_bs_first_ready12;
reply_a->digit_data.byte36.bit_data.bit7 = edrk.flag_this_bs_first_ready12;
reply_a->digit_data.byte36.bit_data.bit3 = edrk.flag_wait_both_ready2;
reply_a->digit_data.byte36.bit_data.bit3 = edrk.flag_wait_both_ready2;
reply_a->digit_data.byte37.byte_data = edrk.errors.e8.all & 0xff;
@ -742,11 +591,6 @@ Data = fast_round(_IQtoF(simple_scalar1.iqKoefOgranIzad)*1000.0);//0;//fast_roun
reply_a->digit_data.byte40.bit_data.bit2 = edrk.StartGED;
reply_a->digit_data.byte40.bit_data.bit3 = edrk.GoWait;
reply_a->digit_data.byte40.bit_data.bit4 = edrk.stop_logs_rs232;
reply_a->digit_data.byte40.bit_data.bit5 = edrk.stop_slow_log;
reply_a->digit_data.byte40.bit_data.bit6 = edrk.disable_limit_power_from_svu;
reply_a->digit_data.byte40.bit_data.bit7 = edrk.disable_uom;
reply_a->digit_data.byte41.byte_data = edrk.errors.e9.all & 0xff;
reply_a->digit_data.byte42.byte_data = (edrk.errors.e9.all >> 8) & 0xff;
@ -792,116 +636,32 @@ Data = fast_round(_IQtoF(simple_scalar1.iqKoefOgranIzad)*1000.0);//0;//fast_roun
// edrk.from_ing1.bits.RASCEPITEL_ON = FROM_ING_RASCEPITEL_ON_OFF;
reply_a->digit_data.byte49.bit_data.bit6 = edrk.from_ing2.bits.SOST_ZAMKA;
reply_a->digit_data.byte49.bit_data.bit7 = edrk.from_shema_filter.bits.RAZBOR_SHEMA;
reply_a->digit_data.byte49.bit_data.bit7 = edrk.from_shema.bits.RAZBOR_SHEMA;
//
reply_a->digit_data.byte50.bit_data.bit0 = edrk.from_shema_filter.bits.SBOR_SHEMA;
reply_a->digit_data.byte50.bit_data.bit0 = edrk.from_shema.bits.SBOR_SHEMA;
reply_a->digit_data.byte50.bit_data.bit1 = edrk.from_shema_filter.bits.ZADA_DISPLAY;
reply_a->digit_data.byte50.bit_data.bit2 = edrk.from_shema_filter.bits.SVU;
reply_a->digit_data.byte50.bit_data.bit1 = edrk.from_shema.bits.ZADA_DISPLAY;
reply_a->digit_data.byte50.bit_data.bit2 = edrk.from_shema.bits.SVU;
// edrk.from_shema.bits.KNOPKA_AVARIA = FROM_ALL_KNOPKA_AVARIA;
reply_a->digit_data.byte50.bit_data.bit3 = edrk.from_shema.bits.QTV_ON_OFF;
reply_a->digit_data.byte50.bit_data.bit4 = edrk.from_shema_filter.bits.UMP_ON_OFF;
reply_a->digit_data.byte50.bit_data.bit5 = edrk.from_shema_filter.bits.READY_UMP;
reply_a->digit_data.byte50.bit_data.bit4 = edrk.from_shema.bits.UMP_ON_OFF;
reply_a->digit_data.byte50.bit_data.bit5 = edrk.from_shema.bits.READY_UMP;
reply_a->digit_data.byte50.bit_data.bit6 = edrk.from_shema.bits.SVU_BLOCK_QTV;
reply_a->digit_data.byte50.bit_data.bit7 = edrk.errors_another_bs_from_can;
// reply_a->digit_data.byte44.byte_data = 0;
reply_a->digit_data.byte51.bit_data.bit0 = inc_sensor.break_sensor1;
reply_a->digit_data.byte51.bit_data.bit1 = inc_sensor.break_sensor2;
reply_a->digit_data.byte51.bit_data.bit2 = pll1.output.flag_find_pll;
reply_a->digit_data.byte51.bit_data.bit3 = log_params.stop_log_slow;
reply_a->digit_data.byte51.bit_data.bit4 = log_params.stop_log_level_1;
reply_a->digit_data.byte51.bit_data.bit5 = log_params.stop_log_level_2;
reply_a->digit_data.byte51.bit_data.bit6 = log_params.stop_log_slow_level_1;
reply_a->digit_data.byte51.bit_data.bit7 = log_params.stop_log_slow_level_2;
reply_a->digit_data.byte52.bit_data.bit0 = edrk.from_zadat4ik.bits.KVITIR;
reply_a->digit_data.byte52.bit_data.bit1 = edrk.from_zadat4ik.bits.PLUS;
reply_a->digit_data.byte52.bit_data.bit2 = edrk.from_zadat4ik.bits.MINUS;
reply_a->digit_data.byte52.bit_data.bit3 = edrk.from_zadat4ik.bits.PROVOROT;
reply_a->digit_data.byte52.bit_data.bit4 = edrk.from_zadat4ik.bits.UOM_READY_ACTIVE;
reply_a->digit_data.byte52.bit_data.bit5 = edrk.from_zadat4ik.bits.UOM_LIMIT_3;
reply_a->digit_data.byte52.bit_data.bit6 = edrk.from_zadat4ik.bits.UOM_LIMIT_2;
reply_a->digit_data.byte52.bit_data.bit7 = edrk.from_zadat4ik.bits.UOM_LIMIT_1;
reply_a->digit_data.byte53.bit_data.bit0 = edrk.Run_UMP;
reply_a->digit_data.byte53.bit_data.bit1 = edrk.Status_UMP_Ok;
reply_a->digit_data.byte53.bit_data.bit2 = edrk.Zaryad_UMP_Ok;
reply_a->digit_data.byte53.bit_data.bit3 = edrk.cmd_to_ump;
reply_a->digit_data.byte53.bit_data.bit4 = edrk.sbor_wait_ump1;
reply_a->digit_data.byte53.bit_data.bit5 = edrk.sbor_wait_ump2;
reply_a->digit_data.byte53.bit_data.bit6 = edrk.flag_enable_on_ump;
reply_a->digit_data.byte53.bit_data.bit7 = edrk.local_ump_on_off;
reply_a->digit_data.byte54.bit_data.bit0 = edrk.local_ready_ump;
///
reply_a->digit_data.byte54.bit_data.bit1 = (modbus_table_can_in[128].all) ? 1 : 0; //cmd_local_charge PCH 0
reply_a->digit_data.byte54.bit_data.bit2 = (modbus_table_can_in[131].all) ? 1 : 0; //cmd_local_uncharge PCH 0
reply_a->digit_data.byte54.bit_data.bit3 = (modbus_table_can_in[129].all) ? 1 : 0; //cmd_local_charge PCH 1
reply_a->digit_data.byte54.bit_data.bit4 = (modbus_table_can_in[132].all) ? 1 : 0; //cmd_local_uncharge PCH 1
reply_a->digit_data.byte54.bit_data.bit5 = edrk.from_shema_filter.bits.UMP_ON_OFF;
reply_a->digit_data.byte54.bit_data.bit6 = edrk.SumSbor;
reply_a->digit_data.byte55.bit_data.bit0 = edrk.power_limit.bits.limit_Iout;
reply_a->digit_data.byte55.bit_data.bit1 = edrk.power_limit.bits.limit_UOM;
reply_a->digit_data.byte55.bit_data.bit2 = edrk.power_limit.bits.limit_by_temper;
reply_a->digit_data.byte55.bit_data.bit3 = edrk.power_limit.bits.limit_from_SVU;
reply_a->digit_data.byte55.bit_data.bit4 = edrk.power_limit.bits.limit_from_uom_fast;
reply_a->digit_data.byte55.bit_data.bit5 = edrk.power_limit.bits.limit_from_freq;
reply_a->digit_data.byte55.bit_data.bit6 = edrk.power_limit.bits.limit_moment;
reply_a->digit_data.byte55.bit_data.bit7 = simple_scalar1.flag_decr_mzz_power;
reply_a->digit_data.byte56.bit_data.bit0 = (edrk.pult_cmd.log_what_memory & 0x1) ? 1 : 0;
reply_a->digit_data.byte56.bit_data.bit1 = (edrk.pult_cmd.log_what_memory & 0x2) ? 1 : 0;
reply_a->digit_data.byte56.bit_data.bit2 = edrk.pult_data.flagSaveDataMoto ? 1 : 0;
reply_a->digit_data.byte56.bit_data.bit3 = (edrk.pult_data.flagSaveSlowLogs) ? 1 : 0;
reply_a->digit_data.byte56.bit_data.bit4 = edrk.pult_cmd.send_log ? 1 : 0;
reply_a->digit_data.byte56.bit_data.bit5 = (log_to_HMI.send_log==1) ? 1 : 0;
reply_a->digit_data.byte56.bit_data.bit6 = (log_to_HMI.send_log==2) ? 1 : 0;
reply_a->digit_data.byte56.bit_data.bit7 = (log_to_HMI.send_log==3) ? 1 : 0;
//
reply_a->digit_data.byte57.bit_data.bit0 = (edrk.break_tempers[0] > ABNORMAL_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte57.bit_data.bit1 = (edrk.break_tempers[1] > ABNORMAL_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte57.bit_data.bit2 = (edrk.break_tempers[2] > ABNORMAL_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte57.bit_data.bit3 = (edrk.break_tempers[3] > ABNORMAL_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte57.bit_data.bit4 = (edrk.break_tempers[0] > ALARM_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte57.bit_data.bit5 = (edrk.break_tempers[1] > ALARM_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte57.bit_data.bit6 = (edrk.break_tempers[2] > ALARM_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte57.bit_data.bit7 = (edrk.break_tempers[3] > ALARM_TEMPER_BREAK_INT) ? 1 : 0;
reply_a->digit_data.byte58.bit_data.bit0 = (edrk.breaker_on==1) ? 1 : 0;
reply_a->digit_data.byte58.bit_data.bit1 = edrk.warnings.e9.bits.BREAK_TEMPER_WARNING;
reply_a->digit_data.byte58.bit_data.bit2 = edrk.warnings.e9.bits.BREAK_TEMPER_ALARM;
reply_a->digit_data.byte58.bit_data.bit3 = edrk.warnings.e9.bits.BREAKER_GED_ON;
// reply_a->digit_data.byte57.byte_data = 0;//(((unsigned long)edrk.canes_reg>>16) & 0x0ff);
// reply_a->digit_data.byte58.byte_data = 0;//(((unsigned long)edrk.canes_reg) & 0x3f);
reply_a->digit_data.byte59.byte_data = 0;//(((unsigned long)edrk.canes_reg>>24) & 0x1);
reply_a->digit_data.byte60.byte_data = 0;
return;
return;
}

View File

@ -13,8 +13,6 @@
#include "xp_project.h"
#include "x_wdog.h"
#include "params_hwp.h"
#include "detect_errors.h"
//XilinxV2
@ -24,7 +22,7 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
{
// îíòðîëüíày ñóììà
unsigned int crc, DataOut, sinusImpulse, doubleImpulse,adc_plate;
int Data,Data1,Data2/*,bitt, DataAnalog1, DataAnalog2*/, tk0,tk1,tk2,tk3,period1,period2, period3;
int Data,Data1,Data2/*,bitt, DataAnalog1, DataAnalog2*/, tk0,tk1,tk2,tk3,period1,period2;
//static int vs11,vs12,vs1;
static int prev_Go = 0;
@ -33,12 +31,6 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
static int flag_prev_turn_on = 0;
static int flag_prev_turn_off = 0;
static int flag_prev_lamp_on_off = 0;
static int soft_off_enable = 0, soft_on_enable = 0;
static float tk_time_soft_off = 0;
static unsigned long tk_time_soft_off_d = 0;
static unsigned int i_af_protect_a = 0, i_af_protect_d = 0;
int enable_line_err = 0, disable_tk_soft_off, disable_protect_tk_soft_off;
stop_wdog();
@ -54,16 +46,7 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
// f.RScount = SECOND*3;
f.terminal_prepare = pcommand->digit_data.byte05.bit_data.bit1;
soft_off_enable = pcommand->digit_data.byte06.bit_data.bit0;
soft_on_enable = pcommand->digit_data.byte06.bit_data.bit1;
// edrk.direct_write_out = pcommand->digit_data.byte06.bit_data.bit2;
disable_tk_soft_off = pcommand->digit_data.byte06.bit_data.bit3;
disable_protect_tk_soft_off = pcommand->digit_data.byte06.bit_data.bit4;
enable_line_err = pcommand->digit_data.byte06.bit_data.bit5;
// Çàïèñàëè âñå âûõîäû
// "àïèñàëè âñå âûõîäû
#if (CHECK_IN_OUT_TERMINAL==1)
@ -89,9 +72,7 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
// write_dig_out();
//calc_norm_ADC(0);
calc_norm_ADC_0(1);
calc_norm_ADC_1(1);
calc_norm_ADC(0);
// ïðîâåðêà êëþ÷åé
tk0 = (pcommand->digit_data.byte01.byte_data);
@ -109,39 +90,6 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
Data = (Data2 + Data1*256);
period2 = Data;
Data1 = pcommand->analog_data.analog3_hi;
Data2 = pcommand->analog_data.analog3_lo;
Data = (Data2 + Data1*256);
period3 = Data;
Data1 = pcommand->analog_data.analog4_hi;
Data2 = pcommand->analog_data.analog4_lo;
Data = (Data2 + Data1*256);
// Data = 200;
tk_time_soft_off = Data*100.0; // mks*10->ns
if (tk_time_soft_off>1300000.0)
tk_time_soft_off = 1300000.0;
tk_time_soft_off_d = (unsigned long)(tk_time_soft_off / DIV_TIME_TK_SOFT_OFF);
if (tk_time_soft_off_d>65535)
tk_time_soft_off_d = 65535;
Data1 = pcommand->analog_data.analog5_hi;
Data2 = pcommand->analog_data.analog5_lo;
Data = (Data2 + Data1*256);
i_af_protect_a = Data;
if (i_af_protect_a>LEVEL_HWP_I_AF) i_af_protect_a = LEVEL_HWP_I_AF;
if (i_af_protect_a<10) i_af_protect_a = 10;
i_af_protect_d = convert_real_to_mv_hwp(4,i_af_protect_a);
if (i_af_protect_d>1500) i_af_protect_d = 1500; // max 1500 mV
update_maz_level_i_af(0, i_af_protect_d);
project.read_all_hwp();
if(pcommand->digit_data.byte05.bit_data.bit3 == 1)
doubleImpulse = 1;
else
@ -154,43 +102,8 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
if ((pcommand->digit_data.byte05.bit_data.bit0 == 1) && (prev_Go == 0))
{
if (pcommand->digit_data.byte05.bit_data.bit2 == 1) // ïðè öèêë èìïóëüñå ïðåäâàðèòåëüíî äàåì êâèòèðîâàíèå
{
update_maz_level_i_af(0, 1500);
project.write_all_hwp();
clear_errors();
project.clear_errors_all_plates();
update_maz_level_i_af(0, i_af_protect_d);
project.write_all_hwp();
}
// test_tk_ak_one_impulse( tk0, tk1, tk2, tk3, period1, period2);
#if (USE_TK_0)
project.cds_tk[0].write.sbus.protect_error.bit.enable_soft_disconnect = !disable_tk_soft_off;
project.cds_tk[0].write.sbus.protect_error.bit.detect_soft_disconnect = !disable_protect_tk_soft_off;
project.cds_tk[0].write.sbus.protect_error.bit.enable_line_err = enable_line_err;
project.cds_tk[0].write.sbus.time_after_err = tk_time_soft_off_d;//(int)(tk_time_soft_off / DIV_TIME_TK_SOFT_OFF);
#endif
#if (USE_TK_1)
project.cds_tk[1].write.sbus.protect_error.bit.enable_soft_disconnect = !disable_tk_soft_off;
project.cds_tk[1].write.sbus.protect_error.bit.detect_soft_disconnect = !disable_protect_tk_soft_off;
project.cds_tk[1].write.sbus.protect_error.bit.enable_line_err = enable_line_err;
project.cds_tk[1].write.sbus.time_after_err = tk_time_soft_off_d;//(int)(tk_time_soft_off / DIV_TIME_TK_SOFT_OFF);
#endif
#if (USE_TK_3)
project.cds_tk[3].write.sbus.protect_error.bit.enable_soft_disconnect = !disable_tk_soft_off;
project.cds_tk[3].write.sbus.protect_error.bit.detect_soft_disconnect = !disable_protect_tk_soft_off;
project.cds_tk[3].write.sbus.protect_error.bit.enable_line_err = enable_line_err;
project.cds_tk[3].write.sbus.time_after_err = tk_time_soft_off_d;//(int)(tk_time_soft_off / DIV_TIME_TK_SOFT_OFF);
#endif
project.write_all_sbus();
project.write_all_hwp();
test_tk_ak_one_impulse( tk0, tk1, tk2, tk3, period1, period2, period3, doubleImpulse, sinusImpulse, soft_off_enable, soft_on_enable);
test_tk_ak_one_impulse( tk0, tk1, tk2, tk3, period1, period2, doubleImpulse, sinusImpulse);
}
if ((pcommand->digit_data.byte05.bit_data.bit0 == 1) &&
@ -206,19 +119,14 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
if (pcommand->digit_data.byte05.bit_data.bit1==1)
{
stop_wdog();
update_maz_level_i_af(0, 1500);
project.write_all_hwp();
clear_errors();
project.clear_errors_all_plates();
update_maz_level_i_af(0, i_af_protect_d);
project.write_all_hwp();
}
}
prev_Prepare = pcommand->digit_data.byte05.bit_data.bit1;
if (pcommand->digit_data.byte05.bit_data.bit2 == 1)
{
prev_Go = 0; // çàöèêëèëè Go
}
@ -372,46 +280,17 @@ void func_fill_answer_to_TMS_test(TMS_TO_TERMINAL_TEST_ALL_STRUCT* reply_ans, CM
reply_test_all.analog_data.analog16_lo=LOBYTE(Data);
reply_test_all.analog_data.analog16_hi=HIBYTE(Data);
Data = _IQtoF(analog.iqU_1) * NORMA_ACP;
reply_ans->analog_data.analog17_lo=LOBYTE(Data);
reply_ans->analog_data.analog17_hi=HIBYTE(Data);
Data = _IQtoF(analog.iqU_2) * NORMA_ACP;
reply_ans->analog_data.analog18_lo=LOBYTE(Data);
reply_ans->analog_data.analog18_hi=HIBYTE(Data);
Data = project.cds_tk[0].read.sbus.time_err_tk_all.bit.tk_3210;
/*
Data = _IQtoF(analog.iqU_3) * NORMA_ACP;
reply_ans->analog_data.analog19_lo=LOBYTE(Data);
reply_ans->analog_data.analog19_hi=HIBYTE(Data);
Data = project.cds_tk[0].read.sbus.time_err_tk_all.bit.tk_7654;
Data = _IQtoF(analog.iqU_4) * NORMA_ACP;
reply_ans->analog_data.analog20_lo=LOBYTE(Data);
reply_ans->analog_data.analog20_hi=HIBYTE(Data);
Data = project.cds_tk[1].read.sbus.time_err_tk_all.bit.tk_3210;
reply_ans->analog_data.analog21_lo=LOBYTE(Data);
reply_ans->analog_data.analog21_hi=HIBYTE(Data);
*/
Data = project.cds_tk[1].read.sbus.time_err_tk_all.bit.tk_7654;
reply_ans->analog_data.analog22_lo=LOBYTE(Data);
reply_ans->analog_data.analog22_hi=HIBYTE(Data);
Data = project.cds_tk[2].read.sbus.time_err_tk_all.bit.tk_3210;
reply_ans->analog_data.analog23_lo=LOBYTE(Data);
reply_ans->analog_data.analog23_hi=HIBYTE(Data);
Data = project.cds_tk[2].read.sbus.time_err_tk_all.bit.tk_7654;
reply_ans->analog_data.analog24_lo=LOBYTE(Data);
reply_ans->analog_data.analog24_hi=HIBYTE(Data);
// Data = project.cds_tk[3].read.sbus.time_err_tk_all.bit.tk_3210;
// reply_ans->analog_data.analog25_lo=LOBYTE(Data);
// reply_ans->analog_data.analog25_hi=HIBYTE(Data);
//
// Data = project.cds_tk[3].read.sbus.time_err_tk_all.bit.tk_7654;
// reply_ans->analog_data.analog26_lo=LOBYTE(Data);
// reply_ans->analog_data.analog26_hi=HIBYTE(Data);
reply_ans->digit_data.byte01.byte_data = 0;
reply_ans->digit_data.byte02.byte_data = 0;
@ -514,16 +393,8 @@ reply_ans->digit_data.byte24.byte_data = 0;
reply_ans->digit_data.byte19.bit_data.bit6 = CAN_timeout[get_real_in_mbox(UNITS_TYPE_BOX,UMU_CAN_DEVICE)];
//reply.digit_data.byte21.bit_data.bit7 = CAN_timeout[VPU1_CAN_DEVICE];
reply_ans->digit_data.byte20.bit_data.bit0 = project.controller.read.errors.bit.er0_out;
reply_ans->digit_data.byte20.bit_data.bit1 = project.controller.read.errors.bit.er0_trig;
reply_ans->digit_data.byte20.bit_data.bit2 = project.controller.read.errors.bit.errHWP;
reply_ans->digit_data.byte20.bit_data.bit3 = project.controller.read.errors.bit.errHWP_trig;
reply_ans->digit_data.byte20.bit_data.bit4 = project.controller.read.errors.bit.error_pbus;
reply_ans->digit_data.byte20.bit_data.bit5 = project.controller.read.errors.bit.pwm_wdog;
reply_ans->digit_data.byte20.bit_data.bit6 = project.controller.read.errors.bit.status_er0;
// reply_ans->digit_data.byte20.bit_data.bit0 = project.controller.read.errors.bit.er0_out;
// reply_ans->digit_data.byte20.bit_data.bit0 = CAN_timeout[get_real_in_mbox(UNITS_TYPE_BOX,VPU_CAN)];
// reply_ans->digit_data.byte20.bit_data.bit1 = CAN_timeout[get_real_in_mbox(MPU_TYPE_BOX,0)];
reply_ans->digit_data.byte20.bit_data.bit0 = CAN_timeout[get_real_in_mbox(UNITS_TYPE_BOX,VPU_CAN)];
reply_ans->digit_data.byte20.bit_data.bit1 = CAN_timeout[get_real_in_mbox(MPU_TYPE_BOX,0)];
reply_ans->digit_data.byte20.bit_data.bit2 = 0;//READY_UKSS_6;
reply_ans->digit_data.byte20.bit_data.bit3 = 0;//READY_UKSS_7;
reply_ans->digit_data.byte20.bit_data.bit4 = 0;//READY_UKSS_8;
@ -565,82 +436,8 @@ reply_ans->digit_data.byte24.byte_data = 0;
reply_ans->digit_data.byte23.byte_data=project.hwp[0].read.comp_s.minus.all & 0x00ff;
reply_ans->digit_data.byte24.byte_data=((project.hwp[0].read.comp_s.minus.all >> 8) & 0x00ff);
reply_ans->digit_data.byte23.byte_data|=project.hwp[0].read.comp_s.plus.all & 0x00ff;
reply_ans->digit_data.byte24.byte_data|=((project.hwp[0].read.comp_s.plus.all >> 8) & 0x00ff);
#if (USE_TK_0)
if (project.cds_tk[0].useit)
{
// reply_ans->digit_data.byte22.bit_data.bit0 = project.cds_tk[0].read.sbus.lock_status_error.bit.err0_in;
reply_ans->digit_data.byte25.bit_data.bit0 = project.cds_tk[0].read.sbus.lock_status_error.bit.err_hwp;
reply_ans->digit_data.byte25.bit_data.bit1 = project.cds_tk[0].read.sbus.lock_status_error.bit.err0_local;
reply_ans->digit_data.byte25.bit_data.bit2 = project.cds_tk[0].read.sbus.lock_status_error.bit.mintime_err_keys_7654;
reply_ans->digit_data.byte25.bit_data.bit3 = project.cds_tk[0].read.sbus.lock_status_error.bit.mintime_err_keys_3210;
reply_ans->digit_data.byte25.bit_data.bit4 = project.cds_tk[0].read.sbus.lock_status_error.bit.line_err_keys_7654;
reply_ans->digit_data.byte25.bit_data.bit5 = project.cds_tk[0].read.sbus.lock_status_error.bit.line_err_keys_3210;
reply_ans->digit_data.byte25.bit_data.bit6 = project.cds_tk[0].read.sbus.lock_status_error.bit.ErrorSoftShutdownFromErr0;
reply_ans->digit_data.byte25.bit_data.bit7 = project.cds_tk[0].read.sbus.lock_status_error.bit.ErrorSoftShutdownForbidComb;
}
else
reply_ans->digit_data.byte25.byte_data = 0;
#else
reply_ans->digit_data.byte25.byte_data = 0;
#endif
#if (USE_TK_1)
if (project.cds_tk[1].useit)
{
reply_ans->digit_data.byte26.bit_data.bit0 = project.cds_tk[1].read.sbus.lock_status_error.bit.err_hwp;
reply_ans->digit_data.byte26.bit_data.bit1 = project.cds_tk[1].read.sbus.lock_status_error.bit.err0_local;
reply_ans->digit_data.byte26.bit_data.bit2 = project.cds_tk[1].read.sbus.lock_status_error.bit.mintime_err_keys_7654;
reply_ans->digit_data.byte26.bit_data.bit3 = project.cds_tk[1].read.sbus.lock_status_error.bit.mintime_err_keys_3210;
reply_ans->digit_data.byte26.bit_data.bit4 = project.cds_tk[1].read.sbus.lock_status_error.bit.line_err_keys_7654;
reply_ans->digit_data.byte26.bit_data.bit5 = project.cds_tk[1].read.sbus.lock_status_error.bit.line_err_keys_3210;
reply_ans->digit_data.byte26.bit_data.bit6 = project.cds_tk[1].read.sbus.lock_status_error.bit.ErrorSoftShutdownFromErr0;
reply_ans->digit_data.byte26.bit_data.bit7 = project.cds_tk[1].read.sbus.lock_status_error.bit.ErrorSoftShutdownForbidComb;
}
else
reply_ans->digit_data.byte26.byte_data = 0;
#else
reply_ans->digit_data.byte26.byte_data = 0;
#endif
#if (USE_TK_2)
if (project.cds_tk[2].useit)
{
reply_ans->digit_data.byte27.bit_data.bit0 = project.cds_tk[2].read.sbus.lock_status_error.bit.err_hwp;
reply_ans->digit_data.byte27.bit_data.bit1 = project.cds_tk[2].read.sbus.lock_status_error.bit.err0_local;
reply_ans->digit_data.byte27.bit_data.bit2 = project.cds_tk[2].read.sbus.lock_status_error.bit.mintime_err_keys_7654;
reply_ans->digit_data.byte27.bit_data.bit3 = project.cds_tk[2].read.sbus.lock_status_error.bit.mintime_err_keys_3210;
reply_ans->digit_data.byte27.bit_data.bit4 = project.cds_tk[2].read.sbus.lock_status_error.bit.line_err_keys_7654;
reply_ans->digit_data.byte27.bit_data.bit5 = project.cds_tk[2].read.sbus.lock_status_error.bit.line_err_keys_3210;
reply_ans->digit_data.byte27.bit_data.bit6 = project.cds_tk[2].read.sbus.lock_status_error.bit.ErrorSoftShutdownFromErr0;
reply_ans->digit_data.byte27.bit_data.bit7 = project.cds_tk[2].read.sbus.lock_status_error.bit.ErrorSoftShutdownForbidComb;
}
else
reply_ans->digit_data.byte27.byte_data = 0;
#else
reply_ans->digit_data.byte27.byte_data = 0;
#endif
#if (USE_TK_3)
if (project.cds_tk[3].useit)
{
reply_ans->digit_data.byte28.bit_data.bit0 = project.cds_tk[3].read.sbus.lock_status_error.bit.err_hwp;
reply_ans->digit_data.byte28.bit_data.bit1 = project.cds_tk[3].read.sbus.lock_status_error.bit.err0_local;
reply_ans->digit_data.byte28.bit_data.bit2 = project.cds_tk[3].read.sbus.lock_status_error.bit.mintime_err_keys_7654;
reply_ans->digit_data.byte28.bit_data.bit3 = project.cds_tk[3].read.sbus.lock_status_error.bit.mintime_err_keys_3210;
reply_ans->digit_data.byte28.bit_data.bit4 = project.cds_tk[3].read.sbus.lock_status_error.bit.line_err_keys_7654;
reply_ans->digit_data.byte28.bit_data.bit5 = project.cds_tk[3].read.sbus.lock_status_error.bit.line_err_keys_3210;
reply_ans->digit_data.byte28.bit_data.bit6 = project.cds_tk[3].read.sbus.lock_status_error.bit.ErrorSoftShutdownFromErr0;
reply_ans->digit_data.byte28.bit_data.bit7 = project.cds_tk[3].read.sbus.lock_status_error.bit.ErrorSoftShutdownForbidComb;
}
else
reply_ans->digit_data.byte28.byte_data = 0;
#else
reply_ans->digit_data.byte28.byte_data = 0;
#endif
reply_ans->digit_data.byte23.byte_data|=project.hwp[0].read.comp_s.minus.all & 0x00ff;
reply_ans->digit_data.byte24.byte_data|=((project.hwp[0].read.comp_s.minus.all >> 8) & 0x00ff);
/*

View File

@ -22,10 +22,6 @@
#include <message2can.h>
#include <edrk_main.h>
#include "pwm_test_lines.h"
#include "params.h"
#include "logs_hmi.h"
//#include "can_setup_21300.h"
//#include "modbus_can.h"
@ -168,7 +164,6 @@ void write_all_data_to_mpu_can(int run_force, unsigned int pause)
static int cur_position_buf_modbus16_can = 0, prev_send_to_can = 0;
int real_mbox;
unsigned int i;
real_mbox = get_real_out_mbox(MPU_TYPE_BOX, edrk.flag_second_PCH);
@ -240,13 +235,6 @@ void write_all_data_to_mpu_can(int run_force, unsigned int pause)
// modbus_table_can_out[ADR_CAN_TEST_PLUS_ONE].all++;
}
// ñîõðàíÿåì âî âðåìåííîé ïàìÿòè ïåðåä íà÷àëîì ïåðåäà÷è âñåãî ìàññèâà ÷òîáû äàííûå íå ìåíÿëèñü âî âðåìÿ ïåðåäà÷è
if (cur_position_buf_modbus16_can == 0)
{
for (i=0;i<SIZE_MODBUS_TABLE;i++)
modbus_table_can_out_temp[i] = modbus_table_can_out[i];
}
if ((cur_position_buf_modbus16_can + SIZE_BUF_WRITE_TO_MODBUS16_CAN) >= SIZE_MODBUS_TABLE)
count_write_to_modbus_can = SIZE_MODBUS_TABLE - cur_position_buf_modbus16_can;
else
@ -261,8 +249,7 @@ void write_all_data_to_mpu_can(int run_force, unsigned int pause)
MPU_TYPE_BOX,
edrk.flag_second_PCH,
cur_position_buf_modbus16_can + 1,
// &modbus_table_can_out[cur_position_buf_modbus16_can].all,
&modbus_table_can_out_temp[cur_position_buf_modbus16_can].all,
&modbus_table_can_out[cur_position_buf_modbus16_can].all,
count_write_to_modbus_can, CAN_BOX_STANDART_ADR, CAN_BOX_PRIORITY_NORMAL);
cur_position_buf_modbus16_can = cur_position_buf_modbus16_can + SIZE_BUF_WRITE_TO_MODBUS16_CAN;
@ -412,9 +399,6 @@ void test_alive_pult_485(void)
}
#define MAX_COUNT_WORK_IN_LOG 150
int modbusNetworkSharing(int flag_update_only_hmi)
{
static unsigned int old_time = 0 , old_time_refresh = 0, time_pause = TIME_PAUSE_MODBUS_REMOUTE;
@ -426,13 +410,8 @@ int modbusNetworkSharing(int flag_update_only_hmi)
static int run_pause = 1, flag_next = 0, prev_flag_next = 0;
static int last_ok_cmd=0;
static int flag_only_one_cmd=0;
static int status_ok = 1, status_err = 0, flag_work_rs_send_log = 0, count_free = 0, count_work_in_log = 0;
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_20_ON;
#endif
RS232_WorkingWith(0,1,0);
// âêë òèï çàïðîñ-îòâåò äëÿ ñèñòåìû òàéìèíãà
@ -456,123 +435,21 @@ int modbusNetworkSharing(int flag_update_only_hmi)
final_code = 0;
switch(status)
{
case 0:
old_time = global_time.miliseconds;
status = 1;
if (time_pause==0)
status = 2;
break;
case 1:
// if (numberInT==0)
// {
if (detect_pause_milisec(time_pause,&old_time))
status = 2;
// }
// else
// status = 2;
break;
case 2:
enable_send_cmd = 1;
control_station.time_detect_answer_485[CONTROL_STATION_INGETEAM_PULT_RS485] = 0;
status = 3;
old_time_status_3 = global_time.miliseconds;
break;
case 3:
// // åñëè ìû â ïåðåäà÷å ëîãîâ è òàì ïóñòàÿ êîìàíäà áåç îáìåíà ïî rs485
// if (flag_work_rs_send_log)
// {
// status = 0;
// status_ok++;
// if (status_ok<0) status_ok=1;
// }
// íå áûëî ïåðåäà÷ ïî rs485 çíà÷èò è ëîâèòü òóò íå÷åãî!
if (rs_b.RS_DataWillSend2 == 0 && enable_send_cmd == 0)
{
status = 0;
status_ok++;
count_free++;
}
else
if (rs_b.RS_DataReadyAnswerAnalyze)
{
// i_led2_on_off(0);
control_station.time_detect_answer_485[CONTROL_STATION_INGETEAM_PULT_RS485] = 0;
control_station.count_ok_modbus[CONTROL_STATION_INGETEAM_PULT_RS485]++;
rs_b.RS_DataReadyAnswerAnalyze = 0;
rs_b.RS_DataWillSend2 = 0;
status = 0;
if (last_ok_cmd==4) // ïðîøëà readAnalogDataFromRemote() ñì íèæå
{
edrk.get_new_data_from_hmi = 1;// ìîæíî çàáðàòü äàííûå?
edrk.get_new_data_from_hmi2 = 1;// ìîæíî çàáðàòü äàííûå?
}
final_code = last_ok_cmd;//numberInT+1;
//status_err = 0;
status_ok++;
}
else
{
if ( (control_station.time_detect_answer_485[CONTROL_STATION_INGETEAM_PULT_RS485]>control_station.setup_time_detect_active_resend_485[CONTROL_STATION_INGETEAM_PULT_RS485])
|| (detect_pause_milisec(time_pause_status_3,&old_time_status_3)) )
{
resetup_mpu_rs(&rs_b);
control_station.time_detect_answer_485[CONTROL_STATION_INGETEAM_PULT_RS485] = 0;
rs_b.RS_DataWillSend2 = 0;
status = 0;
control_station.count_error_modbus[CONTROL_STATION_INGETEAM_PULT_RS485]++;
status_err++;// = 1;
}
}
if (status_ok<0) status_ok=1;
break;
case 4:
break;
case 5:
break;
case 6:
break;
default:
break;
}
/*
if (status==0)
{
old_time = global_time.miliseconds;
status = 1;
if (time_pause==0)
status = 2;
}
if (status==1)
{
// if (numberInT==0)
// {
if (numberInT==0)
{
if (detect_pause_milisec(time_pause,&old_time))
status = 2;
// }
// else
// status = 2;
}
else
status = 2;
}
if (status==2)
@ -585,21 +462,6 @@ int modbusNetworkSharing(int flag_update_only_hmi)
if (status==3)
{
if (rs_b.RS_DataWillSend2 == 0)
{
count_free++;
}
// åñëè ìû â ïåðåäà÷å ëîãîâ è òàì ïóñòàÿ êîìàíäà áåç îáìåíà ïî rs485
if (flag_work_rs_send_log)
{
status = 0;
status_ok++;
if (status_ok<0) status_ok=1;
}
if (rs_b.RS_DataReadyAnswerAnalyze)
{
// i_led2_on_off(0);
@ -607,16 +469,11 @@ int modbusNetworkSharing(int flag_update_only_hmi)
control_station.time_detect_answer_485[CONTROL_STATION_INGETEAM_PULT_RS485] = 0;
control_station.count_ok_modbus[CONTROL_STATION_INGETEAM_PULT_RS485]++;
rs_b.RS_DataReadyAnswerAnalyze = 0;
rs_b.RS_DataWillSend2 = 0;
status = 0;
if (last_ok_cmd==4) // ïðîøëà readAnalogDataFromRemote() ñì íèæå
edrk.get_new_data_from_hmi = 1;// ìîæíî çàáðàòü äàííûå?
final_code = last_ok_cmd;//numberInT+1;
//status_err = 0;
status_ok++;
if (status_ok<0) status_ok=1;
}
else
{
@ -625,16 +482,14 @@ int modbusNetworkSharing(int flag_update_only_hmi)
{
resetup_mpu_rs(&rs_b);
control_station.time_detect_answer_485[CONTROL_STATION_INGETEAM_PULT_RS485] = 0;
rs_b.RS_DataWillSend2 = 0;
status = 0;
control_station.count_error_modbus[CONTROL_STATION_INGETEAM_PULT_RS485]++;
status_err++;// = 1;
}
}
}
*/
// switch (status)
// {
// case 0 : status = 1;
@ -731,9 +586,7 @@ int modbusNetworkSharing(int flag_update_only_hmi)
//
if (enable_send_cmd
// && (log_to_HMI.send_log == 0)
)
if (enable_send_cmd && (log_to_HMI.send_log == 0))
{
//i_led2_on_off(1);
last_ok_cmd = numberInT;
@ -749,13 +602,11 @@ int modbusNetworkSharing(int flag_update_only_hmi)
edrk.test++;
numberInT++;
enable_send_cmd = 0;
break;
case 1:
if ((flag_update_only_hmi==0) && (edrk.flag_enable_update_hmi))
// if (edrk.flag_enable_update_hmi)
update_tables_HMI_analog();
writeAnalogDataToRemote(); // 1 ÷àñòü àíàëîãà
@ -766,7 +617,6 @@ int modbusNetworkSharing(int flag_update_only_hmi)
// else
numberInT++;
enable_send_cmd = 0;
break;
case 2:
@ -782,79 +632,39 @@ int modbusNetworkSharing(int flag_update_only_hmi)
// else
numberInT++;
enable_send_cmd = 0;
break;
case 3:
readAnalogDataFromRemote(); // 1 ÷àñòü
numberInT++;
enable_send_cmd = 0;
break;
case 4:
readAnalogDataFromRemote(); // 2 ÷àñòü
if (log_to_HMI.send_log)
{
if (log_to_HMI.send_log == 1)
numberInT++;
}
else
// ïðîïóñêàåì ñëåä êîìàíäó
numberInT = 0;
enable_send_cmd = 0;
count_work_in_log = 0; // ïîäãîòîâêà äëÿ ëîãîâ
break;
case 5:
if (log_to_HMI.send_log)
{
time_pause = 2;
// ccc[0] = 1;
flag_work_rs_send_log = !sendLogToHMI(status_ok);
edrk.flag_slow_in_main = 1;
enable_send_cmd = 0;
if (count_work_in_log>MAX_COUNT_WORK_IN_LOG)
{
count_work_in_log = 0;
numberInT = 0; // çàïóñêàåì ïîëíûé öèêë
}
else
{
count_work_in_log++;
// îñòàåìñÿ â ýòîì öèêëå ëîãîâ
}
}
else
{
time_pause = TIME_PAUSE_MODBUS_REMOUTE;
// ccc[0] = 0;
numberInT = 0;
enable_send_cmd = 0;
edrk.flag_slow_in_main = 0;
}
sendLogToHMI();
numberInT = 0;
break;
default:
enable_send_cmd = 0;
break;
}
enable_send_cmd = 0;
//i_led2_on_off(0);
}
//sendLogToHMI();
#if(_ENABLE_PWM_LINES_FOR_TESTS_RS)
PWM_LINES_TK_20_OFF;
#endif
sendLogToHMI();
if (flag_update_only_hmi)
return final_code;
@ -870,19 +680,17 @@ int modbusNetworkSharingCAN(void)
// static unsigned int old_time1 = 0 , time_pause1 = TIME_PAUSE_NETWORK_CAN1;
// static unsigned int old_time2 = 0 , time_pause2 = TIME_PAUSE_NETWORK_CAN2;
// static unsigned int old_time3 = 0 , time_pause3 = TIME_PAUSE_NETWORK_CAN3;
static unsigned int time_pause_modbus_can_terminals = TIME_PAUSE_MODBUS_CAN_TERMINALS;
#if (ENABLE_CAN_SEND_TO_MPU_FROM_MAIN)
// if (detect_pause_milisec(time_pause1,&old_time1))
static unsigned int time_pause_modbus_can_mpu = TIME_PAUSE_MODBUS_CAN_MPU;
write_all_data_to_mpu_can(1, time_pause_modbus_can_mpu);
write_all_data_to_mpu_can(1, TIME_PAUSE_MODBUS_CAN_MPU);
#endif
#if (ENABLE_CAN_SEND_TO_TERMINAL_FROM_MAIN)
// if (detect_pause_milisec(time_pause2,&old_time2))
write_all_data_to_terminals_can(1, time_pause_modbus_can_terminals);
write_all_data_to_terminals_can(1, TIME_PAUSE_MODBUS_CAN_TERMINALS);
#endif

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