попытка запустить 23550_on_ship. такая же фигня, шим красивый но неправильный
This commit is contained in:
parent
2163dad313
commit
a6023bbdcb
@ -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.
|
||||
|
@ -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
|
||||
|
||||
|
@ -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);
|
||||
|
@ -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;
|
||||
|
||||
|
||||
|
||||
|
@ -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_ */
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////////////////////
|
||||
|
@ -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 \
|
||||
|
@ -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;
|
||||
|
@ -65,6 +65,9 @@ void exp_regul_iq_fast(_iq k_exp_regul, _iq *InpVarCurr, _iq InpVarInstant);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
@ -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;
|
||||
}
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -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];
|
||||
|
||||
|
||||
|
@ -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;
|
||||
////////////////////////////////////////
|
||||
////////////////////////////////////////
|
||||
|
@ -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;
|
||||
|
@ -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);
|
||||
|
@ -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);
|
||||
|
@ -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;
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -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,
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -257,8 +257,5 @@ int test_xilinx_live(void);
|
||||
|
||||
int enable_er0_control(void);
|
||||
|
||||
void ResetNPeriphPlane(unsigned int np);
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
||||
|
||||
|
@ -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); }
|
||||
|
@ -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
|
||||
{
|
||||
|
@ -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;
|
||||
|
@ -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}
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
@ -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;
|
||||
|
||||
|
@ -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;
|
||||
}
|
||||
|
@ -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}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////////
|
||||
////
|
||||
|
@ -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);
|
||||
|
267
Inu/Src/N12_Xilinx/xp_rotation_sensor.c
Normal file
267
Inu/Src/N12_Xilinx/xp_rotation_sensor.c
Normal file
@ -0,0 +1,267 @@
|
||||
#include "xp_project.h"
|
||||
#include "xp_rotation_sensor.h"
|
||||
|
||||
#include "xp_project.h"
|
||||
|
||||
|
||||
T_rotation_sensor rotation_sensor = T_CDS_ROTATION_SENSOR_DEFAULTS;
|
||||
|
||||
//Äèñêðåòèçàöèþ, ïðè êîòîðîé ðàñ÷èòûâàåòñþ äëèòåëüíîñòü èìïóëüñîâ
|
||||
#define SAMPLING_TIME_NS 1 // 16,666667ns
|
||||
#define SAMPLING_TIME_MS 0 // 1,666667us
|
||||
// Êîëè÷åñòâî èìïóëüñîâ, ïðè êîòîðûõ ïåðåêëþ÷àåòñó ïåðèîä äèñêðåòèçàöèè.
|
||||
// Âåëè÷èíû âûáðàíû ñ "íàõë¸ñòîì" ÷òî áû íå áûëî ïîñòîþííûõ ïåðåêëþ÷åíèé
|
||||
// â ðàéîíå ãðàíè÷íûõ âåëè÷èí
|
||||
#define LEVEL_SWITCH_NANOSEC 327
|
||||
#define LEVEL_SWITCH_MICROSEC 0xC000
|
||||
|
||||
|
||||
static void read_in_sensor_line1(T_cds_in_rotation_sensor *rs);
|
||||
static void read_in_sensor_line2(T_cds_in_rotation_sensor *rs);
|
||||
static void read_command_reg(T_cds_in_rotation_sensor *rs);
|
||||
static void write_command_reg(T_cds_in_rotation_sensor *rs);
|
||||
static void tune_sampling_time(T_rotation_sensor *rs);
|
||||
static void wait_for_registers_updated(T_cds_in_rotation_sensor *rs);
|
||||
static void read_direction_in_plane(T_cds_in_rotation_sensor *rs);
|
||||
|
||||
void rot_sensor_set(T_rotation_sensor *rs)
|
||||
{
|
||||
|
||||
if(rs->use_sensor1 || rs->use_sensor2)
|
||||
{
|
||||
rs->in_plane.set(&rs->in_plane);
|
||||
}
|
||||
if(rs->use_angle_plane)
|
||||
{
|
||||
rs->rotation_plane.set(&rs->rotation_plane);
|
||||
}
|
||||
}
|
||||
|
||||
void in_plane_set(T_cds_in_rotation_sensor* rs)
|
||||
{
|
||||
if(!rs->cds_in->useit)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
rs->cds_in->write.sbus.enabled_channels.all = rs->write.sbus.enabled_channels.all;
|
||||
rs->cds_in->write.sbus.first_sensor.all = rs->write.sbus.first_sensor_inputs.all;
|
||||
rs->cds_in->write.sbus.second_sensor.all = rs->write.sbus.second_sensor_inputs.all;
|
||||
// rs->cds_in->write_sbus(rs->cds_in);
|
||||
write_command_reg(rs);
|
||||
|
||||
}
|
||||
|
||||
|
||||
void angle_plane_set(T_cds_angle_sensor *rs)
|
||||
{
|
||||
if((rs->cds_rs == NULL) || (!rs->cds_rs->useit))
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
rs->cds_rs->write.sbus.config.all = rs->write.sbus.config.all;
|
||||
rs->cds_rs->write_sbus(rs->cds_rs);
|
||||
}
|
||||
|
||||
void sensor_read(T_rotation_sensor *rs)
|
||||
{
|
||||
if(rs->use_sensor1 || rs->use_sensor2 || rs->use_angle_plane)
|
||||
{
|
||||
wait_for_registers_updated(&rs->in_plane);
|
||||
read_direction_in_plane(&rs->in_plane);
|
||||
}
|
||||
else
|
||||
{
|
||||
return;
|
||||
}
|
||||
if(rs->use_sensor1)
|
||||
{
|
||||
rs->in_plane.read_sensor1(&rs->in_plane);
|
||||
}
|
||||
if(rs->use_sensor2)
|
||||
{
|
||||
rs->in_plane.read_sensor2(&rs->in_plane);
|
||||
}
|
||||
if(rs->use_angle_plane)
|
||||
{
|
||||
rs->rotation_plane.read_sensor(&rs->rotation_plane);
|
||||
}
|
||||
#ifdef AUTO_CHANGE_SAMPLING_TIME
|
||||
tune_sampling_time(rs);
|
||||
#endif
|
||||
}
|
||||
|
||||
void in_sensor_read1(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
read_in_sensor_line1(rs);
|
||||
#if C_PROJECT_TYPE != PROJECT_BALZAM
|
||||
rs->out.Impulses1 = rs->read.regs.n_impulses_line1;
|
||||
rs->out.Time1 = rs->read.regs.time_line1 / 60;
|
||||
//Counter`s freq is 60ÌÃö => N/60 = time in mksec
|
||||
#endif
|
||||
rs->out.CountZero1 = rs->read.regs.zero_time_line1;
|
||||
rs->out.CountOne1 = rs->read.regs.one_time_line1;
|
||||
|
||||
rs->out.counter_freq1 = rs->read.regs.comand_reg.bit.sampling_time1;
|
||||
|
||||
rs->out.direction1 = rs->read.pbus.direction.bit.sensor1;
|
||||
}
|
||||
|
||||
void in_sensor_read2(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
read_in_sensor_line2(rs);
|
||||
#if C_PROJECT_TYPE != PROJECT_BALZAM
|
||||
rs->out.Impulses2 = rs->read.regs.n_impulses_line2;
|
||||
rs->out.Time2 = rs->read.regs.time_line2 / 60;
|
||||
#endif
|
||||
rs->out.CountZero2 = rs->read.regs.zero_time_line2;
|
||||
rs->out.CountOne2 = rs->read.regs.one_time_line2;
|
||||
|
||||
rs->out.counter_freq2 = rs->read.regs.comand_reg.bit.sampling_time2;
|
||||
|
||||
rs->out.direction2 = rs->read.pbus.direction.bit.sensor2;
|
||||
}
|
||||
|
||||
void read_in_sensor_line1(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
if(!rs->read.regs.comand_reg.bit.update_registers)
|
||||
{
|
||||
#if C_PROJECT_TYPE != PROJECT_BALZAM
|
||||
rs->read.regs.time_line1 = i_ReadMemory(ADR_SENSOR_S1_T_PERIOD);//TODO check time when turn off
|
||||
rs->read.regs.n_impulses_line1 = i_ReadMemory(ADR_SENSOR_S1_COUNT_IMPULS);
|
||||
#endif
|
||||
rs->read.regs.zero_time_line1 = i_ReadMemory(ADR_SENSOR_S1_T_PERIOD_LOW_ONE_IMPULS);
|
||||
rs->read.regs.one_time_line1 = i_ReadMemory(ADR_SENSOR_S1_T_PERIOD_HIGH_ONE_IMPULS);
|
||||
}
|
||||
}
|
||||
|
||||
void read_in_sensor_line2(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
if(!rs->read.regs.comand_reg.bit.update_registers)
|
||||
{
|
||||
#if C_PROJECT_TYPE != PROJECT_BALZAM
|
||||
rs->read.regs.time_line2 = i_ReadMemory(ADR_SENSOR_S2_T_PERIOD);
|
||||
rs->read.regs.n_impulses_line2 = i_ReadMemory(ADR_SENSOR_S2_COUNT_IMPULS);
|
||||
#endif
|
||||
rs->read.regs.zero_time_line2 = i_ReadMemory(ADR_SENSOR_S2_T_PERIOD_LOW_ONE_IMPULS);
|
||||
rs->read.regs.one_time_line2 = i_ReadMemory(ADR_SENSOR_S2_T_PERIOD_HIGH_ONE_IMPULS);
|
||||
}
|
||||
}
|
||||
|
||||
void write_command_reg(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
WriteMemory(ADR_SENSOR_CMD, rs->write.regs.comand_reg.all);
|
||||
}
|
||||
|
||||
void read_command_reg(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
rs->read.regs.comand_reg.all = i_ReadMemory(ADR_SENSOR_CMD);
|
||||
}
|
||||
|
||||
void update_sensors_data_r(T_rotation_sensor *rs)
|
||||
{
|
||||
rs->in_plane.write.regs.comand_reg.bit.update_registers = 1;
|
||||
write_command_reg(&rs->in_plane);
|
||||
// rs->in_plane.write.regs.comand_reg.bit.update_registers = 0;
|
||||
}
|
||||
|
||||
void read_direction_in_plane(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
/*
|
||||
rs->read.pbus.direction.bit.sensor1 = rs->cds_in->read.pbus.direction_in.bit.dir0 == 2 ? 1 :
|
||||
rs->cds_in->read.pbus.direction_in.bit.dir0 == 1 ? -1 :
|
||||
0;
|
||||
rs->read.pbus.direction.bit.sensor2 = rs->cds_in->read.pbus.direction_in.bit.dir1 == 2 ? 1 :
|
||||
rs->cds_in->read.pbus.direction_in.bit.dir1 == 1 ? -1 :
|
||||
0;
|
||||
rs->read.pbus.direction.bit.sens_err1 = rs->cds_in->read.pbus.direction_in.bit.dir0 == 3;
|
||||
rs->read.pbus.direction.bit.sens_err2 = rs->cds_in->read.pbus.direction_in.bit.dir1 == 3;
|
||||
*/
|
||||
//Direction changes not often. May be, it`s enough to read it in main cycle.
|
||||
}
|
||||
|
||||
void wait_for_registers_updated(T_cds_in_rotation_sensor *rs)
|
||||
{
|
||||
int counter_in_while = 0;
|
||||
read_command_reg(rs);
|
||||
while(rs->read.regs.comand_reg.bit.update_registers)
|
||||
{
|
||||
read_command_reg(rs);
|
||||
rs->count_wait_for_update_registers++;
|
||||
counter_in_while++;
|
||||
if(counter_in_while > 1000)
|
||||
{
|
||||
rs->error_update++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void tune_sampling_time(T_rotation_sensor *rs)
|
||||
{
|
||||
if((rs->use_sensor1 && (rs->in_plane.read.regs.zero_time_line1 < LEVEL_SWITCH_NANOSEC))
|
||||
|| (rs->use_sensor2 && (rs->in_plane.read.regs.zero_time_line2 < LEVEL_SWITCH_NANOSEC)))
|
||||
{
|
||||
rs->in_plane.write.regs.comand_reg.bit.set_sampling_time = SAMPLING_TIME_NS;
|
||||
}
|
||||
|
||||
if((rs->use_sensor1 && (rs->in_plane.read.regs.zero_time_line1 > LEVEL_SWITCH_MICROSEC))
|
||||
|| (rs->use_sensor2 && (rs->in_plane.read.regs.zero_time_line2 > LEVEL_SWITCH_MICROSEC)))
|
||||
{
|
||||
rs->in_plane.write.regs.comand_reg.bit.set_sampling_time = SAMPLING_TIME_MS;
|
||||
}
|
||||
}
|
||||
|
||||
void angle_sensor_read(T_cds_angle_sensor *as)
|
||||
{
|
||||
as->cds_rs->read_pbus(as->cds_rs);
|
||||
|
||||
if(as->cds_rs->read.sbus.config.bit.channel1_enable)
|
||||
{
|
||||
// logpar.log15 = as->cds_rs->read.pbus.sensor[0].turned_angle;
|
||||
// logpar.log16 = as->cds_rs->read.pbus.sensor[0].angle;
|
||||
|
||||
as->out.Delta_angle1 = as->cds_rs->read.pbus.sensor[0].turned_angle;
|
||||
as->out.Current_angle1 = as->cds_rs->read.pbus.sensor[0].angle << 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
as->out.Delta_angle1 = 0;
|
||||
as->out.Current_angle1 = 0;
|
||||
}
|
||||
if(as->cds_rs->read.sbus.config.bit.channel2_enable)
|
||||
{
|
||||
as->out.Delta_angle2 = as->cds_rs->read.pbus.sensor[1].turned_angle;
|
||||
as->out.Current_angle2 = as->cds_rs->read.pbus.sensor[1].angle << 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
as->out.Delta_angle2 = 0;
|
||||
as->out.Current_angle2 = 0;
|
||||
}
|
||||
if(as->cds_rs->read.sbus.config.bit.channel3_enable)
|
||||
{
|
||||
as->out.Delta_angle3 = as->cds_rs->read.pbus.sensor[2].turned_angle;
|
||||
as->out.Current_angle3 = as->cds_rs->read.pbus.sensor[2].angle << 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
as->out.Delta_angle3 = 0;
|
||||
as->out.Current_angle3 = 0;
|
||||
}
|
||||
if(as->cds_rs->read.sbus.config.bit.channel4_enable)
|
||||
{
|
||||
as->out.Delta_angle4 = as->cds_rs->read.pbus.sensor[3].turned_angle;
|
||||
as->out.Current_angle4 = as->cds_rs->read.pbus.sensor[3].angle << 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
as->out.Delta_angle4 = 0;
|
||||
as->out.Current_angle4 = 0;
|
||||
}
|
||||
|
||||
as->out.survey_time_mks = (as->read.sbus.config.bit.survey_time + 1) * 10;
|
||||
|
||||
}
|
||||
|
346
Inu/Src/N12_Xilinx/xp_rotation_sensor.h
Normal file
346
Inu/Src/N12_Xilinx/xp_rotation_sensor.h
Normal file
@ -0,0 +1,346 @@
|
||||
#ifndef XP_ROT_SENS_H
|
||||
#define XP_ROT_SENS_H
|
||||
|
||||
#include "x_basic_types.h"
|
||||
#include "xp_cds_in.h"
|
||||
#include "xp_cds_rs.h"
|
||||
|
||||
|
||||
//RS speed of angle sensor
|
||||
#define TS400 0
|
||||
#define TS350 1
|
||||
#define TS300 2
|
||||
#define TS250 3
|
||||
#define TS200 4
|
||||
|
||||
//Äèñêðåòèçàöèþ, ïðè êîòîðîé ðàñ÷èòûâàåòñþ äëèòåëüíîñòü èìïóëüñîâ
|
||||
#define SAMPLING_TIME_NS 1 // 16,666667ns
|
||||
#define SAMPLING_TIME_MS 0 // 1,666667us
|
||||
|
||||
//Àâòîìàòè÷åñêè ïåðåêëþ÷àåò ñ÷¸ò÷èê, êîãäà êîëè÷åñòâî îòñ÷¸òîâ
|
||||
// íà 1 èìïóëüñ ñòàíîâèòñß ñëèøêîì áîëüøèì èëè ìàëåíüêèì.
|
||||
//#define AUTO_CHANGE_SAMPLING_TIME
|
||||
/*
|
||||
×òî áû ïðî÷èòàòü äàííûå èç äàò÷èêà, íóæíî âûçâàòü
|
||||
rotation_sensor.read_sensors(&rotation_sensor);
|
||||
Ðåçóëüòàò ïëàòû IN áóäåò â
|
||||
rotation_sensor.in_plane.out....
|
||||
Ðåçóëüòàò ïëàòû RS áóäåò â
|
||||
rotation_sensor.rotation_plane.out....
|
||||
*/
|
||||
|
||||
/////////////////////////////////////////////////////////////
|
||||
// IN plane
|
||||
/////////////////////////////////////////////////////////////
|
||||
|
||||
// Registers with data for rotation sensor
|
||||
|
||||
typedef union {
|
||||
unsigned int all;
|
||||
struct {
|
||||
unsigned int filter_sensitivity:12;
|
||||
unsigned int set_sampling_time:1; //(1)-16,666667ns (0)-1,666667us
|
||||
unsigned int sampling_time2:1; //(1)-16,666667ns (0)-1,666667us
|
||||
unsigned int sampling_time1:1;
|
||||
unsigned int update_registers:1; //0 - updated
|
||||
}bit;
|
||||
}T_cds_in_comand;
|
||||
|
||||
#define R_CDS_IN_COMAND_DEFAULT 0
|
||||
|
||||
typedef struct {
|
||||
unsigned int time_line1;
|
||||
unsigned int n_impulses_line1;
|
||||
unsigned int time_line2;
|
||||
unsigned int n_impulses_line2;
|
||||
|
||||
unsigned int zero_time_line1;
|
||||
unsigned int one_time_line1;
|
||||
unsigned int zero_time_line2;
|
||||
unsigned int one_time_line2;
|
||||
|
||||
T_cds_in_comand comand_reg;
|
||||
|
||||
} T_cds_in_rotation_sensor_read_regs;
|
||||
|
||||
#define T_CDS_IN_ROTATION_SENSOR_READ_REGS_DEFAULTS {0,0,0,0, 0,0,0,0, R_CDS_IN_COMAND_DEFAULT}
|
||||
|
||||
typedef struct {
|
||||
T_cds_in_comand comand_reg;
|
||||
|
||||
} T_cds_in_rotation_sensor_write_regs;
|
||||
|
||||
#define T_CDS_IN_ROTATION_SENSOR_WRITE_REGS_DEFAULTS {R_CDS_IN_COMAND_DEFAULT}
|
||||
|
||||
/////////////////////////////////////////////////////////////
|
||||
//read reg parallel bus
|
||||
/////////////////////////////////////////////////////////////
|
||||
typedef struct {
|
||||
union {
|
||||
unsigned int all;
|
||||
struct {
|
||||
int sensor1:4;
|
||||
int sensor2:4;
|
||||
unsigned int sens_err1:1;
|
||||
unsigned int sens_err2:1;
|
||||
unsigned int reserved:6;
|
||||
} bit;
|
||||
} direction;
|
||||
|
||||
} T_cds_in_rotation_sensor_read_pbus;
|
||||
|
||||
#define T_CDS_IN_ROTATION_SENSOR_READ_PBUS_DEFAULTS {0}
|
||||
|
||||
/////////////////////////////////////////////////////////////
|
||||
// write serial bus reg
|
||||
/////////////////////////////////////////////////////////////
|
||||
typedef struct {
|
||||
//0
|
||||
union
|
||||
{
|
||||
UInt16 all;
|
||||
struct{
|
||||
UInt16 discret : 8;
|
||||
UInt16 reserv : 7;
|
||||
UInt16 sens_2_inv_ch_90deg : 1;
|
||||
UInt16 sens_2_direct_ch_90deg : 1;
|
||||
UInt16 sens_2_inv_ch : 1;
|
||||
UInt16 sens_2_direct_ch : 1;
|
||||
UInt16 sens_1_inv_ch_90deg : 1;
|
||||
UInt16 sens_1_direct_ch_90deg : 1;
|
||||
UInt16 sens_1_inv_ch : 1;
|
||||
UInt16 sens_1_direct_ch : 1;
|
||||
}bit;
|
||||
}enabled_channels;
|
||||
|
||||
//1
|
||||
union
|
||||
{
|
||||
UInt16 all;
|
||||
struct{
|
||||
UInt16 inv_ch_90deg : 4;
|
||||
UInt16 direct_ch_90deg : 4;
|
||||
UInt16 inv_ch : 4;
|
||||
UInt16 direct_ch : 4;
|
||||
}bit;
|
||||
}first_sensor_inputs;
|
||||
|
||||
//2
|
||||
union
|
||||
{
|
||||
UInt16 all;
|
||||
struct{
|
||||
UInt16 inv_ch_90deg : 4;
|
||||
UInt16 direct_ch_90deg : 4;
|
||||
UInt16 inv_ch : 4;
|
||||
UInt16 direct_ch : 4;
|
||||
}bit;
|
||||
}second_sensor_inputs;
|
||||
|
||||
} T_cds_in_rotation_sensor_write_sbus;
|
||||
|
||||
#define T_CDS_IN_ROTATION_SENSOR_WRITE_SBUS_DEFAULTS {0, 0, 0}
|
||||
|
||||
////////////////////////////////////////////////////////
|
||||
typedef struct {
|
||||
T_cds_in_rotation_sensor_read_pbus pbus;
|
||||
T_cds_in_rotation_sensor_read_regs regs;
|
||||
}T_cds_in_rotation_sensor_read;
|
||||
|
||||
#define T_CDS_IN_ROTATION_SENSOR_READ_DEFAULTS \
|
||||
{T_CDS_IN_ROTATION_SENSOR_READ_PBUS_DEFAULTS, \
|
||||
T_CDS_IN_ROTATION_SENSOR_READ_REGS_DEFAULTS}
|
||||
|
||||
typedef struct {
|
||||
T_cds_in_rotation_sensor_write_sbus sbus;
|
||||
T_cds_in_rotation_sensor_read_regs regs;
|
||||
}T_cds_in_rotation_sensor_write;
|
||||
|
||||
#define T_CDS_IN_ROTATION_SENSOR_WRITE_DEFAULTS \
|
||||
{T_CDS_IN_ROTATION_SENSOR_WRITE_SBUS_DEFAULTS, \
|
||||
T_CDS_IN_ROTATION_SENSOR_WRITE_REGS_DEFAULTS}
|
||||
|
||||
|
||||
////// Rotation sensor with IN plane
|
||||
typedef struct {
|
||||
//UInt16 plane_address;
|
||||
unsigned int count_wait_for_update_registers;
|
||||
unsigned int error_update;
|
||||
|
||||
struct {
|
||||
|
||||
unsigned int Time1; // Sensor's survey time in mksec
|
||||
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 counter_freq1; // 1 - 60MHz; 0 - 600KHz
|
||||
int direction1; // 1 - direct; 0 - reverse
|
||||
|
||||
unsigned int Time2; // Sensor's survey time in mksec
|
||||
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 counter_freq2; // 1 - 60MHz; 0 - 600KHz
|
||||
int direction2; // 1 - direct; 0 - reverse
|
||||
} out;
|
||||
|
||||
T_cds_in *cds_in;
|
||||
|
||||
T_cds_in_rotation_sensor_write write;
|
||||
T_cds_in_rotation_sensor_read read;
|
||||
|
||||
void (*set)(); // Pointer to calculation function
|
||||
|
||||
void (*read_sensor1)();
|
||||
|
||||
void (*read_sensor2)();
|
||||
|
||||
} T_cds_in_rotation_sensor;
|
||||
|
||||
#define T_CDS_IN_ROTATION_SENSOR_DEFAULT \
|
||||
{0, 0, \
|
||||
{0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, \
|
||||
NULL, \
|
||||
T_CDS_IN_ROTATION_SENSOR_WRITE_DEFAULTS, \
|
||||
T_CDS_IN_ROTATION_SENSOR_READ_DEFAULTS, \
|
||||
in_plane_set, \
|
||||
in_sensor_read1, \
|
||||
in_sensor_read2}
|
||||
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////
|
||||
///// Rotation Plane
|
||||
///////////////////////////////////////////////////////////////////////////
|
||||
typedef union {
|
||||
unsigned int all;
|
||||
struct {
|
||||
unsigned int survey_time:8; //Ïåðèîä îïðîñà ïî 10ìêñ (0==10, 1==20,...)
|
||||
unsigned int channel4_enable:1;
|
||||
unsigned int channel3_enable:1;
|
||||
unsigned int channel2_enable:1;
|
||||
unsigned int channel1_enable:1;
|
||||
unsigned int transmition_speed:3;
|
||||
unsigned int plane_is_master:1;
|
||||
}bit;
|
||||
} T_cds_rotation_plane_config;
|
||||
|
||||
#define T_CDS_ROTATION_PLANE_CONFIG_DEFAULT 0xA031 //{49, 1, 0, 0, 0, 2, 1}
|
||||
|
||||
typedef struct {
|
||||
T_cds_rotation_plane_config config;
|
||||
} T_cds_rotation_plane_write_sbus;
|
||||
|
||||
#define T_CDS_ROTATION_PLANE_WRITE_SBUS_DEFAULT \
|
||||
{T_CDS_ROTATION_PLANE_CONFIG_DEFAULT}
|
||||
|
||||
typedef struct {
|
||||
int direction;
|
||||
unsigned int turned_angle;
|
||||
unsigned int angle;
|
||||
} RsSensor;
|
||||
|
||||
#define SENSOR_DEFAULT {0, 0, 0}
|
||||
|
||||
typedef struct {
|
||||
RsSensor sensor[4];
|
||||
} T_cds_rotation_plane_read_pbus;
|
||||
|
||||
#define T_CDS_ROTATION_PLANE_READ_PBUS_DEFAULT { \
|
||||
{SENSOR_DEFAULT, SENSOR_DEFAULT, SENSOR_DEFAULT, SENSOR_DEFAULT}}
|
||||
|
||||
typedef struct {
|
||||
T_cds_rotation_plane_config config;
|
||||
} T_cds_rotation_plane_read_sbus;
|
||||
|
||||
#define T_CDS_ROTATION_PLANE_READ_SBUS_DEFAULT {T_CDS_ROTATION_PLANE_CONFIG_DEFAULT}
|
||||
|
||||
typedef struct {
|
||||
T_cds_rotation_plane_write_sbus sbus;
|
||||
} T_cds_rotation_plane_write;
|
||||
|
||||
#define T_CDS_ROTATION_PLANE_WRITE_DEFAULT \
|
||||
{T_CDS_ROTATION_PLANE_WRITE_SBUS_DEFAULT}
|
||||
|
||||
typedef struct {
|
||||
T_cds_rotation_plane_read_pbus pbus;
|
||||
T_cds_rotation_plane_read_sbus sbus;
|
||||
} T_cds_rotation_plane_read;
|
||||
|
||||
#define T_CDS_ROTATION_PLANE_READ_DEFAULT \
|
||||
{T_CDS_ROTATION_PLANE_READ_PBUS_DEFAULT, T_CDS_ROTATION_PLANE_READ_SBUS_DEFAULT}
|
||||
|
||||
typedef struct {
|
||||
|
||||
struct {
|
||||
unsigned long Delta_angle1;
|
||||
unsigned long Delta_angle2;
|
||||
unsigned long Delta_angle3;
|
||||
unsigned long Delta_angle4;
|
||||
unsigned long Current_angle1;
|
||||
unsigned long Current_angle2;
|
||||
unsigned long Current_angle3;
|
||||
unsigned long Current_angle4;
|
||||
unsigned int survey_time_mks; //Âðåìß îïðîñà äàò÷èêà â ìêñ
|
||||
unsigned int direction;
|
||||
} out;
|
||||
|
||||
unsigned int error;
|
||||
|
||||
T_cds_rs *cds_rs;
|
||||
|
||||
T_cds_rotation_plane_read read;
|
||||
T_cds_rotation_plane_write write;
|
||||
|
||||
void (*set)(); // Pointer to calculation function
|
||||
|
||||
void (*read_sensor)();
|
||||
|
||||
} T_cds_angle_sensor;
|
||||
|
||||
#define T_CDS_ANGLE_SENSOR_DEFAULT { \
|
||||
{0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, \
|
||||
0, NULL, \
|
||||
T_CDS_ROTATION_PLANE_READ_DEFAULT, \
|
||||
T_CDS_ROTATION_PLANE_WRITE_DEFAULT, \
|
||||
angle_plane_set, angle_sensor_read}
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////////
|
||||
////
|
||||
//////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
typedef struct {
|
||||
UInt16 use_sensor1;
|
||||
UInt16 use_sensor2;
|
||||
UInt16 use_angle_plane;
|
||||
|
||||
T_cds_in_rotation_sensor in_plane;
|
||||
T_cds_angle_sensor rotation_plane;
|
||||
|
||||
void (*set)(); // Pointer to calculation function
|
||||
void (*read_sensors)();
|
||||
void (*update_registers)();
|
||||
|
||||
} T_rotation_sensor;
|
||||
|
||||
#define T_CDS_ROTATION_SENSOR_DEFAULTS {0, 0, 0, \
|
||||
T_CDS_IN_ROTATION_SENSOR_DEFAULT, \
|
||||
T_CDS_ANGLE_SENSOR_DEFAULT, \
|
||||
rot_sensor_set, \
|
||||
sensor_read, \
|
||||
update_sensors_data_r}
|
||||
|
||||
//Public functions
|
||||
void rot_sensor_set(T_rotation_sensor *rs);
|
||||
void sensor_read(T_rotation_sensor *rs);
|
||||
void update_sensors_data_r(T_rotation_sensor *rs);
|
||||
void angle_plane_set(T_cds_angle_sensor *rs);
|
||||
void angle_sensor_read(T_cds_angle_sensor *as);
|
||||
void in_plane_set(T_cds_in_rotation_sensor* rs);
|
||||
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;
|
||||
|
||||
#endif //XP_ROT_SENS_H
|
@ -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 \
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
@ -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
@ -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);
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////
|
||||
|
@ -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++)
|
||||
{
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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)
|
||||
{
|
||||
@ -605,13 +293,13 @@ void simple_scalar(int n_alg,
|
||||
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 );
|
||||
|
||||
// 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));
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -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);
|
||||
|
@ -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);
|
||||
|
@ -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();
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
@ -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\
|
||||
};
|
||||
|
||||
|
||||
|
@ -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];
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -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 // ïîñëåäíèé êîä â ñïèñêå, âñåãäà äîëæåí áûòü, íå óäàëÿòü åãî, èñïîëüçóåì äëÿ ðàçìåðíîñòè ìàññèâà.
|
||||
};
|
||||
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -118,7 +118,7 @@ typedef struct {
|
||||
//Setup
|
||||
SETUP_3_PHASE_PROTECT setup;
|
||||
|
||||
int (*calc_detect_error_3_phase)();
|
||||
int (*calc)();
|
||||
|
||||
} DETECT_PROTECT_3_PHASE;
|
||||
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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_ */
|
||||
|
@ -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;
|
||||
|
@ -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);
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -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
|
||||
|
||||
|
||||
|
@ -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ть, где логи лежат
|
@ -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 }
|
||||
|
||||
|
||||
|
@ -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_ */
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
||||
|
@ -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);
|
||||
|
||||
|
||||
/*
|
||||
|
@ -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
|
||||
|
||||
|
||||
|
@ -15,7 +15,7 @@
|
||||
// void ReceiveAnswerCommandModbus3(RS_DATA *rs_arr);
|
||||
|
||||
#define TIME_PAUSE_MODBUS_MPU 250 //100//500
|
||||
#define TIME_PAUSE_MODBUS_REMOUTE 20 //100 //500
|
||||
#define TIME_PAUSE_MODBUS_REMOUTE 100 //500
|
||||
|
||||
#define TIME_PAUSE_NETWORK_CAN1 444 //500
|
||||
#define TIME_PAUSE_NETWORK_CAN2 990 //500
|
||||
@ -30,11 +30,11 @@
|
||||
|
||||
#define SIZE_BUF_WRITE_TO_MODBUS16_VPU 100 //
|
||||
|
||||
#define SIZE_BUF_WRITE_TO_MODBUS16_REMOUTE 120 //100 // ïåðåäà÷à, ðàçìåð â îäíîé ïîñûëêå àíàëîã.÷àñòè ïóëüòà ÁÑÓ, íå áîëüøå SIZE_ANALOG_DATA_REMOUTE
|
||||
#define SIZE_ANALOG_DATA_REMOUTE 240 //165 // ïåðåäà÷à, ðàçìåð äàííûõ ïî àíàëîãîâîé ÷àñòè ïóëüòà ÁÑÓ
|
||||
#define SIZE_BUF_WRITE_TO_MODBUS16_REMOUTE 100 //100 // ïåðåäà÷à, ðàçìåð â îäíîé ïîñûëêå àíàëîã.÷àñòè ïóëüòà ÁÑÓ, íå áîëüøå SIZE_ANALOG_DATA_REMOUTE
|
||||
#define SIZE_ANALOG_DATA_REMOUTE 200 //165 // ïåðåäà÷à, ðàçìåð äàííûõ ïî àíàëîãîâîé ÷àñòè ïóëüòà ÁÑÓ
|
||||
|
||||
|
||||
#define SIZE_BUF_READ_FROM_MODBUS16_REMOUTE 120 //20//36 // ïðèåì, ðàçìåð â îäíîé ïîñûëêå àíàëîã.÷àñòè ïóëüòà ÁÑÓ, íå áîëüøå SIZE_ANALOG_DATA_FROM_MODBUS16_REMOUTE
|
||||
#define SIZE_BUF_READ_FROM_MODBUS16_REMOUTE 100 //20//36 // ïðèåì, ðàçìåð â îäíîé ïîñûëêå àíàëîã.÷àñòè ïóëüòà ÁÑÓ, íå áîëüøå SIZE_ANALOG_DATA_FROM_MODBUS16_REMOUTE
|
||||
#define SIZE_ANALOG_DATA_FROM_MODBUS16_REMOUTE SIZE_ANALOG_DATA_REMOUTE //20//36 // ïðèåì, ðàçìåð äàííûõ ïî àíàëîãîâîé ÷àñòè ïóëüòà ÁÑÓ
|
||||
|
||||
|
||||
|
@ -1,4 +1,4 @@
|
||||
#include "log_to_memory.h"
|
||||
#include <log_to_mem.h>
|
||||
#include <message_modbus.h>
|
||||
#include <modbus_hmi.h>
|
||||
#include <modbus_hmi_update.h>
|
||||
@ -11,7 +11,6 @@
|
||||
#include "DSP281x_Device.h"
|
||||
#include "MemoryFunctions.h"
|
||||
#include "RS_modbus_svu.h"
|
||||
#include "log_params.h"
|
||||
|
||||
|
||||
#pragma DATA_SECTION(modbus_table_discret_in,".logs");
|
||||
@ -27,15 +26,17 @@ MODBUS_REG_STRUCT modbus_table_analog_in[SIZE_MODBUS_ANALOG_REMOUTE]; //regist
|
||||
//MODBUS_REG_STRUCT modbus_table_analog_out[700]; //registers 40001-49999 modbus RTU
|
||||
MODBUS_REG_STRUCT modbus_table_analog_out[SIZE_MODBUS_ANALOG_REMOUTE]; //registers 40001-49999 modbus RTU
|
||||
|
||||
//#pragma DATA_SECTION(modbus_table_analog_out2, ".logs");
|
||||
//MODBUS_REG_STRUCT modbus_table_analog_out[700]; //registers 40001-49999 modbus RTU
|
||||
//MODBUS_REG_STRUCT modbus_table_analog_out2[SIZE_MODBUS_ANALOG_REMOUTE]; //registers 40001-49999 modbus RTU
|
||||
|
||||
|
||||
//unsigned int flag_waiting_answer = 1;
|
||||
//unsigned int flag_message_sent = 0;
|
||||
|
||||
#pragma DATA_SECTION(log_to_HMI, ".logs");
|
||||
Logs_with_modbus log_to_HMI = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
static int writeLogsArray();
|
||||
static void prepareWriteLogsArray(void);
|
||||
static void fillAnalogDataArrayForLogSend(int num_of_log);
|
||||
///////////////////////////////////////////////////
|
||||
///
|
||||
///////////////////////////////////////////////////
|
||||
@ -53,14 +54,28 @@ void clear_table_remoute(void)
|
||||
{
|
||||
modbus_table_analog_in[i].all = 0;
|
||||
modbus_table_analog_out[i].all = 0;
|
||||
//modbus_table_analog_out2[i].all = 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
///////////////////////////////////////////////////
|
||||
///
|
||||
///////////////////////////////////////////////////
|
||||
|
||||
void fillLogArea() {
|
||||
unsigned int value = 0;
|
||||
unsigned int *p_memory = (unsigned int*)LOG_START_ADRES;
|
||||
long log_size = LOG_BUFFER_SIZE;
|
||||
while (log_size-- > 0) {
|
||||
*(p_memory++) = value;
|
||||
value += 1;
|
||||
// if (log_size % 8 == 0) {
|
||||
// value += 1;
|
||||
// }
|
||||
}
|
||||
}
|
||||
///////////////////////////////////////////////////
|
||||
///
|
||||
///////////////////////////////////////////////////
|
||||
@ -180,9 +195,6 @@ int writeSingleAnalogOutputToRemote(unsigned int adres)
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
///////////////////////////////////////////////////
|
||||
///
|
||||
///////////////////////////////////////////////////
|
||||
@ -292,50 +304,6 @@ int readAnalogDataFromRemote()
|
||||
return succed;
|
||||
}
|
||||
|
||||
|
||||
int writeSingleAnalogDataToRemote(int from_adr, int count_wr)
|
||||
{
|
||||
int succed = 0;
|
||||
static unsigned int old_time = 0;
|
||||
|
||||
static int count_write_to_modbus = 0;
|
||||
static int cur_position_buf_modbus16 = 0;
|
||||
|
||||
|
||||
ModbusRTUsetDataArrays(modbus_table_analog_in, modbus_table_analog_out);
|
||||
|
||||
|
||||
if (!rs_b.flag_LEADING)
|
||||
{
|
||||
cur_position_buf_modbus16 = from_adr;
|
||||
|
||||
// if (control_station.flag_waiting_answer[CONTROL_STATION_INGETEAM_PULT_RS485] == 0)
|
||||
// cur_position_buf_modbus16 = cur_position_buf_modbus16 + SIZE_BUF_WRITE_TO_MODBUS16_REMOUTE;
|
||||
//
|
||||
// if (cur_position_buf_modbus16 >= SIZE_ANALOG_DATA_REMOUTE)
|
||||
// cur_position_buf_modbus16 = 0;
|
||||
|
||||
// //Äûðêà â îáìåíå. Ïðîïóñêàåì.
|
||||
// if ((cur_position_buf_modbus16 > ADRESS_END_FIRST_BLOCK) &&
|
||||
// (cur_position_buf_modbus16 < ADRESS_START_PROTECTION_LEVELS)) {
|
||||
// cur_position_buf_modbus16 = ADRESS_START_PROTECTION_LEVELS;
|
||||
// }
|
||||
|
||||
if ((cur_position_buf_modbus16 + count_wr) > SIZE_ANALOG_DATA_REMOUTE)
|
||||
count_write_to_modbus = SIZE_ANALOG_DATA_REMOUTE - cur_position_buf_modbus16;
|
||||
else
|
||||
count_write_to_modbus = count_wr;
|
||||
|
||||
ModbusRTUsend16(&rs_b, 2,
|
||||
ADR_MODBUS_TABLE_REMOUTE + cur_position_buf_modbus16,
|
||||
count_write_to_modbus);
|
||||
|
||||
succed = 1;
|
||||
}
|
||||
return succed;
|
||||
}
|
||||
|
||||
|
||||
///////////////////////////////////////////////////
|
||||
///
|
||||
///////////////////////////////////////////////////
|
||||
@ -381,6 +349,159 @@ int writeAnalogDataToRemote()
|
||||
return succed;
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////
|
||||
///
|
||||
///////////////////////////////////////////////////
|
||||
int sendLogToHMI()
|
||||
{
|
||||
int succed = 0;
|
||||
unsigned int time_finish_transmitt = 0;
|
||||
if (log_to_HMI.send_log == 0)
|
||||
{
|
||||
log_to_HMI.step = 0;
|
||||
log_to_HMI.flag_data_received = 0;
|
||||
log_to_HMI.flag_log_array_sent = 0;
|
||||
log_to_HMI.log_size_sent = 0;
|
||||
log_to_HMI.current_address = 0;
|
||||
log_to_HMI.number_of_log = 0;
|
||||
setRegisterDiscreteOutput(0, 522);
|
||||
// control_station.flag_message_sent[CONTROL_STATION_INGETEAM_PULT_RS485] = 1;
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (log_to_HMI.step == 0)
|
||||
{
|
||||
modbus_table_analog_out[3].all = logpar.count_log_params_fast_log;
|
||||
|
||||
if (log_to_HMI.log_size_sent == 0 &&
|
||||
(writeSingleAnalogOutputToRemote(3) == 1))
|
||||
{
|
||||
log_to_HMI.log_size_sent = 1;
|
||||
succed = 1;
|
||||
} else if (log_to_HMI.log_size_sent == 1) {
|
||||
log_to_HMI.step = 1;
|
||||
log_to_HMI.flag_log_array_sent = 0;
|
||||
prepareWriteLogsArray();
|
||||
fillAnalogDataArrayForLogSend(log_to_HMI.number_of_log);
|
||||
}
|
||||
}
|
||||
if (log_to_HMI.step == 1) {
|
||||
if (log_to_HMI.flag_log_array_sent == 0) {
|
||||
succed = writeLogsArray(log_to_HMI.number_of_log);
|
||||
} else {
|
||||
log_to_HMI.step = 2;
|
||||
init_timer_milisec(&time_finish_transmitt);
|
||||
}
|
||||
}
|
||||
if (log_to_HMI.step == 2)
|
||||
{
|
||||
if (detect_pause_milisec(1000, &time_finish_transmitt)) {
|
||||
setRegisterDiscreteOutput(1, 522);
|
||||
if (writeDiscreteDataToRemote() == 1) {
|
||||
log_to_HMI.step = 3;
|
||||
succed = 1;
|
||||
}
|
||||
} else {
|
||||
succed = 1;
|
||||
}
|
||||
|
||||
}
|
||||
if (log_to_HMI.step == 3) {
|
||||
succed = readAnalogDataFromRemote();
|
||||
if (modbus_table_analog_in[8].all == 1) {
|
||||
if (detect_pause_milisec(1000, &time_finish_transmitt)) {
|
||||
log_to_HMI.step = 4;
|
||||
}
|
||||
} else {
|
||||
init_timer_milisec(&time_finish_transmitt);
|
||||
}
|
||||
}
|
||||
if (log_to_HMI.step == 4) {
|
||||
setRegisterDiscreteOutput(0, 522);
|
||||
if (writeDiscreteDataToRemote() == 1) {
|
||||
log_to_HMI.step = 5;
|
||||
succed = 1;
|
||||
}
|
||||
}
|
||||
if (log_to_HMI.step == 5) {
|
||||
succed = readAnalogDataFromRemote();
|
||||
if (modbus_table_analog_in[8].all == 0) {
|
||||
if (detect_pause_milisec(1000, &time_finish_transmitt) && log_to_HMI.number_of_log < (logpar.count_log_params_fast_log - 1)) {
|
||||
log_to_HMI.number_of_log += 1;
|
||||
fillAnalogDataArrayForLogSend(log_to_HMI.number_of_log);
|
||||
log_to_HMI.flag_log_array_sent = 0;
|
||||
log_to_HMI.step = 1;
|
||||
} else {
|
||||
succed = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
log_to_HMI.send_log = modbus_table_analog_in[7].all;
|
||||
// control_station.flag_message_sent[CONTROL_STATION_INGETEAM_PULT_RS485] = 1;
|
||||
return succed;
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////
|
||||
///
|
||||
///////////////////////////////////////////////////
|
||||
|
||||
#define START_ARRAY_LOG_SEND 200
|
||||
#define END_ARRAY_LOG_SEND 699
|
||||
#define SIZE_ARRAY_LOG_SEND (END_ARRAY_LOG_SEND - START_ARRAY_LOG_SEND + 1)
|
||||
|
||||
int writeLogsArray()
|
||||
{
|
||||
unsigned long i = 0;
|
||||
int succed = 0;
|
||||
int *p_log_data = (int*)LOG_START_ADRES;
|
||||
ModbusRTUsetDataArrays(modbus_table_analog_in, modbus_table_analog_out);
|
||||
if (!rs_b.flag_LEADING)
|
||||
{
|
||||
ModbusRTUsend16(&rs_b, 2,
|
||||
log_to_HMI.current_address,
|
||||
log_to_HMI.count_write_to_modbus + 1);
|
||||
|
||||
if (err_send_log_16 == 0) { //prev message without errors
|
||||
log_to_HMI.current_address = log_to_HMI.current_address + SIZE_BUF_WRITE_LOG_TO_MODBUS16;
|
||||
}
|
||||
if (log_to_HMI.current_address > END_ARRAY_LOG_SEND) {
|
||||
log_to_HMI.current_address = START_ARRAY_LOG_SEND;
|
||||
// log_to_HMI.flag_end_of_log = 1;
|
||||
log_to_HMI.flag_log_array_sent = 1;
|
||||
}
|
||||
if ((log_to_HMI.current_address + SIZE_BUF_WRITE_LOG_TO_MODBUS16) > END_ARRAY_LOG_SEND) {
|
||||
log_to_HMI.count_write_to_modbus = END_ARRAY_LOG_SEND - log_to_HMI.current_address;
|
||||
} else {
|
||||
log_to_HMI.count_write_to_modbus = SIZE_BUF_WRITE_LOG_TO_MODBUS16;
|
||||
}
|
||||
|
||||
err_send_log_16 += 1;
|
||||
succed = 1;
|
||||
// control_station.flag_message_sent[CONTROL_STATION_INGETEAM_PULT_RS485] = 1;
|
||||
}
|
||||
return succed;
|
||||
}
|
||||
|
||||
void prepareWriteLogsArray(void) {
|
||||
log_to_HMI.start_log_address = logpar.addres_mem - logpar.count_log_params_fast_log * SIZE_ARRAY_LOG_SEND;
|
||||
if (log_to_HMI.start_log_address < START_ADDRESS_LOG) {
|
||||
log_to_HMI.start_log_address = END_ADDRESS_LOG - (START_ADDRESS_LOG - log_to_HMI.start_log_address);
|
||||
}
|
||||
log_to_HMI.log_address_step = logpar.count_log_params_fast_log;
|
||||
}
|
||||
|
||||
void fillAnalogDataArrayForLogSend(int num_of_log) {
|
||||
int i = START_ARRAY_LOG_SEND;
|
||||
unsigned long current_address = log_to_HMI.start_log_address + num_of_log;
|
||||
for (i = START_ARRAY_LOG_SEND; i <= END_ARRAY_LOG_SEND; ++i) {
|
||||
modbus_table_analog_out[i].all = ReadMemory(current_address);
|
||||
current_address += log_to_HMI.log_address_step;
|
||||
}
|
||||
log_to_HMI.current_address = START_ARRAY_LOG_SEND;
|
||||
log_to_HMI.count_write_to_modbus = SIZE_BUF_WRITE_LOG_TO_MODBUS16;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -3,6 +3,24 @@
|
||||
|
||||
#include "modbus_struct.h"
|
||||
|
||||
typedef struct {
|
||||
int send_log;
|
||||
int new_send_log_checked;
|
||||
int log_size_sent;
|
||||
// int flag_ready_send_array;
|
||||
int flag_data_received;
|
||||
int flag_log_array_sent;
|
||||
int flag_log_array_ready_sent;
|
||||
// int flag_end_of_log;
|
||||
int step;
|
||||
int number_of_log;
|
||||
unsigned long count_write_to_modbus;
|
||||
unsigned long current_address;
|
||||
unsigned long start_log_address;
|
||||
int log_address_step;
|
||||
} Logs_with_modbus;
|
||||
|
||||
extern Logs_with_modbus log_to_HMI;
|
||||
|
||||
int readDiscreteOutputsFromRemote();
|
||||
int writeSigleDiscreteDataToRemote(unsigned int adres);
|
||||
@ -10,22 +28,24 @@ int writeSingleAnalogOutputToRemote(unsigned int adres);
|
||||
int writeDiscreteDataToRemote();
|
||||
int readAnalogDataFromRemote();
|
||||
int writeAnalogDataToRemote();
|
||||
int writeSingleAnalogDataToRemote(int from_adr, int count_wr);
|
||||
|
||||
int sendLogToHMI();
|
||||
void setRegisterDiscreteOutput(int value, int adres);
|
||||
int getRegisterDiscreteOutput(int adres);
|
||||
|
||||
|
||||
|
||||
void fillLogArea(); //TODO for testing only
|
||||
|
||||
void clear_table_remoute(void); // clear table
|
||||
|
||||
#define ADRES_LOG_REGISTERS 100
|
||||
#define LOG_START_ADRES 0xA0000UL
|
||||
#define LOG_END_ADRES 0xF0000UL
|
||||
#define LOG_BUFFER_SIZE 0x50000UL //0x100UL
|
||||
#define ADRES_LOG_REGISTERS 100
|
||||
|
||||
|
||||
#define SIZE_MODBUS_TABLE_DISCRET_REMOUTE 36
|
||||
#define SIZE_MODBUS_TABLE_DISCRET_BITS (SIZE_MODBUS_TABLE_DISCRET_REMOUTE * 16)
|
||||
#define SIZE_MODBUS_ANALOG_REMOUTE 900
|
||||
#define SIZE_MODBUS_ANALOG_REMOUTE 700
|
||||
|
||||
|
||||
extern MODBUS_REG_STRUCT modbus_table_analog_in[SIZE_MODBUS_ANALOG_REMOUTE];
|
||||
|
@ -11,9 +11,6 @@
|
||||
#include <protect_levels.h>
|
||||
|
||||
|
||||
#define DELTA_ABNORMAL_P_WATER_MIN 50
|
||||
#define DELTA_ABNORMAL_P_WATER_MAX 100
|
||||
|
||||
void parse_protect_levels_HMI() {
|
||||
|
||||
if (modbus_table_analog_in[91].all > 0) {
|
||||
@ -116,8 +113,7 @@ void parse_protect_levels_HMI() {
|
||||
protect_levels.abnormal_temper_water_ext = modbus_table_analog_in[124].all * 10;
|
||||
}
|
||||
if (modbus_table_analog_in[125].all > 0) {
|
||||
protect_levels.alarm_p_water_min_int = modbus_table_analog_in[125].all * 10;
|
||||
protect_levels.abnormal_p_water_min_int = protect_levels.alarm_p_water_min_int + DELTA_ABNORMAL_P_WATER_MIN;
|
||||
protect_levels.alarm_p_water_min_int = modbus_table_analog_in[125].all * 100;
|
||||
}
|
||||
if (modbus_table_analog_in[126].all > 0) {
|
||||
protect_levels.alarm_temper_water_int = modbus_table_analog_in[126].all * 10;
|
||||
@ -126,8 +122,7 @@ void parse_protect_levels_HMI() {
|
||||
protect_levels.alarm_temper_water_ext = modbus_table_analog_in[127].all * 10;
|
||||
}
|
||||
if (modbus_table_analog_in[128].all > 0) {
|
||||
protect_levels.alarm_p_water_max_int = modbus_table_analog_in[128].all * 10;
|
||||
protect_levels.abnormal_p_water_max_int = protect_levels.alarm_p_water_max_int - DELTA_ABNORMAL_P_WATER_MAX;
|
||||
protect_levels.alarm_p_water_max_int = modbus_table_analog_in[128].all * 100;
|
||||
}
|
||||
|
||||
if (modbus_table_analog_in[129].all > 0) {
|
||||
@ -161,21 +156,18 @@ void parse_protect_levels_HMI() {
|
||||
if (modbus_table_analog_in[138].all > 0) {
|
||||
edrk.iqMIN_U_IN = _IQ(((float)modbus_table_analog_in[138].all) / NORMA_ACP);
|
||||
}
|
||||
|
||||
if (modbus_table_analog_in[139].all > 0) {
|
||||
edrk.iqMIN_U_ZPT = _IQ(((float)modbus_table_analog_in[139].all) / NORMA_ACP);
|
||||
}
|
||||
if (modbus_table_analog_in[140].all > 0) {
|
||||
edrk.iqMIN_U_ZPT = _IQ(((float)modbus_table_analog_in[140].all) / NORMA_ACP);
|
||||
}
|
||||
|
||||
if (modbus_table_analog_in[142].all > 0) {
|
||||
edrk.iqMAX_U_IN = _IQ(((float)modbus_table_analog_in[142].all) / NORMA_ACP);
|
||||
}
|
||||
if (modbus_table_analog_in[143].all > 0) {
|
||||
edrk.iqMAX_U_IN = _IQ(((float)modbus_table_analog_in[143].all) / NORMA_ACP);
|
||||
}
|
||||
|
||||
if (modbus_table_analog_in[144].all > 0) {
|
||||
edrk.iqMAX_U_ZPT = _IQ(((float)modbus_table_analog_in[144].all) / NORMA_ACP);
|
||||
}
|
||||
@ -184,32 +176,32 @@ void parse_protect_levels_HMI() {
|
||||
}
|
||||
|
||||
if (modbus_table_analog_in[146].all > 0) {
|
||||
protect_levels.alarm_Izpt_max = modbus_table_analog_in[146].all;
|
||||
protect_levels.alarm_Izpt_max = modbus_table_analog_out[146].all;
|
||||
}
|
||||
|
||||
if (modbus_table_analog_in[155].all > 0) {
|
||||
protect_levels.alarm_Imax_U01 = modbus_table_analog_in[155].all;
|
||||
if (modbus_table_analog_out[155].all > 0) {
|
||||
protect_levels.alarm_Imax_U01 = modbus_table_analog_out[155].all;
|
||||
}
|
||||
if (modbus_table_analog_in[156].all > 0) {
|
||||
protect_levels.alarm_Imax_U02 = modbus_table_analog_in[156].all;
|
||||
if (modbus_table_analog_out[156].all > 0) {
|
||||
protect_levels.alarm_Imax_U02 = modbus_table_analog_out[156].all;
|
||||
}
|
||||
if (modbus_table_analog_in[157].all > 0) {
|
||||
protect_levels.alarm_Imax_U03 = modbus_table_analog_in[157].all;
|
||||
if (modbus_table_analog_out[157].all > 0) {
|
||||
protect_levels.alarm_Imax_U03 = modbus_table_analog_out[157].all;
|
||||
}
|
||||
if (modbus_table_analog_in[158].all > 0) {
|
||||
protect_levels.alarm_Imax_U04 = modbus_table_analog_in[158].all;
|
||||
if (modbus_table_analog_out[158].all > 0) {
|
||||
protect_levels.alarm_Imax_U04 = modbus_table_analog_out[158].all;
|
||||
}
|
||||
if (modbus_table_analog_in[159].all > 0) {
|
||||
protect_levels.alarm_Imax_U05 = modbus_table_analog_in[159].all;
|
||||
if (modbus_table_analog_out[159].all > 0) {
|
||||
protect_levels.alarm_Imax_U05 = modbus_table_analog_out[159].all;
|
||||
}
|
||||
if (modbus_table_analog_in[160].all > 0) {
|
||||
protect_levels.alarm_Imax_U06 = modbus_table_analog_in[160].all;
|
||||
if (modbus_table_analog_out[160].all > 0) {
|
||||
protect_levels.alarm_Imax_U06 = modbus_table_analog_out[160].all;
|
||||
}
|
||||
if (modbus_table_analog_in[161].all > 0) {
|
||||
protect_levels.alarm_Imax_U07 = modbus_table_analog_in[161].all;
|
||||
if (modbus_table_analog_out[161].all > 0) {
|
||||
protect_levels.alarm_Imax_U07 = modbus_table_analog_out[161].all;
|
||||
}
|
||||
if (modbus_table_analog_in[162].all > 0) {
|
||||
protect_levels.alarm_Iged_max = modbus_table_analog_in[162].all;
|
||||
if (modbus_table_analog_out[162].all > 0) {
|
||||
protect_levels.alarm_Iged_max = modbus_table_analog_out[162].all;
|
||||
}
|
||||
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -1,16 +1,11 @@
|
||||
#ifndef _HMI_UPDATE
|
||||
#define _HMI_UPDATE
|
||||
|
||||
|
||||
#define LIMITER_U_I_PULT 5.0 //10.0
|
||||
|
||||
|
||||
typedef enum {
|
||||
state_not_init = 0, state_ready1 = 1, state_ready2, state_go, state_assemble, state_fault, state_accident
|
||||
} Inverter_state;
|
||||
|
||||
void update_tables_HMI(void);
|
||||
void update_logs_cmd_HMI(void);
|
||||
void update_tables_HMI_on_inited(int perc_load);
|
||||
|
||||
void update_tables_HMI_analog(void);
|
||||
@ -26,14 +21,4 @@ void func_unpack_answer_from_Ingeteam(unsigned int cc);
|
||||
|
||||
extern int hmi_watch_dog;
|
||||
|
||||
void update_nPCH(void);
|
||||
|
||||
void inc_count_build(void);
|
||||
void inc_count_revers(void);
|
||||
|
||||
void set_write_slow_logs(int cmd);
|
||||
|
||||
void update_LoggerParams(void);
|
||||
|
||||
|
||||
#endif //_HMI_UPDATE
|
||||
|
@ -38,7 +38,7 @@ void update_svu_modbus_table(void)
|
||||
// modbus_table_can_out[4].all = Ïåðåãðóçêà ÃÝÄ;
|
||||
modbus_table_can_out[5].all = edrk.Status_Ready.bits.Batt;
|
||||
modbus_table_can_out[6].all = edrk.from_ing1.bits.UPC_24V_NORMA | edrk.from_ing1.bits.OP_PIT_NORMA ? 0 : 1;
|
||||
modbus_table_can_out[7].all = WRotor.RotorDirectionSlow >= 0 ? 0 : 1;
|
||||
modbus_table_can_out[7].all = WRotorPBus.RotorDirection1 >= 0 ? 0 : 1;
|
||||
modbus_table_can_out[8].all = edrk.Mode_ScalarVectorUFConst == ALG_MODE_FOC_POWER ||
|
||||
edrk.Mode_ScalarVectorUFConst == ALG_MODE_SCALAR_POWER ? 1 : 0;
|
||||
current_active_control = get_current_station_control();
|
||||
@ -46,7 +46,7 @@ void update_svu_modbus_table(void)
|
||||
current_active_control == CONTROL_STATION_MPU_KEY_CAN || current_active_control == CONTROL_STATION_MPU_KEY_RS485 ? 2 :
|
||||
current_active_control == CONTROL_STATION_ZADATCHIK_CAN ? 3 :
|
||||
current_active_control == CONTROL_STATION_VPU_CAN ? 4 :
|
||||
current_active_control == CONTROL_STATION_MPU_SVU_CAN || current_active_control == CONTROL_STATION_MPU_SVU_RS485 ? 5 :
|
||||
current_active_control == CONTROL_STATION_MPU_SVU_CAN || current_active_control == CONTROL_STATION_MPU_SVU_RS485 ? 4 :
|
||||
0;
|
||||
modbus_table_can_out[10].all = edrk.errors.e2.bits.T_UO1_MAX || edrk.errors.e6.bits.UO1_KEYS ? 3 :
|
||||
edrk.warnings.e2.bits.T_UO1_MAX ? 2 : 1;
|
||||
@ -64,32 +64,23 @@ void update_svu_modbus_table(void)
|
||||
edrk.warnings.e2.bits.T_UO7_MAX ? 2 : 1;
|
||||
modbus_table_can_out[17].all = edrk.Status_QTV_Ok;// edrk.from_shema.bits.QTV_ON_OFF;
|
||||
modbus_table_can_out[18].all = edrk.from_svu.bits.BLOCKED;
|
||||
modbus_table_can_out[19].all = edrk.from_shema_filter.bits.UMP_ON_OFF;
|
||||
modbus_table_can_out[20].all = edrk.from_shema_filter.bits.READY_UMP;
|
||||
modbus_table_can_out[19].all = edrk.from_shema.bits.UMP_ON_OFF;
|
||||
modbus_table_can_out[20].all = edrk.from_shema.bits.READY_UMP;
|
||||
modbus_table_can_out[21].all = edrk.from_ing1.bits.RASCEPITEL_ON;
|
||||
modbus_table_can_out[22].all = edrk.from_ing1.bits.UPC_24V_NORMA;
|
||||
modbus_table_can_out[23].all = edrk.from_ing1.bits.OHLAD_UTE4KA_WATER;
|
||||
modbus_table_can_out[24].all = edrk.from_ing2.bits.SOST_ZAMKA;
|
||||
modbus_table_can_out[25].all = edrk.from_ing1.bits.ZARYAD_ON | edrk.from_shema_filter.bits.UMP_ON_OFF; //Âèäèìî, çàðÿäà îò âíóòðåííåãî ÓÌÏ íå áóäåò, äîáàâèë ÓÌÏ íàìàãíè÷èâàíèÿ
|
||||
modbus_table_can_out[25].all = edrk.from_ing1.bits.ZARYAD_ON | edrk.from_shema.bits.UMP_ON_OFF; //Âèäèìî, çàðÿäà îò âíóòðåííåãî ÓÌÏ íå áóäåò, äîáàâèë ÓÌÏ íàìàãíè÷èâàíèÿ
|
||||
modbus_table_can_out[26].all = edrk.from_ing1.bits.VENTIL_ON;
|
||||
modbus_table_can_out[27].all = edrk.to_ing.bits.NASOS_1_ON == 1 && edrk.from_ing1.bits.NASOS_ON == 1 ? 1 : 0;
|
||||
modbus_table_can_out[28].all = edrk.to_ing.bits.NASOS_2_ON == 1 && edrk.from_ing1.bits.NASOS_ON == 1 ? 1 : 0;
|
||||
modbus_table_can_out[29].all = edrk.from_ing1.bits.NASOS_NORMA;
|
||||
modbus_table_can_out[30].all = edrk.from_ing1.bits.ZAZEML_ON;
|
||||
modbus_table_can_out[31].all = edrk.from_ing1.bits.NAGREV_ON;
|
||||
modbus_table_can_out[32].all = edrk.from_ing1.bits.BLOCK_IZOL_NORMA == 1 ? 1 : 0;
|
||||
modbus_table_can_out[33].all = edrk.errors.e5.bits.ERROR_ISOLATE == 0 && edrk.from_ing1.bits.BLOCK_IZOL_NORMA == 1 ? 0 : 1;
|
||||
modbus_table_can_out[32].all = edrk.errors.e5.bits.ERROR_ISOLATE == 0 && edrk.from_ing1.bits.BLOCK_IZOL_NORMA == 1 ? 0 : 1;
|
||||
modbus_table_can_out[33].all = edrk.from_ing1.bits.BLOCK_IZOL_NORMA == 0 ? 1 : 0;
|
||||
modbus_table_can_out[34].all = edrk.from_ing1.bits.ALL_KNOPKA_AVARIA;
|
||||
|
||||
if (edrk.MasterSlave == MODE_MASTER)
|
||||
modbus_table_can_out[35].all = 1;
|
||||
else
|
||||
if (edrk.MasterSlave == MODE_SLAVE)
|
||||
modbus_table_can_out[35].all = 0;
|
||||
else
|
||||
modbus_table_can_out[35].all = 2; // MODE_DONTKNOW
|
||||
|
||||
// modbus_table_can_out[35].all = edrk.MasterSlave == MODE_MASTER ? 1 : 0;
|
||||
modbus_table_can_out[35].all = edrk.MasterSlave == MODE_MASTER ? 1 : 0;
|
||||
modbus_table_can_out[36].all = edrk.from_ing1.bits.OP_PIT_NORMA & edrk.from_ing1.bits.UPC_24V_NORMA;
|
||||
modbus_table_can_out[37].all = optical_read_data.status == 1 && optical_write_data.status == 1 ? 1 : 0;
|
||||
modbus_table_can_out[38].all = edrk.warnings.e7.bits.MASTER_SLAVE_SYNC == 0 ? 1 : 0;
|
||||
@ -136,12 +127,12 @@ void update_svu_modbus_table(void)
|
||||
modbus_table_can_out[71].all = fast_round(edrk.p_water_edrk.real_p_water[0]);
|
||||
|
||||
modbus_table_can_out[72].all = fast_round(_IQtoF(edrk.zadanie.iq_oborots_zad_hz_rmp) * NORMA_FROTOR * 60);
|
||||
modbus_table_can_out[73].all = edrk.oborots;// fast_round(_IQtoF(WRotor.iqWRotorSumFilter3) * NORMA_FROTOR * 60);
|
||||
modbus_table_can_out[74].all = edrk.oborots;//fast_round(_IQtoF(WRotor.iqWRotorSumFilter3) * NORMA_FROTOR * 60); //Sensor 1
|
||||
modbus_table_can_out[75].all = edrk.oborots;//fast_round(_IQtoF(WRotor.iqWRotorSumFilter3) * NORMA_FROTOR * 60); //Sensor 1
|
||||
modbus_table_can_out[73].all = fast_round(_IQtoF(WRotor.iqWRotorCalcBeforeRegul1) * NORMA_FROTOR * 60);
|
||||
modbus_table_can_out[74].all = fast_round(_IQtoF(WRotor.iqWRotorCalcBeforeRegul1) * NORMA_FROTOR * 60); //Sensor 1
|
||||
modbus_table_can_out[75].all = fast_round(_IQtoF(WRotor.iqWRotorCalcBeforeRegul1) * NORMA_FROTOR * 60); //Sensor 1
|
||||
|
||||
modbus_table_can_out[76].all = fast_round(_IQtoF(edrk.zadanie.iq_power_zad_rmp) * NORMA_ACP * NORMA_ACP / 1000.0);
|
||||
modbus_table_can_out[77].all = fabs(edrk.power_kw);// fast_round(_IQtoF(filter.PowerScalar) * NORMA_ACP* NORMA_ACP / 1000.0);
|
||||
modbus_table_can_out[76].all = fast_round(_IQtoF(edrk.zadanie.iq_power_zad_rmp) * NORMA_ACP* NORMA_ACP / 1000.0);
|
||||
modbus_table_can_out[77].all = fast_round(_IQtoF(filter.PowerScalar) * NORMA_ACP* NORMA_ACP / 1000.0);
|
||||
|
||||
modbus_table_can_out[78].all = fast_round(edrk.temper_acdrive.winding.filter_real_temper[0]);
|
||||
modbus_table_can_out[79].all = fast_round(edrk.temper_acdrive.winding.filter_real_temper[1]);
|
||||
@ -200,14 +191,10 @@ void update_svu_modbus_table(void)
|
||||
modbus_table_can_out[117].all = edrk.errors.e0.bits.U_IN_MIN;
|
||||
modbus_table_can_out[118].all = edrk.warnings.e0.bits.U_IN_MAX;
|
||||
modbus_table_can_out[119].all = edrk.errors.e0.bits.U_IN_MAX;
|
||||
modbus_table_can_out[120].all = edrk.warnings.e9.bits.SENSOR_ROTOR_1_BREAK; //TODO íåèñïðàâíîñòü äàò÷èêà îáîðîòîâ
|
||||
modbus_table_can_out[121].all = edrk.warnings.e9.bits.SENSOR_ROTOR_2_BREAK; //TODO ïðåâûøåíèå äîïóñòèìûõ îáîðîòîâ
|
||||
modbus_table_can_out[120].all = 0; //TODO íåèñïðàâíîñòü äàò÷èêà îáîðîòîâ
|
||||
modbus_table_can_out[121].all = 0; //TODO ïðåâûøåíèå äîïóñòèìûõ îáîðîòîâ
|
||||
modbus_table_can_out[122].all = edrk.Kvitir;
|
||||
|
||||
|
||||
modbus_table_can_out[137].all = edrk.pult_data.data_from_pult.moto[15];
|
||||
modbus_table_can_out[138].all = edrk.pult_data.data_from_pult.moto[6];
|
||||
|
||||
update_errors_to_svu();
|
||||
update_protect_levels_to_MPU();
|
||||
|
||||
@ -215,79 +202,19 @@ void update_svu_modbus_table(void)
|
||||
|
||||
}
|
||||
|
||||
#define MPU_ADRESS_CMD_START 122 // ó íàñ -1 îòíîñèòåëüíî íèî14, 122 ñîîòâåòñòâóåò 123 ó íèî14
|
||||
#define MPU_ADRESS_CMD_END 144 //138 //
|
||||
|
||||
#if (MPU_ADRESS_CMD_END>=SIZE_MODBUS_TABLE)
|
||||
#define MPU_ADRESS_CMD_END (SIZE_MODBUS_TABLE-1)
|
||||
#endif
|
||||
|
||||
|
||||
#if (MPU_ADRESS_CMD_END - MPU_ADRESS_CMD_START +1 )>CONTROL_STATION_MAX_RAW_DATA
|
||||
#define MPU_LENGTH_CMD CONTROL_STATION_MAX_RAW_DATA
|
||||
#else
|
||||
#define MPU_LENGTH_CMD (MPU_ADRESS_CMD_END - MPU_ADRESS_CMD_START + 1)
|
||||
#endif
|
||||
/////////////////////////////////////////////////////////////////
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
void unpack_answer_from_MPU_SVU_CAN_filter(unsigned int cc)
|
||||
{
|
||||
unsigned int i = 0, j = 0, k, max_data;
|
||||
|
||||
for (i = 0; i < MPU_LENGTH_CMD; i++)
|
||||
{
|
||||
max_data = 0;//control_station.raw_array_data_temp[cc][i][0].all;
|
||||
//min_data = 0;//control_station.raw_array_data_temp[cc][i][0].all;
|
||||
|
||||
for (j=0; j<CONTROL_STATION_MAX_RAW_DATA_TEMP; j++)
|
||||
{
|
||||
if (control_station.raw_array_data_temp[cc][i][j].all > max_data)
|
||||
max_data = control_station.raw_array_data_temp[cc][i][j].all;
|
||||
}
|
||||
|
||||
control_station.raw_array_data[cc][i].all = max_data;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////
|
||||
#define ADRESS_CMD_START 122
|
||||
|
||||
|
||||
void unpack_answer_from_MPU_SVU_CAN(unsigned int cc) {
|
||||
int i = 0, j = 0, k;
|
||||
// static unsigned int prev_CAN_count_cycle_input_units = 0;
|
||||
|
||||
if (control_station.prev_CAN_count_cycle_input_units[cc] != mpu_can_setup.CAN_count_cycle_input_units[0])
|
||||
{
|
||||
k = control_station.count_raw_array_data_temp[cc];
|
||||
for (i = 0, j = 0; i < MPU_LENGTH_CMD && j < CONTROL_STATION_MAX_RAW_DATA; i++, j++)
|
||||
{
|
||||
control_station.raw_array_data_temp[cc][j][k].all = modbus_table_can_in[MPU_ADRESS_CMD_START+i].all;
|
||||
}
|
||||
|
||||
control_station.count_raw_array_data_temp[cc]++;
|
||||
if (control_station.count_raw_array_data_temp[cc]>=CONTROL_STATION_MAX_RAW_DATA_TEMP)
|
||||
control_station.count_raw_array_data_temp[cc] = 0;
|
||||
|
||||
control_station.prev_CAN_count_cycle_input_units[cc] = mpu_can_setup.CAN_count_cycle_input_units[0];
|
||||
}
|
||||
|
||||
|
||||
// for (i = ADRESS_CMD_START, j = 0; i < SIZE_MODBUS_TABLE && j < CONTROL_STATION_MAX_RAW_DATA; i++, j++)
|
||||
// {
|
||||
// control_station.raw_array_data[cc][j].all = modbus_table_can_in[i].all;
|
||||
// }
|
||||
|
||||
unpack_answer_from_MPU_SVU_CAN_filter(cc);
|
||||
int i = 0, j = 0;
|
||||
for (i = ADRESS_CMD_START, j = 0; i < SIZE_MODBUS_TABLE && j < CONTROL_STATION_MAX_RAW_DATA; i++, j++)
|
||||
control_station.raw_array_data[cc][j].all = modbus_table_can_in[i].all;
|
||||
|
||||
}
|
||||
|
||||
void unpack_answer_from_MPU_SVU_RS(unsigned int cc) {
|
||||
int i = 0, j = 0;
|
||||
for (i = MPU_ADRESS_CMD_START, j = 0; i < SIZE_MODBUS_TABLE && j < CONTROL_STATION_MAX_RAW_DATA; i++, j++)
|
||||
for (i = ADRESS_CMD_START, j = 0; i < SIZE_MODBUS_TABLE && j < CONTROL_STATION_MAX_RAW_DATA; i++, j++)
|
||||
control_station.raw_array_data[cc][j].all = modbus_table_rs_in[i].all;
|
||||
}
|
||||
|
||||
@ -476,11 +403,7 @@ void update_errors_to_svu() {
|
||||
modbus_table_can_out[211].bit.bit12 = edrk.warnings.e2.bits.T_AIR2_MAX;
|
||||
modbus_table_can_out[211].bit.bit13 = edrk.warnings.e2.bits.T_AIR3_MAX;
|
||||
|
||||
if (edrk.power_limit.all)
|
||||
modbus_table_can_out[211].bit.bit14 = 1;
|
||||
else
|
||||
modbus_table_can_out[211].bit.bit14 = 0;
|
||||
|
||||
modbus_table_can_out[211].bit.bit14 = edrk.power_limit.all;
|
||||
modbus_table_can_out[211].bit.bit15 = edrk.warnings.e10.bits.WARNING_I_OUT_OVER_1_6_NOMINAL;
|
||||
|
||||
modbus_table_can_out[212].bit.bit0 = edrk.errors.e5.bits.ERROR_PRE_CHARGE_ON;
|
||||
@ -691,10 +614,10 @@ void update_protect_levels_to_MPU() {
|
||||
modbus_table_can_out[183].all = _IQtoF(analog_protect.in_voltage[0].setup.levels.iqNominal_minus20) * NORMA_ACP;//_IQtoF(edrk.iqMIN_U_IN) * NORMA_ACP;
|
||||
modbus_table_can_out[184].all = _IQtoF(analog_protect.in_voltage[1].setup.levels.iqNominal_minus20) * NORMA_ACP;
|
||||
modbus_table_can_out[185].all = _IQtoF(analog_protect.in_voltage[0].setup.levels.iqNominal_plus20) * NORMA_ACP;//_IQtoF(edrk.iqMIN_U_ZPT) * NORMA_ACP;
|
||||
modbus_table_can_out[186].all = _IQtoF(analog_protect.in_voltage[1].setup.levels.iqNominal_plus20) * NORMA_ACP;
|
||||
modbus_table_can_out[187].all = //_IQtoF(edrk.iqMAX_U_IN) * NORMA_ACP;
|
||||
modbus_table_can_out[186].all = _IQtoF(analog_protect.in_voltage[0].setup.levels.iqNominal_plus20) * NORMA_ACP;
|
||||
modbus_table_can_out[187].all = _IQtoF(edrk.iqMAX_U_IN) * NORMA_ACP;
|
||||
modbus_table_can_out[188].all = _IQtoF(edrk.iqMAX_U_IN) * NORMA_ACP;
|
||||
modbus_table_can_out[189].all = //_IQtoF(edrk.iqMAX_U_ZPT) * NORMA_ACP;
|
||||
modbus_table_can_out[189].all = _IQtoF(edrk.iqMAX_U_ZPT) * NORMA_ACP;
|
||||
modbus_table_can_out[190].all = _IQtoF(edrk.iqMAX_U_ZPT) * NORMA_ACP;
|
||||
|
||||
modbus_table_can_out[191].all = protect_levels.alarm_Izpt_max;
|
||||
|
@ -67,7 +67,7 @@ void optical_bus_update_data_write(void)
|
||||
}
|
||||
}
|
||||
|
||||
if (edrk.Status_Ready.bits.ready7 || (edrk.Status_Ready.bits.ready5 && edrk.Status_Ready.bits.ImitationReady2) )
|
||||
if (edrk.Status_Ready.bits.ready7)
|
||||
optical_write_data.data.cmd.bit.ready_cmd = CODE_READY_CMD_READY2;
|
||||
else
|
||||
if (edrk.SumSbor)
|
||||
@ -79,7 +79,7 @@ void optical_bus_update_data_write(void)
|
||||
// optical_write_data.cmd.bit.slave =
|
||||
//
|
||||
// optical_write_data.cmd.bit.start_pwm =
|
||||
optical_write_data.data.cmd.bit.statusQTV = edrk.from_shema_filter.bits.QTV_ON_OFF;
|
||||
optical_write_data.data.cmd.bit.statusQTV = edrk.from_shema.bits.QTV_ON_OFF;
|
||||
// optical_write_data.cmd.bit.stop_pwm =
|
||||
|
||||
optical_write_data.data.cmd.bit.sync_1_2 = sync_data.local_flag_sync_1_2;
|
||||
@ -104,7 +104,6 @@ void optical_bus_update_data_write(void)
|
||||
#pragma CODE_SECTION(optical_bus_write,".fast_run");
|
||||
void optical_bus_write(void)
|
||||
{
|
||||
#if(USE_TK_3)
|
||||
// check error write PBUS OPTICAL BUS
|
||||
project.cds_tk[3].optical_bus_check_error_write(&project.cds_tk[3]);
|
||||
|
||||
@ -118,7 +117,7 @@ void optical_bus_write(void)
|
||||
|
||||
|
||||
project.cds_tk[3].optical_bus_write_data(&project.cds_tk[3]);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
@ -256,9 +255,8 @@ void optical_bus_read(void)
|
||||
// check error write PBUS OPTICAL BUS
|
||||
// project.cds_tk[3].optical_bus_check_error_write(&project.cds_tk[3]);
|
||||
// read data from OPTICAL BUS
|
||||
#if(USE_TK_3)
|
||||
project.cds_tk[3].read_pbus(&project.cds_tk[3]);
|
||||
#endif
|
||||
|
||||
|
||||
return;
|
||||
}
|
||||
@ -266,9 +264,8 @@ void optical_bus_read(void)
|
||||
#pragma CODE_SECTION(optical_bus_read_clear_count_error,".fast_run");
|
||||
void optical_bus_read_clear_count_error(void)
|
||||
{
|
||||
#if(USE_TK_3)
|
||||
|
||||
project.cds_tk[3].optical_data_in.local_count_error = 0;
|
||||
#endif
|
||||
|
||||
return;
|
||||
}
|
||||
@ -284,7 +281,7 @@ STATUS_DATA_READ_OPT_BUS optical_bus_get_status_and_read(void)
|
||||
// read data from OPTICAL BUS
|
||||
// project.cds_tk[3].read_pbus(&project.cds_tk[3]);
|
||||
|
||||
#if(USE_TK_3)
|
||||
|
||||
// check error read PBUS OPTICAL BUS
|
||||
project.cds_tk[3].optical_bus_check_error_read(&project.cds_tk[3]);
|
||||
|
||||
@ -329,9 +326,7 @@ STATUS_DATA_READ_OPT_BUS optical_bus_get_status_and_read(void)
|
||||
|
||||
|
||||
}
|
||||
#else
|
||||
status_read.all = 0;
|
||||
#endif
|
||||
|
||||
return status_read; //íåò äàííûõ èëè îøèáêè
|
||||
|
||||
}
|
||||
|
@ -87,14 +87,12 @@ typedef struct {
|
||||
unsigned int data_was_update_between_pwm_int;
|
||||
unsigned int error_wdog;
|
||||
unsigned int count_error_wdog;
|
||||
unsigned int count_read_optical_bus_old_data; // ñ÷åò÷èê âðåìåíè ñêîëüêî äàííûå íå îáíîâëÿëèñü
|
||||
|
||||
|
||||
// OPTICAL_BUS_CODE_STATUS code_status;
|
||||
} OPTICAL_BUS_DATA;
|
||||
|
||||
|
||||
#define OPTICAL_BUS_DATA_DEFAULT {{0,0,0,0},{0,0,0,0},0,0,0,0,0,0,0,0}
|
||||
#define OPTICAL_BUS_DATA_DEFAULT {{0,0,0,0},{0,0,0,0},0,0,0,0,0,0,0}
|
||||
|
||||
extern OPTICAL_BUS_DATA optical_write_data;
|
||||
extern OPTICAL_BUS_DATA optical_read_data;
|
||||
|
@ -12,13 +12,13 @@
|
||||
|
||||
#include "IQmathLib.h"
|
||||
#include "math_pi.h"
|
||||
#include "limit_lib.h"
|
||||
|
||||
_iq linear_decrease(float current, int alarm_level, int warnig_level);
|
||||
|
||||
|
||||
TEMPERATURE_LIMIT_KOEFFS temper_limit_koeffs = TEMPERATURE_LIMIT_KOEFFS_DEFAULTS;
|
||||
|
||||
void calc_limit_overheat()
|
||||
{
|
||||
void calc_limit_overheat() {
|
||||
int *p_alarm, *p_abnormal;
|
||||
_iq sum_limit = CONST_IQ_1;
|
||||
_iq val;
|
||||
@ -78,3 +78,16 @@ void calc_limit_overheat()
|
||||
edrk.temper_limit_koeffs.code_status = 0;
|
||||
|
||||
}
|
||||
|
||||
_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);
|
||||
}
|
||||
}
|
||||
|
@ -5,39 +5,20 @@
|
||||
#if(_FLOOR6)
|
||||
|
||||
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS 0//1
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_ROTOR 0//1
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_PWM 0//1
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_RS 0//1
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_SYNC 0//1
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_GO 0//1
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS 1
|
||||
|
||||
#else
|
||||
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS 0
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_ROTOR 0
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_PWM 0
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_RS 0
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_SYNC 0//1
|
||||
#define _ENABLE_PWM_LINES_FOR_TESTS_GO 0//1
|
||||
#endif
|
||||
|
||||
|
||||
#if(_FLOOR6)
|
||||
#define MODE_DISABLE_ENABLE_WDOG 1 // 0 - wdog ðàáîòàåò, 1 - çàïðåùåí
|
||||
#else
|
||||
#define MODE_DISABLE_ENABLE_WDOG 0 // 0 - wdog ðàáîòàåò, 1 - çàïðåùåí
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
#define MODE_DISABLE_ENABLE_WDOG 0//1
|
||||
|
||||
|
||||
#define CHECK_IN_OUT_TERMINAL 1
|
||||
|
||||
#define WORK_ON_STEND_D 0//1
|
||||
|
||||
#define U_D_MAX_ERROR_GLOBAL_2800 15658734 // 2800V
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////
|
||||
|
@ -8,104 +8,59 @@
|
||||
#ifndef SRC_MAIN_PARAMS_ALG_H_
|
||||
#define SRC_MAIN_PARAMS_ALG_H_
|
||||
|
||||
// ðàçïðåò ðàñ÷åòà êì íà ñëåéâå, áåðåì ñ ìàñòåðà
|
||||
#define DISABLE_CALC_KM_ON_SLAVE 0//1
|
||||
|
||||
#define DISABLE_WORK_BREAK 0 // çàïðíòèòü ðàáîòó ñ òîðìîçíûìè
|
||||
#define MZZ_ADD_1 0.5 // 0.25 //0.5 èíòåíñèâíîñü íàáîðà ìîìåíòà çà 1 ìñåê
|
||||
#define MZZ_ADD_2 0.1 //0.05 //0.1 èíòåíñèâíîñü íàáîðà ìîìåíòà çà 1 ìñåê
|
||||
#define FZAD_ADD_MAX 0.08 //0.005 //0.08 èíòåíñèâíîñü íàáîðà fzad çà 1 ìñåê
|
||||
#define FZAD_DEC 0.0004 //èíòåíñèâíîñü ñïàäà fzad çà 1 ìñåê
|
||||
|
||||
#define SENSOR_ALG_22220 1
|
||||
#define SENSOR_ALG_23550 2
|
||||
#define POWERZAD_ADD_MAX 0.08 //0.005 //0.08 èíòåíñèâíîñü íàáîðà fzad çà 1 ìñåê
|
||||
#define POWERZAD_DEC 0.0004 //èíòåíñèâíîñü ñïàäà fzad çà 1 ìñåê
|
||||
|
||||
#define POLUS 6 //6 // ÷èñëî ïàð ïîëþñîâ
|
||||
#define BPSI_NORMAL 0.2 //0.3 // ñêîëüæåíèå êîíñòàíòà
|
||||
#define PROVOROT_F_HZ 0.2 // ïðîâîðîò
|
||||
#define PROVOROT_OBOROTS 3 // ïðîâîðîò
|
||||
|
||||
|
||||
#define SENSOR_ALG SENSOR_ALG_22220
|
||||
//#define SENSOR_ALG SENSOR_ALG_23550
|
||||
#define ADD_KP_DF (1000.0/NORMA_MZZ)//(500.0/NORMA_MZZ)//(50.0/NORMA_MZZ)
|
||||
#define ADD_KI_DF (2000.0/NORMA_MZZ)//(1000.0/NORMA_MZZ)//(100.0/NORMA_MZZ)
|
||||
|
||||
#define ADD_KP_DPOWER (1000.0/NORMA_MZZ)//(500.0/NORMA_MZZ)//(50.0/NORMA_MZZ)
|
||||
#define ADD_KI_DPOWER (2000.0/NORMA_MZZ)//(1000.0/NORMA_MZZ)//(100.0/NORMA_MZZ)
|
||||
|
||||
#define NOMINAL_U_ZARYAD 2520 // Çàäàíèå íàïðÿæåíèÿ çàðÿäà ÇÏÒ
|
||||
#define NOMINAL_U_BREAK_LEVEL 2580 // íà÷àëî ðàáîòû òîðìîçíûõ + IQ_DELTA_U_START_RECUP=100V
|
||||
#define NOMINAL_SET_IZAD 910 // òîê îò ïîñòà
|
||||
#define NOMINAL_SET_K_U_DISBALANCE 40//20 // Çàäàíèå Ê íàïðÿæåíèÿ äèñáàëàíñà êîýô. îáðàòíîé ñâÿçè ïî äèñáàëàíñó, íàäî >0 ÷òîá ðàáîòàë àëãîðèòì
|
||||
#define NOMINAL_SET_LIMIT_POWER 6300 // çàïàñ ìîùíîñòü îò ïîñòà
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
///////////////////////////////////////////////////////////////
|
||||
#define U_D_MAX_ERROR_GLOBAL IQ_I_U_VALUE_PLUS_2850 //U_D_MAX_ERROR_GLOBAL_2850
|
||||
|
||||
#define MAX_U_PROC_SMALL 2.5 //1.4
|
||||
#define MAX_U_PROC 1.1 //1.11 //1.4
|
||||
#define MIN_U_PROC 0.8 //0.7
|
||||
|
||||
#define ADD_U_MAX_GLOBAL 200.0 //V Íàñêîëüêî ïîäíèìàåì óñòàâêó GLOBAL îòíîñèòåëüíî ZadanieU_Charge
|
||||
#define ADD_U_MAX_GLOBAL_SMALL 500.0 //V Íàñêîëüêî ïîäíèìàåì óñòàâêó GLOBAL îòíîñèòåëüíî ZadanieU_Charge
|
||||
#define LEVEL_DETECT_U_SMALL 1000.0 //V Íàñêîëüêî ïîäíèìàåì óñòàâêó GLOBAL îòíîñèòåëüíî ZadanieU_Charge
|
||||
|
||||
#define KOEF_IM_ON_TORMOG 0.65// 0.75 // íà ñêîëüêî óìåíüøàòü âîçìîæíóþ ìîùíîñòü ïðè òîðìîæåíèè
|
||||
#define KOEF_IM_ON_TORMOG_WITH_MAX_TEMPER_BREAK 0.1// ñ ïåðåãðåâîì òîìîçíûõ íà ñêîëüêî óìåíüøàòü âîçìîæíóþ ìîùíîñòü ïðè òîðìîæåíèè
|
||||
|
||||
///////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
#define MZZ_ADD_1 0.5 // 0.25 //0.5 èíòåíñèâíîñü íàáîðà ìîìåíòà çà 1 ìñåê
|
||||
#define MZZ_ADD_2 0.15 ///0.1 //0.05 //0.1 èíòåíñèâíîñü íàáîðà ìîìåíòà çà 1 ìñåê
|
||||
#define MZZ_ADD_3 0.25 //0.05 ///0.1 //0.05 //0.1 èíòåíñèâíîñü íàáîðà ìîìåíòà çà 1 ìñåê
|
||||
|
||||
#define FZAD_ADD_MAX 0.08 //0.005 //0.08 èíòåíñèâíîñü íàáîðà fzad çà 1 ìñåê
|
||||
#define FZAD_DEC 0.0004 //èíòåíñèâíîñü ñïàäà fzad çà 1 ìñåê
|
||||
|
||||
#define POWERZAD_ADD_MAX 0.08 //0.005 //0.08 èíòåíñèâíîñü íàáîðà fzad çà 1 ìñåê
|
||||
#define POWERZAD_DEC 0.0004 //èíòåíñèâíîñü ñïàäà fzad çà 1 ìñåê
|
||||
|
||||
#define POLUS 6 //6 // ÷èñëî ïàð ïîëþñîâ
|
||||
#define BPSI_NORMAL 0.22 //0.3 // ñêîëüæåíèå êîíñòàíòà
|
||||
#define BPSI_MAXIMAL 0.35 //0.3 // ñêîëüæåíèå êîíñòàíòà
|
||||
#define BPSI_MINIMAL 0.05 //0.3 // ñêîëüæåíèå êîíñòàíòà
|
||||
#define PROVOROT_F_HZ 0.2 // ïðîâîðîò
|
||||
#define PROVOROT_OBOROTS 10 // ïðîâîðîò
|
||||
|
||||
|
||||
#define ADD_KP_DF (1000.0/NORMA_MZZ)//(500.0/NORMA_MZZ)//(50.0/NORMA_MZZ)
|
||||
#define ADD_KI_DF (2000.0/NORMA_MZZ)//(1000.0/NORMA_MZZ)//(100.0/NORMA_MZZ)
|
||||
|
||||
#define ADD_KP_DPOWER (1000.0/NORMA_MZZ)//(500.0/NORMA_MZZ)//(50.0/NORMA_MZZ)
|
||||
#define ADD_KI_DPOWER (2000.0/NORMA_MZZ)//(1000.0/NORMA_MZZ)//(100.0/NORMA_MZZ)
|
||||
|
||||
#define MIN_MZZ_FOR_DF 210
|
||||
#define MIN_MZZ_FOR_DPOWER 210
|
||||
#define MIN_MZZ_FOR_DF 210
|
||||
#define MIN_MZZ_FOR_DPOWER 210
|
||||
|
||||
|
||||
////////////////////
|
||||
|
||||
|
||||
#define PID_KP_IM 0.036 //0.018 //0.0013// 0.018 //0.036 //0.018 //0.18 //0.095 // PID Kp
|
||||
#define PID_KI_IM 0.32 // 0.16 //0.32 //0.16 //0.08//0.8//0.025 //0.08 // PID Ki
|
||||
#define PID_KD_IM 0.0000 //*100 // PID Kd
|
||||
#define PID_KC_IM 0.09 // PID Kc
|
||||
#define PID_KP_IM 0.018 //0.0013// 0.018 //0.036 //0.018 //0.18 //0.095 // PID Kp
|
||||
#define PID_KI_IM 0.08//0.8//0.025 //0.08 // PID Ki
|
||||
#define PID_KD_IM 0.0000 //*100 // PID Kd
|
||||
#define PID_KC_IM 0.09 // PID Kc
|
||||
|
||||
|
||||
#define PID_KP_F 12.0//6.0//12.0 //6.0 //18 //12//6//26//12 //40 //20 //12 //20 //60.0 //20.0 //0.095 // PID Kp
|
||||
#define PID_KI_F 0.00020 //0.00010 // 0.008 // PID Ki
|
||||
//#define PID_KI_F 0.00030 //0.00010 // 0.008 // PID Ki
|
||||
#define PID_KD_F 0.000 //*100 PID Kd
|
||||
#define PID_KC_F 0.00005//0.005 // PID Kc
|
||||
//#define PID_KC_F 0.000 // PID Kc
|
||||
#define PID_KP_F 18 //12//6//26//12 //40 //20 //12 //20 //60.0 //20.0 //0.095 // PID Kp
|
||||
#define PID_KI_F 0.00020 //0.00010 // 0.008 // PID Ki
|
||||
//#define PID_KI_F 0.00030 //0.00010 // 0.008 // PID Ki
|
||||
#define PID_KD_F 0.000 //*100 PID Kd
|
||||
#define PID_KC_F 0.005 // PID Kc
|
||||
//#define PID_KC_F 0.000 // PID Kc
|
||||
|
||||
#define PID_KP_POWER 9//3//26//12 //40 //20 //12 //20 //60.0 //20.0 //0.095 // PID Kp
|
||||
//#define PID_KI_F 0.00020 //0.00010 // 0.008 // PID Ki
|
||||
#define PID_KI_POWER 0.00030 //0.00010 // 0.008 // PID Ki
|
||||
#define PID_KD_POWER 0.000 //*100 PID Kd
|
||||
#define PID_KC_POWER 0.0001 // PID Kc
|
||||
#define PID_KP_POWER 9//3//26//12 //40 //20 //12 //20 //60.0 //20.0 //0.095 // PID Kp
|
||||
//#define PID_KI_F 0.00020 //0.00010 // 0.008 // PID Ki
|
||||
#define PID_KI_POWER 0.00030 //0.00010 // 0.008 // PID Ki
|
||||
#define PID_KD_POWER 0.000 //*100 PID Kd
|
||||
#define PID_KC_POWER 0.005 // PID Kc
|
||||
|
||||
|
||||
|
||||
///////////////////
|
||||
// ěŕęń. k îăđŕíč÷ĺíî ýëĺęňđîíčęîé
|
||||
|
||||
#define K_STATOR_MAX 0.93 // 0.91 // äëÿ DEF_PERIOD_MIN_MKS = 60 ìêñ
|
||||
#define K_STATOR_MIN 0.020 // 0.91 // äëÿ DEF_PERIOD_MIN_MKS = 60 ìêñ
|
||||
|
||||
#define K_STATOR_MAX 0.85 // 0.91 // äëÿ DEF_PERIOD_MIN_MKS = 60 ìêñ
|
||||
//#define K_STATOR_MAX 0.89 //äë˙ DEF_PERIOD_MIN_MKS = 80 ěęń
|
||||
|
||||
|
||||
@ -115,101 +70,40 @@
|
||||
|
||||
#define MAX_ZADANIE_U_CHARGE 2800.0//1500.0 //V
|
||||
//#define MAX_ZADANIE_F_ROTOR 70
|
||||
|
||||
#define MAX_ZADANIE_OBOROTS_ROTOR 230.0 //340 //240 1000 //260.0 // +/- ob/min
|
||||
#define MIN_ZADANIE_OBOROTS_ROTOR -230.0 //-180.0 //-230.0 // 1000 //260.0 // +/- ob/min
|
||||
|
||||
#define MAX_1_ZADANIE_OBOROTS_ROTOR 120.0 //340 //240 1000 //260.0 // +/- ob/min
|
||||
#define MIN_1_ZADANIE_OBOROTS_ROTOR -90.0 //-230.0 // 1000 //260.0 // +/- ob/min
|
||||
#define MAX_ZADANIE_OBOROTS_ROTOR 230 //340 //240 1000 //260.0 // +/- ob/min
|
||||
#define MIN_ZADANIE_OBOROTS_ROTOR 0 // 1000 //260.0 // +/- ob/min
|
||||
|
||||
|
||||
#define DEAD_ZONE_ZADANIE_OBOROTS_ROTOR 10.0
|
||||
#define MAX_ZADANIE_I_M 1000.0// 1000.0 //750.0 // A
|
||||
|
||||
#define MAX_ZADANIE_I_M 950.0// 1000.0 //750.0 // A
|
||||
#define MAX_ZADANIE_POWER 1000.0 // kWt
|
||||
#define MIN_ZADANIE_POWER 0 // kWt
|
||||
|
||||
#define MAX_ZADANIE_POWER 6300.0 // kWt
|
||||
#define MIN_ZADANIE_POWER -6300.0 // kWt
|
||||
|
||||
#define MAX_1_ZADANIE_POWER 3000.0 // kWt
|
||||
#define MIN_1_ZADANIE_POWER -3000.0 // kWt
|
||||
#define MAX_ZADANIE_K_M 0.92 // A
|
||||
#define MAX_ZADANIE_F 60.0 // Hz
|
||||
#define MIN_ZADANIE_F 0.0 //60.0 // Hz
|
||||
|
||||
|
||||
#define SUPER_MAX_ZADANIE_LIMIT_POWER 6500.0 // kWt
|
||||
|
||||
#define MAX_ZADANIE_LIMIT_POWER 6300.0 // kWt
|
||||
#define MAX_1_ZADANIE_LIMIT_POWER 2000.0 // kWt
|
||||
|
||||
#define MIN_ZADANIE_LIMIT_POWER 100.0 // kWt
|
||||
#define MIN_ZADANIE_LIMIT_POWER_FROM_SVU 50.0 // kWt
|
||||
#define POWER_ZAPAS_FOR_UOM 5 //50 // äîï çàïàñ äëÿ ÓÎÌ
|
||||
|
||||
#define DEAD_ZONE_ZADANIE_POWER 50.0 // kWt
|
||||
#define DEAD_ZONE_ZADANIE_LIMIT_POWER 50.0 // kWt
|
||||
#define MAX_ZADANIE_K_U_DISBALANCE 2.0 //1.0 // k
|
||||
#define MAX_ZADANIE_KPLUS_U_DISBALANCE 1.0 // k
|
||||
|
||||
|
||||
|
||||
#define MAX_ZADANIE_K_M K_STATOR_MAX // A
|
||||
#define MAX_ZADANIE_F 30.0 // Hz
|
||||
#define MIN_ZADANIE_F -30.0 //60.0 // Hz
|
||||
|
||||
|
||||
#define MAX_ZADANIE_K_U_DISBALANCE 2.0 //1.0 // k
|
||||
#define MAX_ZADANIE_KPLUS_U_DISBALANCE 1.0 // k
|
||||
|
||||
|
||||
|
||||
#define T_NARAST_ZADANIE_F 5.0 // sec
|
||||
#define T_NARAST_ZADANIE_OBOROTS_ROTOR 80.0 //20.0 //30.0 //15.0 // sec
|
||||
|
||||
#define T1_NARAST_ZADANIE_OBOROTS_ROTOR_PLUS 80.0 //20.0 //30.0 //15.0 // sec
|
||||
#define T1_NARAST_ZADANIE_OBOROTS_ROTOR_MINUS 40.0 //20.0 //30.0 //15.0 // sec
|
||||
|
||||
#define T2_NARAST_ZADANIE_OBOROTS_ROTOR_PLUS 80.0 //160.0 //20.0 //30.0 //15.0 // sec
|
||||
#define T2_NARAST_ZADANIE_OBOROTS_ROTOR_MINUS 40.0 //20.0 //30.0 //15.0 // sec
|
||||
|
||||
#define T_SLOW_NARAST_ZADANIE_OBOROTS_ROTOR_PLUS 600.0 //160.0 //20.0 //30.0 //15.0 // sec
|
||||
#define T_SLOW_NARAST_ZADANIE_OBOROTS_ROTOR_MINUS 600.0 //20.0 //30.0 //15.0 // sec
|
||||
|
||||
|
||||
|
||||
#define T_NARAST_ZADANIE_K_M 15.0 // sec
|
||||
#define T_NARAST_ZADANIE_I_M 15.0 // sec
|
||||
|
||||
#define T1_NARAST_ZADANIE_POWER_PLUS 80.0 //30.0 // sec
|
||||
#define T1_NARAST_ZADANIE_POWER_MINUS 30.0 //30.0 // sec
|
||||
#define T2_NARAST_ZADANIE_POWER_PLUS 80.0 //30.0 // sec
|
||||
#define T2_NARAST_ZADANIE_POWER_MINUS 30.0 //30.0 // sec
|
||||
|
||||
#define T_NARAST_ZADANIE_LIMIT_POWER 5.0 //30.0 // sec
|
||||
|
||||
#define T1_NARAST_ZADANIE_LIMIT_POWER_PLUS 30.0 //30.0 // sec
|
||||
#define T1_NARAST_ZADANIE_LIMIT_POWER_MINUS 5.0 //30.0 // sec
|
||||
#define T2_NARAST_ZADANIE_LIMIT_POWER_PLUS 80.0 //30.0 // sec
|
||||
#define T2_NARAST_ZADANIE_LIMIT_POWER_MINUS 5.0 //30.0 // sec
|
||||
|
||||
|
||||
#define T_NARAST_ZADANIE_U_CHARGE 2.0 // sec
|
||||
#define T_NARAST_ZADANIE_K_U_DISBALANCE 15.0 // sec
|
||||
#define T_NARAST_ZADANIE_KPLUS_U_DISBALANCE 15.0 // sec
|
||||
|
||||
#define T_NARAST_ZADANIE_IMITATION_OBOROTS_ROTOR 30.0 // sec
|
||||
#define T_NARAST_ZADANIE_F 15.0 // sec
|
||||
#define T_NARAST_ZADANIE_OBOROTS_ROTOR 30.0 // sec
|
||||
#define T_NARAST_ZADANIE_K_M 15.0 // sec
|
||||
#define T_NARAST_ZADANIE_I_M 15.0 // sec
|
||||
#define T_NARAST_ZADANIE_POWER 100.0 //30.0 // sec
|
||||
#define T_NARAST_ZADANIE_U_CHARGE 30.0 // sec
|
||||
#define T_NARAST_ZADANIE_K_U_DISBALANCE 15.0 // sec
|
||||
#define T_NARAST_ZADANIE_KPLUS_U_DISBALANCE 15.0 // sec
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#define ENABLE_DECR_MZZ_POWER_IZAD 1
|
||||
// çàïàñ ìîùíîñòè ïðè çàäàíèè ìîùíîñòè îò ÑÂÓ
|
||||
#define POWER_AIN_100KW 186413
|
||||
|
||||
#define DELTA_LEVEL_POWER_AIN_DECR_MZZ_DEF (3*POWER_AIN_100KW) // 300 kW // 559240 //300 êÂò//186413 //100kW // iqP = P (W) /3000/3000 * 2^24 //
|
||||
#define MIN_DELTA_LEVEL_POWER_AIN_DECR_MZZ_DEF (5*POWER_AIN_100KW) // 500 kW
|
||||
#define SMEWENIE_LEVEL_POWER_AIN_DECR_MZZ_DEF 0 //(1*POWER_AIN_100KW) // 100 kW
|
||||
|
||||
// ìåíÿåòñÿ îò 1 - ïîëíûé ðàçìàõ äî 0 - íåò îãðàíè÷åíèÿ
|
||||
#define MAX_KOEF_OGRAN_POWER_LIMIT CONST_IQ_05 // 0.5
|
||||
#define EXP_FILTER_KOEF_OGRAN_POWER_LIMIT 4.40//2.22 // â ñåêóíäàõ
|
||||
|
||||
|
||||
|
||||
|
@ -8,41 +8,19 @@
|
||||
#ifndef SRC_MAIN_PARAMS_BSU_H_
|
||||
#define SRC_MAIN_PARAMS_BSU_H_
|
||||
|
||||
#include "iq_values_norma_f.h"
|
||||
#include "iq_values_norma_iu.h"
|
||||
#include "iq_values_norma_oborot.h"
|
||||
|
||||
|
||||
|
||||
#define TKAK_23550 1
|
||||
#define TKAK_EDRK 2
|
||||
|
||||
|
||||
#define TKAK_VERSION TKAK_23550
|
||||
//#define TKAK_VERSION TKAK_EDRK
|
||||
|
||||
|
||||
// äëÿ 23550_sp2
|
||||
#define TK_DEAD_TIME_NS 25000 //25.0 //40.0
|
||||
#define TK_ACKN_TIME_NS 2200
|
||||
#define TK_MIN_TIME_NS 25000 //80.0 //35.0 // 15.0 //40.0
|
||||
#define TK_SOFT_OFF_TIME_NS 20000 //25.0 //40.0
|
||||
|
||||
#define DIV_TIME_TK_SOFT_OFF 20 // 20 nsec -> 1 bit
|
||||
#define DIV_TIME_TK_DEAD 640 //0.16 // 160 nsec -> 1 bit
|
||||
#define DIV_TIME_TK_MIN 640 //0.16 // 160 nsec -> 1 bit
|
||||
|
||||
#define DIV_TIME_TK_ACKN 20 // 20 nsec -> 1 bit
|
||||
|
||||
|
||||
// äëÿ ýäðê sp2
|
||||
|
||||
#define TK_DEAD_TIME_MKS 25.0 //40.0
|
||||
#define TK_ACKN_TIME_MKS 2.2
|
||||
#define TK_MIN_TIME_MKS 25.0 // 15.0 //40.0
|
||||
|
||||
#define DIV_TIME_TK 0.4 // 0.16
|
||||
|
||||
|
||||
#define MAX_READ_SBUS 1 //10
|
||||
|
||||
|
||||
@ -78,21 +56,18 @@
|
||||
|
||||
//////////////////////
|
||||
|
||||
#define ENABLE_ROTOR_SENSOR_ZERO_SIGNAL 0
|
||||
#define ENABLE_ROTOR_SENSOR_1_PM67 1
|
||||
#define ENABLE_ROTOR_SENSOR_2_PM67 0
|
||||
|
||||
#define ENABLE_ROTOR_SENSOR_1_PBUS 0//1
|
||||
#define ENABLE_ROTOR_SENSOR_2_PBUS 0//1
|
||||
|
||||
#define ENABLE_ROTOR_SENSOR_1 1
|
||||
#define ENABLE_ROTOR_SENSOR_2 0
|
||||
|
||||
|
||||
#if (ENABLE_ROTOR_SENSOR_1_PM67==1 && ENABLE_ROTOR_SENSOR_2_PM67==0)
|
||||
#if (ENABLE_ROTOR_SENSOR_1==1 && ENABLE_ROTOR_SENSOR_2==0)
|
||||
// ïðîáðîñ 1-ãî äàò÷èêà íà âõîä 2-ãî
|
||||
#define ENABLE_COMBO_SENSOR_1_TO_2 1
|
||||
#define ENABLE_COMBO_SENSOR_2_TO_1 0
|
||||
#endif
|
||||
|
||||
#if (ENABLE_ROTOR_SENSOR_1_PM67==0 && ENABLE_ROTOR_SENSOR_2_PM67==1)
|
||||
#if (ENABLE_ROTOR_SENSOR_1==0 && ENABLE_ROTOR_SENSOR_2==1)
|
||||
// ïðîáðîñ 2-ãî äàò÷èêà íà âõîä 1-ãî
|
||||
#define ENABLE_COMBO_SENSOR_2_TO_1 1
|
||||
#define ENABLE_COMBO_SENSOR_1_TO_2 0
|
||||
@ -100,7 +75,7 @@
|
||||
|
||||
|
||||
|
||||
#if (ENABLE_ROTOR_SENSOR_1_PM67==1 && ENABLE_ROTOR_SENSOR_2_PM67==1)
|
||||
#if (ENABLE_ROTOR_SENSOR_1==1 && ENABLE_ROTOR_SENSOR_2==1)
|
||||
|
||||
#define ENABLE_COMBO_SENSOR_1 0
|
||||
#define ENABLE_COMBO_SENSOR_1 0
|
||||
|
@ -1,9 +1,8 @@
|
||||
|
||||
|
||||
#define LEVEL_HWP_U_ZPT 2900 //2800 // V 0-2900 V
|
||||
#define LEVEL_HWP_I_AF 800 //700 // A 0-450A
|
||||
#define LEVEL_HWP_I_ZPT 1600 // A 0-2000??
|
||||
#define LEVEL_HWP_U_ABC 3100 //2900 //2800 // V 0-2000V
|
||||
#define LEVEL_HWP_I_BREAK 900 //750 // A 0-2000A
|
||||
#define LEVEL_HWP_I_AF 600 // A 0-450A
|
||||
#define LEVEL_HWP_I_ZPT 500 // A 0-2000??
|
||||
#define LEVEL_HWP_U_ABC 2900 //2800 // V 0-2000V
|
||||
#define LEVEL_HWP_I_BREAK 750 // A 0-2000A
|
||||
|
||||
#define convert_real_to_mv_hwp(nc,value) ((float)value*(float)R_ADC[0][nc]/(float)K_LEM_ADC[0][nc]*10.0)
|
||||
|
@ -20,12 +20,12 @@
|
||||
|
||||
#define COS_FI 0.87
|
||||
// Level of nominal currents
|
||||
#define I_OUT_NOMINAL_IQ 5033164// 900 A //8388608 ~ 1500A //5592405 ~ 1000A // 10066329 ~ 1800A
|
||||
#define I_OUT_NOMINAL_IQ 10066329 //8388608 ~ 1500A //5592405 ~ 1000A // 10066329 ~ 1800A
|
||||
//11184811 ~ 2000A // 12482249 ~ 2232A // 6710886 ~ 1200A
|
||||
#define I_OUT_NOMINAL 900
|
||||
#define I_OUT_NOMINAL 1800
|
||||
|
||||
#define MOTOR_CURRENT_NOMINAL 650.0 //930.0
|
||||
#define MOTOR_CURRENT_MAX 900.00 //1489.0
|
||||
#define MOTOR_CURRENT_NOMINAL 650.0//930.0
|
||||
#define MOTOR_CURRENT_MAX 1000.00//1489.0
|
||||
|
||||
|
||||
|
||||
|
@ -5,66 +5,17 @@
|
||||
* Author: yura
|
||||
*/
|
||||
|
||||
#ifndef _PARAMS_NORMA_H_
|
||||
#define _PARAMS_NORMA_H_
|
||||
#ifndef SRC_MAIN_PARAMS_NORMA_H_
|
||||
#define SRC_MAIN_PARAMS_NORMA_H_
|
||||
|
||||
#include <adc_tools.h>
|
||||
|
||||
////////////////////////////////////////////////////
|
||||
#define NORMA_FROTOR_INT 20
|
||||
#define NORMA_ACP_INT 3000
|
||||
#define NORMA_ANGLE 360
|
||||
////////////////////////////////////////////////////
|
||||
////////////////////////////////////////////////////
|
||||
//#define NORMA_FROTOR 20.0
|
||||
//#define NORMA_ACP 3000.0
|
||||
|
||||
#define NORMA_FROTOR ((float)NORMA_FROTOR_INT)
|
||||
#define NORMA_ACP ((float)NORMA_ACP_INT)
|
||||
|
||||
|
||||
#define NORMA_MZZ_INT NORMA_ACP_INT
|
||||
#define NORMA_MZZ ((float)NORMA_MZZ_INT)
|
||||
|
||||
#define NORMA_I_U_INT NORMA_MZZ_INT
|
||||
|
||||
////////////////////////////////////////////////////
|
||||
////////////////////////////////////////////////////
|
||||
////////////////////////////////////////////////////
|
||||
|
||||
#define NORMA_FROTOR 20.0
|
||||
#define NORMA_MZZ NORMA_ACP
|
||||
//#define F_STATOR_MAX NORMA_FROTOR // ěŕęń. ńęîđîńňü îăđŕíč÷ĺíŕ ýëĺęňđîíčęîé
|
||||
|
||||
|
||||
|
||||
|
||||
#define NORMA_ACP_P 100.0
|
||||
|
||||
#define NORMA_ACP_RMS 2127.66
|
||||
|
||||
#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
|
||||
|
||||
|
||||
|
||||
|
||||
#endif /* _PARAMS_NORMA_H_ */
|
||||
#endif /* SRC_MAIN_PARAMS_NORMA_H_ */
|
||||
|
@ -8,18 +8,16 @@
|
||||
#ifndef SRC_MAIN_PARAMS_PROTECT_ADC_H_
|
||||
#define SRC_MAIN_PARAMS_PROTECT_ADC_H_
|
||||
#include <params_motor.h>
|
||||
#include <params_hwp.h>
|
||||
|
||||
|
||||
#define LEVEL_ADC_I_AF LEVEL_HWP_I_AF // A 0-450A
|
||||
#define LEVEL_ADC_I_ZPT LEVEL_HWP_I_ZPT // A 0-2000??
|
||||
//#define LEVEL_ADC_U_ABC 1000 // V 0-2000V
|
||||
#define LEVEL_ADC_I_BREAK LEVEL_HWP_I_BREAK // A 0-2000A
|
||||
#define LEVEL_ADC_U_ZPT_MAX LEVEL_HWP_U_ZPT
|
||||
#define LEVEL_ADC_U_ZPT_MIN 1800
|
||||
#define LEVEL_ADC_U_IN_MAX LEVEL_HWP_U_ABC
|
||||
#define LEVEL_ADC_U_IN_MIN 1380
|
||||
#define LEVEL_ADC_I_OUT_MAX I_OUT_NOMINAL //(I_OUT_NOMINAL * 1.9)
|
||||
#define LEVEL_ADC_I_AF 700 // A 0-450A
|
||||
#define LEVEL_ADC_I_ZPT 500 // A 0-2000??
|
||||
#define LEVEL_ADC_U_ABC 1000 // V 0-2000V
|
||||
#define LEVEL_ADC_I_BREAK 280 // A 0-2000A
|
||||
#define LEVEL_ADC_U_ZPT_MAX 2900
|
||||
#define LEVEL_ADC_U_ZPT_MIN 1800
|
||||
#define LEVEL_ADC_U_IN_MAX 2250
|
||||
#define LEVEL_ADC_U_IN_MIN 1380
|
||||
#define LEVEL_ADC_I_OUT_MAX I_OUT_NOMINAL//(I_OUT_NOMINAL * 1.9)
|
||||
|
||||
|
||||
#endif /* SRC_MAIN_PARAMS_PROTECT_ADC_H_ */
|
||||
|
@ -9,13 +9,10 @@
|
||||
#define SRC_MAIN_PARAMS_PWM24_H_
|
||||
|
||||
///////////////////////////////////////////////////////
|
||||
#if (_SIMULATE_AC==1)
|
||||
#define FREQ_PWM 100 //450 //800 /* ÷àñòîòà ØÈÌà */ //3138 // 2360//2477 //
|
||||
#else
|
||||
#define FREQ_PWM 450 //800 /* ÷àñòîòà ØÈÌà */ //3138 // 2360//2477 //
|
||||
#endif
|
||||
|
||||
#define DEF_PERIOD_MIN_MKS 60 // 80 //60 // áåðåì ìèíèìàëüíîå âðåìÿ ðàáîòû êëþ÷à = 2*TK_MIN_TIME_MKS = 30 ñ çàïàñîì
|
||||
#define FREQ_PWM 450 //800 /* ÷àñòîòà ØÈÌà */ //3138 // 2360//2477 //
|
||||
|
||||
#define DEF_PERIOD_MIN_MKS 80 //60 // áåðåì ìèíèìàëüíîå âðåìÿ ðàáîòû êëþ÷à = 2*TK_MIN_TIME_MKS = 30 ñ çàïàñîì
|
||||
// + TK_DEAD_TIME_MKS + 5mks çàïàñ = 60
|
||||
#define DEF_PERIOD_MIN_BR_XTICS 165
|
||||
|
||||
|
@ -3,13 +3,6 @@
|
||||
#define INDEX_T_WATER_INT 1
|
||||
|
||||
|
||||
#define ALARM_TEMPER_BREAK_INT 1100
|
||||
#define ABNORMAL_TEMPER_BREAK_INT 900
|
||||
#define DELTA_TEMPER_BREAK_INT 20
|
||||
|
||||
|
||||
|
||||
|
||||
// koef to svu
|
||||
#define K_TEMPER_TO_SVU 10.0
|
||||
#define K_P_WATER_TO_SVU 100.0
|
||||
@ -43,15 +36,15 @@
|
||||
|
||||
|
||||
// air
|
||||
#define ALARM_TEMPER_AIR_INT 450
|
||||
#define ABNORMAL_TEMPER_AIR_INT 400
|
||||
#define ALARM_TEMPER_AIR_INT 400
|
||||
#define ABNORMAL_TEMPER_AIR_INT 300
|
||||
|
||||
//ac drive
|
||||
#define ALARM_TEMPER_ACDRIVE_WINDING 1300
|
||||
#define ABNORMAL_TEMPER_ACDRIVE_WINDING 1200
|
||||
#define ALARM_TEMPER_ACDRIVE_WINDING 1600
|
||||
#define ABNORMAL_TEMPER_ACDRIVE_WINDING 1500
|
||||
|
||||
#define ALARM_TEMPER_ACDRIVE_BEAR 900
|
||||
#define ABNORMAL_TEMPER_ACDRIVE_BEAR 800
|
||||
#define ALARM_TEMPER_ACDRIVE_BEAR 1100
|
||||
#define ABNORMAL_TEMPER_ACDRIVE_BEAR 1000
|
||||
|
||||
#define ALARM_TEMPER_BSU 600
|
||||
#define ABNORMAL_TEMPER_BSU 500
|
||||
|
@ -28,171 +28,14 @@
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
void tkak_init_plate(int k, int tkak0_off_protect, int tk_disable_output_a, int tk_disable_output_b)
|
||||
{
|
||||
unsigned int t_ticks;
|
||||
//tkak 0
|
||||
project.cds_tk[k].status_serial_bus.max_read_error = MAX_READ_SBUS;// SERIAL_BUS Timing setup
|
||||
|
||||
|
||||
if (k==3)
|
||||
{
|
||||
// project.cds_tk[k].setup_pbus.use_reg_in_pbus.all = 0x0; // PBUS all off
|
||||
// òóò ó íàñ òîëüêî òîðìîçíûå
|
||||
if (tkak0_off_protect==1)
|
||||
project.cds_tk[k].write.sbus.mask_protect_tk.all = 0x0000; // only break ack+cur
|
||||
else
|
||||
project.cds_tk[k].write.sbus.mask_protect_tk.all = 0x0303; // only break ack+cur
|
||||
|
||||
// project.cds_tk[k].write.sbus.mask_tk_out_40pin.all = 0x0003; // optical bus+break
|
||||
project.cds_tk[k].write.sbus.mask_tk_out_40pin.all = 0x00cf; // optical bus+break
|
||||
|
||||
#if (TKAK_VERSION==TKAK_EDRK)
|
||||
project.cds_tk[k].write.sbus.ack_time.bit.time = (int)(TK_ACKN_TIME_MKS / 0.02);
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.mintime = (int)(TK_MIN_TIME_MKS / DIV_TIME_TK);
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.deadtime = (int)(TK_DEAD_TIME_MKS / DIV_TIME_TK);
|
||||
#endif
|
||||
|
||||
#if (TKAK_VERSION==TKAK_23550)
|
||||
project.cds_tk[k].write.sbus.ack_time.bit.time = (int)(TK_ACKN_TIME_NS/1000.0 / 0.02);
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.mintime = (int)(TK_MIN_TIME_NS/1000.0 / DIV_TIME_TK);
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.deadtime = (int)(TK_DEAD_TIME_NS/1000.0 / DIV_TIME_TK);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
project.cds_tk[k].setup_pbus.use_reg_in_pbus.all = 0x0; // PBUS all off
|
||||
|
||||
if (tk_disable_output_a==1 && tk_disable_output_b==1)
|
||||
{
|
||||
project.cds_tk[k].write.sbus.mask_tk_out_40pin.all = 0x0000; //mask key 1-use key,0-not use key
|
||||
project.cds_tk[k].write.sbus.mask_protect_tk.all = 0xff00; // cur+ack 1-on protect.
|
||||
}
|
||||
else
|
||||
if (tk_disable_output_a==0 && tk_disable_output_b==1)
|
||||
{
|
||||
project.cds_tk[k].write.sbus.mask_tk_out_40pin.all = 0x000f; //mask key 1-use key,0-not use key
|
||||
project.cds_tk[k].write.sbus.mask_protect_tk.all = 0x0f0f; // cur+ack 1-on protect.
|
||||
}
|
||||
else
|
||||
if (tk_disable_output_a==1 && tk_disable_output_b==0)
|
||||
{
|
||||
project.cds_tk[k].write.sbus.mask_tk_out_40pin.all = 0x00f0; //mask key 1-use key,0-not use key
|
||||
project.cds_tk[k].write.sbus.mask_protect_tk.all = 0xf0f0; // cur+ack 1-on protect.
|
||||
}
|
||||
else
|
||||
if (tk_disable_output_a==0 && tk_disable_output_b==0)
|
||||
{
|
||||
project.cds_tk[k].write.sbus.mask_tk_out_40pin.all = 0x00ff; //mask key 1-use key,0-not use key
|
||||
project.cds_tk[k].write.sbus.mask_protect_tk.all = 0xffff; // cur+ack 1-on protect.
|
||||
}
|
||||
|
||||
if (tkak0_off_protect==1)
|
||||
project.cds_tk[k].write.sbus.mask_protect_tk.all = 0x0000; // cur+ack 1-on protect.
|
||||
|
||||
|
||||
#if (TKAK_VERSION==TKAK_EDRK)
|
||||
project.cds_tk[k].write.sbus.ack_time.bit.time = (int)(TK_ACKN_TIME_MKS / 0.02);
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.mintime = (int)(TK_MIN_TIME_MKS / DIV_TIME_TK);
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.deadtime = (int)(TK_DEAD_TIME_MKS / DIV_TIME_TK);
|
||||
#endif
|
||||
|
||||
|
||||
#if (TKAK_VERSION==TKAK_23550)
|
||||
|
||||
|
||||
// TK_ACKN_TIME_NS
|
||||
|
||||
t_ticks = (unsigned int)(TK_ACKN_TIME_NS / DIV_TIME_TK_ACKN);
|
||||
|
||||
#if (TK_ACKN_TIME_NS>(DIV_TIME_TK_ACKN*255))
|
||||
#error "TK_ACKN_TIME_NS âûøå ïðåäåëà!"
|
||||
#endif
|
||||
project.cds_tk[k].write.sbus.ack_time.bit.time = (unsigned int)t_ticks;
|
||||
|
||||
|
||||
// TK_MIN_TIME_NS
|
||||
|
||||
t_ticks = (unsigned int)(TK_MIN_TIME_NS / DIV_TIME_TK_MIN);
|
||||
|
||||
#if (TK_MIN_TIME_NS>(DIV_TIME_TK_MIN*255))
|
||||
#error "TK_MIN_TIME_NS âûøå ïðåäåëà!"
|
||||
#endif
|
||||
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.mintime = (unsigned int)t_ticks;
|
||||
|
||||
|
||||
//TK_DEAD_TIME_NS
|
||||
|
||||
// ìèíèìàëüíîå çíà÷åíèå äëÿ dead_time = 5 ìêñ, ìåíüøå - çàãðóçèòñÿ âñå ðàâíî 5 ìêñ
|
||||
t_ticks = (unsigned int)(TK_DEAD_TIME_NS / DIV_TIME_TK_DEAD);
|
||||
|
||||
#if (TK_DEAD_TIME_NS>(DIV_TIME_TK_DEAD*255))
|
||||
#error "TK_DEAD_TIME_MKS âûøå ïðåäåëà!"
|
||||
#endif
|
||||
project.cds_tk[k].write.sbus.dead_min_time.bit.deadtime = (unsigned int)(t_ticks);
|
||||
|
||||
|
||||
// TK_SOFT_OFF_TIME_NS
|
||||
|
||||
t_ticks = (unsigned int)(TK_SOFT_OFF_TIME_NS / DIV_TIME_TK_SOFT_OFF);
|
||||
|
||||
#if (TK_SOFT_OFF_TIME_NS>(DIV_TIME_TK_SOFT_OFF*65535))
|
||||
#error "TK_SOFT_OFF_TIME_MKS âûøå ïðåäåëà!"
|
||||
#endif
|
||||
project.cds_tk[k].write.sbus.time_after_err = (unsigned int)t_ticks;
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_soft_disconnect = 1;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.detect_soft_disconnect = 0;//1;
|
||||
|
||||
}
|
||||
|
||||
if (tkak0_off_protect==1)
|
||||
{
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_err_power = 0;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_err_switch = 0;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.disable_err_hwp = 0;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.disable_err0_in = 0;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.disable_err_mintime = 0;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_line_err = 0;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_soft_disconnect = 0;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.detect_soft_disconnect = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_err_power = 1;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.disable_err_hwp = 1;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.disable_err0_in = 1;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.disable_err_mintime = 1;
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_line_err = 1;//1;//0;//1;
|
||||
|
||||
// íà ñòàðûõ ïåðåõîäíûõ ïëàòàõ ýòîãî ñèãíàëà íåò! íóæíà ïåðåìûêà!
|
||||
if (project.cds_tk[k].type_cds_xilinx == TYPE_CDS_XILINX_SP6)
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_err_switch = 0;
|
||||
else
|
||||
project.cds_tk[k].write.sbus.protect_error.bit.enable_err_switch = 1;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
#define convert_real_to_mv_hwp(nc,value) ((float)value*(float)R_ADC[0][nc]/(float)K_LEM_ADC[0][nc]*10.0)
|
||||
|
||||
////////////////////////////////////////////////////////////////
|
||||
// ãðóçèì íàñòðîéêè â ïåðèôåð. ïëàòû è HWP
|
||||
////////////////////////////////////////////////////////////////
|
||||
void project_prepare_config(void)
|
||||
{
|
||||
int k = 0;
|
||||
|
||||
// write here setup for all plates
|
||||
//
|
||||
//
|
||||
@ -221,15 +64,15 @@ void project_prepare_config(void)
|
||||
//Direction
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg2 = 1; // use
|
||||
|
||||
//#if (ENABLE_ROTOR_SENSOR_1_PBUS==1)
|
||||
#if (ENABLE_ROTOR_SENSOR_1==1)
|
||||
// sensor1
|
||||
//SpeedS1_cnt
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg3 = 1; // use
|
||||
//SpeedS1_cnt90
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg4 = 1; // use
|
||||
//#endif
|
||||
#endif
|
||||
|
||||
//#if (ENABLE_ROTOR_SENSOR_2_PBUS==1)
|
||||
//#if (ENABLE_ROTOR_SENSOR_2==1)
|
||||
// sensor2
|
||||
//SpeedS2_cnt
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg5 = 1; // use
|
||||
@ -238,39 +81,38 @@ void project_prepare_config(void)
|
||||
//#endif
|
||||
|
||||
//#if (TYPE_CDS_XILINX_IN_0==TYPE_CDS_XILINX_SP2)
|
||||
// if (project.cds_in[0].type_cds_xilinx == TYPE_CDS_XILINX_SP2)
|
||||
if (project.cds_in[0].type_cds_xilinx == TYPE_CDS_XILINX_SP2)
|
||||
//is Channel Alive
|
||||
// project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg13 = 1; // use
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg13 = 1; // use
|
||||
//#endif
|
||||
|
||||
|
||||
if (project.cds_in[0].type_cds_xilinx == TYPE_CDS_XILINX_SP6)
|
||||
{
|
||||
|
||||
#if (ENABLE_ROTOR_SENSOR_1_PBUS==1)
|
||||
//#if (ENABLE_ROTOR_SENSOR_1==1)
|
||||
//Time since zero point S1
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg7 = 1; // use
|
||||
// Impulses since zero point Rising S1
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg8 = 1; // use
|
||||
//Impulses since zero point Falling S1
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg9 = 1; // use
|
||||
#endif
|
||||
//#endif
|
||||
|
||||
|
||||
#if (ENABLE_ROTOR_SENSOR_2_PBUS==1)
|
||||
//#if (ENABLE_ROTOR_SENSOR_2==1)
|
||||
//Time since zero point S2
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg10 = 1; // use
|
||||
// Impulses since zero point Rising S2
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg11 = 1; // use
|
||||
//Impulses since zero point Falling S2
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg12 = 1; // use
|
||||
#endif
|
||||
//#endif
|
||||
|
||||
//is Channel Alive
|
||||
project.cds_in[0].setup_pbus.use_reg_in_pbus.bit.reg13 = 1; // use
|
||||
|
||||
project.cds_in[0].status_serial_bus.max_read_error = MAX_READ_SBUS;
|
||||
}
|
||||
project.cds_in[0].status_serial_bus.max_read_error = MAX_READ_SBUS;
|
||||
|
||||
|
||||
#endif
|
||||
@ -344,21 +186,8 @@ void project_prepare_config(void)
|
||||
//////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////
|
||||
|
||||
#if (USE_TK_0)
|
||||
tkak_init_plate(0, TKAK0_OFF_PROTECT, TK_DISABLE_OUTPUT_A1, TK_DISABLE_OUTPUT_B1);
|
||||
#endif
|
||||
#if (USE_TK_1)
|
||||
tkak_init_plate(1, TKAK1_OFF_PROTECT, TK_DISABLE_OUTPUT_C1, TK_DISABLE_OUTPUT_A2);
|
||||
#endif
|
||||
#if (USE_TK_2)
|
||||
tkak_init_plate(2, TKAK2_OFF_PROTECT, TK_DISABLE_OUTPUT_B2, TK_DISABLE_OUTPUT_C2);
|
||||
#endif
|
||||
|
||||
#if (USE_TK_3)
|
||||
tkak_init_plate(3, TKAK3_OFF_PROTECT, 0, 0);
|
||||
#endif
|
||||
|
||||
/*
|
||||
#if (USE_TK_0)
|
||||
//tkak 0
|
||||
project.cds_tk[0].status_serial_bus.max_read_error = MAX_READ_SBUS;// SERIAL_BUS Timing setup
|
||||
@ -401,7 +230,7 @@ void project_prepare_config(void)
|
||||
project.cds_tk[0].write.sbus.protect_error.bit.disable_err_hwp = 0;
|
||||
project.cds_tk[0].write.sbus.protect_error.bit.disable_err0_in = 0;
|
||||
project.cds_tk[0].write.sbus.protect_error.bit.disable_err_mintime = 0;
|
||||
project.cds_tk[0].write.sbus.protect_error.bit.enable_line_err = 0;
|
||||
project.cds_tk[0].write.sbus.protect_error.bit.enable_line_err = 1;
|
||||
#else
|
||||
|
||||
|
||||
@ -466,7 +295,7 @@ void project_prepare_config(void)
|
||||
project.cds_tk[1].write.sbus.protect_error.bit.disable_err_hwp = 0;
|
||||
project.cds_tk[1].write.sbus.protect_error.bit.disable_err0_in = 0;
|
||||
project.cds_tk[1].write.sbus.protect_error.bit.disable_err_mintime = 0;
|
||||
project.cds_tk[1].write.sbus.protect_error.bit.enable_line_err = 0;
|
||||
project.cds_tk[1].write.sbus.protect_error.bit.enable_line_err = 1;
|
||||
#else
|
||||
|
||||
project.cds_tk[1].write.sbus.protect_error.bit.enable_err_power = 1;
|
||||
@ -528,7 +357,7 @@ void project_prepare_config(void)
|
||||
project.cds_tk[2].write.sbus.protect_error.bit.disable_err_hwp = 0;
|
||||
project.cds_tk[2].write.sbus.protect_error.bit.disable_err0_in = 0;
|
||||
project.cds_tk[2].write.sbus.protect_error.bit.disable_err_mintime = 0;
|
||||
project.cds_tk[2].write.sbus.protect_error.bit.enable_line_err = 0;
|
||||
project.cds_tk[2].write.sbus.protect_error.bit.enable_line_err = 1;
|
||||
|
||||
#else
|
||||
|
||||
@ -576,7 +405,7 @@ void project_prepare_config(void)
|
||||
project.cds_tk[3].write.sbus.protect_error.bit.disable_err_hwp = 0;
|
||||
project.cds_tk[3].write.sbus.protect_error.bit.disable_err0_in = 0;
|
||||
project.cds_tk[3].write.sbus.protect_error.bit.disable_err_mintime = 0;
|
||||
project.cds_tk[3].write.sbus.protect_error.bit.enable_line_err = 0;
|
||||
project.cds_tk[3].write.sbus.protect_error.bit.enable_line_err = 1;
|
||||
|
||||
#else
|
||||
|
||||
@ -596,7 +425,7 @@ void project_prepare_config(void)
|
||||
#endif
|
||||
|
||||
#endif
|
||||
*/
|
||||
|
||||
//////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////
|
||||
@ -651,14 +480,7 @@ void project_prepare_config(void)
|
||||
// out1
|
||||
project.cds_out[1].status_serial_bus.max_read_error = MAX_READ_SBUS;// SERIAL_BUS Timing setup
|
||||
|
||||
#if (OUT1_OFF_PROTECT==1)
|
||||
|
||||
project.cds_out[1].write.sbus.protect_error.bit.disable_err0_in = 0;
|
||||
project.cds_out[1].write.sbus.protect_error.bit.disable_err_hwp = 0;
|
||||
project.cds_out[1].write.sbus.protect_error.bit.enable_err_power = 0;
|
||||
project.cds_out[1].write.sbus.protect_error.bit.enable_err_switch = 0;
|
||||
|
||||
#else
|
||||
project.cds_out[1].write.sbus.protect_error.bit.enable_err_power = 1;
|
||||
project.cds_out[1].write.sbus.protect_error.bit.disable_err0_in = 1;
|
||||
project.cds_out[1].write.sbus.protect_error.bit.disable_err_hwp = 1;
|
||||
@ -671,7 +493,6 @@ void project_prepare_config(void)
|
||||
project.cds_out[1].write.sbus.protect_error.bit.enable_err_switch = 0;
|
||||
else
|
||||
project.cds_out[1].write.sbus.protect_error.bit.enable_err_switch = 1;
|
||||
#endif
|
||||
|
||||
project.cds_out[1].write.sbus.enable_protect_out.all = 0x0000;
|
||||
|
||||
@ -733,20 +554,20 @@ void project_prepare_config(void)
|
||||
|
||||
// ïåðâûé äàò÷èê In1-ïðÿìîé, In2-ïðÿìîé90ãðàä.
|
||||
// íà íåèñïîëüçóåìûå ïèøåì 0xf
|
||||
project.cds_in[0].write.sbus.first_sensor.bit.direct_ch = 0x0; // in2
|
||||
project.cds_in[0].write.sbus.first_sensor.bit.direct_ch_90deg = 0x1; // in1
|
||||
project.cds_in[0].write.sbus.first_sensor.bit.direct_ch = 0x1; // in2
|
||||
project.cds_in[0].write.sbus.first_sensor.bit.direct_ch_90deg = 0x2; // in1
|
||||
// ýòè îòêëþ÷åíû
|
||||
project.cds_in[0].write.sbus.first_sensor.bit.inv_ch = 0x0f; // in0
|
||||
project.cds_in[0].write.sbus.first_sensor.bit.inv_ch_90deg = 0x0f; // in0
|
||||
|
||||
// êàê áû ïåðâûé, íî ñ ïåðåêðåñòîì In2-ïðÿìîé, In1-ïðÿìîé90ãðàä.
|
||||
project.cds_in[0].write.sbus.second_sensor.bit.direct_ch = 0x01; // in0
|
||||
project.cds_in[0].write.sbus.second_sensor.bit.direct_ch_90deg = 0x00; // in1
|
||||
project.cds_in[0].write.sbus.second_sensor.bit.direct_ch = 0x02; // in0
|
||||
project.cds_in[0].write.sbus.second_sensor.bit.direct_ch_90deg = 0x01; // in1
|
||||
// ýòè îòêëþ÷åíû
|
||||
project.cds_in[0].write.sbus.second_sensor.bit.inv_ch = 0x0f; // in0
|
||||
project.cds_in[0].write.sbus.second_sensor.bit.inv_ch_90deg = 0x0f; // in0
|
||||
// ìåòêà íóëß
|
||||
project.cds_in[0].write.sbus.zero_sensors.bit.for_sensor1 = 0x02; //
|
||||
project.cds_in[0].write.sbus.zero_sensors.bit.for_sensor1 = 0x0; //
|
||||
project.cds_in[0].write.sbus.zero_sensors.bit.for_sensor2 = 0x0f; //
|
||||
// âêëþ÷àåì òîëüêî îäíó ìåòóêó íóëß
|
||||
project.cds_in[0].write.sbus.zero_sensors.bit.enable_sensor1 = 1;
|
||||
@ -960,13 +781,13 @@ void project_prepare_config(void)
|
||||
//////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////
|
||||
//Incremental sensor_init
|
||||
#if (ENABLE_ROTOR_SENSOR_1_PM67==1)
|
||||
#if (ENABLE_ROTOR_SENSOR_1==1)
|
||||
inc_sensor.use_sensor1 = 1;
|
||||
#else
|
||||
inc_sensor.use_sensor1 = 0;
|
||||
#endif
|
||||
|
||||
#if (ENABLE_ROTOR_SENSOR_2_PM67==1)
|
||||
#if (ENABLE_ROTOR_SENSOR_2==1)
|
||||
inc_sensor.use_sensor2 = 1;
|
||||
#else
|
||||
inc_sensor.use_sensor2 = 0;
|
||||
@ -982,13 +803,7 @@ void project_prepare_config(void)
|
||||
|
||||
|
||||
inc_sensor.pm67regs.write_comand_reg.bit.set_sampling_time = SAMPLING_TIME_MS;
|
||||
// 23550
|
||||
// inc_sensor.pm67regs.write_comand_reg.bit.filter_sensitivity = 5; //0x0; //äî 170 îá.ìèí
|
||||
// 22220
|
||||
inc_sensor.pm67regs.write_comand_reg.bit.filter_sensitivity = 300;//5; //0x0; //äî 170 îá.ìèí
|
||||
|
||||
|
||||
|
||||
inc_sensor.pm67regs.write_comand_reg.bit.filter_sensitivity = 5; //0x0; //äî 170 îá.ìèí
|
||||
inc_sensor.set(&inc_sensor);
|
||||
|
||||
//Rotation sensor_init
|
||||
|
@ -43,7 +43,7 @@
|
||||
|
||||
// Íàñòðîéêà ñêîðîñòåé RS232
|
||||
#define RS232_SPEED_A 57600//115200//57600
|
||||
#define RS232_SPEED_B 57600//115200//57600//
|
||||
#define RS232_SPEED_B 57600//115200//57600//115200//57600//
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////////
|
||||
///////////////////////////////////////////////////////////////////////////////////
|
||||
@ -123,20 +123,20 @@
|
||||
|
||||
#if (_FLOOR6_ADD==1)
|
||||
|
||||
#define USE_ADC_0 1
|
||||
#define USE_ADC_1 1
|
||||
//#define USE_ADC_0 1
|
||||
//#define USE_ADC_1 1
|
||||
//////
|
||||
#define USE_IN_0 1
|
||||
//#define USE_IN_0 1
|
||||
////
|
||||
//#define USE_IN_1 1
|
||||
////////
|
||||
//#define USE_OUT_0 1
|
||||
////////
|
||||
////////
|
||||
#define USE_TK_0 1
|
||||
#define USE_TK_1 1
|
||||
//#define USE_TK_0 1
|
||||
//#define USE_TK_1 1
|
||||
//////
|
||||
#define USE_TK_2 1
|
||||
//#define USE_TK_2 1
|
||||
#define USE_TK_3 1
|
||||
|
||||
//#define USE_HWP_0 1
|
||||
@ -161,7 +161,6 @@
|
||||
#define USE_TK_3 1
|
||||
|
||||
#define USE_HWP_0 1
|
||||
#define USE_HWP_1 1
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -111,7 +111,7 @@ typedef struct {
|
||||
LEVEL_ADC_U_IN_MAX,LEVEL_ADC_U_IN_MAX, LEVEL_ADC_U_IN_MIN,LEVEL_ADC_U_IN_MIN,\
|
||||
LEVEL_ADC_U_ZPT_MAX,LEVEL_ADC_U_ZPT_MAX,LEVEL_ADC_U_ZPT_MIN,LEVEL_ADC_U_ZPT_MIN,\
|
||||
LEVEL_ADC_I_ZPT,\
|
||||
LEVEL_ADC_I_BREAK, LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,\
|
||||
LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,LEVEL_ADC_I_AF,\
|
||||
LEVEL_ADC_I_OUT_MAX}
|
||||
|
||||
extern PROTECT_LEVELS protect_levels;
|
||||
|
@ -9,8 +9,6 @@
|
||||
#include <pump_control.h>
|
||||
|
||||
#include "control_station.h"
|
||||
#include "digital_filters.h"
|
||||
#include "sbor_shema.h"
|
||||
|
||||
#pragma DATA_SECTION(pumps, ".slow_vars")
|
||||
PUMP_CONTROL pumps = PUMP_CONTROL_DEFAULTS;
|
||||
@ -77,15 +75,6 @@ void pump_control(void)
|
||||
pump_off_without_time_wait = 1;
|
||||
}
|
||||
|
||||
if (control_station.active_array_cmd[CONTROL_STATION_CMD_MODE_PUMP] == 6)
|
||||
{
|
||||
// edrk.SelectPump1_2 = 1;
|
||||
pumps.SelectedPump1_2 = 0;
|
||||
edrk.ManualStartPump = 1;
|
||||
edrk.AutoStartPump = 0;
|
||||
pump_off_without_time_wait = 1;
|
||||
}
|
||||
|
||||
edrk.SumStartPump = edrk.AutoStartPump || edrk.ManualStartPump;
|
||||
|
||||
turn_on_nasos_1_2(pump_off_without_time_wait);
|
||||
@ -132,8 +121,7 @@ int fast_stop_pump=0;
|
||||
|
||||
if ( edrk.SumStartPump==1 && edrk.errors.e5.bits.PRE_READY_PUMP == 0 && fast_stop_pump==0)
|
||||
{
|
||||
if (pumps.SelectedPump1_2 == 0 /*&& edrk.ManualStartPump == 0*/)
|
||||
{
|
||||
if (pumps.SelectedPump1_2 == 0 && edrk.ManualStartPump == 0) {
|
||||
//Âûáîð íàñîñà èñõîäÿ èç îòðàáîòàíîãî âðåìåíè
|
||||
switch (select_pump()) {
|
||||
case 1:
|
||||
@ -230,15 +218,13 @@ int select_pump() {
|
||||
int p_n = 0;
|
||||
if (pumps.lock_pump == 0) {
|
||||
|
||||
p_n = calc_auto_moto_pump();
|
||||
if (p_n == 0)
|
||||
p_n = 1;
|
||||
|
||||
// if (pumps.pump1_engine_minutes > pumps.pump2_engine_minutes) {
|
||||
// p_n = 2;
|
||||
// } else {
|
||||
// p_n = 1;
|
||||
// }
|
||||
|
||||
p_n = 1;
|
||||
} else {
|
||||
p_n = edrk.SelectPump1_2;
|
||||
}
|
||||
|
@ -16,10 +16,10 @@ void pwm_test_lines_start(void)
|
||||
{
|
||||
cmd_pwm_test_lines = 0xffff;
|
||||
|
||||
// i_WriteMemory(ADR_TK_MASK_1, 0);
|
||||
i_WriteMemory(ADR_TK_MASK_1, 0);
|
||||
i_WriteMemory(ADR_PWM_DIRECT2,0xffff);
|
||||
i_WriteMemory(ADR_PWM_DRIVE_MODE, 3); // on direct tk lines
|
||||
i_WriteMemory(ADR_PWM_DIRECT2,0xffff);
|
||||
// i_WriteMemory(ADR_PWM_DRIVE_MODE, 3); // on direct tk lines
|
||||
// i_WriteMemory(ADR_PWM_DIRECT2,0xffff);
|
||||
|
||||
i_WriteMemory(ADR_TK_MASK_1, 0x0); //Turn on additional 16 tk lines
|
||||
}
|
||||
@ -27,10 +27,8 @@ void pwm_test_lines_start(void)
|
||||
void pwm_test_lines_stop(void)
|
||||
{
|
||||
cmd_pwm_test_lines = 0xffff;
|
||||
|
||||
i_WriteMemory(ADR_TK_MASK_1, 0xffff); //Turn off additional 16 tk lines
|
||||
i_WriteMemory(ADR_PWM_DIRECT2,0xffff);
|
||||
|
||||
// i_WriteMemory(ADR_PWM_DRIVE_MODE, 0); // off direct tk lines
|
||||
i_WriteMemory(ADR_PWM_DRIVE_MODE, 0); // off direct tk lines
|
||||
}
|
||||
|
||||
|
@ -11,25 +11,17 @@
|
||||
#include "adc_tools.h"
|
||||
#include "control_station.h"
|
||||
#include "control_station_project.h"
|
||||
#include "digital_filters.h"
|
||||
#include "detect_errors.h"
|
||||
|
||||
#define RASCEPITEL_MANUAL_ALWAYS_ON 0//1
|
||||
///////////////////////////////////////////////
|
||||
///////////////////////////////////////////////
|
||||
//#define IQ_MINIMAL_DELTA_RUN_CHARGE_1 559240 //100V
|
||||
//#define IQ_MINIMAL_DELTA_RUN_CHARGE_2 1118480 //200V
|
||||
#define IQ_MINIMAL_DELTA_RUN_CHARGE 279620 // 50V //559240 //100 V
|
||||
|
||||
//#define IQ_MINIMAL_DELTA_RUN_CHARGE 279620 // 50V
|
||||
#define IQ_MINIMAL_DELTA_RUN_CHARGE_1 1118480// 200 V ///279620 // 50V
|
||||
#define IQ_MINIMAL_DELTA_RUN_CHARGE_2 1118480// 200 V //279620 // 50V
|
||||
|
||||
#define IQ_MINIMAL_DELTA_RUN_WORK 2796202 // 500V // 2236960 // 400V // 1677720 // 300 V // 559240 // 100V
|
||||
#define IQ_MINIMAL_DELTA_RUN_WORK 1677720 // 300 V // 559240 // 100V
|
||||
|
||||
#define IQ_MINIMAL_ZAD_U_CHARGE 55924 // 10V
|
||||
#define IQ_MAXIMAL_ZAD_U_CHARGE 14596177 // 2610V
|
||||
#define IQ_MINIMAL_DELTA_RUN_CHARGE2 139810 //25 V
|
||||
#define TIME_WAIT_CHARGE_ON 300 //30 sec
|
||||
#define TIME_WAIT_CHARGE_ON 100 //10 sec
|
||||
#define TIME_PAUSE_U_RISE 30 // 1 sec
|
||||
|
||||
#define IQ_MINIMAL_RISE_U 55924 // 10V
|
||||
@ -71,7 +63,7 @@ unsigned int zaryad_on_off(unsigned int flag)
|
||||
}
|
||||
|
||||
// åñòü ðàçáåæêà ïî áàíêàì
|
||||
if (_IQabs(filter.iqU_1_long-filter.iqU_2_long)>IQ_MINIMAL_DELTA_RUN_WORK) //IQ_MINIMAL_DELTA_RUN_CHARGE_1
|
||||
if (_IQabs(filter.iqU_1_long-filter.iqU_2_long)>IQ_MINIMAL_DELTA_RUN_CHARGE)
|
||||
{
|
||||
edrk.errors.e6.bits.ER_DISBAL_BATT |= 1;
|
||||
edrk.to_ing.bits.ZARYAD_ON = 0;
|
||||
@ -83,8 +75,8 @@ unsigned int zaryad_on_off(unsigned int flag)
|
||||
|
||||
// çàðßä íîðìà è áûëî âêëþ÷åíî, âûêëþ÷àåì
|
||||
if ( edrk.from_ing1.bits.ZARYAD_ON &&
|
||||
(filter.iqU_1_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_1)
|
||||
|| filter.iqU_2_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_1))
|
||||
(filter.iqU_1_long>=(edrk.zadanie.iq_ZadanieU_Charge)
|
||||
|| filter.iqU_2_long>=(edrk.zadanie.iq_ZadanieU_Charge))
|
||||
)
|
||||
{
|
||||
restart_charge = 1;
|
||||
@ -94,8 +86,8 @@ unsigned int zaryad_on_off(unsigned int flag)
|
||||
{
|
||||
//TODO !!! ïî ñóòè ïîâòîðÿåò ïðåäûäóùèé if. Óäàëèòü?
|
||||
if ( edrk.from_ing1.bits.ZARYAD_ON==0 &&
|
||||
(filter.iqU_1_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2)
|
||||
|| filter.iqU_2_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2)) )
|
||||
(filter.iqU_1_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE)
|
||||
|| filter.iqU_2_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE)) )
|
||||
{
|
||||
restart_charge = 1;
|
||||
edrk.to_ing.bits.ZARYAD_ON = 0;
|
||||
@ -103,8 +95,8 @@ unsigned int zaryad_on_off(unsigned int flag)
|
||||
else
|
||||
{
|
||||
// çàðßä ìåíüøå íóæíîãî, âêëþ÷àåì.
|
||||
if ( (filter.iqU_1_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2))
|
||||
&& (filter.iqU_2_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2)) )
|
||||
if ( (filter.iqU_1_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE))
|
||||
&& (filter.iqU_2_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE)) )
|
||||
edrk.to_ing.bits.ZARYAD_ON = 1;
|
||||
|
||||
}
|
||||
@ -160,8 +152,8 @@ unsigned int zaryad_on_off(unsigned int flag)
|
||||
else//restart_charge==0
|
||||
{
|
||||
// ïî÷åìó-òî çàðßä ñòàë ìåíüøå!!!
|
||||
if ( (filter.iqU_1_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2))
|
||||
|| (filter.iqU_2_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2)) )
|
||||
if ( (filter.iqU_1_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE))
|
||||
|| (filter.iqU_2_long<(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE)) )
|
||||
edrk.errors.e6.bits.ERROR_PRE_CHARGE_U |= 1;
|
||||
|
||||
} //restart_charge==0
|
||||
@ -175,11 +167,11 @@ unsigned int zaryad_on_off(unsigned int flag)
|
||||
prev_U2 = filter.iqU_2_long;
|
||||
}
|
||||
|
||||
if ( (filter.iqU_1_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2))
|
||||
&& (filter.iqU_2_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE_2))
|
||||
if ( (filter.iqU_1_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE))
|
||||
&& (filter.iqU_2_long>=(edrk.zadanie.iq_ZadanieU_Charge-IQ_MINIMAL_DELTA_RUN_CHARGE))
|
||||
&& (_IQabs(filter.iqU_1_long-filter.iqU_2_long)<IQ_MINIMAL_DELTA_RUN_WORK)
|
||||
&& (filter.iqU_1_long<=(edrk.zadanie.iq_ZadanieU_Charge+IQ_MINIMAL_DELTA_RUN_CHARGE_2))
|
||||
&& (filter.iqU_2_long<=(edrk.zadanie.iq_ZadanieU_Charge+IQ_MINIMAL_DELTA_RUN_CHARGE_2))
|
||||
&& (filter.iqU_1_long<=(edrk.zadanie.iq_ZadanieU_Charge+IQ_MINIMAL_DELTA_RUN_CHARGE))
|
||||
&& (filter.iqU_2_long<=(edrk.zadanie.iq_ZadanieU_Charge+IQ_MINIMAL_DELTA_RUN_CHARGE))
|
||||
&& edrk.to_ing.bits.ZARYAD_ON==0
|
||||
&& edrk.from_ing1.bits.ZARYAD_ON==0
|
||||
&& edrk.errors.e5.bits.ERROR_PRE_CHARGE_ON==0
|
||||
@ -259,7 +251,7 @@ void set_status_pump_fan(void)
|
||||
///////////////////////////////////////////////
|
||||
int detect_zaryad_ump(void)
|
||||
{
|
||||
if (edrk.from_shema_filter.bits.UMP_ON_OFF==1)
|
||||
if (edrk.from_shema.bits.UMP_ON_OFF==1)
|
||||
{
|
||||
if ( (filter.iqUin_m1>=edrk.iqMIN_U_IN)
|
||||
&& (filter.iqUin_m2>=edrk.iqMIN_U_IN)
|
||||
@ -284,7 +276,7 @@ int detect_zaryad_ump(void)
|
||||
///////////////////////////////////////////////
|
||||
///////////////////////////////////////////////
|
||||
|
||||
#define TIME_WAIT_SBOR 8500
|
||||
#define TIME_WAIT_SBOR 2500
|
||||
#define TIME_WAIT_ANSWER_NASOS 500
|
||||
#define TIME_WAIT_OK_NASOS 50
|
||||
|
||||
@ -300,10 +292,6 @@ void sbor_shema_pusk_nasos(unsigned int t_start, unsigned int t_finish)
|
||||
// ïóñê íàñîñà
|
||||
if (edrk.Sbor_Mode == t_start)
|
||||
{
|
||||
edrk.enter_to_pump_stage = 1;
|
||||
// ñáðîñèëè ïðåäóïðåæäåíèÿ ïî íàñîñàì, âîçìîæíî è íå ïðàâèëüíî ýòî!
|
||||
edrk.warnings.e5.bits.PUMP_1 = edrk.warnings.e5.bits.PUMP_2 = 0;
|
||||
|
||||
if (control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_PUMP]==0)
|
||||
edrk.AutoStartPump = 1;
|
||||
|
||||
@ -317,7 +305,7 @@ void sbor_shema_pusk_nasos(unsigned int t_start, unsigned int t_finish)
|
||||
// æäåì ïóñêà íàñîñà
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish)
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_PUMP;
|
||||
edrk.Stage_Sbor = 1;
|
||||
|
||||
status_pump = get_status_p_water_min(edrk.StatusPumpFanAll);
|
||||
|
||||
@ -350,7 +338,7 @@ void sbor_shema_pusk_nasos(unsigned int t_start, unsigned int t_finish)
|
||||
}
|
||||
|
||||
// íàñîñ íå ïóñòèëñÿ, ïðîáóåì âòîðîé
|
||||
if (edrk.Sbor_Mode==(t_start + ((t_finish-t_start)>>1) ))
|
||||
if (edrk.Sbor_Mode==(t_start + (t_finish-t_start)>>1))
|
||||
{
|
||||
|
||||
|
||||
@ -427,7 +415,7 @@ void sbor_shema_pusk_zaryad(unsigned int t_start, unsigned int t_finish)
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish && (edrk.Status_Charge || (control_station.active_array_cmd[CONTROL_STATION_CMD_ENABLE_ON_CHARGE]==0))
|
||||
&& edrk.from_ing1.bits.ZARYAD_ON==0 && edrk.StatusPumpFanAll)
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_ZARYAD;
|
||||
edrk.Stage_Sbor = 2;
|
||||
if ((edrk.Status_Charge || (control_station.active_array_cmd[CONTROL_STATION_CMD_ENABLE_ON_CHARGE]==0))
|
||||
&& edrk.from_ing1.bits.ZARYAD_ON==0 && edrk.StatusPumpFanAll)
|
||||
{
|
||||
@ -461,29 +449,16 @@ void sbor_shema_pusk_zaryad(unsigned int t_start, unsigned int t_finish)
|
||||
}
|
||||
void sbor_shema_pusk_ump(unsigned int t_start, unsigned int t_finish)
|
||||
{
|
||||
static int enable_run_ump=0;
|
||||
// âêëþ÷àåì UMP
|
||||
if (edrk.Sbor_Mode==t_start && edrk.Zaryad_OK == 1)
|
||||
{
|
||||
// edrk.Run_UMP = 1;
|
||||
enable_run_ump = 0;
|
||||
edrk.Run_UMP = 1;
|
||||
}
|
||||
|
||||
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish)
|
||||
{
|
||||
|
||||
if (enable_run_ump==0)
|
||||
{
|
||||
if (edrk.from_shema_filter.bits.READY_UMP==1
|
||||
|| control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_UMP]==1)
|
||||
{
|
||||
edrk.Run_UMP = 1;
|
||||
enable_run_ump = 1;
|
||||
}
|
||||
}
|
||||
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_UMP_ON;
|
||||
edrk.Stage_Sbor = 3;
|
||||
if (edrk.Zaryad_OK == 1 && edrk.Status_UMP_Ok==1 && edrk.Zaryad_UMP_Ok==1)
|
||||
edrk.Sbor_Mode = t_finish;
|
||||
|
||||
@ -523,7 +498,7 @@ void sbor_shema_pusk_qtv(unsigned int t_start, unsigned int t_finish)
|
||||
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish )
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_QTV;
|
||||
edrk.Stage_Sbor = 4;
|
||||
if ((edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 && edrk.Status_UMP_Ok))
|
||||
edrk.Sbor_Mode = t_finish;
|
||||
|
||||
@ -564,7 +539,7 @@ void sbor_shema_stop_ump(unsigned int t_start, unsigned int t_finish)
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish)
|
||||
{
|
||||
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_UMP_OFF;
|
||||
edrk.Stage_Sbor = 5;
|
||||
if (edrk.Status_UMP_Ok==0)
|
||||
edrk.Sbor_Mode = t_finish;
|
||||
|
||||
@ -603,7 +578,7 @@ void sbor_shema_rascepitel_level_1(unsigned int t_start, unsigned int t_finish)
|
||||
#if(RASCEPITEL_MANUAL_ALWAYS_ON==1)
|
||||
if (edrk.Sbor_Mode==t_start && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 ))
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_RASCEPITEL_1;
|
||||
edrk.Stage_Sbor = 6;
|
||||
// åñëè äðóãîé ÁÑ íå ñîáðàí, çàìûêàåì ðàñöåïèòåëü
|
||||
if (optical_read_data.data.cmd.bit.ready_cmd != CODE_READY_CMD_READY2 )
|
||||
{
|
||||
@ -617,7 +592,7 @@ void sbor_shema_rascepitel_level_1(unsigned int t_start, unsigned int t_finish)
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 )
|
||||
&& edrk.RunZahvatRascepitel && edrk.Run_Rascepitel==0)
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_RASCEPITEL_1;
|
||||
edrk.Stage_Sbor = 6;
|
||||
// åñëè äðóãîé ÁÑ íå ñîáðàí, çàìûêàåì ðàñöåïèòåëü
|
||||
// äðóãîé ÁÑ ñáðîñèë îáîðîòû åñëè îíè áûëè è ñíÿë ØÈÌ åñëè áûë
|
||||
if (optical_read_data.data.cmd.bit.rascepitel_cmd == CODE_RASCEPITEL_CMD_ENABLE_ON_AND_THIS_ON ) // 01 - ìîæíî âêëþ÷àòü ðàñöåïèòåëü, ñâîé âêëþ÷åí
|
||||
@ -632,7 +607,7 @@ void sbor_shema_rascepitel_level_1(unsigned int t_start, unsigned int t_finish)
|
||||
|
||||
if (edrk.Sbor_Mode==t_start && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 ) && edrk.Status_Rascepitel_Ok==0)
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_RASCEPITEL_1;
|
||||
edrk.Stage_Sbor = 6;
|
||||
// åñëè äðóãîé ÁÑ íå ñîáðàí, çàìûêàåì ðàñöåïèòåëü
|
||||
if (optical_read_data.data.cmd.bit.ready_cmd != CODE_READY_CMD_READY2 )
|
||||
{
|
||||
@ -646,7 +621,7 @@ void sbor_shema_rascepitel_level_1(unsigned int t_start, unsigned int t_finish)
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 )
|
||||
&& edrk.RunZahvatRascepitel && edrk.Status_Rascepitel_Ok==0 && edrk.Run_Rascepitel==0)
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_RASCEPITEL_1;
|
||||
edrk.Stage_Sbor = 6;
|
||||
// åñëè äðóãîé ÁÑ íå ñîáðàí, çàìûêàåì ðàñöåïèòåëü
|
||||
// äðóãîé ÁÑ ñáðîñèë îáîðîòû åñëè îíè áûëè è ñíÿë ØÈÌ åñëè áûë
|
||||
if (optical_read_data.data.cmd.bit.rascepitel_cmd == CODE_RASCEPITEL_CMD_ENABLE_ON_AND_THIS_ON ) // 01 - ìîæíî âêëþ÷àòü ðàñöåïèòåëü, ñâîé âêëþ÷åí
|
||||
@ -684,7 +659,7 @@ void sbor_shema_rascepitel_level_2(unsigned int t_start, unsigned int t_finish)
|
||||
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish)
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_RASCEPITEL_2;
|
||||
edrk.Stage_Sbor = 7;
|
||||
#if(RASCEPITEL_MANUAL_ALWAYS_ON==1)
|
||||
edrk.Sbor_Mode = t_finish; // ïåðåïðûãíóëè äàëüøå
|
||||
#else
|
||||
@ -763,7 +738,7 @@ void sbor_shema_rascepitel_level_3(unsigned int t_start, unsigned int t_finish)
|
||||
// òóò æäåì âêëþ÷åíèÿ ðàñöåïèòåëÿ
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish)
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_RASCEPITEL_3;
|
||||
edrk.Stage_Sbor = 8;
|
||||
if (edrk.Status_Rascepitel_Ok==1)
|
||||
{
|
||||
// Ðàñöåïèòåëü âêëþ÷èëñÿ!
|
||||
@ -790,7 +765,7 @@ void sbor_shema_rascepitel_level_4(unsigned int t_start, unsigned int t_finish)
|
||||
{
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 && edrk.Status_Rascepitel_Ok))
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_RASCEPITEL_4;
|
||||
edrk.Stage_Sbor = 9;
|
||||
if (optical_read_data.data.cmd.bit.ready_cmd==CODE_READY_CMD_READY1TO2) // òîò ÁÑ ñîáèðàåòñÿ åùå
|
||||
{
|
||||
// îæèäàåì äîñáîðà âòîðîãî ÁÑ
|
||||
@ -826,7 +801,7 @@ void sbor_shema_wait_ready_another(unsigned int t_start, unsigned int t_finish)
|
||||
|
||||
if (edrk.Sbor_Mode>t_start && edrk.Sbor_Mode<t_finish && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 && edrk.Status_Rascepitel_Ok))
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_WAIT_READY_ANOTHER;
|
||||
edrk.Stage_Sbor = 10;
|
||||
if (optical_read_data.data.cmd.bit.ready_cmd!=CODE_READY_CMD_READY1TO2)
|
||||
{
|
||||
edrk.Sbor_Mode = t_finish; // ïåðåïðûãíóëè äàëüøå
|
||||
@ -851,8 +826,8 @@ void sbor_shema_wait_finish(unsigned int t_start, unsigned int t_finish)
|
||||
{
|
||||
if (edrk.Sbor_Mode>t_start && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 && edrk.Status_Rascepitel_Ok))
|
||||
{
|
||||
edrk.Stage_Sbor = STAGE_SBOR_STATUS_FINISH;
|
||||
edrk.SborFinishOk = 1;
|
||||
edrk.Stage_Sbor = 11;
|
||||
edrk.SborFinishOk = 1;
|
||||
// allow_discharge = 1;
|
||||
}
|
||||
|
||||
@ -876,8 +851,6 @@ void sbor_shema_wait_finish(unsigned int t_start, unsigned int t_finish)
|
||||
#define TIME_WAIT_ANSWER_UMP_ON 150 //15 sec
|
||||
#define TIME_WAIT_ANSWER_UMP_OFF 40 //4 sec
|
||||
|
||||
#define TIME_PAUSE_AFTER_GET_READY_UMP 50 // 5 sec
|
||||
|
||||
///////////////////////////////////////////////
|
||||
int ump_on_off(unsigned int flag)
|
||||
{
|
||||
@ -889,7 +862,7 @@ static unsigned int time_wait_answer_off_ump=0;
|
||||
|
||||
int cmd_ump=0;//,cmd_p2=0;
|
||||
static int UMP_Ok = 0;
|
||||
static int prev_error = 0, count_ready_upm = 0; //, flag_enable_on_ump = 0;
|
||||
static int prev_error = 0;
|
||||
|
||||
|
||||
cmd_ump = 0;
|
||||
@ -908,7 +881,6 @@ static int prev_error = 0, count_ready_upm = 0; //, flag_enable_on_ump = 0;
|
||||
|
||||
edrk.cmd_to_ump = cmd_ump;
|
||||
|
||||
|
||||
if (cmd_ump)
|
||||
{
|
||||
|
||||
@ -918,72 +890,44 @@ static int prev_error = 0, count_ready_upm = 0; //, flag_enable_on_ump = 0;
|
||||
// }
|
||||
// else
|
||||
|
||||
// æäåì ãîòîâíîñòü!
|
||||
if (edrk.from_shema_filter.bits.READY_UMP == 1)
|
||||
{
|
||||
// äàåì çàäåðæêó TIME_PAUSE_AFTER_GET_READY_UMP
|
||||
if (count_ready_upm<TIME_PAUSE_AFTER_GET_READY_UMP)
|
||||
count_ready_upm++;
|
||||
else
|
||||
edrk.flag_enable_on_ump = 1;
|
||||
}
|
||||
else
|
||||
count_ready_upm = 0;
|
||||
|
||||
|
||||
if (edrk.flag_enable_on_ump)
|
||||
{
|
||||
edrk.sbor_wait_ump2 = 1;
|
||||
edrk.to_shema.bits.UMP_ON_OFF = 1;
|
||||
|
||||
if (pause_detect_error(&time_wait_answer_on_ump, TIME_WAIT_ANSWER_UMP_ON, 1)==0)
|
||||
if (pause_detect_error(&time_wait_answer_on_ump,TIME_WAIT_ANSWER_UMP_ON,1)==0)
|
||||
{
|
||||
edrk.sbor_wait_ump1 = 1;
|
||||
if (edrk.from_shema_filter.bits.UMP_ON_OFF==1)
|
||||
|
||||
if (edrk.from_shema.bits.UMP_ON_OFF==1)
|
||||
UMP_Ok = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
edrk.sbor_wait_ump1 = 0;
|
||||
if (edrk.from_shema_filter.bits.UMP_ON_OFF==0)
|
||||
|
||||
if (edrk.from_shema.bits.UMP_ON_OFF==0)
|
||||
{
|
||||
edrk.errors.e7.bits.UMP_NOT_ANSWER |= 1;
|
||||
UMP_Ok = 0;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
edrk.sbor_wait_ump2 = 0;
|
||||
}
|
||||
|
||||
|
||||
time_wait_rele_off_ump = 0;
|
||||
time_wait_answer_off_ump = 0;
|
||||
time_wait_rele_off_ump = 0;
|
||||
time_wait_answer_off_ump = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
count_ready_upm = 0;
|
||||
UMP_Ok = 0;
|
||||
time_wait_rele_on_ump = 0;
|
||||
time_wait_answer_on_ump = 0;
|
||||
|
||||
edrk.to_shema.bits.UMP_ON_OFF = 0;
|
||||
|
||||
edrk.flag_enable_on_ump = 0;
|
||||
|
||||
edrk.sbor_wait_ump2 = 0;
|
||||
|
||||
if (pause_detect_error(&time_wait_answer_off_ump, TIME_WAIT_ANSWER_UMP_OFF, 1)==0)
|
||||
if (pause_detect_error(&time_wait_answer_off_ump,TIME_WAIT_ANSWER_UMP_OFF,1)==0)
|
||||
{
|
||||
edrk.sbor_wait_ump1 = 1;
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
edrk.sbor_wait_ump1 = 0;
|
||||
// îòêëþ÷èëè äåòåêò ÷òî UMP âäðóã âêëþ÷èëñÿ!!!
|
||||
if (edrk.from_shema_filter.bits.UMP_ON_OFF==1)
|
||||
if (edrk.from_shema.bits.UMP_ON_OFF==1)
|
||||
edrk.errors.e7.bits.UMP_NOT_ANSWER |= 1;
|
||||
}
|
||||
|
||||
@ -994,6 +938,7 @@ static int prev_error = 0, count_ready_upm = 0; //, flag_enable_on_ump = 0;
|
||||
time_wait_rele_off_ump = 0;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
prev_error = edrk.summ_errors;
|
||||
@ -1230,12 +1175,14 @@ static int prev_error = 0, perehod_sost = 0, flag_wait_break_perehod_sost = 0, p
|
||||
unsigned int sbor_shema(int mode)
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
// static unsigned int time_wait_sbor = 0;
|
||||
static int prev_ready_final = 0;
|
||||
static unsigned int time_wait_razbor = 0;
|
||||
static unsigned int allow_discharge = 0, may_be_discharge=0;
|
||||
int enable_sbor;
|
||||
static unsigned int t1,t2, delta_t, first_run = 1, add_t1 = 0;
|
||||
static unsigned int t1,t2, delta_t;
|
||||
// static int Run_Pred_Zaryad;
|
||||
|
||||
|
||||
@ -1262,8 +1209,6 @@ unsigned int sbor_shema(int mode)
|
||||
// edrk.Run_Rascepitel = 0;
|
||||
|
||||
edrk.Status_Sbor = 1;
|
||||
first_run = 1;
|
||||
edrk.enter_to_pump_stage = 0;
|
||||
return (edrk.Sbor_Mode);
|
||||
}
|
||||
|
||||
@ -1278,73 +1223,31 @@ unsigned int sbor_shema(int mode)
|
||||
edrk.errors.e11.bits.ERROR_VERY_LONG_SBOR |= 1;
|
||||
}
|
||||
|
||||
if (first_run)
|
||||
{
|
||||
if (edrk.flag_another_bs_first_ready12==1 && edrk.flag_this_bs_first_ready12==0)
|
||||
{
|
||||
// äðóãîé ÁÑ óæå ñîáèðàåòñÿ?
|
||||
add_t1 = 80; // ðàçáåæêà 12 ñåê
|
||||
}
|
||||
else
|
||||
if (edrk.flag_another_bs_first_ready12==0 && edrk.flag_this_bs_first_ready12==1)
|
||||
{
|
||||
// äðóãîé ÁÑ íå ñîáèðàåòñÿ?
|
||||
add_t1 = 5; // ðàçáåæêà 1 ñåê
|
||||
}
|
||||
else
|
||||
if (edrk.flag_this_bs_first_ready12==0 && edrk.flag_another_bs_first_ready12==0)
|
||||
{
|
||||
// òóò íåïîíÿòíî êàê îêàçàëèñü
|
||||
if (edrk.flag_second_PCH == 1)
|
||||
add_t1 = 120; // ðàçáåæêà 18 ñåê
|
||||
else
|
||||
add_t1 = 80; // ðàçáåæêà 7 ñåê
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// if (optical_read_data.data.cmd.bit.ready_cmd==CODE_READY_CMD_READY1TO2 && edrk.flag_second_PCH == 1)
|
||||
// {
|
||||
// // äðóãîé ÁÑ óæå ñîáèðàåòñÿ?
|
||||
// add_t1 = 150; // ðàçáåæêà 15 ñåê
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
// if (edrk.flag_second_PCH == 0)
|
||||
// add_t1 = 0;
|
||||
// else
|
||||
// add_t1 = 70; // ðàçáåæêà 7 ñåê
|
||||
// }
|
||||
|
||||
first_run = 0;
|
||||
}
|
||||
|
||||
// ïóñê íàñîñà
|
||||
t1 = 10 + add_t1;
|
||||
t1 = 50;
|
||||
delta_t = 300;//200;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_pusk_nasos(t1,t2);//350
|
||||
sbor_shema_pusk_nasos(t1,t2);//250
|
||||
|
||||
t1 = t2+30;//380
|
||||
t1 = t2;
|
||||
delta_t = 700;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_pusk_zaryad(t1,t2);//1080
|
||||
sbor_shema_pusk_zaryad(t1,t2);//950
|
||||
|
||||
t1 = t2+10;//1090
|
||||
delta_t = 750+750+300+600;//2400 äîëãî æäåì âäðóã óìï çàíÿò íà âòîðîé áñ
|
||||
t1 = t2;
|
||||
delta_t = 350;//200
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_pusk_ump(t1,t2);//3490
|
||||
sbor_shema_pusk_ump(t1,t2);//1150
|
||||
|
||||
t1 = t2+30; //3520 æäåì 3 ñåê åùå
|
||||
t1 = t2+30; // æäåì 3 ñåê åùå
|
||||
delta_t = 200;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_pusk_qtv(t1,t2);//3720
|
||||
sbor_shema_pusk_qtv(t1,t2);//1350
|
||||
|
||||
t1 = t2;
|
||||
delta_t = 150;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_stop_ump(t1,t2);//3870
|
||||
sbor_shema_stop_ump(t1,t2);//1500
|
||||
|
||||
// åñëè äðóã ÁÑ íå ñîáðàí, òî ðàçðåøàåì ñâîå ïîäêëþ÷åíèå ðàñöåïèòåëÿ è ïåðåõîä íà tfinish
|
||||
// èíà÷å äàåì çàïðîñ è æäåì îò tstart äî tfinish ðàçðåøåíèå íà ïîäêëþ÷åíèå ðàñöåïèòåëÿ è ñðàçó ðàçðåøàåì åãî ïîäêëþ÷åíèå
|
||||
@ -1352,38 +1255,283 @@ unsigned int sbor_shema(int mode)
|
||||
t1 = t2;
|
||||
delta_t = 250;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_rascepitel_level_1(t1,t2);//4120
|
||||
sbor_shema_rascepitel_level_1(t1,t2);//1750
|
||||
|
||||
// æäåì âêëþ÷åíèÿ ðàñöåïèòåëÿ äî tfinish
|
||||
// èëè äî tfinish æäåì ïîäòâåðæäåíèÿ çàõâàòà
|
||||
t1 = t2;
|
||||
delta_t = 300;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_rascepitel_level_2(t1,t2);//4420
|
||||
sbor_shema_rascepitel_level_2(t1,t2);//2050
|
||||
|
||||
t1 = t2;
|
||||
delta_t = 200;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_rascepitel_level_3(t1,t2);//4620
|
||||
sbor_shema_rascepitel_level_3(t1,t2);//2250
|
||||
|
||||
// íàø ðàñöåïèòåëü âêëþ÷èëñÿ, íî âòîðîé ÁÑ òîæå ñîáèðàåòñÿ, ïîýòîìó òóò æäåì ïîêà îí âêëþ÷èò ñâîé ðàñöåïèòåëü
|
||||
// èíà÷å ñðàçó tfinish
|
||||
t1 = t2;
|
||||
delta_t = 300;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_rascepitel_level_4(t1,t2);//4920
|
||||
sbor_shema_rascepitel_level_4(t1,t2);//2550
|
||||
|
||||
// æäåì äî tfinish ïîäòâåðæäåíèÿ îêîí÷àíèÿ ñáîðà îò äðóãîãî ÁÑ
|
||||
// åñëè íå äîæäàëèñü, òî îøèáêà
|
||||
t1 = t2;
|
||||
delta_t = 1800;
|
||||
delta_t = 300;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_wait_ready_another(t1,t2);//6720
|
||||
sbor_shema_wait_ready_another(t1,t2);//2850
|
||||
|
||||
t1 = t2;
|
||||
delta_t = 50;
|
||||
t2 = t1 + delta_t;
|
||||
sbor_shema_wait_finish(t1,t2);//6770
|
||||
sbor_shema_wait_finish(t1,t2);//2950
|
||||
|
||||
|
||||
// if (edrk.Sbor_Mode == 0)
|
||||
// {
|
||||
// if (control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_PUMP]==0)
|
||||
// edrk.AutoStartPump = 1;
|
||||
// }
|
||||
//
|
||||
// // æäåì ïóñêà íàñîñà
|
||||
// if (edrk.Sbor_Mode>50 && edrk.Sbor_Mode<250)
|
||||
// {
|
||||
// if (edrk.StatusPumpFanAll )
|
||||
// {
|
||||
// edrk.Sbor_Mode = 250;
|
||||
// }
|
||||
//
|
||||
// // íàñîñ íå ïóñòèëñÿ
|
||||
// if (edrk.Sbor_Mode>200 && edrk.StatusPumpFanAll==0)
|
||||
// {
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.Status_Sbor = 2;
|
||||
// edrk.AutoStartPump = 0;
|
||||
// }
|
||||
//
|
||||
//
|
||||
// }
|
||||
//
|
||||
|
||||
// /////////////////////////////////////
|
||||
// // çàïóñê çàðÿäà âíóòðåííåãî
|
||||
// if (edrk.Sbor_Mode == 250)
|
||||
// {
|
||||
// if (control_station.active_array_cmd[CONTROL_STATION_CMD_ENABLE_ON_CHARGE]==1)
|
||||
// edrk.Run_Pred_Zaryad = 1; // çàïóñê ïðåäçàðßäà!
|
||||
// }
|
||||
|
||||
////
|
||||
// if (edrk.Sbor_Mode>=250 && edrk.StatusPumpFanAll==0 && edrk.SumStartPump)
|
||||
// {
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.Status_Sbor = 3;
|
||||
//
|
||||
// }
|
||||
|
||||
// // æäåì çàâåðøåíèÿ ðàáîòû ïðåäçàðÿäà
|
||||
// // òóò ïðåäçàðßä äîëæåí óæå çàêîí÷èòü ðàáîòó
|
||||
//
|
||||
// if (edrk.Sbor_Mode>250 && edrk.Sbor_Mode<900 && (edrk.Status_Charge || (control_station.active_array_cmd[CONTROL_STATION_CMD_ENABLE_ON_CHARGE]==0))
|
||||
// && edrk.from_ing1.bits.ZARYAD_ON==0 && edrk.StatusPumpFanAll)
|
||||
// {
|
||||
// edrk.Zaryad_OK = 1;
|
||||
// edrk.Run_Pred_Zaryad = 0;
|
||||
//
|
||||
// edrk.Sbor_Mode = 900;
|
||||
// }
|
||||
//
|
||||
//
|
||||
// if (edrk.Sbor_Mode>850 && edrk.Zaryad_OK == 0)
|
||||
// {
|
||||
// edrk.Run_Pred_Zaryad = 0;
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.Status_Sbor = 4;
|
||||
// }
|
||||
//
|
||||
|
||||
//// âêëþ÷àåì UMP
|
||||
// if (edrk.Sbor_Mode==950 && edrk.Zaryad_OK == 1)
|
||||
// {
|
||||
// edrk.Run_UMP = 1;
|
||||
// }
|
||||
//
|
||||
// if (edrk.Sbor_Mode>950 && edrk.Sbor_Mode>1250 && (edrk.Zaryad_OK == 1 && edrk.Status_UMP_Ok==1))
|
||||
// {
|
||||
// edrk.Sbor_Mode=1250;
|
||||
// }
|
||||
//
|
||||
//
|
||||
// if (edrk.Sbor_Mode>1300 && (edrk.Zaryad_OK == 0 || edrk.Status_UMP_Ok==0))
|
||||
// {
|
||||
// edrk.Run_UMP = 0;
|
||||
// edrk.Run_Pred_Zaryad = 0;
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.errors.e7.bits.UMP_NOT_ANSWER |= 1;
|
||||
// edrk.Run_QTV = 0;
|
||||
// edrk.Status_Sbor = 9;
|
||||
// }
|
||||
|
||||
|
||||
|
||||
////////////////
|
||||
|
||||
|
||||
//
|
||||
//
|
||||
// if (edrk.Sbor_Mode==950 && edrk.Zaryad_OK == 1)
|
||||
// {
|
||||
//// if ()
|
||||
// edrk.Run_QTV = 1;
|
||||
// }
|
||||
//
|
||||
//
|
||||
// if (edrk.Sbor_Mode>960 && edrk.Sbor_Mode<1110 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 ) )
|
||||
// {
|
||||
// edrk.Sbor_Mode = 1110;
|
||||
// }
|
||||
//
|
||||
// if (edrk.Sbor_Mode>1100 && (edrk.Zaryad_OK == 0 || edrk.Status_QTV_Ok==0 ))
|
||||
// {
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.Run_QTV = 0;
|
||||
// edrk.Status_Sbor = 5;
|
||||
// }
|
||||
|
||||
|
||||
// if (edrk.Sbor_Mode==1110 && edrk.Sbor_Mode<1250 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 ) && edrk.Status_Rascepitel_Ok==0)
|
||||
// {
|
||||
// // åñëè äðóãîé ÁÑ íå ñîáðàí, çàìûêàåì ðàñöåïèòåëü
|
||||
// if (optical_read_data.data.cmd.bit.ready_cmd != CODE_READY_CMD_READY2 )
|
||||
// {
|
||||
// edrk.Run_Rascepitel = 1;
|
||||
// edrk.Sbor_Mode = 1250; // ïåðåïðûãíóëè äàëüøå
|
||||
// }
|
||||
// else
|
||||
// edrk.RunZahvatRascepitel = 1; // ïðîñèì äðóãîé ÁÑ ñáðîñèòü îáîðîòû è ðàçðåøèòü ïîäêëþ÷åíèå ðàñöåïèòåëÿ
|
||||
// }
|
||||
////
|
||||
// if (edrk.Sbor_Mode>1120 && edrk.Sbor_Mode<1250 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 )
|
||||
// && edrk.RunZahvatRascepitel && edrk.Status_Rascepitel_Ok==0 && edrk.Run_Rascepitel==0)
|
||||
// {
|
||||
// // åñëè äðóãîé ÁÑ íå ñîáðàí, çàìûêàåì ðàñöåïèòåëü
|
||||
// // äðóãîé ÁÑ ñáðîñèë îáîðîòû åñëè îíè áûëè è ñíÿë ØÈÌ åñëè áûë
|
||||
// if (optical_read_data.data.cmd.bit.rascepitel_cmd == CODE_RASCEPITEL_CMD_ENABLE_ON_AND_THIS_ON ) // 01 - ìîæíî âêëþ÷àòü ðàñöåïèòåëü, ñâîé âêëþ÷åí
|
||||
// {
|
||||
// edrk.Run_Rascepitel = 1;
|
||||
// edrk.Sbor_Mode = 1250; // ïåðåïðûãíóëè äàëüøå
|
||||
//
|
||||
// }
|
||||
// }
|
||||
|
||||
// if (edrk.Sbor_Mode>1250 && edrk.Sbor_Mode<1350 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 )
|
||||
// && edrk.Status_Rascepitel_Ok==1 && edrk.Run_Rascepitel==1)
|
||||
// {
|
||||
// // äîæäàëèñü âêëþ÷åíèÿ ðàñöåïèòåëÿ è ïðûãíóëè äàëüøå
|
||||
// edrk.Sbor_Mode = 1350; // ïåðåïðûãíóëè äàëüøå
|
||||
// }
|
||||
//
|
||||
////
|
||||
// // ïî ñèãíàëó edrk.RunZahvatRascepitel äîëæåí òîò ÁÑ ñáðîñèòü îáîðîòû è ïîäòâåðäèòü âîçìîæíîñòü âêëþ÷åíèå ðàñöåïèòåëÿ
|
||||
// if (edrk.Sbor_Mode>1320 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 )
|
||||
// && edrk.RunZahvatRascepitel && edrk.Status_Rascepitel_Ok==0 && edrk.Run_Rascepitel==0)
|
||||
// {
|
||||
// //
|
||||
//// if (optical_read_data.data.cmd.bit.rascepitel_cmd != CODE_RASCEPITEL_CMD_ENABLE_ON_AND_THIS_ON ) // 01 - ìîæíî âêëþ÷àòü ðàñöåïèòåëü, ñâîé âêëþ÷åí
|
||||
// {
|
||||
// // íå äîæäàëèñü ïîäòâåðæäåíèÿ íà âêëþ÷åíèå ñâîåãî ðàñöåïèòåëÿ
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.Run_QTV = 0;
|
||||
// edrk.Status_Sbor = 7;
|
||||
// edrk.errors.e1.bits.NO_CONFIRM_ON_RASCEPITEL |= 1;
|
||||
// edrk.RunZahvatRascepitel = 0;
|
||||
//// edrk.Run_Rascepitel = 0;
|
||||
// }
|
||||
// }
|
||||
|
||||
// // òóò æäåì âêëþ÷åíèÿ ðàñöåïèòåëÿ
|
||||
// if (edrk.Sbor_Mode>1350 && edrk.Sbor_Mode<1490 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 ) && edrk.Status_Rascepitel_Ok==1)
|
||||
// {
|
||||
// // Ðàñöåïèòåëü âêëþ÷èëñÿ!
|
||||
// // ìîæíî ïåðåïðûãèâàòü â êîíåö
|
||||
// edrk.Sbor_Mode = 1490; // ïåðåïðûãíóëè äàëüøå
|
||||
// edrk.RunZahvatRascepitel = 0;
|
||||
//
|
||||
//// edrk.Run_Rascepitel = 1;
|
||||
// }
|
||||
//
|
||||
//
|
||||
//
|
||||
//
|
||||
//
|
||||
// if (edrk.Sbor_Mode>=1490 && (edrk.Zaryad_OK == 0 || edrk.Status_QTV_Ok==0 || edrk.Status_Rascepitel_Ok==0))
|
||||
// {
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.Run_QTV = 0;
|
||||
//// edrk.Run_Rascepitel = 0;
|
||||
// edrk.RunZahvatRascepitel = 0;
|
||||
// edrk.Status_Sbor = 6;
|
||||
// }
|
||||
//
|
||||
|
||||
// if (edrk.Sbor_Mode>1550 && edrk.Sbor_Mode<2000 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 && edrk.Status_Rascepitel_Ok))
|
||||
// {
|
||||
// if (optical_read_data.data.cmd.bit.ready_cmd==CODE_READY_CMD_READY1TO2) // òîò ÁÑ ñîáèðàåòñÿ åùå
|
||||
// {
|
||||
// // îæèäàåì äîñáîðà âòîðîãî ÁÑ
|
||||
// // íî ðàñöåïèòåëü óæå âêëþ÷èëñÿ.
|
||||
// if (optical_read_data.data.cmd.bit.rascepitel_cmd == CODE_RASCEPITEL_CMD_ENABLE_ON_AND_THIS_ON)
|
||||
// edrk.Sbor_Mode = 2150; // ïåðåïðûãíóëè äàëüøå
|
||||
//
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
// edrk.Sbor_Mode = 2150; // ïåðåïðûãíóëè äàëüøå
|
||||
//
|
||||
// }
|
||||
//
|
||||
// }
|
||||
|
||||
//
|
||||
// if (edrk.Sbor_Mode>2100 && edrk.Sbor_Mode<2150 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 && edrk.Status_Rascepitel_Ok))
|
||||
// {
|
||||
// if (optical_read_data.data.cmd.bit.ready_cmd==CODE_READY_CMD_READY1TO2) // òîò ÁÑ ñîáèðàåòñÿ åùå, íî ÷òî-òî äîëãî îí!
|
||||
// {
|
||||
// edrk.errors.e7.bits.ERROR_SBOR_SHEMA |= 1;
|
||||
// edrk.errors.e1.bits.ANOTHER_BS_VERY_LONG_WAIT |= 1;
|
||||
// edrk.Run_QTV = 0;
|
||||
// // edrk.Run_Rascepitel = 0;
|
||||
// edrk.RunZahvatRascepitel = 0;
|
||||
// edrk.Status_Sbor = 8;
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
// edrk.Sbor_Mode = 2150; // ïåðåïðûãíóëè äàëüøå
|
||||
//
|
||||
// }
|
||||
//
|
||||
//
|
||||
// }
|
||||
//
|
||||
|
||||
|
||||
|
||||
//
|
||||
// if (edrk.Sbor_Mode>2150 && (edrk.Zaryad_OK == 1 && edrk.Status_QTV_Ok==1 && edrk.Status_Rascepitel_Ok))
|
||||
// {
|
||||
// edrk.SborFinishOk = 1;
|
||||
// // allow_discharge = 1;
|
||||
// }
|
||||
//
|
||||
//
|
||||
// if (edrk.Sbor_Mode>2200 && (edrk.SborFinishOk) )
|
||||
// {
|
||||
// time_wait_sbor = 0;
|
||||
// }
|
||||
// else
|
||||
// edrk.Sbor_Mode++;
|
||||
|
||||
edrk.Razbor_Mode = 0;
|
||||
edrk.RazborNotFinish = 0;
|
||||
@ -1402,8 +1550,6 @@ unsigned int sbor_shema(int mode)
|
||||
/////////////////////////////////////////////////////////
|
||||
else
|
||||
{
|
||||
first_run = 1;
|
||||
edrk.enter_to_pump_stage = 0;
|
||||
// ðàçáîð ñõåìû
|
||||
if (edrk.Razbor_Mode==0)
|
||||
edrk.RazborNotFinish = 1;
|
||||
@ -1582,7 +1728,7 @@ unsigned int sbor_shema(int mode)
|
||||
|
||||
edrk.Status_Charge = zaryad_on_off(edrk.Run_Pred_Zaryad);
|
||||
|
||||
if (control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_UMP]==1 || edrk.Status_Ready.bits.ImitationReady2)
|
||||
if (control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_UMP]==1)
|
||||
{
|
||||
edrk.Status_UMP_Ok = edrk.Run_UMP;
|
||||
edrk.Zaryad_UMP_Ok = 1;
|
||||
@ -1594,7 +1740,7 @@ unsigned int sbor_shema(int mode)
|
||||
edrk.Zaryad_UMP_Ok = detect_zaryad_ump();
|
||||
}
|
||||
|
||||
if (control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_QTV]==1 || edrk.Status_Ready.bits.ImitationReady2)
|
||||
if (control_station.active_array_cmd[CONTROL_STATION_CMD_DISABLE_ON_QTV]==1)
|
||||
{
|
||||
edrk.Status_QTV_Ok = edrk.Run_QTV;
|
||||
edrk.to_shema.bits.QTV_ON_OFF = 0;
|
||||
@ -1671,94 +1817,12 @@ unsigned int sbor_shema(int mode)
|
||||
|
||||
|
||||
if (edrk.Status_Ready.bits.ready5==1 && edrk.Status_Ready.bits.ready6==1 && edrk.Status_Ready.bits.MasterSlaveActive)
|
||||
{
|
||||
if (edrk.Status_Ready.bits.ImitationReady2)
|
||||
edrk.Status_Ready.bits.preImitationReady2 = 1;
|
||||
edrk.Status_Ready.bits.ready_final = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
edrk.Status_Ready.bits.ready_final = 0;
|
||||
edrk.Status_Ready.bits.preImitationReady2 = 0;
|
||||
}
|
||||
|
||||
if (edrk.Status_Ready.bits.ready_final && prev_ready_final==0)
|
||||
edrk.count_sbor++;
|
||||
|
||||
prev_ready_final = edrk.Status_Ready.bits.ready_final;
|
||||
|
||||
return (edrk.Sbor_Mode);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
unsigned int imit_signals_rascepitel(unsigned int *counter, unsigned int max_pause, unsigned int s, unsigned int cmd_clear)
|
||||
{
|
||||
if (cmd_clear==1)
|
||||
{
|
||||
(*counter) = 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (s)
|
||||
{
|
||||
if ((*counter)>=max_pause)
|
||||
return 1;
|
||||
else
|
||||
(*counter)++;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (s==0)
|
||||
{
|
||||
if ((*counter)==0)
|
||||
return 0;
|
||||
else
|
||||
(*counter)--;
|
||||
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
#define TIME_WAIT_OFF_BLOCK_KEY 100
|
||||
void auto_block_key_on_off(void)
|
||||
{
|
||||
static unsigned int count_err = TIME_WAIT_OFF_BLOCK_KEY;
|
||||
|
||||
if (edrk.SumSbor && edrk.enter_to_pump_stage)
|
||||
{
|
||||
edrk.Status_Ready.bits.Batt = 1;
|
||||
edrk.to_ing.bits.BLOCK_KEY_OFF = 0;
|
||||
count_err = 0;
|
||||
}
|
||||
|
||||
if (filter.iqU_1_long >= U_LEVEL_ON_BLOCK_KEY || filter.iqU_2_long >= U_LEVEL_ON_BLOCK_KEY)
|
||||
{
|
||||
edrk.Status_Ready.bits.Batt = 1;
|
||||
edrk.to_ing.bits.BLOCK_KEY_OFF = 0;
|
||||
count_err = 0;
|
||||
}
|
||||
|
||||
if (filter.iqU_1_long <= U_LEVEL_OFF_BLOCK_KEY && filter.iqU_2_long <= U_LEVEL_OFF_BLOCK_KEY && edrk.SumSbor==0)
|
||||
{
|
||||
if (pause_detect_error(&count_err,TIME_WAIT_OFF_BLOCK_KEY,1))
|
||||
{
|
||||
edrk.to_ing.bits.BLOCK_KEY_OFF = 1;
|
||||
edrk.Status_Ready.bits.Batt = 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
count_err = 0;
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
///////////////////////////////////////////////
|
||||
|
||||
|
||||
|
@ -9,16 +9,7 @@
|
||||
#define SRC_MAIN_SBOR_SHEMA_H_
|
||||
|
||||
|
||||
#define U_LEVEL_ON_BLOCK_KEY 559240 // 100V
|
||||
#define U_LEVEL_OFF_BLOCK_KEY 279620 // 50V
|
||||
|
||||
unsigned int sbor_shema(int mode);
|
||||
void rascepitel_on_off(unsigned int flag, int *status_perehod, int *status_on_off, int *final_status_on_off);
|
||||
void auto_block_key_on_off(void);
|
||||
|
||||
unsigned int imit_signals_rascepitel(unsigned int *counter, unsigned int max_pause, unsigned int s, unsigned int cmd_clear);
|
||||
void set_status_pump_fan(void);
|
||||
|
||||
|
||||
|
||||
#endif /* SRC_MAIN_SBOR_SHEMA_H_ */
|
||||
|
@ -11,22 +11,17 @@
|
||||
#include "Spartan2E_Adr.h"
|
||||
#include "Spartan2E_Functions.h"
|
||||
#include "TuneUpPlane.h"
|
||||
#include "pwm_test_lines.h"
|
||||
#include "xp_write_xpwm_time.h"
|
||||
#include "profile_interrupt.h"
|
||||
|
||||
#include "edrk_main.h"
|
||||
#define SIZE_SYNC_BUF 20
|
||||
#define SIZE_SYNC_BUF 10
|
||||
|
||||
//#pragma DATA_SECTION(logbuf_sync1,".fa");
|
||||
unsigned int logbuf_sync1[SIZE_SYNC_BUF];
|
||||
unsigned int c_logbuf_sync1=0;
|
||||
|
||||
//unsigned int capnum0;
|
||||
//unsigned int capnum1;
|
||||
//unsigned int capnum2;
|
||||
//unsigned int capnum3;
|
||||
#pragma DATA_SECTION(logbuf_sync1,".logs");
|
||||
long logbuf_sync1[SIZE_SYNC_BUF];
|
||||
|
||||
unsigned int capnum0;
|
||||
unsigned int capnum1;
|
||||
unsigned int capnum2;
|
||||
unsigned int capnum3;
|
||||
int delta_capnum = 0;
|
||||
int delta_error = 0;
|
||||
//int level_find_sync_zero = LEVEL_FIND_SYNC_ZERO;
|
||||
@ -35,109 +30,16 @@ unsigned int temp;
|
||||
unsigned int count_error_sync = 0;
|
||||
|
||||
unsigned int count_timeout_sync = 0;
|
||||
//unsigned int enable_profile_led1_sync = 1;
|
||||
//unsigned int enable_profile_led2_sync = 0;
|
||||
unsigned int enable_profile_led1_sync = 1;
|
||||
unsigned int enable_profile_led2_sync = 0;
|
||||
|
||||
SYNC_TOOLS_DATA sync_data=SYNC_TOOLS_DATA_DEFAULT;
|
||||
|
||||
|
||||
#pragma CODE_SECTION(calculate_sync_detected,".fast_run2");
|
||||
void calculate_sync_detected(void)
|
||||
{
|
||||
|
||||
|
||||
|
||||
// if (capnum0 > 1000) {
|
||||
// return;
|
||||
// }
|
||||
// sync_data.level_find_sync_zero = LEVEL_FIND_SYNC_ZERO;
|
||||
|
||||
delta_capnum = sync_data.capnum0 - sync_data.capnum1;
|
||||
|
||||
if (delta_capnum > 0) //ïàäàåò
|
||||
{
|
||||
sync_data.pwm_freq_plus_minus_zero = -1;//1;
|
||||
|
||||
if (count_error_sync < MAX_COUNT_ERROR_SYNC) {
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
} else
|
||||
sync_data.local_flag_sync_1_2 = 0;
|
||||
}
|
||||
else
|
||||
if (delta_capnum < 0) //ðàñò¸ò
|
||||
{
|
||||
|
||||
if (sync_data.capnum0 > sync_data.level_find_sync_zero)
|
||||
{
|
||||
delta_error = sync_data.capnum0 - sync_data.level_find_sync_zero;
|
||||
|
||||
if (delta_error > 50) {
|
||||
if (count_error_sync < MAX_COUNT_ERROR_SYNC) {
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
} else
|
||||
sync_data.local_flag_sync_1_2 = 0;
|
||||
} else {
|
||||
if (count_error_sync > 0) {
|
||||
count_error_sync--;
|
||||
}
|
||||
if (count_error_sync == 0)
|
||||
sync_data.local_flag_sync_1_2 = 1;
|
||||
}
|
||||
sync_data.pwm_freq_plus_minus_zero = 1;
|
||||
}
|
||||
else
|
||||
if (sync_data.capnum0 < sync_data.level_find_sync_zero)
|
||||
{
|
||||
|
||||
delta_error = sync_data.level_find_sync_zero - sync_data.capnum0;
|
||||
|
||||
if (delta_error > 50) {
|
||||
if (count_error_sync < MAX_COUNT_ERROR_SYNC) {
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
} else
|
||||
sync_data.local_flag_sync_1_2 = 0;
|
||||
} else {
|
||||
if (count_error_sync > 0) {
|
||||
count_error_sync--;
|
||||
}
|
||||
if (count_error_sync == 0)
|
||||
sync_data.local_flag_sync_1_2 = 1;
|
||||
}
|
||||
|
||||
sync_data.pwm_freq_plus_minus_zero = -1;
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
sync_data.pwm_freq_plus_minus_zero = 0;
|
||||
sync_data.local_flag_sync_1_2 = 1;
|
||||
count_error_sync = 0;
|
||||
}
|
||||
} else
|
||||
sync_data.pwm_freq_plus_minus_zero = 0;
|
||||
|
||||
sync_data.delta_error_sync = delta_error;
|
||||
sync_data.delta_capnum = sync_data.capnum0 - sync_data.level_find_sync_zero; //delta_capnum;
|
||||
sync_data.count_error_sync = count_error_sync;
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
#pragma CODE_SECTION(sync_detected,".fast_run2");
|
||||
void sync_detected(void)
|
||||
{
|
||||
|
||||
#if(_ENABLE_PWM_LINES_FOR_TESTS_SYNC)
|
||||
PWM_LINES_TK_18_ON;
|
||||
#endif
|
||||
|
||||
sync_data.latch_interrupt = 1;
|
||||
// stop_sync_interrupt();
|
||||
|
||||
@ -148,31 +50,47 @@ void sync_detected(void)
|
||||
// EvbRegs.EVBIMRC.bit.CAP6INT = 0;
|
||||
|
||||
// if (edrk.disable_interrupt_sync==0)
|
||||
|
||||
|
||||
// WriteMemory(ADR_SAW_REQUEST, 0x8000);
|
||||
// sync_data.capnum0 = ReadMemory(ADR_SAW_VALUE);
|
||||
|
||||
// WriteMemory(ADR_SAW_REQUEST, 0x8000);
|
||||
// sync_data.capnum0 = ReadMemory(ADR_SAW_VALUE);
|
||||
|
||||
// pause_1000(1);
|
||||
{
|
||||
WriteMemory(ADR_SAW_REQUEST, 0x8000);
|
||||
capnum0 = ReadMemory(ADR_SAW_VALUE);
|
||||
|
||||
WriteMemory(ADR_SAW_REQUEST, 0x8000);
|
||||
sync_data.capnum1 = ReadMemory(ADR_SAW_VALUE);
|
||||
capnum0 = ReadMemory(ADR_SAW_VALUE);
|
||||
|
||||
pause_1000(1);
|
||||
|
||||
WriteMemory(ADR_SAW_REQUEST, 0x8000);
|
||||
sync_data.capnum1 = ReadMemory(ADR_SAW_VALUE);
|
||||
capnum1 = ReadMemory(ADR_SAW_VALUE);
|
||||
|
||||
WriteMemory(ADR_SAW_REQUEST, 0x8000);
|
||||
capnum1 = ReadMemory(ADR_SAW_VALUE);
|
||||
|
||||
sync_data.count_timeout_sync = 0;
|
||||
sync_data.timeout_sync_signal = 0;
|
||||
//i_led2_on_off(1);
|
||||
// EALLOW;
|
||||
//
|
||||
// //use mask to clear EVAIFRA register
|
||||
// EvbRegs.EVBIFRC.bit.CAP6INT = 1;
|
||||
|
||||
logbuf_sync1[c_logbuf_sync1++] = sync_data.capnum0;
|
||||
// logbuf_sync1[c_logbuf_sync1++] = sync_data.capnum1;
|
||||
// Acknowledge this interrupt to receive more interrupts from group 5
|
||||
// PieCtrlRegs.PIEACK.bit.ACK5 = 1; //???????CAP6
|
||||
|
||||
if (c_logbuf_sync1==SIZE_SYNC_BUF)
|
||||
c_logbuf_sync1=0;
|
||||
// capnum3 = EvbRegs.CAP6FIFO;
|
||||
asm(" NOP;");
|
||||
// asm(" NOP;");
|
||||
// asm(" NOP;");
|
||||
// asm(" NOP;");
|
||||
//
|
||||
// if (EvbRegs.CAPFIFOB.bit.CAP6FIFO == 3) {
|
||||
// capnum3 = EvbRegs.CAP6FIFO;
|
||||
// capnum3 = EvbRegs.CAP6FIFO;
|
||||
// capnum3 = EvbRegs.CAP6FIFO;
|
||||
// }
|
||||
// EDIS;
|
||||
|
||||
// EnableInterrupts();
|
||||
// return;
|
||||
|
||||
if (sync_data.count_pause_ready < MAX_COUNT_PAUSE_READY) {
|
||||
sync_data.count_pause_ready++;
|
||||
@ -180,13 +98,77 @@ void sync_detected(void)
|
||||
} else
|
||||
sync_data.sync_ready = 1;
|
||||
|
||||
////////////////////////////////////
|
||||
// if (capnum0 > 1000) {
|
||||
// return;
|
||||
// }
|
||||
// sync_data.level_find_sync_zero = LEVEL_FIND_SYNC_ZERO;
|
||||
delta_capnum = capnum0 - capnum1;
|
||||
|
||||
// calculate_sync_detected();
|
||||
if (delta_capnum > 0) //ïàäàåò
|
||||
{
|
||||
sync_data.pwm_freq_plus_minus_zero = 1;
|
||||
|
||||
if (count_error_sync < MAX_COUNT_ERROR_SYNC) {
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
} else
|
||||
sync_data.local_flag_sync_1_2 = 0;
|
||||
} else if (delta_capnum < 0) //ðàñò¸ò
|
||||
{
|
||||
if (capnum0 > sync_data.level_find_sync_zero) {
|
||||
delta_error = capnum0 - sync_data.level_find_sync_zero;
|
||||
|
||||
if (delta_error > 50) {
|
||||
if (count_error_sync < MAX_COUNT_ERROR_SYNC) {
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
} else
|
||||
sync_data.local_flag_sync_1_2 = 0;
|
||||
} else {
|
||||
if (count_error_sync > 0) {
|
||||
count_error_sync--;
|
||||
}
|
||||
if (count_error_sync == 0)
|
||||
sync_data.local_flag_sync_1_2 = 1;
|
||||
}
|
||||
|
||||
// sync_data.capnum0 = capnum0;
|
||||
sync_data.pwm_freq_plus_minus_zero = 1;
|
||||
|
||||
} else if (capnum0 < sync_data.level_find_sync_zero) {
|
||||
|
||||
delta_error = sync_data.level_find_sync_zero - capnum0;
|
||||
|
||||
if (delta_error > 50) {
|
||||
if (count_error_sync < MAX_COUNT_ERROR_SYNC) {
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
count_error_sync++;
|
||||
} else
|
||||
sync_data.local_flag_sync_1_2 = 0;
|
||||
} else {
|
||||
if (count_error_sync > 0) {
|
||||
count_error_sync--;
|
||||
}
|
||||
if (count_error_sync == 0)
|
||||
sync_data.local_flag_sync_1_2 = 1;
|
||||
}
|
||||
|
||||
sync_data.pwm_freq_plus_minus_zero = -1;
|
||||
|
||||
} else {
|
||||
sync_data.pwm_freq_plus_minus_zero = 0;
|
||||
sync_data.local_flag_sync_1_2 = 1;
|
||||
count_error_sync = 0;
|
||||
}
|
||||
} else
|
||||
sync_data.pwm_freq_plus_minus_zero = 0;
|
||||
|
||||
sync_data.delta_error_sync = delta_error;
|
||||
sync_data.delta_capnum = capnum0 - sync_data.level_find_sync_zero; //delta_capnum;
|
||||
sync_data.count_error_sync = count_error_sync;
|
||||
sync_data.capnum0 = capnum0;
|
||||
|
||||
|
||||
|
||||
@ -195,7 +177,7 @@ void sync_detected(void)
|
||||
// EvbRegs.EVBIFRC.all = BIT2;
|
||||
//
|
||||
|
||||
|
||||
}
|
||||
// // Acknowledge interrupt to receive more interrupts from PIE group 5
|
||||
// PieCtrlRegs.PIEACK.all = PIEACK_GROUP5;
|
||||
|
||||
@ -253,11 +235,6 @@ void sync_detected(void)
|
||||
// PieCtrlRegs.PIEACK.all = PIEACK_GROUP5;
|
||||
|
||||
sync_data.count_interrupts++;
|
||||
|
||||
#if(_ENABLE_PWM_LINES_FOR_TESTS_SYNC)
|
||||
PWM_LINES_TK_18_OFF;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
@ -273,18 +250,15 @@ interrupt void Sync_handler(void) {
|
||||
PieCtrlRegs.PIEIER5.all &= MG57; // Set "group" priority
|
||||
PieCtrlRegs.PIEACK.all = 0xFFFF; // Enable PIE interrupts
|
||||
|
||||
WriteMemory(ADR_SAW_REQUEST, 0x8000);
|
||||
sync_data.capnum0 = ReadMemory(ADR_SAW_VALUE);
|
||||
|
||||
stop_sync_interrupt_local(); // çàïðåòèëè ïðåðûâàíèÿ, ðàçðåøèì èõ ïî òàéìåðó, ÷òîá èçáåæàòü äðåáåçãà ïðè ïëîõîé îïòèêå.
|
||||
|
||||
|
||||
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
|
||||
if (profile_interrupt.for_led1.bits.sync)
|
||||
if (enable_profile_led1_sync)
|
||||
i_led1_on_off_special(1);
|
||||
#endif
|
||||
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
|
||||
if (profile_interrupt.for_led2.bits.sync)
|
||||
if (enable_profile_led2_sync)
|
||||
i_led2_on_off_special(1);
|
||||
#endif
|
||||
|
||||
@ -315,11 +289,11 @@ interrupt void Sync_handler(void) {
|
||||
PieCtrlRegs.PIEIER5.all = TempPIEIER;
|
||||
|
||||
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
|
||||
if (profile_interrupt.for_led1.bits.sync)
|
||||
if (enable_profile_led1_sync)
|
||||
i_led1_on_off_special(0);
|
||||
#endif
|
||||
#if (_ENABLE_INTERRUPT_PROFILE_LED2)
|
||||
if (profile_interrupt.for_led2.bits.sync)
|
||||
if (enable_profile_led2_sync)
|
||||
i_led2_on_off_special(0);
|
||||
#endif
|
||||
|
||||
@ -332,18 +306,10 @@ void setup_sync_int(void) {
|
||||
|
||||
// EALLOW;
|
||||
|
||||
if (edrk.flag_second_PCH==1)
|
||||
sync_data.level_find_sync_zero = xpwm_time.pwm_tics+5;
|
||||
else
|
||||
sync_data.level_find_sync_zero = LEVEL_FIND_SYNC_ZERO;
|
||||
|
||||
sync_data.level_find_sync_zero = LEVEL_FIND_SYNC_ZERO;
|
||||
sync_data.timeout_sync_signal = 0;
|
||||
sync_data.count_timeout_sync = 0;
|
||||
|
||||
// sync_data.what_main_pch = 1; // Ïåðâûé Ï×
|
||||
// sync_data.what_main_pch = 2; // Âòîðîé Ï×
|
||||
sync_data.what_main_pch = 0; // Ëþáîé Ï×
|
||||
|
||||
|
||||
|
||||
/////////////////////////////////////////////
|
||||
|
@ -1,6 +1,6 @@
|
||||
|
||||
|
||||
#define LEVEL_FIND_SYNC_ZERO 10 //74 //24
|
||||
#define LEVEL_FIND_SYNC_ZERO 74 //24
|
||||
#define MAX_COUNT_ERROR_SYNC 100
|
||||
#define MAX_COUNT_TIMEOUT_SYNC 100
|
||||
#define MAX_COUNT_PAUSE_READY 100
|
||||
@ -21,8 +21,7 @@ typedef struct {
|
||||
int delta_error_sync;
|
||||
int delta_capnum;
|
||||
int count_error_sync;
|
||||
unsigned int capnum0;
|
||||
unsigned int capnum1;
|
||||
int capnum0;
|
||||
|
||||
int PWMcounterVal;
|
||||
int local_flag_sync_1_2;
|
||||
@ -34,8 +33,7 @@ typedef struct {
|
||||
int enable_do_sync;
|
||||
int latch_interrupt;
|
||||
int enabled_interrupt;
|
||||
unsigned int count_interrupts;
|
||||
unsigned int what_main_pch;
|
||||
int count_interrupts;
|
||||
|
||||
|
||||
|
||||
@ -70,7 +68,7 @@ typedef struct {
|
||||
// } cmd;
|
||||
} SYNC_TOOLS_DATA;
|
||||
|
||||
#define SYNC_TOOLS_DATA_DEFAULT {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
|
||||
#define SYNC_TOOLS_DATA_DEFAULT {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
|
||||
|
||||
extern SYNC_TOOLS_DATA sync_data;
|
||||
|
||||
@ -90,7 +88,7 @@ int get_status_sync_line(void);
|
||||
void clear_sync_error(void);
|
||||
|
||||
void Sync_alg(void);
|
||||
void calculate_sync_detected(void);
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -7,9 +7,8 @@
|
||||
#include "MemoryFunctions.h"
|
||||
#include "Spartan2E_Adr.h"
|
||||
#include "x_wdog.h"
|
||||
#include "project.h"
|
||||
|
||||
#pragma CODE_SECTION(pause_10,".fast_run");
|
||||
|
||||
void pause_10(unsigned long t)
|
||||
{
|
||||
unsigned long i;
|
||||
@ -28,21 +27,13 @@ void test_impulse(unsigned int impulse_channel,long impulse_time)
|
||||
i_WriteMemory(ADR_PWM_DIRECT,0xffff);
|
||||
}
|
||||
|
||||
#pragma CODE_SECTION(test_double_impulse,".fast_run");
|
||||
void test_double_impulse(unsigned int impulse_channel_1,unsigned int impulse_channel_2,long impulse_time,long middle_impulse_time,long last_impulse_time, int soft_off_enable, int soft_on_enable)
|
||||
|
||||
void test_double_impulse(unsigned int impulse_channel_1,unsigned int impulse_channel_2,long impulse_time,long middle_impulse_time)
|
||||
{
|
||||
project.disable_all_interrupt();
|
||||
// i_WriteMemory(ADR_PWM_DIRECT,impulse_channel_2);
|
||||
// pause_10(middle_impulse_time);
|
||||
|
||||
if (soft_on_enable)
|
||||
{
|
||||
i_WriteMemory(ADR_PWM_DIRECT,impulse_channel_2);
|
||||
pause_10(last_impulse_time);
|
||||
}
|
||||
|
||||
i_WriteMemory(ADR_PWM_DIRECT,impulse_channel_1);
|
||||
// pause_10(impulse_time);
|
||||
pause_10(impulse_time);
|
||||
|
||||
|
||||
@ -50,23 +41,12 @@ void test_double_impulse(unsigned int impulse_channel_1,unsigned int impulse_cha
|
||||
pause_10(middle_impulse_time);
|
||||
|
||||
i_WriteMemory(ADR_PWM_DIRECT, impulse_channel_1);
|
||||
pause_10(last_impulse_time);
|
||||
|
||||
if (soft_off_enable)
|
||||
{
|
||||
i_WriteMemory(ADR_PWM_DIRECT,impulse_channel_2);
|
||||
pause_10(last_impulse_time);
|
||||
}
|
||||
|
||||
pause_10(middle_impulse_time);
|
||||
i_WriteMemory(ADR_PWM_DIRECT,0xffff);
|
||||
|
||||
project.enable_all_interrupt();
|
||||
}
|
||||
|
||||
void test_sin_impulse(unsigned int impulse_channel_1,unsigned int impulse_channel_2, unsigned int impulse_channel_3, long impulse_time,long middle_impulse_time)
|
||||
{
|
||||
project.disable_all_interrupt();
|
||||
|
||||
i_WriteMemory(ADR_PWM_DIRECT,impulse_channel_2);
|
||||
pause_10(middle_impulse_time);
|
||||
|
||||
@ -81,14 +61,12 @@ void test_sin_impulse(unsigned int impulse_channel_1,unsigned int impulse_channe
|
||||
pause_10(impulse_time);
|
||||
i_WriteMemory(ADR_PWM_DIRECT,0xffff);
|
||||
|
||||
project.enable_all_interrupt();
|
||||
}
|
||||
|
||||
|
||||
void test_tk_ak_one_impulse(int tk0, int tk1, int tk2, int tk3, int period, int periodMiddle, int periodLast, int doubleImpulse, int sinImpulse, int soft_off_enable, int soft_on_enable)
|
||||
void test_tk_ak_one_impulse(int tk0, int tk1, int tk2, int tk3, int period, int periodMiddle, int doubleImpulse, int sinImpulse)
|
||||
{
|
||||
long p2 = 0, pM = 0, pL = 0;
|
||||
float pf;
|
||||
long p2 = 0, pM = 0;
|
||||
unsigned int tk0_0 = 0, tk0_1 = 0, tk0_2 = 0, tk0_3 = 0, tk0_4 = 0, tk0_5 = 0, tk0_6 = 0, tk0_7 = 0;
|
||||
unsigned int tk1_0 = 0, tk1_1 = 0, tk1_2 = 0, tk1_3 = 0, tk1_4 = 0, tk1_5 = 0, tk1_6 = 0, tk1_7 = 0;
|
||||
unsigned int tk2_0 = 0, tk2_1 = 0, tk2_2 = 0, tk2_3 = 0, tk2_4 = 0, tk2_5 = 0, tk2_6 = 0, tk2_7 = 0;
|
||||
@ -114,25 +92,13 @@ void test_tk_ak_one_impulse(int tk0, int tk1, int tk2, int tk3, int period, int
|
||||
period=1;
|
||||
if (period>=1000)
|
||||
period=1000;
|
||||
pf = (float)(period) *11.724;/// 2.8328173374613003095975232198142;//(periodMiddle)*12;
|
||||
p2 = pf;
|
||||
// p2=(period) * 19 / 10;//(period)*12;
|
||||
p2=(period) * 19 / 10;//(period)*12;
|
||||
|
||||
if (periodMiddle<=1)
|
||||
periodMiddle=1;
|
||||
if (periodMiddle>=1000)
|
||||
periodMiddle=1000;
|
||||
// pM=(periodMiddle) * 19 / 10;//(periodMiddle)*12;
|
||||
pf = (float)(periodMiddle)*11.724;// / 2.8328173374613003095975232198142;//(periodMiddle)*12;
|
||||
pM = pf;
|
||||
|
||||
if (periodLast<=1)
|
||||
periodLast=1;
|
||||
if (periodLast>=1000)
|
||||
periodLast=1000;
|
||||
// pM=(periodMiddle) * 19 / 10;//(periodMiddle)*12;
|
||||
pf = (float)(periodLast)*11.724;// / 2.8328173374613003095975232198142;//(periodMiddle)*12;
|
||||
pL = pf;
|
||||
pM=(periodMiddle) * 19 / 10;//(periodMiddle)*12;
|
||||
|
||||
|
||||
|
||||
@ -222,55 +188,6 @@ void test_tk_ak_one_impulse(int tk0, int tk1, int tk2, int tk3, int period, int
|
||||
Dkey0 = 0xF9FF;
|
||||
Dkey1 = 0xF0FF;
|
||||
}
|
||||
else if (tk0_0){
|
||||
Dkey0 = 0xfffe;
|
||||
Dkey1 = 0xfffc;
|
||||
}
|
||||
else if (tk0_3){
|
||||
Dkey0 = 0xfffd;
|
||||
Dkey1 = 0xfffc;
|
||||
}
|
||||
else if (tk0_4){
|
||||
Dkey0 = 0xfffb;
|
||||
Dkey1 = 0xfff3;
|
||||
}
|
||||
else if (tk0_7){
|
||||
Dkey0 = 0xfff7;
|
||||
Dkey1 = 0xfff3;
|
||||
}
|
||||
else if (tk1_0){
|
||||
Dkey0 = 0xffef;
|
||||
Dkey1 = 0xffcf;
|
||||
}
|
||||
else if (tk1_3){
|
||||
Dkey0 = 0xffdf;
|
||||
Dkey1 = 0xffcf;
|
||||
}
|
||||
else if (tk1_4){
|
||||
Dkey0 = 0xffbf;
|
||||
Dkey1 = 0xff3f;
|
||||
}
|
||||
else if (tk1_7){
|
||||
Dkey0 = 0xff7f;
|
||||
Dkey1 = 0xff3f;
|
||||
}
|
||||
else if (tk2_0){
|
||||
Dkey0 = 0xfeff;
|
||||
Dkey1 = 0xfcff;
|
||||
}
|
||||
else if (tk2_3){
|
||||
Dkey0 = 0xfdff;
|
||||
Dkey1 = 0xfcff;
|
||||
}
|
||||
else if (tk2_4){
|
||||
Dkey0 = 0xfbff;
|
||||
Dkey1 = 0xf3ff;
|
||||
}
|
||||
else if (tk2_7){
|
||||
Dkey0 = 0xf7ff;
|
||||
Dkey1 = 0xf3ff;
|
||||
}
|
||||
|
||||
}
|
||||
else if(sinImpulse)
|
||||
{
|
||||
@ -352,7 +269,7 @@ void test_tk_ak_one_impulse(int tk0, int tk1, int tk2, int tk3, int period, int
|
||||
|
||||
}
|
||||
if(doubleImpulse)
|
||||
test_double_impulse(Dkey0, Dkey1, p2, pM, pL, soft_off_enable, soft_on_enable);
|
||||
test_double_impulse(Dkey0, Dkey1, p2, pM);
|
||||
else if(sinImpulse)
|
||||
test_sin_impulse(Dkey0, Dkey1, Dkey2, p2, pM);
|
||||
else
|
||||
|
@ -4,8 +4,7 @@
|
||||
|
||||
|
||||
|
||||
void test_tk_ak_one_impulse(int tk0, int tk1, int tk2, int tk3, int period, int periodMiddle, int periodLast, int doubleImpulse, int sinImpulse, int soft_off_enable, int soft_on_enable);
|
||||
void test_double_impulse(unsigned int impulse_channel_1,unsigned int impulse_channel_2,long impulse_time,long middle_impulse_time, long last_impulse_time, int soft_off_enable, int soft_on_enable);
|
||||
void test_tk_ak_one_impulse(int tk0, int tk1, int tk2, int tk3, int period, int periodMiddle, int doubleImpulse, int sinImpulse);
|
||||
|
||||
|
||||
#endif
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user