#3 Скомпилилось, но пока ничего не вызывается

Все основные файлы подтянуты без изменений

Изменены (только папка main_matlab):
- заглушки для ненужных функций (main_matlab.c)
- iq библиотека (IQmathLib_matlab.c)
- библиотеки DSP281x
This commit is contained in:
Razvalyaev 2025-01-13 11:09:58 +03:00
parent 06c76feb3b
commit 7e0063eee0
317 changed files with 97782 additions and 65 deletions

2201
Inu/Src/N12_Libs/CAN_Setup.c Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,751 @@
#ifndef _CAN_SETUP
#define _CAN_SETUP
#include <CAN_project.h>
#include "word_structurs.h"
#include "DSP281x_Device.h"
#define MAX_COUNT_UNITES_TERMINAL 4 // ôèêñ
#define MAX_COUNT_UNITES_UKSS 16 // ôèêñ
#define MAX_COUNT_UNITES_MPU 4 // ôèêñ
#define MAX_COUNT_UNITES_ALARM_LOG 2 // ôèêñ
////////////////////////////////////////
#define CAN_ADR_TERMINAL_DEFAULT 0x00EEEE01
#define START_CAN_ADR_UNITS_DEFAULT 0x00235500
#define CAN_ADR_MPU_DEFAULT 0x00CEB0E1
#define CAN_ADR_ALARM_LOG_DEFAULT 0x0BCDEF01
////////////////////////////////////////
// ïîäñ÷åò êîë-âà áëîêîâ MPU
// äîëæíû áûòü àêòèâèðîâàíû â CAN_project.c
////////////////////////////////////////
#ifndef USE_MPU_0
#define USE_MPU_0 0
#endif
#ifndef USE_MPU_1
#define USE_MPU_1 0
#endif
#ifndef USE_MPU_2
#define USE_MPU_2 0
#endif
#ifndef USE_MPU_3
#define USE_MPU_3 0
#endif
#define MPU_UNIT_QUA_UNITS ( USE_MPU_0 + USE_MPU_1 \
+ USE_MPU_2 + USE_MPU_3 \
) //êîë-âî ÿùèêîâ äëÿ MPU_CAN
///////////////////////////////////////////
// êîë-âî ÿùèêîâ äëÿ TERMINAL_CAN
///////////////////////////////////////////
////////////////////////////////////////
// ïîäñ÷åò êîë-âà áëîêîâ TERMINAL
// äîëæíû áûòü àêòèâèðîâàíû â CAN_project.c
////////////////////////////////////////
#ifndef USE_TERMINAL_1_OSCIL
#define USE_TERMINAL_1_OSCIL 0
#endif
#ifndef USE_TERMINAL_1_CMD
#define USE_TERMINAL_1_CMD 0
#endif
#ifndef USE_TERMINAL_2_OSCIL
#define USE_TERMINAL_2_OSCIL 0
#endif
#ifndef USE_TERMINAL_2_CMD
#define USE_TERMINAL_2_CMD 0
#endif
#define TERMINAL_UNIT_QUA_UNITS ( USE_TERMINAL_1_OSCIL + USE_TERMINAL_1_CMD \
+ USE_TERMINAL_2_OSCIL + USE_TERMINAL_2_CMD \
) //êîë-âî ÿùèêîâ äëÿ TERMINAL_CAN
////////////////////////////////////////
// ïîäñ÷åò êîë-âà áëîêîâ ALARM_LOG
// äîëæíû áûòü àêòèâèðîâàíû â CAN_project.c
////////////////////////////////////////
#ifndef USE_ALARM_LOG_0
#define USE_ALARM_LOG_0 0
#endif
#ifndef USE_ALARM_LOG_1
#define USE_ALARM_LOG_1 0
#endif
#define ALARM_LOG_UNIT_QUA_UNITS ( USE_ALARM_LOG_0 + USE_ALARM_LOG_1 \
) //êîë-âî ÿùèêîâ äëÿ ALARM_LOG_CAN
////////////////////////////////////////
// ïîäñ÷åò êîë-âà áëîêîâ ukss
// äîëæíû áûòü àêòèâèðîâàíû â CAN_project.c
////////////////////////////////////////
#ifndef USE_UKSS_0
#define USE_UKSS_0 0
#endif
#ifndef USE_UKSS_1
#define USE_UKSS_1 0
#endif
#ifndef USE_UKSS_2
#define USE_UKSS_2 0
#endif
#ifndef USE_UKSS_3
#define USE_UKSS_3 0
#endif
#ifndef USE_UKSS_4
#define USE_UKSS_4 0
#endif
#ifndef USE_UKSS_5
#define USE_UKSS_5 0
#endif
#ifndef USE_UKSS_6
#define USE_UKSS_6 0
#endif
#ifndef USE_UKSS_7
#define USE_UKSS_7 0
#endif
#ifndef USE_UKSS_8
#define USE_UKSS_8 0
#endif
#ifndef USE_UKSS_9
#define USE_UKSS_9 0
#endif
#ifndef USE_UKSS_10
#define USE_UKSS_10 0
#endif
#ifndef USE_UKSS_11
#define USE_UKSS_11 0
#endif
#ifndef USE_UKSS_12
#define USE_UKSS_12 0
#endif
#ifndef USE_UKSS_13
#define USE_UKSS_13 0
#endif
#ifndef USE_UKSS_14
#define USE_UKSS_14 0
#endif
#ifndef USE_UKSS_15
#define USE_UKSS_15 0
#endif
#ifndef USE_R_B_0
#define USE_R_B_0 0
#endif
#ifndef USE_R_B_1
#define USE_R_B_1 0
#endif
#ifndef USE_R_B_2
#define USE_R_B_2 0
#endif
#ifndef USE_R_B_3
#define USE_R_B_3 0
#endif
#ifndef USE_R_B_4
#define USE_R_B_4 0
#endif
#ifndef USE_R_B_5
#define USE_R_B_5 0
#endif
#ifndef USE_R_B_6
#define USE_R_B_6 0
#endif
#ifndef USE_R_B_7
#define USE_R_B_7 0
#endif
#ifndef USE_R_B_8
#define USE_R_B_8 0
#endif
#ifndef USE_R_B_9
#define USE_R_B_9 0
#endif
#ifndef USE_R_B_10
#define USE_R_B_10 0
#endif
#ifndef USE_R_B_11
#define USE_R_B_11 0
#endif
#ifndef USE_R_B_12
#define USE_R_B_12 0
#endif
#ifndef USE_R_B_13
#define USE_R_B_13 0
#endif
#ifndef USE_R_B_14
#define USE_R_B_14 0
#endif
#ifndef USE_R_B_15
#define USE_R_B_15 0
#endif
#define UNIT_QUA_UNITS ( 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) // 2 //3//8 //êîëè÷åñòâî CAN óñòðîéñòâ ïåðåäàþùèõ â ñèñòåìå CANMODBUS - êîë-âî Unites
///////////////////////////////////////////
// íàñòðîéêè CAN_Open
///////////////////////////////////////////
#ifdef INGITIM_CAN_OPEN
#define MBOX0_CANOPEN 0x00000013 //0x180 t1PDO1
#define MBOX1_CANOPEN 0x0000018d //0x280 t2PDO1
#define MBOX2_CANOPEN 0x000000c5 //0x380 t3PDO1
#define MBOX3_CANOPEN 0x12000000 //0x480 t4PDO1
#define MBOX4_CANOPEN 0x16000000 //0x580 t4PDO1
#define MBOX5_CANOPEN 0x1a000000 //0x680 t4PDO1
#define CANOPEN_CAN_SETUP_DEFAULT { {MBOX0_CANOPEN,MBOX1_CANOPEN,MBOX2_CANOPEN,0,0,0,0,0,0,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,2,-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}, \
3}
#endif
#ifdef BWC_CAN_FATEC
#define MBOX0_CANOPEN 0x08040000 //201; 010 0000 0001
#define MBOX1_CANOPEN 0x0C040000 //301; 011 0000 0001
#define MBOX2_CANOPEN 0x10040000 //401; 100 0000 0001
#define MBOX3_CANOPEN 0x14040000 //501; 101 0000 0001
#define MBOX4_CANOPEN 0x08080000 //202; 010 0000 0010
#define MBOX5_CANOPEN 0x0C080000 //302; 011 0000 0010
#define MBOX6_CANOPEN 0x10080000 //402; 100 0000 0010
#define MBOX7_CANOPEN 0x14080000 //502; 101 0000 0010
#define CANOPEN_CAN_SETUP_DEFAULT { {MBOX0_CANOPEN,MBOX1_CANOPEN,MBOX2_CANOPEN,MBOX3_CANOPEN,MBOX4_CANOPEN,MBOX5_CANOPEN,MBOX6_CANOPEN,MBOX7_CANOPEN,0,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,2,3,4,5,6,7,-1,-1,-1,-1,-1,-1,-1,-1}, \
{-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}, \
0}
#endif
#ifdef BWC_CAN_SIEMENS
#define MBOX0_CANOPEN 0x00040000 // 0x08040000 //201; 010 0000 0001
#define MBOX1_CANOPEN 0x00080000 //301; 011 0000 0001
#define CANOPEN_CAN_SETUP_DEFAULT { {MBOX0_CANOPEN,MBOX1_CANOPEN,0,0,0,0,0,0,0,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,2,3,4,5,6,7,-1,-1,-1,-1,-1,-1,-1,-1}, \
{-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}, \
0}
#endif
#ifndef CANOPEN_CAN_SETUP_DEFAULT
#define CANOPEN_CAN_SETUP_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}, \
0}
#endif
/////////////////////////////////////////////////////////////////////
extern int CAN_input_data[];
extern int CAN_output_data[];
extern int* CAN_output;
extern int flag_enable_can_from_mpu;
/////////////////////////////////////////////////////////////////////
#define UNIT_QUA 32 //12 // ­  êîëè÷åñòâî CAN óñòðîéñòâ â ñèñòåìå - ßùèêîâ
#define TERMINAL_UNIT_LEN 128
#define UNIT_LEN 128
#define FIFO_LEN 10
#define NEW_FIFO_LEN 128
#define NEW_CYCLE_FIFO_LEN 256
#define NEW_CYCLE_FIFO_LEN_MASK (NEW_CYCLE_FIFO_LEN-1)
////////////////////////////////////////////////////
////////////////////////////////////////////////////
////////////////////////////////////////////////////
typedef struct
{
int * adr_from;
unsigned int adr_to;
unsigned int adr;
unsigned int quant;
int busy;
int FLY;
int extended;
} CYCLE;
typedef struct
{
int * adr_from;
unsigned long adr_to;
unsigned long adr;
unsigned long quant;
int busy;
int FLY;
int extended;
int box;
int priority;
unsigned int quant_block;
} NEW_CYCLE_DATA;
typedef struct
{
int box;
long hiword;
long loword;
} PACK;
typedef struct
{
int adr;
PACK pak[FIFO_LEN];
}FIFO;
typedef struct
{
int index_data; // òåêóùèé èíäåêñ ïðè çàãðóçêå äàííûìè
int index_send; // òåêóùèé èíäåêñ ïðè ïåðåäà÷å
int flag_inter; // ìû æäåì ñáðîñà â ïðåðûâàíèè
unsigned int count_lost; // êîëè÷åñòâî ïîòåðü
unsigned int count_load; // çàãðóçêà ìàññèâà
unsigned int count_free; // ñâîáîäà ìàññèâà
NEW_CYCLE_DATA cycle_data[NEW_CYCLE_FIFO_LEN];
int cycle_box[UNIT_QUA];
int lost_box[UNIT_QUA];
}NEW_CYCLE_FIFO;
//////////////////////////////////////
//////////////////////////////////////
//////////////////////////////////////
#define USE_BOX 1
#define NOT_USE_BOX 0
#define CAN_BOX_TYPE_IN 1
#define CAN_BOX_TYPE_OUT 2
#define FREE_TYPE_BOX 0
#define UNITS_TYPE_BOX 1
#define MPU_TYPE_BOX 2
#define CANOPEN_TYPE_BOX 3
#define SMPU_TYPE_BOX 4
#define TERMINAL_TYPE_BOX 5
#define ALARM_LOG_TYPE_BOX 6
/////////////////////////////////////////////////////////////////////
#define CAN_BOX_PRIORITY_NORMAL 0
#define CAN_BOX_PRIORITY_LOW -1
#define CAN_BOX_PRIORITY_HIGH 1
/////////////////////////////////////////////////////////////////////
#define CAN_BOX_EXTENDED_ADR 1
#define CAN_BOX_STANDART_ADR 0
/////////////////////////////////////////////////////////////////////
#define CAN_BOX_STAT_ON 1
#define CAN_BOX_STAT_OFF 0
/////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////
typedef struct {
long can_in_mbox_adr[16];
long can_out_mbox_adr[16];
int adr_box[16];
int adr_in_mbox[16];
int max_number;
} CANOPEN_CAN_SETUP;
/////////////////////////////////////////////////////////////////////
typedef struct {
long can_mbox_adr[32];
// long can_out_mbox_adr[16];
int type_box[32];
int local_number_box[32];
int type_in_out_box[32];
int max_number_in;
int max_number_out;
} MAILBOXS_CAN_SETUP;
#define MAILBOXS_CAN_SETUP_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}
/////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////
typedef struct {
unsigned long can_base_adr;
long can_in_mbox_adr[MAX_COUNT_UNITES_UKSS];
long can_out_mbox_adr[MAX_COUNT_UNITES_UKSS];
int adr_box[MAX_COUNT_UNITES_UKSS+1];
int adr_in_mbox[MAX_COUNT_UNITES_UKSS+1];
int adr_out_mbox[MAX_COUNT_UNITES_UKSS+1];
int active_box[MAX_COUNT_UNITES_UKSS];
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;
/////////////////////////////////////////////////////////////////////
typedef struct {
unsigned long can_base_adr;
long can_in_mbox_adr[MAX_COUNT_UNITES_MPU];
long can_out_mbox_adr[MAX_COUNT_UNITES_MPU];
int adr_box[MAX_COUNT_UNITES_MPU];
int adr_in_mbox[MAX_COUNT_UNITES_MPU];
int adr_out_mbox[MAX_COUNT_UNITES_MPU];
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;
/////////////////////////////////////////////////////////////////////
typedef struct {
unsigned long can_base_adr;
long can_in_mbox_adr[MAX_COUNT_UNITES_TERMINAL];
long can_out_mbox_adr[MAX_COUNT_UNITES_TERMINAL];
int adr_box[MAX_COUNT_UNITES_TERMINAL];
int adr_in_mbox[MAX_COUNT_UNITES_TERMINAL];
int adr_out_mbox[MAX_COUNT_UNITES_TERMINAL];
int active_box[MAX_COUNT_UNITES_TERMINAL];
unsigned int CAN_count_cycle_input_units[MAX_COUNT_UNITES_TERMINAL];
int max_number;
} TERMINAL_CAN_SETUP;
////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////
typedef struct {
unsigned long can_base_adr;
long can_in_mbox_adr[MAX_COUNT_UNITES_ALARM_LOG];
long can_out_mbox_adr[MAX_COUNT_UNITES_ALARM_LOG];
int adr_box[MAX_COUNT_UNITES_ALARM_LOG];
int adr_in_mbox[MAX_COUNT_UNITES_ALARM_LOG];
int adr_out_mbox[MAX_COUNT_UNITES_ALARM_LOG];
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, \
{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, \
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, \
{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, \
{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, \
{USE_ALARM_LOG_0,USE_ALARM_LOG_1}, \
_ALARM_LOG_DEFAULT_ZERO, \
0}
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
typedef struct {
WORD_INT2BITS_STRUCT buf[TERMINAL_UNIT_LEN];
} TERMINAL_UNITES_STRUCT;
////
typedef TERMINAL_UNITES_STRUCT *TERMINAL_UNITES_STRUCT_handle;
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
extern int TerminalUnites[TERMINAL_UNIT_QUA_UNITS][TERMINAL_UNIT_LEN];
extern int Unites[UNIT_QUA_UNITS][UNIT_LEN];
////////////////////////////////////////////////////////////////////////////////
extern CYCLE cycle[]; // 26.01.2011 Dimas
extern NEW_CYCLE_FIFO new_cycle_fifo;
extern int CanOpenUnites[CANOPENUNIT_LEN];
//add yura
extern MAILBOXS_CAN_SETUP mailboxs_can_setup;
extern FIFO fifo;
extern int CAN_timeout[];
extern int CAN_request_sent[];
extern unsigned int CAN_timeout_cicle[];
//////////////////////////////////////////////////
//////////////////////////////////////////////////
int init_units_can_boxs(UNITES_CAN_SETUP *p);
int init_canopen_can_boxs(CANOPEN_CAN_SETUP *p);
int init_mpu_can_boxs(MPU_CAN_SETUP *p );
int init_terminal_can_boxs(TERMINAL_CAN_SETUP *p );
int init_alarm_log_can_boxs(ALARM_LOG_CAN_SETUP *p );
//////////////////////////////////////////////////
void init_mailboxs_can( UNITES_CAN_SETUP *p_units,
MPU_CAN_SETUP *p_mpu,
TERMINAL_CAN_SETUP *p_terminal,
ALARM_LOG_CAN_SETUP *p_alarm_log,
CANOPEN_CAN_SETUP *p_canopen,
MAILBOXS_CAN_SETUP *p_mailboxs
);
void init_all_mailboxs(unsigned long can_base_adr_units, unsigned long can_base_adr_mpu, unsigned long can_base_adr_alarm_log, unsigned long can_base_adr_terminal);
void InitCan(unsigned long can_base_adr_units, unsigned long can_base_adr_mpu, unsigned long can_base_adr_alarm_log, unsigned long can_base_adr_terminal);
//void CAN_send(int box, unsigned long hiword, unsigned long loword);
//void CAN_word_send(int type_box, int box, int Addr, int Data);
//void CAN_array_send(int type_box, int box, int Addr, int * Data);
void CAN_cycle_send(int type_box, int box, unsigned long Addr, int * Data, unsigned long quant, int extended, int priority);
//void FIFO_send(int box, unsigned long hiword, unsigned long loword);
//int CAN_FLY_free(int box);
//int CAN_FIFO_free(unsigned int quant);
int CAN_cycle_free(int box);
int CAN_cycle_full_free(int box, int statistics_flag);
//void CAN_cycle_stop(int box);
//void CAN_cycle_step(int box);
void CAN_request(unsigned int addr, unsigned int quant);
void CAN_assign(unsigned int addr, unsigned int quant);
void reset_CAN_timeout_cicle(int box);
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);
void parse_data_from_mbox(unsigned int box, unsigned long hiword,
unsigned long loword);
int get_real_out_mbox(int type_box, int box);
int get_real_in_mbox(int type_box, int box);
void messagePaserToUnitesIngitim(int box, unsigned long h_word, unsigned long l_word);
//////////////////
void new_fifo_calc_load(void);
int new_fifo_load(int box,unsigned long hiword, unsigned long loword);
int new_cycle_fifo_load(int box, unsigned long adr, int * adr_from, unsigned long addr_to, unsigned long quant, int extended, int priority, int cmd_wait);
int get_new_cycle_fifo_load_level(void);
void CAN_send2(int box,unsigned long hiword, unsigned long loword);
int CAN_cycle_fifo_step(void);
int CAN_cycle_fifo_one_box(void);
//////////////////
int CAN_may_be_send_cycle_fifo(void);
void stop_can_interrupt(void);
void start_can_interrupt(void);
//// Prototype statements for functions found within this file.
interrupt void CAN_handler(void);
interrupt void CAN_reset_err(void);
extern UNITES_CAN_SETUP unites_can_setup;
extern MPU_CAN_SETUP mpu_can_setup;
extern unsigned int CanTimeOutErrorTR;
extern unsigned int CanBusOffError;
#endif // _CAN_SETUP

View File

@ -0,0 +1,31 @@
#ifndef _RS_MODBUS_PULT_H
#define _RS_MODBUS_PULT_H
#include "modbus_struct.h"
#include "RS_Functions.h"
void ModbusRTUsend1(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start, unsigned int count_bits);
void ModbusRTUreceiveAnswer1(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUreceive3(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUsend3(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start,unsigned int count_word);
void ModbusRTUreceiveAnswer3(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUsend4(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start, unsigned int count_word);
void ModbusRTUreceiveAnswer4(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUreceive4(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUsend5(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start);
void ModbusRTUreceiveAnswer5(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUsend6(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start);
void ModbusRTUreceiveAnswer6(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUsend15(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start,unsigned int count_bits);
void ModbusRTUreceiveAnswer15(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUreceive15(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUsend16(RS_DATA_STRUCT *rs_arr,int adr_contr, unsigned int adr_start,unsigned int count_words);
void ModbusRTUreceive16(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUreceiveAnswer16(RS_DATA_STRUCT *RS232_Arr);
void ModbusRTUsetDataArrays(MODBUS_REG_STRUCT *array_in, MODBUS_REG_STRUCT *array_out);
void ModbusRTUsetDiscretDataArray(MODBUS_REG_STRUCT *discrete_in, MODBUS_REG_STRUCT *discrete_out);
extern int flag_wait_anwer_cmd1;
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,543 @@
/*
* oscil_can.c
*
* Created on: 24 ìàÿ 2020 ã.
* Author: yura
*/
#include "alarm_log_can.h"
#include "CAN_Setup.h"
#include "global_time.h"
#include "CRC_Functions.h"
#pragma DATA_SECTION(alarm_log_can, ".slow_vars")
ALARM_LOG_CAN alarm_log_can = ALARM_LOG_CAN_CAN_DEFAULTS;
//int oscil_buffer[OSCIL_CAN_NUMBER_CHANNEL][OSCIL_CAN_NUMBER_POINTS];
void alarm_log_clear_buffer(ALARM_LOG_CAN_handle al)
{
unsigned int i,k;
/*
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
for (k=0;k<(OSCIL_CAN_NUMBER_POINTS+OSCIL_CAN_NUMBER_POINTS_ADD);k++)
oc->oscil_buffer[i][k] = 0;
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
for (k=0;k<OSCIL_CAN_NUMBER_POINTS;k++)
oc->temp_oscil_buffer[i][k] = 0;
oc->current_position = 0;
// oc->enable_rewrite = 1;
*/
}
int compress_size = 0;
void alarm_log_compress_temp_buffer(ALARM_LOG_CAN_handle al)
{
// compress_size = fastlz_compress_level(1, al->start_adr_real_logs, 100, al->start_adr_temp);
// compress_size = lzf_compress(al->start_adr_real_logs, 2000, al->start_adr_temp, 2000);
}
void alarm_log_copy_temp_buffer(ALARM_LOG_CAN_handle al)
{
unsigned int i,k;
unsigned long clog, temp_length;//real_length
int *adr_finish_temp, *adr_current;
// real_length = al->real_points * al->oscills;
// real_adr = al->start_adr_real_logs;
temp_length = al->temp_points * al->oscills; // ñêîëüêî äàííûõ íàäî âûåðåçàòü èç ëîãà
al->temp_log_ready = 0;
if (al->current_adr_real_log == al->start_adr_real_logs) // ìû â íà÷àëå, ëîãîâ íåòó?
return;
adr_current = al->current_adr_real_log; // âûñòàâèëè êîíåö ëîãà
adr_finish_temp = al->start_adr_temp + temp_length; // òóò êîíåö ëîãà temp
// òåïåðü íà÷èíàÿ ñ êîíöà adr_finish ñêîïèðóåì â temp_log
// ñ ó÷åòîì òîãî ÷òî ìû êîïèðóåì èç öèêëè÷åñêîãî áóôåðà â îáû÷íûé, íóæíà ðàçâåðòêà äàííûõ
for (clog=0; clog<temp_length ;clog++)
{
if ( (adr_current >= al->start_adr_real_logs) )
{
*adr_finish_temp = *adr_current; // ñêîïèðëâàëè äàííûå
// åäåì íàçàä
adr_current--;
}
else
*adr_finish_temp = 0; // à íåòó äàííûõ!
// åäåì íàçàä
adr_finish_temp--;
// çàêîëüöåâàëèñü?
if (adr_current < al->start_adr_real_logs)
{
if (al->finish_adr_real_log) // ëîã ïðîêðó÷èâàëñÿ?
adr_current = al->finish_adr_real_log; // ïåðåøëè â êîíåö.
else
adr_current = al->start_adr_real_logs - 1;
}
}
al->temp_log_ready = 1;
/*
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
for (k=0;k<(OSCIL_CAN_NUMBER_POINTS+OSCIL_CAN_NUMBER_POINTS_ADD);k++)
oc->oscil_buffer[i][k] = 0;
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
for (k=0;k<OSCIL_CAN_NUMBER_POINTS;k++)
oc->temp_oscil_buffer[i][k] = 0;
oc->current_position = 0;
// oc->enable_rewrite = 1;
*/
}
//#define CAN_BOX_PRIORITY_LOW_MAX_SIZE_BLOCKS 3330L// 9999L
void alarm_log_send_buffer(ALARM_LOG_CAN_handle al)
{
static unsigned int old_time = 0;
// static int prev_send_to_can = 0;
static unsigned long old_t = 0;
unsigned int i;
int real_mbox;
static int flag_send_buf = 0;
static unsigned long quant_local = 0;
static unsigned long addr_to = 0;
static int *start_adr;
static unsigned int k = 0;
// if (flag_send_buf)
// {
//
//
//
// return;
// }
if (al->global_enable==0)
return;
real_mbox = get_real_out_mbox(ALARM_LOG_TYPE_BOX, ALARM_LOG_NUMBER_BOX_IN_CAN);
if (al->stage==1)
{
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_ON))
{
CAN_cycle_send(
ALARM_LOG_TYPE_BOX,
ALARM_LOG_NUMBER_BOX_IN_CAN,
(unsigned long)(0xfffc*3L),
&(al->cmd_fffc[0]), 3, CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
CAN_cycle_send(
ALARM_LOG_TYPE_BOX,
ALARM_LOG_NUMBER_BOX_IN_CAN,
(unsigned long)(0xfffd*3L),
&(al->cmd_fffd[0]), 3, CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
CAN_cycle_send(
ALARM_LOG_TYPE_BOX,
ALARM_LOG_NUMBER_BOX_IN_CAN,
(unsigned long)(0xfffe*3L),
&(al->cmd_fffe[0]), 3, CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
al->stage = 2;
quant_local = ((unsigned long)al->oscills * (unsigned long)al->temp_points);
al->progress_can = quant_local;
addr_to = 0;
start_adr = al->start_adr_temp;
}
return;
}
if (al->stage==2)
{
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_OFF) && (get_new_cycle_fifo_load_level()<=2) )
{
// if ((unsigned long)quant_local>(unsigned long)CAN_BOX_PRIORITY_LOW_MAX_SIZE_BLOCKS)
// {
// k++;
// }
al->progress_can = quant_local;
if ((unsigned long)quant_local > al->can_max_size_one_block)
{
al->crc16 = GetCRC16_IBM( al->crc16, (unsigned int *)start_adr, al->can_max_size_one_block);
CAN_cycle_send(
ALARM_LOG_TYPE_BOX,
ALARM_LOG_NUMBER_BOX_IN_CAN,
addr_to,
start_adr, al->can_max_size_one_block , CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
start_adr += al->can_max_size_one_block;
quant_local -= al->can_max_size_one_block;
addr_to += al->can_max_size_one_block;
}
else
{
al->crc16 = GetCRC16_IBM_v2( al->crc16, (unsigned int *)start_adr, ((unsigned long)quant_local) );
CAN_cycle_send(
ALARM_LOG_TYPE_BOX,
ALARM_LOG_NUMBER_BOX_IN_CAN,
addr_to,
start_adr, ((unsigned long)quant_local) , CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
al->stage = 3;
quant_local = 0;
}
}
return;
}
if (al->stage==3)
{
al->cmd_ffff[1] = al->crc16; // CRC16
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_OFF))
{
al->progress_can = 0;
CAN_cycle_send(
ALARM_LOG_TYPE_BOX,
ALARM_LOG_NUMBER_BOX_IN_CAN,
(unsigned long)(0xffff*3L),
&(al->cmd_ffff[0]), 3 , CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
al->stage = 100;
k--;
}
return;
}
if (al->stage==4)
{
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_OFF))
{
CAN_cycle_send(
ALARM_LOG_TYPE_BOX,
ALARM_LOG_NUMBER_BOX_IN_CAN,
(unsigned long)(0xfffc*3L),
&(al->cmd_fffc[0]), 3, CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
al->stage = 100;
k--;
}
return;
}
if (al->stage==100)
{
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_ON))
{
// prev_send_to_can = 1;
al->stage = 0;
al->timer_send = (global_time.miliseconds - old_t);
}
return;
}
// áûëà êîìàíäà íà îòïðàâêó ïîñûëêè è îíà åùå íå óøëà, òîãäà ñáðàñûâàåì ñ÷åò÷èê âðåìåíè ïàóçû ìåæäó ïîñûëêàìè,
// ò.å. OSCIL_TIME_WAIT ìåæäó êîíöîì îòïðàâêè ïîñûëêè è íîâîé ïîñûëêè.
// if (prev_send_to_can && CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_OFF)==0)
// {
// old_time = (unsigned int)global_time.miliseconds;
// return;
// }
//////
// if (prev_send_to_can)
// {
//
// }
//////
// prev_send_to_can = 0;
if ((al->prev_status_alarm != al->status_alarm) && al->status_alarm)
{
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_ON))
{
al->prepare_data_can(al);
if (al->copy2temp)
{
al->copy_temp_buffer(al);
// alarm_log_compress_temp_buffer(al);
if (al->temp_log_ready == 1)
{
old_t = global_time.miliseconds;
al->stage = 1;
}
else
{
old_t = global_time.miliseconds;
al->stage = 4; // ïåðåäàåì ïóñòîå ñîîáùåíèå - ýòî îøèáêà, äàííûõ íåò!
}
}
else
{
old_t = global_time.miliseconds;
al->stage = 4; // ïåðåäàåì ïóñòîå ñîîáùåíèå - ýòî îøèáêà, äàííûõ íåò!
}
// flag_send_buf = 1;
// CAN_cycle_send(
// ALARM_LOG_TYPE_BOX,
// ALARM_LOG_NUMBER_BOX_IN_CAN,
// 0xfffc,
// &(al->cmd_fffc[0]), 3, CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
//
// CAN_cycle_send(
// ALARM_LOG_TYPE_BOX,
// ALARM_LOG_NUMBER_BOX_IN_CAN,
// 0xfffd,
// &(al->cmd_fffd[0]), 3, CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
//
// CAN_cycle_send(
// ALARM_LOG_TYPE_BOX,
// ALARM_LOG_NUMBER_BOX_IN_CAN,
// 0xfffe,
// &(al->cmd_fffe[0]), 3, CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
// al->stage = 1;
//
// CAN_cycle_send(
// ALARM_LOG_TYPE_BOX,
// ALARM_LOG_NUMBER_BOX_IN_CAN,
// 0,
// al->start_adr, ((unsigned long)al->oscills * (unsigned long)al->points) , CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
// al->stage = 2;
//
// CAN_cycle_send(
// ALARM_LOG_TYPE_BOX,
// ALARM_LOG_NUMBER_BOX_IN_CAN,
// 0xffff,
// &(al->cmd_ffff[0]), 3 , CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
// al->stage = 0;
//
//
// prev_send_to_can = 1;
}
}
al->prev_status_alarm = al->status_alarm;
/*
oc->global_enable = TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x1;
oc->send_after_cmd = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x2) >> 1;
oc->cmd_send = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x4) >> 2;
oc->stop_update_on_error = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x8) >> 3;
oc->stop_update_on_stop_pwm = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x10) >> 4;
TerminalUnites[oc->number_can_box_terminal_oscil][0] &= ~0x4; // clear cmd_send
oc->number_ch = TerminalUnites[oc->number_can_box_terminal_oscil][1];
oc->number_points = TerminalUnites[oc->number_can_box_terminal_oscil][2];
oc->step = TerminalUnites[oc->number_can_box_terminal_oscil][3];
if (oc->global_enable==0)
return;
real_mbox = get_real_out_mbox(TERMINAL_TYPE_BOX, oc->number_can_box_terminal_oscil);
// áûëà êîìàíäà íà îòïðàâêó ïîñûëêè è îíà åùå íå óøëà, òîãäà ñðáàñûâàåì ñ÷åò÷èê âðåìåíè ïàóçû ìåæäó ïîñûëêàìè,
// ò.å. OSCIL_TIME_WAIT ìåæäó êîíöîì îòïðàâêè ïîñûëêè è íîâîé ïîñûëêè.
if (prev_send_to_can && CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_OFF)==0)
{
old_time = (unsigned int)global_time.miliseconds;
return;
}
prev_send_to_can = 0;
if (oc->send_after_cmd==0)
{
if (!detect_pause_milisec(OSCIL_TIME_WAIT,&old_time))
return;
}
if ( (oc->send_after_cmd==0 || (oc->send_after_cmd==1 && oc->cmd_send==1 ) ) )
{
oc->cmd_send = 0; // clear cmd
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_ON))
{
// oc->enable_rewrite = 0;
old_t = oc->current_position;//
// old_t = global_time.microseconds;
oc->prepare_data_can(oc);
// oc->timer_send = (global_time.microseconds - old_t);
oc->timer_send = (oc->current_position - old_t);
flag_send_buf = 1;
CAN_cycle_send(
TERMINAL_TYPE_BOX,
oc->number_can_box_terminal_oscil,
0,
&(oc->temp_oscil_buffer[0][0]), (oc->number_ch * oc->number_points) , CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
prev_send_to_can = 1;
// while (CAN_cycle_free(real_mbox)==0);
// oc->timer_send = (global_time.microseconds - old_t)/100;
oc->enable_rewrite = 1;
// if (cur_position_buf_modbus16_can >= SIZE_MODBUS_TABLE)
// {
// cur_position_buf_modbus16_can = 0;
//// modbus_table_can_out[ADR_CAN_TEST_PLUS_ONE].all++;
// }
//
// 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
// count_write_to_modbus_can = SIZE_BUF_WRITE_TO_MODBUS16_CAN;
//
// if (CAN_cycle_free(real_mbox))
// {
// CAN_cycle_send(
// MPU_TYPE_BOX,
// edrk.flag_second_PCH,
// cur_position_buf_modbus16_can + 1,
// &modbus_table_can_out[cur_position_buf_modbus16_can].all,
// count_write_to_modbus_can, 0);
//
// cur_position_buf_modbus16_can = cur_position_buf_modbus16_can + SIZE_BUF_WRITE_TO_MODBUS16_CAN;
// }
//
//
}
}
*/
}
#pragma CODE_SECTION(alarm_log_prepare_data_can,".fast_run");
void alarm_log_prepare_data_can(ALARM_LOG_CAN_handle al)
{
unsigned int old_position, t_position;
int i, k;
// unsigned int crc;
al->crc16 = 0xffff;
// crc = GetCRC16_IBM( crc, (unsigned int *)al->start_adr_temp, al->temp_points*al->oscills);
// al->crc16 = crc;
al->cmd_fffc[0] = 0x1234;
al->cmd_fffc[1] = 0x5678;
al->cmd_fffc[2] = 0x9abc;
al->cmd_fffd[0] = al->post_points;
al->cmd_fffd[1] = al->step;
al->cmd_fffd[2] = 0x7777;
al->cmd_fffe[0] = al->start; // START
al->cmd_fffe[1] = al->oscills;
al->cmd_fffe[2] = al->temp_points;
al->cmd_ffff[0] = al->stop; // STOP
al->cmd_ffff[1] = al->crc16; // CRC16
al->cmd_ffff[2] = 0x3333;
/*
old_position = oc->current_position;
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
{
t_position = old_position;
for (k=OSCIL_CAN_NUMBER_POINTS-1;k>=0;k--)
{
if (t_position==0)
{
t_position = (OSCIL_CAN_NUMBER_POINTS+OSCIL_CAN_NUMBER_POINTS_ADD)-1;
}
else
t_position = t_position - 1;
oc->temp_oscil_buffer[i][k] = oc->oscil_buffer[i][t_position];
}
}
*/
return;
}

View File

@ -0,0 +1,135 @@
/*
* oscil_can.h
*
* Created on: 24 ìàÿ 2020 ã.
* Author: yura
*/
#ifndef SRC_LIBS_NIO12_ALARM_LOG_CAN_H_
#define SRC_LIBS_NIO12_ALARM_LOG_CAN_H_
#define CAN_BOX_PRIORITY_LOW_MAX_SIZE_BLOCKS 195L //3330L // 9999L
#define ALARM_LOG_NUMBER_BOX_IN_CAN 0
#define ALARM_LOG_CODE_STATUS_LOG_STOP 1 // Ëîã îñòàíîâëåí
#define ALARM_LOG_CODE_STATUS_LOG_RUN 2 // Ëîã èäåò...
#define ALARM_LOG_CODE_STATUS_LOG_RUN_TO_STOP 3 // Ëîã èäåò, íî èäåò äîçàïèñü, ñêîðî îñòàíîâèòñÿ.
/*
#define OSCIL_CAN_NUMBER_CHANNEL 32 // ìàêñèìàëüíîå âîçìîæíîå êîë-âî êàíàëîâ äëÿ áóôåðà
#define OSCIL_CAN_NUMBER_POINTS 500 // ìàêñèìàëüíîå âîçìîæíîå êîë-âî òî÷åê äëÿ áóôåðà (äëÿ îäíîãî êàíàëà)
#define OSCIL_TIME_WAIT 5000 // ïåðèîä ïîñûëêè âñåãî ìàññèâà â CAN (ìëñåê)
#define OSCIL_CAN_NUMBER_POINTS_ADD 100 // çàïàñ òî÷åê ïðè âûïîëíåíèè ôóíêöèè êîïèðîâàíèÿ ðàáî÷åãî áóôåðà âî âðåìåííûé. oscil_buffer->temp_oscil_buffer
#define OSCIL_CAN_NUMBER_POINTS_AFTER_STOP 100 // ñêîëüêî òî÷åê çàïèñûâàòü ïîñëå îñòàíîâêè çàïèñè áóôåðà ïî àâàðèè èëè øèìó
*/
typedef struct {
unsigned int global_enable; // ðàçðåøåíèå ïåðåäà÷è ëîãîâ
unsigned int copy2temp; // êîïèðîâàòü ëîãè â temp ïåðåä ïåðåäà÷åé
unsigned int stage;
int cmd_fffc[3];
int cmd_fffd[3];
int cmd_fffe[3];
int cmd_ffff[3];
unsigned int post_points; // êîë-âî òî÷åê ïîñëå àâàðèè
unsigned int step; // øàã îäíîé òî÷êè, ìêñåê
unsigned int start; // êîä êîìàíäû START
unsigned int oscills; // êîë-âî êàíàëîâ - êîëîíîê
unsigned long real_points; // âñåãî êîë-âî òî÷åê, ïîëíûé ðàçìåð äàííûõ ïîëó÷èì = points*oscills
// íóæíûé êóñîê äëÿ êîïèè, äàííîå êîëè÷åñòâî ñêîïèðóåòñÿ èç öèêëè÷åñêîãî áóôåðà âî âðåìåííûé ëîã.
unsigned int stop; // êîä êîìàíäû START
unsigned int crc16; // crc16 äàííûõ
int *start_adr_real_logs; // íà÷àëî ìàññèâà äàííûõ, äî êîïèðîâàíèÿ
// àäðåñ íà÷àëà ðåàëüíûõ ëîãîâ â öèêëè÷åñêîì áóôåðå
int *start_adr_temp; // íà÷àëî ìàññèâà äàííûõ, ïîñëå êîïèðîâàíèÿ
// àäðåñ äëÿ âðåìåííîãî ðàçìåùåíèÿ êîïèè ëîãà, ëîã ñêîïèðóåòñÿ èç öèêëè÷åñêîãî áóôåðà â ýòîò ðàçâåðíóâøèñü.
int *finish_adr_real_log; // îêîí÷àíèå áëîêà ëîãîâ, äî êîïèðîâàíèÿ
// êîíåö ëîãîâ â öèêëè÷åñêîì áóôåðå
int *current_adr_real_log; // óêàçàòåëü íà àäðåñ ãäå îñòàíîâèëâñü çàïèñü ëîãîâ â öèêëè÷åñêîì áóôåðå
// int *finish_adr_temp; // êîíåö ëîãà â temp áóôåðå
unsigned long temp_points; // âñåãî êîë-âî òî÷åê, ïîëíûé ðàçìåð äàííûõ ïîëó÷èì = temp_points*oscills
// ðåàëüíûé ðàçìåð öèêëè÷åñêãî áóôåðà â òî÷êàõ.
unsigned long progress_can; // îáðàòíûé ñ÷åò÷èê, ñêîëüêî îñòàëîñü ïåðåäàòü
unsigned int prev_status_alarm; // ïðåä. ñîñòîÿíèå status_alarm
unsigned int status_alarm; // êîä àâàðèè, ëîã àâòîìàòè÷åñêè ïåðåäàåòñÿ ïðè èçìåíåíèè ýòîãî ñòàòóñà èç 0->1
unsigned int timer_send; // âðåìÿ ïåðåäà÷è âñåãî áëîêà
unsigned int temp_log_ready; // ãîòîâíîñòü äàííûõ temp äëÿ ñ÷èòûâàíèÿ ïî CAN
unsigned long can_max_size_one_block; // ðàçìåð îäíîãî áëîêà ïåðåäàâàåìîãî çà ðàç, íàäî êðàòíîå 3.
void (*clear)(); // Clear buffers
void (*send)(); // Send buffers
void (*copy_temp_buffer)(); // Copy work buffers to temp buffers
void (*prepare_data_can)(); // Ïðåäâàðèòåëüíàÿ ïîäãîòîâêà ïåðåä ïåðåäà÷åé
} ALARM_LOG_CAN;
typedef ALARM_LOG_CAN *ALARM_LOG_CAN_handle;
#define ALARM_LOG_CAN_CAN_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, \
CAN_BOX_PRIORITY_LOW_MAX_SIZE_BLOCKS, \
alarm_log_clear_buffer, \
alarm_log_send_buffer, \
alarm_log_copy_temp_buffer, \
alarm_log_prepare_data_can \
}
void alarm_log_clear_buffer(ALARM_LOG_CAN_handle);
void alarm_log_send_buffer(ALARM_LOG_CAN_handle);
//void alarm_log_next_position(ALARM_LOG_CAN_handle);
void alarm_log_prepare_data_can(ALARM_LOG_CAN_handle);
void alarm_log_copy_temp_buffer(ALARM_LOG_CAN_handle);
extern ALARM_LOG_CAN alarm_log_can;
#endif /* SRC_LIBS_NIO12_ALARM_LOG_CAN_H_ */

View File

@ -0,0 +1,26 @@
//#define XLOW_FREQUENCY_MODE
#include "big_dsp_module.h"
#include "DSP281x_Device.h" // DSP281x Headerfile Include File
#include "DSP281x_Examples.h" // DSP281x Examples Include File
void setup_adr_pcb_controller()
{
EALLOW;
GpioMuxRegs.GPBMUX.bit.TDIRB_GPIOB11=0;
GpioMuxRegs.GPBDIR.bit.GPIOB11=0;
EDIS;
}
int get_adr_pcb_controller()
{
return !GpioDataRegs.GPBDAT.bit.GPIOB11;
}

View File

@ -0,0 +1,19 @@
#ifndef _BIGDSPMODULE
#define _BIGDSPMODULE
#ifdef __cplusplus
extern "C" {
#endif
void setup_adr_pcb_controller();
int get_adr_pcb_controller();
#ifdef __cplusplus
}
#endif
#endif /* _BIGDSPMODULE */

View File

@ -0,0 +1,24 @@
/*
* build_version.c
*
* Created on: 17 ÿíâ. 2022 ã.
* Author: yura
*/
#include "build_version.h"
float build_data_f = BUILD_DATA;
float build_time_f = BUILD_TIME;
int build_data_i = (BUILD_DATA*1000);
int build_time_i = (BUILD_TIME*1000);
int build_year = BUILD_YEAR;
int build_month = BUILD_MONTH;
int build_day = BUILD_DAY;

View File

@ -0,0 +1,30 @@
/*
* build_version.h
*
* Created on: 17 ÿíâ. 2022 ã.
* Author: yura
*/
#ifndef SRC_N12_LIBS_BUILD_VERSION_H_
#define SRC_N12_LIBS_BUILD_VERSION_H_
#ifndef BUILD_DATA
#define BUILD_DATA 22.00
#endif
#ifndef BUILD_TIME
#define BUILD_TIME 00.01
#endif
extern float build_data_f;
extern float build_time_f;
extern int build_data_i;
extern int build_time_i;
extern int build_year, build_month, build_day;
#endif /* SRC_N12_LIBS_BUILD_VERSION_H_ */

View File

@ -0,0 +1,194 @@
/*
* control_station.c
*
* Created on: 1 èþí. 2020 ã.
* Author: Yura
*/
#include "control_station.h"
#include "global_time.h"
#pragma DATA_SECTION(control_station, ".slow_vars")
CONTROL_STATION control_station = CONTROL_STATION_DEFAULTS;
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
void control_station_clear(CONTROL_STATION_handle cs)
{
int i,k,j;
for (i=0;i<COUNT_CONTROL_STATION;i++)
{
cs->count_error_modbus[i] = 0;
cs->count_ok_modbus[i] = 0;
cs->flag_waiting_answer[i] = 0;
cs->flag_message_sent[i] = 0;
cs->active_control_station[i] = 0;
cs->alive_control_station[i] = 0;
for (k=0;k<CONTROL_STATION_CMD_LAST;k++)
cs->array_cmd[i][k] = 0;
cs->detect_get_data_control_station[i] = 0;
cs->period_detect_active[i] = 0;
cs->setup_time_detect_active[i] = CONTROL_STATION_SETUP_TIME_DETECT_ACTIVE;
cs->setup_time_detect_active_resend_485[i] = CONTROL_STATION_SETUP_TIME_DETECT_ACTIVE_RESEND_485;
cs->setup_time_send_cmd_after_off[i] = CONTROL_STATION_SETUP_TIME_SEND_CMD_AFTER_OFF;
cs->time_detect_active[i] = 0;
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;
}
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
void control_station_update_timers(CONTROL_STATION_handle cs)
{
static unsigned int old_time = 0;
volatile int i;
if (!detect_pause_milisec(CONTROL_STATION_TIME_WAIT,&old_time))
return;
for (i=0;i<COUNT_CONTROL_STATION;i++)
{
if (cs->flag_message_sent[i] == 1)
(cs->time_detect_answer_485[i])++;
// cs->time_detect_answer_485[i] = 0;
if (cs->detect_get_data_control_station[i])
{
cs->period_detect_active[i] = cs->time_detect_active[i];
cs->time_detect_active[i] = 0;
cs->detect_get_data_control_station[i] = 0;
cs->alive_control_station[i] = 1;
}
else
{
if (cs->time_detect_active[i]>=cs->setup_time_detect_active[i])
{
cs->alive_control_station[i] = 0; // òóò ñäîõ
cs->period_detect_active[i] = 0;
// cs->flag_message_sent[i] = 0;
cs->time_detect_active[i] = cs->setup_time_detect_active[i]+1;
}
else
{
cs->time_detect_active[i]++;
// if (cs->flag_message_sent[i])
// {
// if (cs->flag_waiting_answer[i])
// cs->time_detect_active[i]++;
// else
// {
// cs->time_detect_active[i] = 0;
// }
// }
// else
// cs->time_detect_active[i]++;
}
}
}
}
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
void control_station_detect_active_station(CONTROL_STATION_handle cs)
{
}
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,134 @@
/*
* control_station.h
*
* Created on: 1 èþí. 2020 ã.
* Author: Vladislav
*/
#ifndef SRC_LIBS_NIO12_CONTROL_STATION_H_
#define SRC_LIBS_NIO12_CONTROL_STATION_H_
#include <control_station_project.h> // ãðóçèì âíåøíèå íàñòðîéêè ïðîåêòà
#include "word_structurs.h"
//////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////
#define COUNT_CONTROL_STATION CONTROL_STATION_LAST // êîë-âî ïîñòîâ óïðàâëåíèÿ
//#define COUNT_CMD_ARR_CONTROL_STATION CONTROL_STATION_LAST // êîë-âî ïîñòîâ óïðàâëåíèÿ
//////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////
#define CONTROL_STATION_TIME_WAIT 250//500 // ïåðèîä îïðîñà ìñåê
#define CONTROL_STATION_SETUP_TIME_DETECT_ACTIVE 18//12//6 // â òèêàõ îò CONTROL_STATION_TIME_WAIT
#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 // ñêîëüêî äàííûõ õðàíèì äëÿ âðåìåííîãî áóôåðà
//////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////
typedef struct {
unsigned int time_detect_active[COUNT_CONTROL_STATION]; // òåêóùèé òàéìåð äëÿ ïðîïàäàíèè ñâÿçè, ñáðàñûâàåòñÿ ïðè íàëè÷èè ñâÿçè
unsigned int period_detect_active[COUNT_CONTROL_STATION]; // ïåðèîä îáìåíà ñ ïîñòîì
unsigned int time_detect_answer_485[COUNT_CONTROL_STATION]; // òåêóùèé òàéìåð äëÿ îæèäàíèÿ îòâåòà ïî Modbus
unsigned int setup_time_detect_active[COUNT_CONTROL_STATION]; // âðåìÿ äî ñáðîñà ïðè ïðîïàäàíèè ñâÿçè
unsigned int setup_time_detect_active_resend_485[COUNT_CONTROL_STATION]; // âðåìÿ äî ñáðîñà ïðè ïðîïàäàíèè ñâÿçè, äîëæåí áûòü ìåíüøå setup_time_detect_active
unsigned int setup_time_send_cmd_after_off[COUNT_CONTROL_STATION]; // âðåìÿ çàäåðæêè íà ïåðåêëþ÷åíèå êîìàíä, íàïðèìåð íà Go. ×òîá íå áûëî äðåáåçãà íà âêë/âûêë.
unsigned int active_control_station[COUNT_CONTROL_STATION]; // àêòèâíûé ïîñò óïðàâëåíèÿ, âîçìîæíî èõ ìîæåò áûòü íåñêîëüêî îäíîâðåìåííî?
unsigned int detect_get_data_control_station[COUNT_CONTROL_STATION]; // åñëè åñòü îáìåí ñ ïîñòîì, òî âûñòàâëÿåì òóò ôëàã, îí ñáðîñèòñÿ ïðè update_timers
unsigned int alive_control_station[COUNT_CONTROL_STATION]; // ôëàã î òîì ÷òî ñâÿçü ñ ïîñòîì åñòü
int array_cmd[COUNT_CONTROL_STATION][CONTROL_STATION_CMD_LAST]; // ìàññèâ äàííûõ ïîëó÷åííûõ îò êàæäîãî èç ïîñòîâ, äàííûå ïîñëå parse
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]; // îæèäàòü ëè îòâåò ïî ñèñòåìå çàïðîñ-îòâåò
unsigned int count_ok_modbus[COUNT_CONTROL_STATION]; // ñ÷åò÷èê îøèáîê ïî êîìàíäå modbus 15
unsigned int count_error_modbus[COUNT_CONTROL_STATION]; // ñ÷åò÷èê îøèáîê ïî êîìàíäå modbus 15
unsigned int flag_refresh_array[COUNT_CONTROL_STATION]; // ôëàã íà îæèäàíèå îáíîâëåíèÿ äàííûõ îò modbus
/*
unsigned int cmd_go_from_control_station[COUNT_CONTROL_STATION]; // cmd_go îò ïîñòà ïóñê/ñòîï ØÈÌà
unsigned int set_izad_from_control_station[COUNT_CONTROL_STATION]; // òîê îò ïîñòà
unsigned int set_rotor_from_control_station[COUNT_CONTROL_STATION]; // îáîðîòû îò ïîñòà
unsigned int cmd_charge_from_control_station[COUNT_CONTROL_STATION]; // ñáîð ñõåìû îò ïîñòà
unsigned int cmd_uncharge_from_control_station[COUNT_CONTROL_STATION]; // ðàçáîð ñõåìû îò ïîñòà
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)(); // Îáíóëÿåì òàéìåðû íà ïîñòàõ ñ êîòîðûìè åñòü îáìåí
void (*detect_active_station)(); // îïðåäåëÿåì êàêîé ïîñò àêòèâåí
} CONTROL_STATION;
typedef CONTROL_STATION *CONTROL_STATION_handle;
#define CONTROL_STATION_DEFAULTS { \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
{0}, \
control_station_clear, \
control_station_update_timers, \
control_station_detect_active_station \
}
void control_station_clear(CONTROL_STATION_handle);
void control_station_update_timers(CONTROL_STATION_handle);
void control_station_detect_active_station(CONTROL_STATION_handle);
extern CONTROL_STATION control_station;
#endif /* SRC_LIBS_NIO12_CONTROL_STATION_H_ */

View File

@ -0,0 +1,367 @@
#include "IQmathLib.h"
#include "DSP281x_Examples.h" // DSP281x Examples Include File
#include "DSP281x_Device.h" // DSP281x Headerfile Include File
#include "filter_v1.h"
//#include "filter.h"
//#include "myfir16.h"
/*
#define IIR16_COEFF {\
-10304,25264,4493,8986,4493}
#define IIR16_ISF 1298
#define IIR16_NBIQ 1
#define IIR16_QFMAT 14
#define FIR16_COEFF_50_75HZ {\
4927,-1568135,-2289592,-2814717,-2881240,-2030268,471,3407677,7601571,11730182,\
14023990,12910061,6880988,-4194369,-19136408,-34799420,-46792491,-49938254,-39649165,-12779469,\
30867456,88408033,153681876,218365909,273219549,309985256}
#define FIR16_COEFF_58 {\
1165,2622601,2884733,3409000,4129869,5178410,6489088,8127441,10093469,12387172,\
15008553,17957610,21168811,24707691,28443180,32375278,36438450,40567161,44761411,48890130,\
53018853,56885437,60620954,64028796,67108963,69861455,72155199,73924660,75300908,76087336,\
}
#define FIR16_COEFF_WROTOR {\
316,1245500,1245499,1245499,1245498,1311034,1376569,1376568,1442103,1507637,\
1573172,1638706,1769776,1835310,1966380,2031914,2162984,2294053,2425123,2556192,\
2752797,2883866,3080471,3211539,3408144,3604749,3801353,3997957,4194562,4391166,\
4653306,4849910,5112050,5308653,5570793,5832933,6095072,6357212,6619351,6881491,\
7143630,7471306,7733445,7995584,8323260,8585399,8913074,9240749,9502889,9830564,\
10158239,10420379,10748054,11075729,11337869,11665544,11993219,12320895,12583034,12910710,\
13238386,13500525,13828201,14090341,14418017,14680157,15007833,15269973,15532113,15859790,\
16121930,16384071,16646211,16908352,17104957,17367098,17629239,17825844,18022449,18284591,\
18481196,18677802,18874407,19071013,19202083,19398689,19529759,19660830,19791900,19922971,\
20054041,20185112,20250647,20381718,20447253,20512789,20578324,20578323,20643859,20643859,\
20709395}
*/
/* Filter Symbolic Constants */
//#define FIR_ORDER_58 58
//#define FIR_ORDER_50_75HZ 50
//#define FIR16_COEFF {\
// 16519,532422588}
/* Filter Symbolic Constants */
//#define FIR_ORDER 2
/* Create an Instance of FIRFILT_GEN module and place the object in "firfilt" section */
//#pragma DATA_SECTION(fir, "firfilt");
//FIR16 fir = FIR16_DEFAULTS;
//FIR16 fir_58 = FIR16_DEFAULTS;
//FIR16 fir_wrotor = FIR16_DEFAULTS;
//FIR16 fir_50_75hz_0 = FIR16_DEFAULTS;
/*
FIR16 fir_50_75hz_1 = FIR16_DEFAULTS;
FIR16 fir_50_75hz_2 = FIR16_DEFAULTS;
FIR16 fir_50_75hz_3 = FIR16_DEFAULTS;
FIR16 fir_50_75hz_4 = FIR16_DEFAULTS;
FIR16 fir_50_75hz_5 = FIR16_DEFAULTS;
*/
/* Define the Delay buffer for the 50th order filterfilter and place it in "firldb" section */
//#pragma DATA_SECTION(dbuffer_fir,"firldb");
//long dbuffer_fir[(FIR_ORDER+2)/2];
//long dbuffer_fir_50_75hz_0[(FIR_ORDER_50_75HZ+2)/2];
/*long dbuffer_fir_50_75hz_1[(FIR_ORDER_50_75HZ+2)/2];
long dbuffer_fir_50_75hz_2[(FIR_ORDER_50_75HZ+2)/2];
long dbuffer_fir_50_75hz_3[(FIR_ORDER_50_75HZ+2)/2];
long dbuffer_fir_50_75hz_4[(FIR_ORDER_50_75HZ+2)/2];
long dbuffer_fir_50_75hz_5[(FIR_ORDER_50_75HZ+2)/2];
*/
//#pragma DATA_SECTION(dbuffer_fir_58,"firldb");
//long dbuffer_fir_58[(FIR_ORDER_58+2)/2];
//#pragma DATA_SECTION(dbuffer_fir_wrotor,"firldb");
/* Define Constant Co-efficient Array and place the
.constant section in ROM memory */
//long const coeff_fir[(FIR_ORDER+2)/2]= FIR16_COEFF;
//long const coeff_fir_58[(FIR_ORDER_58+2)/2]= FIR16_COEFF_58;
//long const coeff_fir_50_75hz_0[(FIR_ORDER_50_75HZ+2)/2]= FIR16_COEFF_50_75HZ;
/*long const coeff_fir_50_75hz_1[(FIR_ORDER_50_75HZ+2)/2]= FIR16_COEFF_50_75HZ;
long const coeff_fir_50_75hz_2[(FIR_ORDER_50_75HZ+2)/2]= FIR16_COEFF_50_75HZ;
long const coeff_fir_50_75hz_3[(FIR_ORDER_50_75HZ+2)/2]= FIR16_COEFF_50_75HZ;
long const coeff_fir_50_75hz_4[(FIR_ORDER_50_75HZ+2)/2]= FIR16_COEFF_50_75HZ;
long const coeff_fir_50_75hz_5[(FIR_ORDER_50_75HZ+2)/2]= FIR16_COEFF_50_75HZ;
*/
/* Finter Input and Output Variables */
/* Create an Instance of IIR5BIQD16 module and place the object in "iirfilt" section */
//#pragma DATA_SECTION(iir, "iirfilt");
//IIR5BIQ16 iir = IIR5BIQ16_DEFAULTS;
/* =============================================================================
Modify the delay buffer size to comensurate with the no of biquads in the filter
Size of the Delay buffer=2*nbiq
==============================================================================*/
/* Define the Delay buffer for the cascaded 6 biquad IIR filter and place it in "iirfilt" section */
//#pragma DATA_SECTION(dbuffer_iir,"iirfilt");
//int dbuffer_iir[2*IIR16_NBIQ];
/* =============================================================================
Modify the array size and symbolic constant to suit your filter requiremnt.
Size of the coefficient array=5*nbiq
==============================================================================*/
/* Define the Delay buffer for the cascaded 6 biquad IIR filter and place it in "iirfilt" section */
//const int coeff_iir[5*IIR16_NBIQ]=IIR16_COEFF;
/*
void init_my_filter_fir()
{
// FIR Generic Filter Initialisation
fir.order=FIR_ORDER;
fir.dbuffer_ptr=dbuffer_fir;
fir.coeff_ptr=(long *)coeff_fir;
fir.init(&fir);
}
void init_my_filter_fir_50_75hz()
{
// FIR Generic Filter Initialisation
fir_50_75hz_0.order=FIR_ORDER_50_75HZ;
fir_50_75hz_0.dbuffer_ptr=dbuffer_fir_50_75hz_0;
fir_50_75hz_0.coeff_ptr=(long *)coeff_fir_50_75hz_0;
fir_50_75hz_0.init(&fir_50_75hz_0);
}
//#pragma CODE_SECTION(calc_my_filter_fir,".fast_run");
int calc_my_filter_fir(int xn)
{
int yn;
// xn=sgen.out;
fir.input=xn;
fir.calc(&fir);
yn=fir.output;
return yn;
}
void init_my_filter_fir_58()
{
// FIR Generic Filter Initialisation
fir_58.order=FIR_ORDER_58;
fir_58.dbuffer_ptr=dbuffer_fir_58;
fir_58.coeff_ptr=(long *)coeff_fir_58;
fir_58.init(&fir_58);
}
//#pragma CODE_SECTION(calc_my_filter_fir_58,".fast_run");
int calc_my_filter_fir_58(int xn)
{
int yn;
// xn=sgen.out;
fir_58.input=xn;
fir_58.calc(&fir_58);
yn=fir_58.output;
return yn;
}
void calc_my_filter_fir_50_75hz(_iq xn_0,_iq xn_1,_iq xn_2,_iq xn_3,_iq xn_4,_iq xn_5,
_iq *yn_0,_iq *yn_1,_iq *yn_2,_iq *yn_3,_iq *yn_4,_iq *yn_5)
{
fir_50_75hz_0.input=_IQtoIQ15(xn_0);
fir_50_75hz_0.calc(&fir_50_75hz_0);
*yn_0=_IQ15toIQ(fir_50_75hz_0.output);
}
void init_my_filter_iir()
{
// IIR Filter Initialisation
iir.dbuffer_ptr=dbuffer_iir;
iir.coeff_ptr=(int *)coeff_iir;
iir.qfmat=IIR16_QFMAT;
iir.nbiq=IIR16_NBIQ;
iir.isf=IIR16_ISF;
iir.init(&iir);
}
//#pragma CODE_SECTION(calc_my_filter_iir,".fast_run");
int calc_my_filter_iir(int xn)
{
int yn;
// xn=sgen.out;
iir.input=xn;
iir.calc(&iir);
yn=iir.output;
return yn;
}
*/
#pragma CODE_SECTION(exp_regul_iq19,".fast_run");
_iq19 exp_regul_iq19(_iq19 k_exp_regul, _iq19 InpVarCurr, _iq19 InpVarInstant)
{
_iq19 t1;
t1 = (InpVarCurr + _IQ19mpy( (InpVarInstant-InpVarCurr), k_exp_regul));
return t1;
}
#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;
t1 = (InpVarFiltered + _IQmpy( (InpVarInstant-InpVarFiltered), k_exp_regul));
return t1;
}
#pragma CODE_SECTION(exp_regul_iq,".fast_run");
void exp_regul_iq_fast(_iq k_exp_regul, _iq *InpVarCurr, _iq InpVarInstant)
{
_iq t1;
volatile _iq t2,t3,t4;
t2 = (InpVarInstant- *InpVarCurr);
t3 = _IQmpy( t2, k_exp_regul);
t4 = *InpVarCurr + t3;
t1 = t4;
*InpVarCurr = t1;
// t1 = (InpVarCurr + _IQmpy( (InpVarInstant-InpVarCurr), k_exp_regul));
// return t1;
}
/*
_iq18 filter_1p(_iq18 predx,_iq18 predy, _iq18 inpx)
{
_iq18 t1;
t1 = _IQ18mpy(k1_filter_1p_fast,(predx+inpx))+_IQ18mpy(k2_filter_1p_fast,predy);
return t1;
}
*/
/*
void init_filter_batter2()
{
u_filter_batter2[0]=0;
u_filter_batter2[1]=0;
u_filter_batter2[2]=0;
i_filter_batter2[0]=0;
i_filter_batter2[1]=0;
i_filter_batter2[2]=0;
k_filter_batter2[0]=_IQ(K1_FILTER_BATTER2_3HZ);
k_filter_batter2[1]=_IQ(K2_FILTER_BATTER2_3HZ);
k_filter_batter2[2]=_IQ(K3_FILTER_BATTER2_3HZ );
}
//#pragma CODE_SECTION(filter_batter2,".fast_run");
_iq filter_batter2(_iq InpVarCurr)
{
_iq y;
y = _IQmpy(k_filter_batter2[0],( InpVarCurr + _IQmpyI32(i_filter_batter2[0],2) + i_filter_batter2[1] ) ) +
_IQmpy(k_filter_batter2[1], u_filter_batter2[0]) + _IQmpy(k_filter_batter2[2], u_filter_batter2[1]);
u_filter_batter2[1]=u_filter_batter2[0];
u_filter_batter2[0]=y;
i_filter_batter2[1]=i_filter_batter2[0];
i_filter_batter2[0]=InpVarCurr;
return y;
}
*/

View File

@ -0,0 +1,73 @@
#ifndef _MY_FILTER
#define _MY_FILTER
#ifdef __cplusplus
extern "C" {
#endif
#include "IQmathLib.h"
//#include "filter.h"
//#include "myfir16.h"
#define k1_filter_1p_fast 62643 // 0.238965*262144
#define k2_filter_1p_fast 136857 // 0.52207*262144
#define k3_filter_1p_fast2 8552
#define filter_1p_fast(predx, predy,inpx) predy=_IQ18mpy(k1_filter_1p_fast,(predx+inpx))+_IQ18mpy(k2_filter_1p_fast,predy);predx=inpx
#define filter_1p_fast2(predx, predy,inpx) predy=_IQ18mpy(k3_filter_1p_fast2,(predx+inpx));predx=inpx
//extern FIR16 fir;
//extern FIR16 fir_wrotor;
//extern IIR5BIQ16 iir;
void init_my_filter_fir();
int calc_my_filter_fir(int xn);
void init_my_filter_fir_58();
int calc_my_filter_fir_58(int xn);
void calc_my_filter_fir_50_75hz(_iq xn_0,_iq xn_1,_iq xn_2,_iq xn_3,_iq xn_4,_iq xn_5,
_iq *yn_0,_iq *yn_1,_iq *yn_2,_iq *yn_3,_iq *yn_4,_iq *yn_5);
void init_my_filter_fir_50_75hz();
void init_my_filter_iir();
int calc_my_filter_iir(int xn);
_iq19 exp_regul_iq19(_iq19 k_exp_regul, _iq19 InpVarCurr, _iq19 InpVarInstant);
_iq exp_regul_iq(_iq k_exp_regul, _iq InpVarFiltered, _iq InpVarInstant);
_iq18 filter_1p(_iq18 predx,_iq18 predy, _iq18 inpx);
void exp_regul_iq_fast(_iq k_exp_regul, _iq *InpVarCurr, _iq InpVarInstant);
#ifdef __cplusplus
}
#endif
#endif /* _MY_FILTER */

View File

@ -0,0 +1,149 @@
#include "global_time.h"
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;
global_time.freq_pwm_hz = freq_pwm;
global_time.microseconds_add = 1000000L / global_time.freq_pwm_hz;
}
#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;
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)
{
gt->minuts++;
gt->seconds = 0;
if(gt->minuts == 60)
{
gt->hours++;
gt->minuts = 0;
}
}
}
//gt->total_seconds10 += 10;
gt->total_seconds10full = gt->total_seconds10 + miliseconds_temp10/100;
}
void init_timer_sec(unsigned int *start_time)
{
*start_time = global_time.total_seconds;
}
void init_timer_milisec(unsigned int *start_time)
{
*start_time = global_time.miliseconds;
}
int detect_pause_sec(unsigned int wait_pause, unsigned int *old_time)
{
unsigned long delta;
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)
{
*old_time = (unsigned int)global_time.total_seconds;
return 1;
}
else
return 0;
}
int detect_pause_milisec(unsigned int wait_pause, unsigned int *old_time)
{
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 (delta>=wait_pause)
{
*old_time = (unsigned int)global_time.miliseconds;
return 1;
}
else
return 0;
}
unsigned int get_delta_milisec(unsigned int *old_time, unsigned int upd)
{
unsigned long delta;
if(global_time.miliseconds >= *old_time)
{
delta = (unsigned int)((unsigned int)global_time.miliseconds - *old_time);
}
else
{
delta = (unsigned int)((unsigned int)global_time.miliseconds + (0xFFFFUL - *old_time));
}
if (upd)
*old_time = (unsigned int)global_time.miliseconds;
return delta;
}

View File

@ -0,0 +1,58 @@
#ifndef _GLOBAL_TIME
#define _GLOBAL_TIME
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;
unsigned int hours;
unsigned int freq_pwm_hz;
unsigned int microseconds_add;
void (*calc)(); //Ñ÷èòàåò â ïðåðûâàíèè ØÈÌ'à
} GLOBAL_TIME;
typedef GLOBAL_TIME *GLOBAL_TIME_handle;
void global_time_calc(GLOBAL_TIME_handle);
void init_global_time_struct(unsigned int freq_pwm);
/*-----------------------------------------------------------------------------
Default initalizer for the GLOBAL_TIME object.
-----------------------------------------------------------------------------*/
#define GLOBAL_TIME_DEFAULTS { 0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
global_time_calc \
}
/*------------------------------------------------------------------------------
Prototypes for the functions in global_time.c
------------------------------------------------------------------------------*/
extern GLOBAL_TIME global_time;
void init_timer_sec(unsigned int *start_time); //Èíèöèàëèçèðóåò ïåðåìåííóþ, âðåìß ñòàðòà â ñåêóíäàõ
void init_timer_milisec(unsigned int *start_time); //Èíèöèàëèçèðóåò ïåðåìåííóþ, âðåìß ñòàðòà â ìèëèñåêóíäàõ
int detect_pause_sec(unsigned int wait_pause, unsigned int *old_time); //ïàóçà â ñåêóíäàõ
int detect_pause_milisec(unsigned int wait_pause, unsigned int *old_time); //Ïàóçà â ìèëèñåêóíäàõ (íå áîëåå 60000ìëñåê)
unsigned int get_delta_milisec(unsigned int *old_time, unsigned int upd); // âåðíóëè ñêîëüêî âðåìåíè ïðîøëî îò âðåìåíè old_time ; upd=1 - îáíîâèòü old_time - òåêóùèì
#endif //_GLOBAL_TIME

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -0,0 +1,50 @@
/*
* math_pi.h
*
* Created on: 6 íîÿá. 2020 ã.
* Author: stud
*/
#ifndef SRC_LIBS_NIO12_MATH_PI_H_
#define SRC_LIBS_NIO12_MATH_PI_H_
#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_PI6 8784530 //30
#define CONST_IQ_PI3 17569060 // 60
#define CONST_IQ_PI05 26353589 // 90
#define CONST_IQ_PI 52707178 // 180
//#define CONST_IQ_OUR1 35664138 //
#define CONST_IQ_2PI 105414357 // 360
#define CONST_IQ_120G 35138119 // 120 grad
#define CONST_IQ_3 50331648 // 3
//#define IQ_ALFA_SATURATION1 15099494//16441671//15099494
//#define IQ_ALFA_SATURATION2 1677721//16441671//15099494
#define PI 3.1415926535897932384626433832795
#endif /* SRC_LIBS_NIO12_MATH_PI_H_ */

437
Inu/Src/N12_Libs/mathlib.c Normal file
View File

@ -0,0 +1,437 @@
/*
ÖÍÈÈ ÑÝÒ (ñ) 2002 ã.
Processor: TMS320C32
Filename: vector_troll.h
ÑÈÑÒÅÌÀ ÂÅÊÒÎÐÍÎÃÎ ÓÏÐÀÂËÅÍÈy
Edit date: 04-12-02
Function:
Revisions:
*/
#include "IQmathLib.h"
#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"
_iq SQRT_32 = _IQ(0.8660254037844);
_iq CONST_23 = _IQ(2.0/3.0);
_iq CONST_15 = _IQ(1.5);
#define real float
float my_satur_float(float Input, float Positive, float Negative, float DeadZone)
{
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)
{
if (DeadZone!=0 && Input>-DeadZone && Input<DeadZone)
Input = 0;
else
if (Input>=Positive) Input=Positive;
else
if (Input<=Negative) Input=Negative;
return Input;
}
/*
real pid_regul(real Kp_regul, real Tperiod_regul, real Minimum, real Maximum,
real yk, real *uk1, real *yk1, real *yzad, real *ek, real *ek1, real *ek2,
real d0, real d1, real d2)
{
real uk;
*ek = - yk + *yzad;
uk = *uk1 + Kp_regul * ( d0 * *ek + d1 * *ek1 + d2 * *ek2 );
if (uk>Maximum) uk=Maximum;
if (uk<Minimum) uk=Minimum;
*yk1 = yk;
*ek2 = *ek1;
*ek1 = *ek;
*uk1 = uk;
return uk;
}
real pid_regul2(real Kp_regul, real Tperiod_regul, real Minimum, real Maximum,
real yk, real *uk1, real *yk1, real *yk2, real *yzad,
real d0, real d1, real d2)
{
real uk;
uk = *uk1 + Kp_regul * ( *yk1 - yk + d1 * ( *yzad - yk ) + d2 * ( 2 * *yk1 - *yk2 - yk ) );
if (uk>Maximum) uk=Maximum;
if (uk<Minimum) uk=Minimum;
*yk2 = *yk1;
*yk1 = yk;
*uk1 = uk;
return uk;
}
real pi_regul(real Kp_regul, real Tintegral_regul, real Tperiod_regul, real Minimum, real Maximum, real InpVar, real *VarIntegral)
{
real VarProp, VarOut;
*VarIntegral += InpVar*Tperiod_regul/Tintegral_regul;
VarProp = InpVar*Kp_regul;
if (*VarIntegral>Maximum) *VarIntegral=Maximum;
if (*VarIntegral<Minimum) *VarIntegral=Minimum;
VarOut = *VarIntegral+VarProp;
if (VarOut>Maximum) VarOut=Maximum;
if (VarOut<Minimum) VarOut=Minimum;
return VarOut;
}
real exp_regul(real Tperiod_regul, real Texp_regul, real InpVarCurr, real InpVarInstant)
{
real VarOut;
VarOut = InpVarCurr + Tperiod_regul*(InpVarInstant-InpVarCurr)/Texp_regul;
return VarOut;
}
*/
float zad_intensiv(float StepP, float StepN, float InpVarCurr, float InpVarInstant)
{
float deltaVar, VarOut;
deltaVar = InpVarInstant-InpVarCurr;
if ((deltaVar>StepP) || (deltaVar<-StepN))
{
if (deltaVar>0) InpVarCurr += StepP;
else InpVarCurr -= StepN;
}
else
InpVarCurr=InpVarInstant;
VarOut = InpVarCurr;
return VarOut;
}
#pragma CODE_SECTION(zad_intensiv_q,".fast_run");
_iq zad_intensiv_q(_iq StepP, _iq StepN, _iq InpVarCurr, _iq InpVarInstant)
{
_iq deltaVar, VarOut;
deltaVar = InpVarInstant-InpVarCurr;
if ((deltaVar>StepP) || (deltaVar<-StepN))
{
if (deltaVar>0) InpVarCurr += StepP;
else InpVarCurr -= StepN;
}
else
InpVarCurr=InpVarInstant;
VarOut = InpVarCurr;
return VarOut;
}
real pi_regul3(real Kp_regul, real ki_regul, real Tperiod_regul, real Minimum, real Maximum,
real InpVar, real *InpVarPrev, real *OutVarPrev)
{
real VarOut;
VarOut = Kp_regul*(ki_regul/Kp_regul*Tperiod_regul/2.0+1)*InpVar + Kp_regul*(ki_regul/Kp_regul*Tperiod_regul/2.0-1) * (*InpVarPrev) + *OutVarPrev;
if (VarOut>Maximum) VarOut=Maximum;
if (VarOut<Minimum) VarOut=Minimum;
*InpVarPrev = InpVar;
*OutVarPrev = VarOut;
return VarOut;
}
real pi_regul4(real Kp_regul, real ki_regul, real Tperiod_regul, real Minimum, real Maximum,
real InpVar, real *InpVarPrev, real *OutVarPrev)
{
real VarOut;
VarOut = Kp_regul*InpVar + Kp_regul*(ki_regul/Kp_regul*Tperiod_regul-1) * (*InpVarPrev) + *OutVarPrev;
if (VarOut>Maximum) VarOut=Maximum;
if (VarOut<Minimum) VarOut=Minimum;
*InpVarPrev = InpVar;
*OutVarPrev = VarOut;
return VarOut;
}
/********************************************************************/
/* Ðàñ÷åò ìîäóëy òîêà èç ïîêàçàíèé òðåõ ôàç */
/********************************************************************/
#pragma CODE_SECTION(im_calc,".fast_run");
_iq im_calc( _iq ia, _iq ib, _iq ic)
{
_iq isa,isb, t;
isa = _IQmpy(CONST_15,ia);
isb = _IQmpy(SQRT_32,ib-ic );
// ( _IQ19mpy(SQRT_32, _IQ15toIQ19(ib)) - _IQ15mpy(SQRT_32, _IQ15toIQ19(ic)) );
t = _IQmag(isa,isb);
t = _IQmpy(CONST_23,t);
return (t);
}
float exp_regul(float Tperiod_regul, float Texp_regul, float InpVarCurr, float InpVarInstant)
{
float VarOut;
VarOut = InpVarCurr + Tperiod_regul*(InpVarInstant-InpVarCurr)/Texp_regul;
return VarOut;
}
_iq calc_rms_array_simple(RMS_CALC_ARRAY *v) {
_iq summ_squares = 0;
int i = 0;
if (v->data_array == 0) return 0;
for (i = 0; i < v->size_array; ++i) {
summ_squares += _IQmpy(v->data_array[i], v->data_array[i]);
}
return _IQsqrt(summ_squares / v->size_array);
}
//_iq calc_rms_array_var_period(RMS_CALC_ARRAY_THINNING *v) {
// _iq summ_squares = 0;
// int i = 0;
// int count_elem = 0;
// if (v->signal_period > v->size_array) {
// v->signal_period = v->size_array;
// }
// count_elem = v->signal_period;
// i = v->last_elem_position;
// while (count_elem > 0) {
// summ_squares += _IQmpy(v->data_array[i], v->data_array[i]);
// i -= 1;
// if (i < 0) { i = v->size_array - 1; }
// count_elem -= 1;
//
// }
// v->Out_rms = _IQsqrt(summ_squares / v->signal_period);
// return v->Out_rms;
//}
_iq calc_rms_array_var_period_IQ15(RMS_CALC_ARRAY_THINNING *v) {
_iq16 summ_squares = 0;
int i = 0;
int count_elem = 0;
if (v->data_array == 0) {
return 0;
}
if (v->signal_period > v->size_array) {
v->signal_period = v->size_array;
}
count_elem = v->signal_period;
i = v->last_elem_position;
while (count_elem > 0) {
summ_squares += 0;//_IQ15mpy(v->data_array[i], v->data_array[i]);
i -= 1;
if (i < 0) { i = v->size_array - 1; }
count_elem -= 1;
}
v->Out_rms =_IQ15toIQ(_IQ15sqrt(summ_squares / v->signal_period));
return v->Out_rms;
}
float fast_round(float x)
{
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;
}
return (float)i;
}
float fast_round_with_delta(float prev, float x, float delta)
{
float d;
long i;
i = (long)x;
if (x<0)
{
d = i - x;
if (d>=0.5)
i = i - 1;
}
else
{
d = x - i;
if (d>=0.5)
i = i + 1;
}
if (fabs(prev-x)>=delta)
return (float)i;
else
return (float)prev;
}
float fast_round_with_limiter(float x, float lim)
{
float d;
long i;
if (fabs(x)<=lim)
return 0;
i = (long)x;
if (x<0)
{
d = i - x;
if (d>=0.5)
i = i - 1;
}
else
{
d = x - i;
if (d>=0.5)
i = i + 1;
}
return (float)i;
}
#pragma CODE_SECTION(calc_rms,".fast_run");
_iq calc_rms(_iq input, _iq input_prev, _iq freq_signal)
{
static _iq pi_pwm = _IQ(PI*NORMA_FROTOR/(FREQ_PWM/5.0));
_iq cosw, sinw, wdt, y2, z1, z2, z3, y;
wdt = _IQmpy(pi_pwm,freq_signal);
sinw = _IQsinPU(wdt);
cosw = _IQcosPU(wdt);
if (cosw==0)
return 0;
z1 = input_prev - _IQmpy(input,cosw);
// z2 = sinw;
z3 = _IQdiv(z1,sinw);
y2 = _IQmpy(input,input)+_IQmpy(z3,z3);
// cosw = _IQsin();
y = _IQsqrt(y2);
return y;
}

View File

@ -0,0 +1,81 @@
#ifndef _MATHLIB
#define _MATHLIB
#include "IQmathLib.h"
/*
real pi_regul(real Kp_regul, real Tintegral_regul, real Tperiod_regul,
real Minimum, real Maximum, real InpVar, real *VarIntegral);
real exp_regul(real Tperiod_regul, real Texp_regul, 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,
real d0, real d1, real d2);
real pid_regul(real Kp_regul, real Tperiod_regul, real Minimum, real Maximum,
real yk, real *uk1, real *yk1, real *yzad, real *ek, real *ek1, real *ek2,
real d0, real d1, real d2);
real pi_regul3(real Kp_regul, real ki_regul, real Tperiod_regul, real Minimum, real Maximum,
real InpVar, real *InpVarPrev, real *OutVarPrev);
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);
float exp_regul(float Tperiod_regul, float Texp_regul, float InpVarCurr, float InpVarInstant);
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);
#define exp_regul_fast(Tperiod_regul,Texp_regul,InpVarCurr,InpVarInstant) (InpVarCurr + Tperiod_regul*(InpVarInstant-InpVarCurr)/Texp_regul)
typedef struct {
_iq *data_array;
int size_array;
_iq (*calc)();
} RMS_CALC_ARRAY;
#define RMS_CALC_DEFAULTS { 0,0, calc_rms_array_simple}
_iq calc_rms_array_simple(RMS_CALC_ARRAY *v);
typedef struct {
_iq16 *data_array;
int size_array;
int last_elem_position;
int signal_period;
_iq Out_rms;
_iq (*calc)();
} RMS_CALC_ARRAY_THINNING;
#define RMS_CALC_THINNING_DEFAULTS { 0,0,0,0,0, calc_rms_array_var_period_IQ15}
_iq calc_rms_array_var_period(RMS_CALC_ARRAY_THINNING *v);
_iq calc_rms_array_var_period_IQ15(RMS_CALC_ARRAY_THINNING *v);
float fast_round(float x);
float fast_round_with_limiter(float x, float lim);
float fast_round_with_delta(float prev, float x, float delta);
_iq calc_rms(_iq input, _iq input_prev, _iq freq_signal);
#endif

View File

@ -0,0 +1,89 @@
#include "modbus_table_v2.h"
#include "DSP281x_Examples.h" // DSP281x Examples Include File
#include "DSP281x_Device.h" // DSP281x Headerfile Include File
#include "RS_Functions.h"
#include "xp_project.h"
//#include "modbus_fill_table.h"
//#include "adc_tools.h"
//#include "can_setup.h"
//#include "isolation.h"
//#include "rotation_speed.h"
// #include "IQmathLib.h"
//#include "errors.h"
//#include "params.h"
//#include "can_watercool.h"
// #include "doors_control.h"
#pragma DATA_SECTION(modbus_table_rs_in,".logs");
MODBUS_REG_STRUCT modbus_table_rs_in[SIZE_MODBUS_TABLE];
#pragma DATA_SECTION(modbus_table_rs_out,".logs");
MODBUS_REG_STRUCT modbus_table_rs_out[SIZE_MODBUS_TABLE];
#pragma DATA_SECTION(modbus_table_can_in,".logs");
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];
void clear_modbus_table_in()
{
int i;
for (i=0;i<SIZE_MODBUS_TABLE;i++)
{
modbus_table_rs_in[i].all = 0;
modbus_table_can_in[i].all = 0;
}
}
void clear_modbus_table_out()
{
int i;
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;
}
}
void initModbusTable(void) {
/* modbus_table_rs_in = modbus_table_mpu_in;
modbus_table_can_in = modbus_table_mpu_in;
modbus_table_rs_out = modbus_table_mpu_out;
modbus_table_can_out = modbus_table_mpu_out;
*/
clear_modbus_table_in();
clear_modbus_table_out();
}
void copy_from_can_out_to_rs_out(void)
{
int i;
// modbus_table_can_out[0].all = 0;
for (i=0;i<SIZE_MODBUS_TABLE;i++)
{
modbus_table_rs_out[i].all = modbus_table_can_out[i].all;
}
}

View File

@ -0,0 +1,42 @@
#ifndef _MODBUS_TABLE_V2
#define _MODBUS_TABLE_V2
//#include "RS_Functions_modbus.h"
#include "modbus_struct.h"
#ifdef __cplusplus
extern "C" {
#endif
//#define ADR_MODBUS_TABLE 0x0001
#define ADR_MODBUS_TABLE 0x0001
#define ADR_MODBUS_TABLE_REMOUTE 0x0000
//#define SIZE_MODBUS_TABLE 820 //409 // 21300 //700 // 745.2
#define SIZE_MODBUS_TABLE 250 //490
//#define ADR_CAN_TEST_PLUS_ONE 28
//#define ADR_CAN_TEST_PLUS_TWO 18
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];
void clear_modbus_table_in();
void clear_modbus_table_out();
void copy_from_can_out_to_rs_out(void);
void initModbusTable(void);
#ifdef __cplusplus
}
#endif
#endif /* _MODBUS_TABLE_V2 */

File diff suppressed because it is too large Load Diff

View File

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

View File

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

View File

@ -0,0 +1,37 @@
//#include "RS_Functions_modbus.h"
#include "options_table.h"
#include "DSP281x_Device.h"
#include "MemoryFunctions.h"
#pragma DATA_SECTION(options_controller, ".slow_vars")
MODBUS_REG_STRUCT options_controller[SIZE_OPTIONS_TABLE];
int store_data_flash(MODBUS_REG_STRUCT *modbus_t, unsigned int size)
{
volatile unsigned long Address1, Address2;
volatile unsigned long Length, LengthW;
unsigned int cerr, repl, count_ok;
Address1 = (unsigned long)modbus_t;
Address2 = ADR_STORE_OPTION_TO_FLASH;
LengthW = size;
if( (Address2 < 0x100000) || (Address2 > 0x180000) || ((Address2+LengthW) > 0x180000) )
{
return 1;
}
RunFlashData(Address1,Address2,LengthW, &cerr, &repl, &count_ok );
return 0;
}

View File

@ -0,0 +1,17 @@
#ifndef _OPTIONS_TABLE_H
#define _OPTIONS_TABLE_H
#include "modbus_struct.h"
#define ADR_STORE_OPTION_TO_FLASH 0x16000
#define SIZE_OPTIONS_TABLE 200
extern MODBUS_REG_STRUCT options_controller[SIZE_OPTIONS_TABLE];
int store_data_flash(MODBUS_REG_STRUCT *modbus_t, unsigned int size);
#endif // end _OPTIONS_TABLE_H

View File

@ -0,0 +1,293 @@
/*
* oscil_can.c
*
* Created on: 24 ìàÿ 2020 ã.
* Author: yura
*/
#include "oscil_can.h"
#include "CAN_Setup.h"
#include "global_time.h"
#pragma DATA_SECTION(oscil_can, ".slow_vars")
OSCIL_CAN oscil_can = OSCIL_CAN_DEFAULTS;
//int oscil_buffer[OSCIL_CAN_NUMBER_CHANNEL][OSCIL_CAN_NUMBER_POINTS];
void oscil_clear_buffer(OSCIL_CAN_handle oc)
{
unsigned int i,k;
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
for (k=0;k<(OSCIL_CAN_NUMBER_POINTS+OSCIL_CAN_NUMBER_POINTS_ADD);k++)
oc->oscil_buffer[i][k] = 0;
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
for (k=0;k<OSCIL_CAN_NUMBER_POINTS;k++)
oc->temp_oscil_buffer[i][k] = 0;
oc->current_position = 0;
// oc->enable_rewrite = 1;
}
void oscil_send_buffer(OSCIL_CAN_handle oc)
{
static unsigned int old_time = 0;
static int prev_send_to_can = 0;
unsigned long old_t;
unsigned int i;
int real_mbox;
static int flag_send_buf = 0;
// if (flag_send_buf)
// {
//
//
//
// return;
// }
oc->global_enable = TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x1;
oc->send_after_cmd = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x2) >> 1;
oc->cmd_send = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x4) >> 2;
oc->stop_update_on_error = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x8) >> 3;
oc->stop_update_on_stop_pwm = (TerminalUnites[oc->number_can_box_terminal_oscil][0] & 0x10) >> 4;
TerminalUnites[oc->number_can_box_terminal_oscil][0] &= ~0x4; // clear cmd_send
oc->number_ch = TerminalUnites[oc->number_can_box_terminal_oscil][1];
oc->number_points = TerminalUnites[oc->number_can_box_terminal_oscil][2];
oc->step = TerminalUnites[oc->number_can_box_terminal_oscil][3];
if (oc->global_enable==0)
return;
real_mbox = get_real_out_mbox(TERMINAL_TYPE_BOX, oc->number_can_box_terminal_oscil);
// áûëà êîìàíäà íà îòïðàâêó ïîñûëêè è îíà åùå íå óøëà, òîãäà ñðáàñûâàåì ñ÷åò÷èê âðåìåíè ïàóçû ìåæäó ïîñûëêàìè,
// ò.å. OSCIL_TIME_WAIT ìåæäó êîíöîì îòïðàâêè ïîñûëêè è íîâîé ïîñûëêè.
if (prev_send_to_can && CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_OFF)==0)
{
old_time = (unsigned int)global_time.miliseconds;
return;
}
prev_send_to_can = 0;
if (oc->send_after_cmd==0)
{
if (!detect_pause_milisec(OSCIL_TIME_WAIT,&old_time))
return;
}
if ( (oc->send_after_cmd==0 || (oc->send_after_cmd==1 && oc->cmd_send==1 ) ) )
{
oc->cmd_send = 0; // clear cmd
if (CAN_cycle_full_free(real_mbox,CAN_BOX_STAT_ON))
{
// oc->enable_rewrite = 0;
old_t = oc->current_position;//
// old_t = global_time.microseconds;
oc->prepare_data_can(oc);
// oc->timer_send = (global_time.microseconds - old_t);
oc->timer_send = (oc->current_position - old_t);
flag_send_buf = 1;
CAN_cycle_send(
TERMINAL_TYPE_BOX,
oc->number_can_box_terminal_oscil,
0,
&(oc->temp_oscil_buffer[0][0]), (oc->number_ch * oc->number_points) , CAN_BOX_EXTENDED_ADR, CAN_BOX_PRIORITY_LOW );
prev_send_to_can = 1;
// while (CAN_cycle_free(real_mbox)==0);
// oc->timer_send = (global_time.microseconds - old_t)/100;
oc->enable_rewrite = 1;
// if (cur_position_buf_modbus16_can >= SIZE_MODBUS_TABLE)
// {
// cur_position_buf_modbus16_can = 0;
//// modbus_table_can_out[ADR_CAN_TEST_PLUS_ONE].all++;
// }
//
// 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
// count_write_to_modbus_can = SIZE_BUF_WRITE_TO_MODBUS16_CAN;
//
// if (CAN_cycle_free(real_mbox))
// {
// CAN_cycle_send(
// MPU_TYPE_BOX,
// edrk.flag_second_PCH,
// cur_position_buf_modbus16_can + 1,
// &modbus_table_can_out[cur_position_buf_modbus16_can].all,
// count_write_to_modbus_can, 0);
//
// cur_position_buf_modbus16_can = cur_position_buf_modbus16_can + SIZE_BUF_WRITE_TO_MODBUS16_CAN;
// }
//
//
}
}
}
//#pragma CODE_SECTION(oscil_next_position,".fast_run");
void oscil_next_position(OSCIL_CAN_handle oc)
{
static int prev_status_pwm = 0;
static int prev_status_error = 0;
static int cmd_stop_after_stop_pwm = 0;
static int cmd_stop_after_stop_error = 0;
static int count_write_after_stop = 0;
static int prev_stop_update_on_stop_pwm = 0;
static int prev_stop_update_on_stop_error = 0;
//////////
if (oc->stop_update_on_error)
{
if (oc->status_error && prev_status_error==0)
{
// ïîñëå âûñòàâëåíèÿ îøèáêè ìû òîðìîçèì ëîã
count_write_after_stop = OSCIL_CAN_NUMBER_POINTS_AFTER_STOP;
cmd_stop_after_stop_error = 1;
}
if (oc->status_error==0 && prev_status_error)
{
// ïîñëå ñáðîñà îøèáîê ìû çàïóñêàåì ëîã.
cmd_stop_after_stop_error = 0;
}
}
else
cmd_stop_after_stop_error = 0;
////////////
if (oc->stop_update_on_stop_pwm==1 && prev_stop_update_on_stop_pwm==0)
{
// ïîñëå âêëþ÷åíèÿ íàñòðîéêè onPWM ìû òîðìîçèì ëîã åñëè îí çàïèñûâàëñÿ.
cmd_stop_after_stop_pwm = 1;
}
if (oc->stop_update_on_stop_pwm)
{
if (oc->status_pwm==0 && prev_status_pwm)
{
// ïîñëå âûêëþ÷åíèÿ PWM ìû òîðìîçèì ëîã åñëè îí çàïèñûâàëñÿ.
count_write_after_stop = OSCIL_CAN_NUMBER_POINTS_AFTER_STOP;
cmd_stop_after_stop_pwm = 1;
}
if (oc->status_pwm && prev_status_pwm==0)
{
// ïîñëå âêëþ÷åíèÿ PWM ìû çàïóñêàåì ëîã.
cmd_stop_after_stop_pwm = 0;
}
}
else
cmd_stop_after_stop_pwm = 0;
prev_stop_update_on_stop_pwm = oc->stop_update_on_stop_pwm;
prev_stop_update_on_stop_error = oc->stop_update_on_error;
prev_status_error = oc->status_error;
prev_status_pwm = oc->status_pwm;
////////////
oc->current_step++;
if (oc->current_step>=oc->step)
{
oc->current_step = 0;
if (cmd_stop_after_stop_error || cmd_stop_after_stop_pwm)
{
if (count_write_after_stop)
{
count_write_after_stop--;
oc->current_position++;
oc->code_status_log = OSCIL_CODE_STATUS_LOG_RUN_TO_STOP;
}
else
oc->code_status_log = OSCIL_CODE_STATUS_LOG_STOP;
}
else
{
oc->current_position++;
oc->code_status_log = OSCIL_CODE_STATUS_LOG_RUN;
}
if (oc->current_position==(OSCIL_CAN_NUMBER_POINTS+OSCIL_CAN_NUMBER_POINTS_ADD))
oc->current_position = 0;
}
}
#pragma CODE_SECTION(oscil_prepare_data_can,".fast_run");
void oscil_prepare_data_can(OSCIL_CAN_handle oc)
{
unsigned int old_position, t_position;
int i, k;
old_position = oc->current_position;
for (i=0;i<OSCIL_CAN_NUMBER_CHANNEL;i++)
{
t_position = old_position;
for (k=OSCIL_CAN_NUMBER_POINTS-1;k>=0;k--)
{
if (t_position==0)
{
t_position = (OSCIL_CAN_NUMBER_POINTS+OSCIL_CAN_NUMBER_POINTS_ADD)-1;
}
else
t_position = t_position - 1;
oc->temp_oscil_buffer[i][k] = oc->oscil_buffer[i][t_position];
}
}
}

View File

@ -0,0 +1,103 @@
/*
* oscil_can.h
*
* Created on: 24 ìàÿ 2020 ã.
* Author: yura
*/
#ifndef SRC_LIBS_NIO12_OSCIL_CAN_H_
#define SRC_LIBS_NIO12_OSCIL_CAN_H_
#define OSCIL_CODE_STATUS_LOG_STOP 1 // Ëîã îñòàíîâëåí
#define OSCIL_CODE_STATUS_LOG_RUN 2 // Ëîã èäåò...
#define OSCIL_CODE_STATUS_LOG_RUN_TO_STOP 3 // Ëîã èäåò, íî èäåò äîçàïèñü, ñêîðî îñòàíîâèòñÿ.
#define OSCIL_CAN_NUMBER_CHANNEL 32 // ìàêñèìàëüíîå âîçìîæíîå êîë-âî êàíàëîâ äëÿ áóôåðà
#define OSCIL_CAN_NUMBER_POINTS 500 // ìàêñèìàëüíîå âîçìîæíîå êîë-âî òî÷åê äëÿ áóôåðà (äëÿ îäíîãî êàíàëà)
#define OSCIL_TIME_WAIT 5000 // ïåðèîä ïîñûëêè âñåãî ìàññèâà â CAN (ìëñåê)
#define OSCIL_CAN_NUMBER_POINTS_ADD 100 // çàïàñ òî÷åê ïðè âûïîëíåíèè ôóíêöèè êîïèðîâàíèÿ ðàáî÷åãî áóôåðà âî âðåìåííûé. oscil_buffer->temp_oscil_buffer
#define OSCIL_CAN_NUMBER_POINTS_AFTER_STOP 100 // ñêîëüêî òî÷åê çàïèñûâàòü ïîñëå îñòàíîâêè çàïèñè áóôåðà ïî àâàðèè èëè øèìó
typedef struct {
int oscil_buffer[OSCIL_CAN_NUMBER_CHANNEL][OSCIL_CAN_NUMBER_POINTS+OSCIL_CAN_NUMBER_POINTS_ADD];
int temp_oscil_buffer[OSCIL_CAN_NUMBER_CHANNEL][OSCIL_CAN_NUMBER_POINTS];
unsigned int global_enable;
unsigned int number_ch;
unsigned int number_points;
unsigned int step;
unsigned int send_after_cmd;
unsigned int cmd_send;
unsigned int current_step;
unsigned int enable_rewrite;
unsigned int current_position;
unsigned int timer_send;
unsigned int code_status_log;
unsigned int status_error; // ñòàòóñ àâàðèè 0-íåò àâàðèè/1- åñòü
unsigned int status_pwm; // ñòàòóñ ØÈÌà 0-Øèì íå çàïóùåí/1-çàïóùåí
unsigned int stop_update_on_error; // îñòàíîâèì îáíîâëåíèå áóôåðà ïî àâàðèè
unsigned int stop_update_on_stop_pwm; // îñòàíîâèì îáíîâëåíèå áóôåðà ïî ñòîïó ØÈÌà
int number_can_box_terminal_oscil;
int number_can_box_terminal_cmd;
unsigned int pause_can; // ïàóçà ìåæäó ïîñûëêàìè CAN
void (*clear)(); // Clear buffers
void (*send)(); // Send buffers
void (*set_next_position)(); // Set next position in buffers
void (*prepare_data_can)(); // Set next position in buffers
} OSCIL_CAN;
typedef OSCIL_CAN *OSCIL_CAN_handle;
#define OSCIL_CAN_DEFAULTS { {0},{0}, \
0, \
OSCIL_CAN_NUMBER_CHANNEL, \
OSCIL_CAN_NUMBER_POINTS, \
1, \
0, \
0, \
0, \
1, \
0, \
0, \
0, \
0, \
0, \
1, \
1, \
0,0, \
OSCIL_TIME_WAIT, \
oscil_clear_buffer, \
oscil_send_buffer, \
oscil_next_position, \
oscil_prepare_data_can \
}
void oscil_clear_buffer(OSCIL_CAN_handle);
void oscil_send_buffer(OSCIL_CAN_handle);
void oscil_next_position(OSCIL_CAN_handle);
void oscil_prepare_data_can(OSCIL_CAN_handle);
extern OSCIL_CAN oscil_can;
#endif /* SRC_LIBS_NIO12_OSCIL_CAN_H_ */

View File

@ -0,0 +1,63 @@
#ifndef PARAMS_H
#define PARAMS_H
////////////////////////////////////////////////////////////////
// Loaded capasitors level
#define V_CAPASITORS_LOADED_IQ 11184810 //13421772 ~ 2400V // 11184810 ~ 2000V
#define V_NOMINAL 15099494 //15099494 ~ 2700V
// Level of nominal current and maximum current
#define I_OUT_NOMINAL_IQ 9777761 //6431266 ~ 1150A //2796202 ~ 500A //By TU 1240A RMS - 1748A ~ 9777761 IQ
#define I_OUT_LIMIT_IQ 8388608 //8388608 ~ 1500A //5592405 ~ 1000A // 4473924 ~ 800A //1.5*In - 2622A ~ 14666642 IQ
//11184811 ~ 2000A // 12482249 ~ 2232A // 6710886 ~ 1200A
// Input voltage levels for protection
#define V_IN_PLUS_20 (2340)
#define V_IN_PLUS_25 2650 //2450
#define V_IN_MINUS_20 (1560)
#define V_IN_MINUS_25 1462
//ACP program errors level
#define ERR_LEVEL_ADC_PLUS 3950 //+1270A //2950 // +650A //3467 // 3367 //3367 //3267 // 0xfff-0x29c
#define ERR_LEVEL_ADC_MINUS 150 //-1270A //1150 //-650A // 267 //367
#define ERR_LEVEL_ADC_PLUS_6 650 //875 ~ 2500V //650 ~ 3000B // 740 ~ 2800B //
#define ERR_LEVEL_ADC_MINUS_6 1205 //1775V ~ 1205
#define ERR_LEVEL_I_FAZA_PLUS 594 //1760A ~ 1058 //2000A ~ 924 //843 ~ 2100A // 594 ~ 2500A
#define ERR_LEVEL_I_FAZA_MINUS 3496 //1760A ~ 3031 //2000A ~ 3166 //3226 ~2100A // 3496 ~ 2500A
#define ERR_LEVEL_I_ZPT_PLUS 520 //520 ~ 1500A
#define ERR_LEVEL_BREAK_REZ 858 //858 ~ 800A
#define MIN_DETECT_UD_ZERO 2300
#define ERR_LEVEL_ADC_PLUS_6_ON_GO_IQ 16777216 //3000V // 16217975 //2900V
#define ERR_LEVEL_ADC_PLUS_6_IQ 16777216 //3000V //15658734 //2800V
// Temperature protection levels
#define TEMPERATURE_LIMIT 600 //Area temperature
#define TEMPERATURE_WARNING 500
#define TEMPERATURE_WATER_LIMIT 500 //Water temeperature
#define TEMPERATURE_WATER_WARNING 450
#define TEMPERATURE_WATER_FAZA_LIMIT 500 //Water temperature on phase output
#define TEMPERATURE_WATER_FAZA_WARNING 450
#define TEMPERATURE_WATER_SNABBER_RESISTORS_LIMIT 500
#define TEMPERATURE_WATER_SNABBER_RESISTORS_WARNING 450
#define TEMPERATURE_WATER_DROSSEL_LIMIT 600 //Output drossel water limits
#define TEMPERATURE_WATER_DROSSEL_WARNING 500
#define TEMPERATURE_WATER_DIODS_LIMIT 500 //water temperature at rectifier outlet
#define TEMPERATURE_WATER_DIODS_WARNING 450
#define TEMPERATURE_WATER_CHOPPER_LIMIT 500
#define TEMPERATURE_WATER_CHOPPER_WARNING 450
#define TEMPERATURE_REZISTORS_LIMIT_BV 600 //temperature on coolers of input filter resistors
#define TEMPERATURE_REZISTORS_WARNING_BV 500
#define TEMPERATURE_REZISTORS_LIMIT_BI 500 //temperature on the coolers of the output filter resistors
#define TEMPERATURE_REZISTORS_WARNING_BI 450
#define TEMPERATURE_INPUT_BSO_DN20 500
#define TEMPERATURE_INPUT_BSO_DN100 500
#define TEMPERATURE_OUTPUT_BSO_DN20 400
#define TEMPERATURE_OUTPUT_BSO_DN100 400
////////////////////////////////////
#define TEMPERATURE_AREA_DATCHIK_ERROR -100
#endif //PARAMS_H

View File

@ -0,0 +1,64 @@
/*=====================================================================================
File name: PID_REG3.C (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description: The PID controller with anti-windup
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
-------------------------------------------------------------------------------------*/
#include "pid_reg3.h"
#include "IQmathLib.h" // Include header for IQmath library
#define IQ_100 1677721600
#pragma CODE_SECTION(pid_reg3_calc,".fast_run");
void pid_reg3_calc(PIDREG3 *v)
{
_iq Ud2;
// Compute the error
v->Err = v->Ref - v->Fdb;
// Compute the proportional output
v->Up = _IQmpy(v->Kp,v->Err);
// Compute the integral output
v->Ui = v->Ui + _IQmpy(v->Ki,v->Up) + _IQmpy(v->Kc,v->SatErr);
/*
// Saturate the integral output
if (v->Ui > v->OutMax)
v->Ui = v->OutMax;
else if (v->Ui < v->OutMin)
v->Ui = v->OutMin;
*/
// Compute the derivative output
Ud2 = v->Up - v->Up1;// _IQmpy(IQ_100,(v->Up - v->Up1));
v->Ud = _IQmpy(v->Kd,Ud2);
// Compute the pre-saturated output
v->OutPreSat = v->Up + v->Ui + v->Ud;
// Saturate the output
if (v->OutPreSat > v->OutMax)
v->Out = v->OutMax;
else if (v->OutPreSat < v->OutMin)
v->Out = v->OutMin;
else
v->Out = v->OutPreSat;
// Compute the saturate difference
v->SatErr = v->Out - v->OutPreSat;
// Update the previous proportional output
v->Up1 = v->Up;
}

View File

@ -0,0 +1,98 @@
/* =================================================================================
File name: PID_REG3.H (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description:
Header file containing constants, data type definitions, and
function prototypes for the PIDREG3.
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
------------------------------------------------------------------------------*/
#ifndef __PIDREG3_H__
#define __PIDREG3_H__
#include "IQmathLib.h"
//#include "dmctype.h"
typedef struct { _iq Ref; // Input: Reference input
_iq Fdb; // Input: Feedback input
_iq Err; // Variable: Error
_iq Kp; // Parameter: Proportional gain
_iq Up; // Variable: Proportional output
_iq Ui; // Variable: Integral output
_iq Ud; // Variable: Derivative output
_iq OutPreSat; // Variable: Pre-saturated output
_iq OutMax; // Parameter: Maximum output
_iq OutMin; // Parameter: Minimum output
_iq Out; // Output: PID output
_iq SatErr; // Variable: Saturated difference
_iq Ki; // Parameter: Integral gain
_iq Kc; // Parameter: Integral correction gain
_iq Kd; // Parameter: Derivative gain
_iq Up1; // History: Previous proportional output
void (*calc)(); // Pointer to calculation function
} PIDREG3;
typedef PIDREG3 *PIDREG3_handle;
/*-----------------------------------------------------------------------------
Default initalizer for the PIDREG3 object.
-----------------------------------------------------------------------------*/
#define PIDREG3_DEFAULTS { 0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
0, \
(void (*)(PIDREG3_handle))pid_reg3_calc }
/*------------------------------------------------------------------------------
Prototypes for the functions in PIDREG3.C
------------------------------------------------------------------------------*/
void pid_reg3_calc(PIDREG3_handle);
#endif // __PIDREG3_H__

View File

@ -0,0 +1,51 @@
/*=====================================================================================
File name: RMP3CNTL.C (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description: The ramp3 down control
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
-------------------------------------------------------------------------------------*/
#include "dmctype.h"
#include "IQmathLib.h" // Include header for IQmath library
#include "rmp_cntl_v1.h"
#pragma CODE_SECTION(rmp_cntl_v1_calc,".fast_run");
void rmp_cntl_v1_calc(RMP_V1 *v)
{
_iq tmp;
tmp = v->DesiredInput - v->Out;
if (tmp > (_iq)v->RampPlus)
{
//v->RampDoneFlag = 0;
v->Out += v->RampPlus;
if (v->Out > v->RampHighLimit)
v->Out = v->RampHighLimit;
}
else
{
if (tmp < (_iq)v->RampMinus)
{
//v->RampDoneFlag = 0;
v->Out += (_iq)v->RampMinus;
if (v->Out < v->RampLowLimit)
v->Out = v->RampLowLimit;
}
else
{
v->Out = v->DesiredInput;
//v->RampDoneFlag = 0x7FFFFFFF;
}
}
}

View File

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

View File

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

View File

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

View File

@ -0,0 +1,38 @@
/* =================================================================================
File name: SVGEN_DQ.H (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description:
Header file containing constants, data type definitions, and
function prototypes for the SVGEN_DQ.
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
------------------------------------------------------------------------------*/
#ifndef __SVGEN_DQ_H__
#define __SVGEN_DQ_H__
typedef struct { _iq Ualpha; // Input: reference alpha-axis phase voltage
_iq Ubeta; // Input: reference beta-axis phase voltage
_iq Ta; // Output: reference phase-a switching function
_iq Tb; // Output: reference phase-b switching function
_iq Tc; // Output: reference phase-c switching function
void (*calc)(); // Pointer to calculation function
} SVGENDQ;
typedef SVGENDQ *SVGENDQ_handle;
/*-----------------------------------------------------------------------------
Default initalizer for the SVGENDQ object.
-----------------------------------------------------------------------------*/
#define SVGENDQ_DEFAULTS { 0,0,0,0,0, \
(void (*)(Uint32))svgendq_calc }
/*------------------------------------------------------------------------------
Prototypes for the functions in SVGEN_DQ.C
------------------------------------------------------------------------------*/
void svgendq_calc(SVGENDQ_handle);
#endif // __SVGEN_DQ_H__

View File

@ -0,0 +1,122 @@
/*=====================================================================================
File name: SVGEN_DQ.C (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description: Space-vector PWM generation based on d-q components
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
-------------------------------------------------------------------------------------*/
#include "dmctype.h"
#include "IQmathLib.h" // Include header for IQmath library
#include "math_pi.h"
#include "svgen_dq.h"
_iq iq_max = _IQ(1.0)-1;
//#pragma CODE_SECTION(svgendq_calc,".fast_run2");
void svgendq_calc(SVGENDQ *v)
{
_iq Va,Vb,Vc,t1,t2,temp_sv1,temp_sv2;
Uint16 Sector = 0; // Sector is treated as Q0 - independently with global Q
Sector = 0; \
temp_sv1=_IQdiv2(v->Ubeta); /*divide by 2*/ \
temp_sv2=_IQmpy(CONST_SQRT3_2,v->Ualpha); /* 0.8660254 = sqrt(3)/2*/ \
// Inverse clarke transformation
Va = v->Ubeta; \
Vb = -temp_sv1 + temp_sv2; \
Vc = -temp_sv1 - temp_sv2; \
// 60 degree Sector determination
if (Va>0)
Sector = 1;
if (Vb>0)
Sector = Sector + 2;
if (Vc>0)
Sector = Sector + 4;
// X,Y,Z (Va,Vb,Vc) calculations X = Va, Y = Vb, Z = Vc \ Va = v.Ubeta;
Vb = temp_sv1 + temp_sv2;
Vc = temp_sv1 - temp_sv2;
// Sector 0: this is special case for (Ualpha,Ubeta) = (0,0)
if (Sector==0) // Sector 0: this is special case for (Ualpha,Ubeta) = (0,0)
{
v->Ta = CONST_IQ_05;
v->Tb = CONST_IQ_05;
v->Tc = CONST_IQ_05;
}
if (Sector==1) // Sector 1: t1=Z and t2=Y (abc ---> Tb,Ta,Tc)
{
t1 = Vc;
t2 = Vb;
v->Tb = _IQdiv2((CONST_IQ_1-t1-t2)); // tbon = (1-t1-t2)/2
v->Ta = v->Tb+t1; // taon = tbon+t1
v->Tc = v->Ta+t2; // tcon = taon+t2
}
else if (Sector==2) // Sector 2: t1=Y and t2=-X (abc ---> Ta,Tc,Tb)
{
t1 = Vb;
t2 = -Va;
v->Ta = _IQdiv2((CONST_IQ_1-t1-t2)); // taon = (1-t1-t2)/2
v->Tc = v->Ta+t1; // tcon = taon+t1
v->Tb = v->Tc+t2; // tbon = tcon+t2
}
else if (Sector==3) // Sector 3: t1=-Z and t2=X (abc ---> Ta,Tb,Tc)
{
t1 = -Vc;
t2 = Va;
v->Ta = _IQdiv2((CONST_IQ_1-t1-t2)); // taon = (1-t1-t2)/2
v->Tb = v->Ta+t1; // tbon = taon+t1
v->Tc = v->Tb+t2; // tcon = tbon+t2
}
else if (Sector==4) // Sector 4: t1=-X and t2=Z (abc ---> Tc,Tb,Ta)
{
t1 = -Va;
t2 = Vc;
v->Tc = _IQdiv2((CONST_IQ_1-t1-t2)); // tcon = (1-t1-t2)/2
v->Tb = v->Tc+t1; // tbon = tcon+t1
v->Ta = v->Tb+t2; // taon = tbon+t2
}
else if (Sector==5) // Sector 5: t1=X and t2=-Y (abc ---> Tb,Tc,Ta)
{
t1 = Va;
t2 = -Vb;
v->Tb = _IQdiv2((CONST_IQ_1-t1-t2)); // tbon = (1-t1-t2)/2
v->Tc = v->Tb+t1; // tcon = tbon+t1
v->Ta = v->Tc+t2; // taon = tcon+t2
}
else if (Sector==6) // Sector 6: t1=-Y and t2=-Z (abc ---> Tc,Ta,Tb)
{
t1 = -Vb;
t2 = -Vc;
v->Tc = _IQdiv2((CONST_IQ_1-t1-t2)); // tcon = (1-t1-t2)/2
v->Ta = v->Tc+t1; // taon = tcon+t1
v->Tb = v->Ta+t2; // tbon = taon+t2
}
// Convert the unsigned GLOBAL_Q format (ranged (0,1)) -> signed GLOBAL_Q format (ranged (-1,1))
v->Ta = _IQmpy2(v->Ta - CONST_IQ_05);
v->Tb = _IQmpy2(v->Tb - CONST_IQ_05);
v->Tc = _IQmpy2(v->Tc - CONST_IQ_05);
if (v->Ta > iq_max) v->Ta = iq_max;
if (v->Tb > iq_max) v->Tb = iq_max;
if (v->Tc > iq_max) v->Tc = iq_max;
if (v->Ta < -iq_max) v->Ta = -iq_max;
if (v->Tb < -iq_max) v->Tb = -iq_max;
if (v->Tc < -iq_max) v->Tc = -iq_max;
}

164
Inu/Src/N12_Libs/svgen_mf.c Normal file
View File

@ -0,0 +1,164 @@
/*=====================================================================================
File name: SVGEN_MF.C (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description: Space-vector PWM generation based on magnitude and frequency components
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
-------------------------------------------------------------------------------------*/
#include "IQmathLib.h" // Include header for IQmath library
#include "dmctype.h"
#include "svgen_mf.h"
#include <params.h>
static _iq iq1_0=_IQ(1.0);
static _iq iq6_0=_IQ(6.0);
static _iq iq0_5=_IQ(0.5);
static _iq iq2_0=_IQ(2.0);
static _iq iq3_0=_IQ(3.0);
static _iq iq4_0=_IQ(4.0);
static _iq iq5_0=_IQ(5.0);
//#pragma CODE_SECTION(svgenmf_calc,".fast_run");
void svgenmf_calc(SVGENMF *v)
{
_iq StepAngle,EntryOld,dx,dy;
_iq T = iq1_0;//_IQ(1.0);
// Normalise the freq input to appropriate step angle
// Here, 1 pu. = 60 degree
//#ifdef DOUBLE_UPDATE_PWM
// StepAngle = (_IQmpy(v->Freq,v->FreqMax))>>1; // decrise step /2 for double update
//#else
StepAngle = _IQmpy(v->Freq,v->FreqMax); // normal step
//#endif
// Calculate new angle alpha
EntryOld = v->NewEntry;
v->Full_Alpha = v->Full_Alpha + StepAngle;
if (v->Full_Alpha < 0)
v->Full_Alpha = v->Full_Alpha+iq6_0;
if (v->Full_Alpha >= iq6_0)
v->Full_Alpha = v->Full_Alpha-iq6_0;
//new sector detect
if (v->Full_Alpha >= iq5_0)
{
v->SectorPointer=5;
v->Alpha = v->Full_Alpha-iq5_0;
}
else
if (v->Full_Alpha >= iq4_0)
{
v->SectorPointer=4;
v->Alpha = v->Full_Alpha-iq4_0;
}
else
if (v->Full_Alpha >= iq3_0)
{
v->SectorPointer=3;
v->Alpha = v->Full_Alpha-iq3_0;
}
else
if (v->Full_Alpha >= iq2_0)
{
v->SectorPointer=2;
v->Alpha = v->Full_Alpha-iq2_0;
}
else
if (v->Full_Alpha >= iq1_0)
{
v->SectorPointer=1;
v->Alpha = v->Full_Alpha-iq1_0;
}
else
{
v->SectorPointer=0;
v->Alpha = v->Full_Alpha;
}
// v->Alpha = v->Alpha + StepAngle;
// if (v->Alpha >= iq1_0)
// v->Alpha = v->Alpha-iq1_0;
v->NewEntry = v->Alpha;
dy = _IQsin(_IQmpy(v->NewEntry,PI_THIRD)); // dy = sin(NewEntry)
dx = _IQsin(PI_THIRD-_IQmpy(v->NewEntry,PI_THIRD)); // dx = sin(60-NewEntry)
// Determine which sector
// if (v->NewEntry-EntryOld<0)
// {
// if (v->SectorPointer==5)
// v->SectorPointer = 0;
// else
// v->SectorPointer = v->SectorPointer + 1;
// }
if (v->SectorPointer==0) // Sector 1 calculations - a,b,c --> a,b,c
{
v->Ta = _IQmpy(iq0_5,(T-dx-dy));
v->Tb = v->Ta + dx;
v->Tc = T - v->Ta;
}
else if (v->SectorPointer==1) // Sector 2 calculations - a,b,c --> b,a,c & dx <--> dy
{
v->Tb = _IQmpy(iq0_5,(T-dx-dy));
v->Ta = v->Tb + dy;
v->Tc = T - v->Tb;
}
else if (v->SectorPointer==2) // Sector 3 calculations - a,b,c --> b,c,a
{
v->Tb = _IQmpy(iq0_5,(T-dx-dy));
v->Tc = v->Tb + dx;
v->Ta = T - v->Tb;
}
else if (v->SectorPointer==3) // Sector 4 calculations - a,b,c --> c,b,a & dx <--> dy
{
v->Tc = _IQmpy(iq0_5,(T-dx-dy));
v->Tb = v->Tc + dy;
v->Ta = T - v->Tc;
}
else if (v->SectorPointer==4) // Sector 5 calculations - a,b,c --> c,a,b
{
v->Tc = _IQmpy(iq0_5,(T-dx-dy));
v->Ta = v->Tc + dx;
v->Tb = T - v->Tc;
}
else if (v->SectorPointer==5) // Sector 6 calculations - a,b,c --> a,c,b & dx <--> dy
{
v->Ta = _IQmpy(iq0_5,(T-dx-dy));
v->Tc = v->Ta + dy;
v->Tb = T - v->Ta;
}
// Convert the unsigned GLOBAL_Q format (ranged (0,1)) -> signed GLOBAL_Q format (ranged (-1,1))
// Then, multiply with a gain and add an offset.
v->Ta = _IQmpy(iq2_0,(v->Ta-iq0_5));
v->Ta = _IQmpy(v->Gain,v->Ta) + v->Offset;
v->Tb = _IQmpy(iq2_0,(v->Tb-iq0_5));
v->Tb = _IQmpy(v->Gain,v->Tb) + v->Offset;
v->Tc = _IQmpy(iq2_0,(v->Tc-iq0_5));
v->Tc = _IQmpy(v->Gain,v->Tc) + v->Offset;
}

View File

@ -0,0 +1,46 @@
/* =================================================================================
File name: SVGEN_MF.H (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description:
Header file containing constants, data type definitions, and
function prototypes for the SVGEN_MF.
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
------------------------------------------------------------------------------*/
#ifndef __SVGEN_MF_H__
#define __SVGEN_MF_H__
typedef struct { _iq Gain; // Input: reference gain voltage (pu)
_iq Offset; // Input: reference offset voltage (pu)
_iq Freq; // Input: reference frequency (pu)
_iq FreqMax; // Parameter: Maximum step angle = 6*base_freq*T (pu)
_iq Alpha; // History: Sector angle (pu)
_iq Full_Alpha;
_iq NewEntry; // History: Sine (angular) look-up pointer (pu)
Uint32 SectorPointer; // History: Sector number (Q0) - independently with global Q
_iq Ta; // Output: reference phase-a switching function (pu)
_iq Tb; // Output: reference phase-b switching function (pu)
_iq Tc; // Output: reference phase-c switching function (pu)
void (*calc)(); // Pointer to calculation function
} SVGENMF;
typedef SVGENMF *SVGENMF_handle;
/*-----------------------------------------------------------------------------
Default initalizer for the SVGENMF object.
-----------------------------------------------------------------------------*/
#define SVGENMF_DEFAULTS { 0,0,0,0,0,0,0,0,0,0,0, \
(void (*)(Uint32))svgenmf_calc }
#define PI_THIRD _IQ(1.04719755119660) // This is 60 degree
/*------------------------------------------------------------------------------
Prototypes for the functions in SVGEN_MF.C
------------------------------------------------------------------------------*/
void svgenmf_calc(SVGENMF_handle);
#endif // __SVGEN_MF_H__

View File

@ -0,0 +1,736 @@
/*
* uf_alg_ing.c
*
* Created on: 10 ôåâð. 2020 ã.
* Author: yura
*/
#include "IQmathLib.h"
#include "DSP281x_Examples.h" // DSP281x Examples Include File
#include "DSP281x_Device.h" // DSP281x Headerfile Include File
#include "uf_alg_ing.h"
#include <master_slave.h>
#include <params_alg.h>
#include <params_motor.h>
#include <params_norma.h>
#include <params_pwm24.h>
#include <v_pwm24_v2.h>
#include "math_pi.h"
#include "svgen_dq.h"
#include "svgen_mf.h"
#include "dq_to_alphabeta_cos.h"
#include "params_norma.h"
//#pragma DATA_SECTION(svgen_mf1,".fast_vars");
SVGENMF svgen_mf1 = SVGENMF_DEFAULTS;
//#pragma DATA_SECTION(svgen_mf2,".fast_vars");
//SVGENMF svgen_mf2 = SVGENMF_DEFAULTS;
//#pragma DATA_SECTION(svgen_dq_1,".fast_vars");
SVGENDQ svgen_dq_1 = SVGENDQ_DEFAULTS;
//#pragma DATA_SECTION(svgen_dq_2,".fast_vars");
//SVGENDQ svgen_dq_2 = SVGENDQ_DEFAULTS;
UF_ALG_VALUE uf_alg = UF_ALG_VALUE_DEFAULT;
void InitVariablesSvgen_Ing(unsigned int freq)
{
svgen_dq_1.Ualpha = 0;
svgen_dq_1.Ubeta = 0;
// svgen_dq_2.Ualpha = 0;
// svgen_dq_2.Ubeta = 0;
uf_alg.hz_to_angle = _IQ(2.0 * PI * NORMA_FROTOR / freq ); // îäèí ðàç çà òàêò ØÈÌà
// uf_alg.hz_to_angle = _IQ(2.0 * PI * NORMA_FROTOR / freq /2.0 ); // äâà ðàçà çà òàêò ØÈÌà
// Initialize the SVGEN_MF module
// svgen_mf1.FreqMax = _IQ(6*NORMA_FROTOR/freq);
// svgen_mf2.FreqMax = _IQ(6*NORMA_FROTOR/freq);
//
//
// svgen_mf2.Offset=_IQ(0);
// svgen_mf1.Offset=_IQ(0);
init_alpha_Ing(0);
}
void init_alpha_Ing(unsigned int master_slave)
{
uf_alg.winding_displacement_bs1 = 0;
uf_alg.winding_displacement_bs2 = 0;
// power_ain1.init(&power_ain1);
// power_ain2.init(&power_ain2);
// svgen_mf1.NewEntry = 0;//_IQ(0.5);
// svgen_mf2.NewEntry = 0;
// svgen_mf1.SectorPointer = 0;
// svgen_mf2.SectorPointer = 0;
//ñäâèã ïî óìîë÷àíèþ 0 ãðàäóñîâ
// svgen_mf1.Alpha = _IQ(0);
// svgen_mf2.Alpha = _IQ(0);
//
//
//
#if (SETUP_SDVIG_OBMOTKI == SDVIG_OBMOTKI_30_PLUS)
// 30 ãðàä. ñäâèã
// òóò íå ðàäèàíû, à íîðìèðîâàííûå ê 60 ãðàä=1.
// svgen_mf1.Alpha = _IQ(0.5);
// svgen_mf2.Alpha = _IQ(0);
//
// svgen_mf1.Full_Alpha = svgen_mf1.Alpha;
// svgen_mf2.Full_Alpha = svgen_mf2.Alpha;
// òóò ðàäèàíû
uf_alg.winding_displacement_bs1 = CONST_IQ_PI6; //_IQ(0.5);
uf_alg.winding_displacement_bs2 = 0;
#else
#if (SETUP_SDVIG_OBMOTKI == SDVIG_OBMOTKI_30_MINUS)
// -30 ãðàä. ñäâèã
// òóò íå ðàäèàíû, à íîðìèðîâàííûå ê 60 ãðàä=1.
// svgen_mf1.Alpha = _IQ(0);
// svgen_mf2.Alpha = _IQ(0.5);
// svgen_mf1.Full_Alpha = svgen_mf1.Alpha;
// svgen_mf2.Full_Alpha = svgen_mf2.Alpha;
//
// òóò ðàäèàíû
uf_alg.winding_displacement_bs2 = CONST_IQ_PI6; // _IQ(0.5);
uf_alg.winding_displacement_bs1 = 0;
#else
#if (SETUP_SDVIG_OBMOTKI == SDVIG_OBMOTKI_ZERO)
// 0 ãðàä. ñäâèã
// svgen_mf1.Alpha = _IQ(0);
// svgen_mf2.Alpha = _IQ(0);
// svgen_mf1.Full_Alpha = svgen_mf1.Alpha;
// svgen_mf2.Full_Alpha = svgen_mf2.Alpha;
uf_alg.winding_displacement_bs1 = 0;
uf_alg.winding_displacement_bs2 = 0;
#else
#error "!!!ÎØÈÁÊÀ!!! Íå îïðåäåëåí SETUP_SDVIG_OBMOTKI â params_motor.h!!!"
#endif
#endif
#endif
}
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
#pragma CODE_SECTION(uf_disbalance_uzpt,".fast_run");
void uf_disbalance_uzpt(_iq Uzad_uf1, unsigned int disable_alg_u_disbalance, _iq kplus_u_disbalance, _iq k_u_disbalance,
_iq U_1, _iq U_2,
_iq Uzad_max,
_iq *Kplus_out)
{
_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;
// change_pwm_freq(Fzad_uf);
Uplus = U_2;//filter.iqU_2_fast; // òóò Uplus áåðåò îò U2 ò.ê. òóò çíàê "-" ñêîðåå âñåãî íå ó÷èòûâàåòß ãäå-òî
Uminus = U_1;//filter.iqU_1_fast;
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) // åñëè ìû çàäàëè èçâíå, òî åãî è èñïîëüçóåì, ýòî äëÿ òåñòà.
{
Kplus = kplus_u_disbalance;
}
else
{
if (delta_U != 0)
{
Kplus = _IQmpy(k_u_disbalance, _IQmpy(Uzad_uf1, (_IQdiv( (Uplus-Uminus), (Uplus+Uminus) )) ) );//CONST_1 + _IQmpy(k_u_disbalance, _IQmpy(Uzad_uf1, ( _IQdiv(_IQmpy(CONST_2,Uplus),(Uplus+Uminus)) - CONST_1 ) ) );
}
else
{
Kplus = 0;
}
}
}
else
{
// Uplus = 0;
// Uminus = 0;
// delta_U = 0;
Kplus = 0;
}
KplusMax = _IQmpy(Uzad_uf1,CONST_IQ_05);
if (Kplus>=KplusMax)
{
Kplus = KplusMax;
}
if (Kplus<=-KplusMax)
{
Kplus = -KplusMax;
}
*Kplus_out = Kplus;
}
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////
// kplus_u_disbalance äîëæåí áûòü ðàâåí = 0, åñëè íå íîëü, òî ýòî òåñò
// enable_alg_u_disbalance - ðàçðåøèòü ðàáîòó àëãîðèòìà ðàçáàëàíñà
// k_u_disbalance - êîýô. ñèëû àëãîðèòìà ðàçáàëàíñà.
////////////////////////////////////////////////////////////////////////////
//#pragma CODE_SECTION(uf_const_f_24_Ing,".fast_run");
void uf_const_f_24_Ing(_iq Fzad_uf1,_iq Fzad_uf2,_iq Uzad_uf1, _iq Uzad_uf2,
unsigned int enable_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 *Kplus_out)
{
_iq pwm_t,delta_U,Uplus,Uminus;
_iq Kplus;
static _iq u1=0,u2=0;
volatile _iq KplusMax;
uf_disbalance_uzpt(Uzad_uf1, enable_alg_u_disbalance, kplus_u_disbalance, k_u_disbalance, U_1, U_2, Uzad_max, &Kplus);
// change_pwm_freq(Fzad_uf);
*Kplus_out = Kplus;
/////////////////////////////////////////
svgen_mf1.Gain = _IQsat(Uzad_uf1,Uzad_max,0); // Pass inputs to svgen_mf1
svgen_mf1.Freq = Fzad_uf1; // Pass inputs to svgen_mf1
// svgen_mf2.Gain = _IQsat(Uzad_uf2,Uzad_max,0);; // Pass inputs to svgen_mf1
// svgen_mf2.Freq = Fzad_uf2; // Pass inputs to svgen_mf1
svgen_mf1.calc(&svgen_mf1); // Call compute function for svgen_mf1
// svgen_mf2.calc(&svgen_mf2); // Call compute function for svgen_mf2
/////////////////////////////////////////
/*
logpar.log1 = (int16)(_IQtoIQ15(Uzad_uf1));
logpar.log2 = (int16)(_IQtoIQ15(Fzad_uf1));
logpar.log3 = (int16)((svgen_pwm24_1.Ta_0));
logpar.log4 = (int16)((svgen_pwm24_1.Ta_1));
logpar.log5 = (int16)(_IQtoIQ15(svgen_mf1.Ta));
logpar.log6 = (int16)(_IQtoIQ15(_IQdiv(Kplus,CONST_IQ_10)));
logpar.log7 = (int16)(_IQtoIQ15(_IQdiv(Kminus,CONST_IQ_10)));
logpar.log8 = (int16)(_IQtoIQ15(Uplus));
logpar.log9 = (int16)(_IQtoIQ15(Uminus));
*/
// 1
// a
pwm_t = correct_balance_uzpt_pwm24 (svgen_mf1.Ta, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_1, &svgen_pwm24_1.Ta_0, &svgen_pwm24_1.Ta_1, &svgen_pwm24_1.Ta_imp, pwm_t);
// b
pwm_t = correct_balance_uzpt_pwm24 (svgen_mf1.Tb, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_1, &svgen_pwm24_1.Tb_0, &svgen_pwm24_1.Tb_1, &svgen_pwm24_1.Tb_imp,pwm_t);
// c
pwm_t = correct_balance_uzpt_pwm24 (svgen_mf1.Tc, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_1, &svgen_pwm24_1.Tc_0, &svgen_pwm24_1.Tc_1, &svgen_pwm24_1.Tc_imp,pwm_t);
// 2
svgen_pwm24_2.Ta_0 = svgen_pwm24_1.Ta_0;
svgen_pwm24_2.Ta_1 = svgen_pwm24_1.Ta_1;
svgen_pwm24_2.Tb_0 = svgen_pwm24_1.Tb_0;
svgen_pwm24_2.Tb_1 = svgen_pwm24_1.Tb_1;
svgen_pwm24_2.Tc_0 = svgen_pwm24_1.Tc_0;
svgen_pwm24_2.Tc_1 = svgen_pwm24_1.Tc_1;
// a
// pwm_t = correct_balance_uzpt_pwm24 (svgen_mf1.Ta, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_2, &svgen_pwm24_2.Ta_0, &svgen_pwm24_2.Ta_1, &svgen_pwm24_2.Ta_imp,pwm_t);
//// b
// pwm_t = correct_balance_uzpt_pwm24 (svgen_mf1.Tb, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_2, &svgen_pwm24_2.Tb_0, &svgen_pwm24_2.Tb_1, &svgen_pwm24_2.Tb_imp,pwm_t);
//// c2
// pwm_t = correct_balance_uzpt_pwm24 (svgen_mf1.Tc, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_2, &svgen_pwm24_2.Tc_0, &svgen_pwm24_2.Tc_1, &svgen_pwm24_2.Tc_imp,pwm_t);
//
////
if (flag_km_0)
{
svgen_pwm24_1.prev_level = V_PWM24_PREV_PWM_WORK_KM0;
svgen_pwm24_2.prev_level = V_PWM24_PREV_PWM_WORK_KM0;
}
else
{
svgen_pwm24_1.prev_level = V_PWM24_PREV_PWM_WORK;
svgen_pwm24_2.prev_level = V_PWM24_PREV_PWM_WORK;
}
/////////
/////////
// logpar.log10 = (int16)((svgen_pwm24_1.Ta_0));
// logpar.log11 = (int16)((svgen_pwm24_1.Ta_1));
}
////////////////////////////////////////////////////////////
#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,
unsigned int master,
unsigned int n_bs,
_iq *Kplus_out,
_iq *tetta_out,
_iq *Uzad_out
)
{
// static _iq hz_to_angle = _IQ(2.0 * PI * NORMA_FROTOR / FREQ_PWM / 2.0);
// static _iq tetta = 0;
_iq pwm_t;
_iq Kplus;
_iq Ud = 0;
_iq Uq = 0;
_iq add_tetta = 0;
DQ_TO_ALPHABETA dq_to_ab = DQ_TO_ALPHABETA_DEFAULTS;
////////////////////////////////////////
uf_disbalance_uzpt(Uzad_uf1, disable_alg_u_disbalance, kplus_u_disbalance, k_u_disbalance,
U_1, U_2,
Uzad_max,
&Kplus);
////////////////////////////////////////
////////////////////////////////////////
////////////////////////////////////////
if (master==MODE_MASTER)
{
// ìû master
add_tetta = _IQmpy(Fzad_uf1, uf_alg.hz_to_angle);
uf_alg.tetta += add_tetta;
Ud = 0;
Uq = _IQsat(Uzad_uf1,Uzad_max,0);
}
else
if (master==MODE_SLAVE)
{
// ìû slave
add_tetta = 0;
uf_alg.tetta = master_tetta;
Ud = 0;
Uq = _IQsat(master_Uzad_uf1,Uzad_max,0);
}
else
{
// ìû íåïîíÿòíî êòî!
Ud = 0;
Uq = 0;
add_tetta = 0;
uf_alg.tetta = 0;
}
////////////////////////////////////////
////////////////////////////////////////
uf_alg.Ud = Ud;
uf_alg.Uq = Uq;
if (uf_alg.tetta > CONST_IQ_2PI)
{
uf_alg.tetta -= CONST_IQ_2PI;
}
if (uf_alg.tetta < 0)
{
uf_alg.tetta += CONST_IQ_2PI;
}
if (n_bs==0)
uf_alg.tetta_bs = uf_alg.tetta + uf_alg.winding_displacement_bs1;
else
uf_alg.tetta_bs = uf_alg.tetta + uf_alg.winding_displacement_bs2;
dq_to_ab.Tetta = uf_alg.tetta_bs;
////////////////////////////////////////
////////////////////////////////////////
dq_to_ab.Ud = Ud;
dq_to_ab.Uq = Uq;
dq_to_ab.calc2(&dq_to_ab);
svgen_dq_1.Ualpha = dq_to_ab.Ualpha;
svgen_dq_1.Ubeta = dq_to_ab.Ubeta;
////////////////////////////////////////
uf_alg.Ualpha = dq_to_ab.Ualpha;
uf_alg.Ubeta = dq_to_ab.Ubeta;
////////////////////////////////////////
// svgen_dq_1.Ualpha = 0;
// svgen_dq_1.Ubeta = 0;
svgen_dq_1.calc(&svgen_dq_1);
uf_alg.svgen_dq_Ta = svgen_dq_1.Ta;
uf_alg.svgen_dq_Tb = svgen_dq_1.Tb;
uf_alg.svgen_dq_Tc = svgen_dq_1.Tc;
////////////////////////////////////////
// dq_to_ab.Tetta = uf_alg.tetta;
// dq_to_ab.Ud = Ud;
// dq_to_ab.Uq = Uq;
// dq_to_ab.calc2(&dq_to_ab);
//
// svgen_dq_2.Ualpha = dq_to_ab.Ualpha;
// svgen_dq_2.Ubeta = dq_to_ab.Ubeta;
//
// svgen_dq_2.calc(&svgen_dq_2);
// 1
// a
pwm_t = correct_balance_uzpt_pwm24 (svgen_dq_1.Ta, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_1, &svgen_pwm24_1.Ta_0, &svgen_pwm24_1.Ta_1, &svgen_pwm24_1.Ta_imp, pwm_t);
// b
pwm_t = correct_balance_uzpt_pwm24 (svgen_dq_1.Tb, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_1, &svgen_pwm24_1.Tb_0, &svgen_pwm24_1.Tb_1, &svgen_pwm24_1.Tb_imp,pwm_t);
// c
pwm_t = correct_balance_uzpt_pwm24 (svgen_dq_1.Tc, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_1, &svgen_pwm24_1.Tc_0, &svgen_pwm24_1.Tc_1, &svgen_pwm24_1.Tc_imp,pwm_t);
// 2 àíàëîãè÷íî 1 ò.ê. òóò ïàðàë. ðàáîòà â Ingeteam
svgen_pwm24_2.Ta_0 = svgen_pwm24_1.Ta_0;
svgen_pwm24_2.Ta_1 = svgen_pwm24_1.Ta_1;
svgen_pwm24_2.Tb_0 = svgen_pwm24_1.Tb_0;
svgen_pwm24_2.Tb_1 = svgen_pwm24_1.Tb_1;
svgen_pwm24_2.Tc_0 = svgen_pwm24_1.Tc_0;
svgen_pwm24_2.Tc_1 = svgen_pwm24_1.Tc_1;
//
//// a
// pwm_t = correct_balance_uzpt_pwm24 (svgen_dq_1.Ta, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_2, &svgen_pwm24_2.Ta_0, &svgen_pwm24_2.Ta_1, &svgen_pwm24_2.Ta_imp,pwm_t);
//// b
// pwm_t = correct_balance_uzpt_pwm24 (svgen_dq_1.Tb, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_2, &svgen_pwm24_2.Tb_0, &svgen_pwm24_2.Tb_1, &svgen_pwm24_2.Tb_imp,pwm_t);
//// c2
// pwm_t = correct_balance_uzpt_pwm24 (svgen_dq_1.Tc, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24 (&svgen_pwm24_2, &svgen_pwm24_2.Tc_0, &svgen_pwm24_2.Tc_1, &svgen_pwm24_2.Tc_imp,pwm_t);
////////////////////////////////////////
////////////////////////////////////////
////
if (flag_km_0)
{
svgen_pwm24_1.prev_level = V_PWM24_PREV_PWM_WORK_KM0;
svgen_pwm24_2.prev_level = V_PWM24_PREV_PWM_WORK_KM0;
}
else
{
svgen_pwm24_1.prev_level = V_PWM24_PREV_PWM_WORK;
svgen_pwm24_2.prev_level = V_PWM24_PREV_PWM_WORK;
}
////////////////////////////////////////
////////////////////////////////////////
// logpar.log1 = (int16)(_IQtoIQ15(uz1));
// logpar.log2 = (int16)(_IQtoIQ15(fz1));
// logpar.log3 = (int16)(_IQtoIQ15(Ud));
// logpar.log4 = (int16)(_IQtoIQ15(Uq));
// logpar.log5 = (int16)(_IQtoIQ15(svgen_dq_1.Ualpha));
// logpar.log6 = (int16)(_IQtoIQ15(svgen_dq_1.Ubeta));
// logpar.log7 = (int16)(_IQtoIQ15(svgen_dq_1.Ta));
// logpar.log8 = (int16)(_IQtoIQ15(svgen_dq_1.Tb));
// logpar.log9 = (int16)(_IQtoIQ15(svgen_dq_1.Tc));
// logpar.log10 = (int16)(_IQtoIQ12(analog.tetta));
// logpar.log11 = (int16)(svgen_pwm24_1.Ta_0.Ti);
// logpar.log12 = (int16)((svgen_pwm24_1.Ta_1.Ti));
// logpar.log13 = (int16)(svgen_pwm24_1.Tb_0.Ti);
// logpar.log14 = (int16)((svgen_pwm24_1.Tb_1.Ti));
// logpar.log15 = (int16)(svgen_pwm24_1.Tc_0.Ti);
// logpar.log16 = (int16)((svgen_pwm24_1.Tc_1.Ti));
// svgen_pwm24_1.calc(&svgen_pwm24_1);
// svgen_pwm24_2.calc(&svgen_pwm24_2);
// !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
// !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
// set_predel_dshim24_simple0(&svgen_pwm24_1.Ta_0,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
// set_predel_dshim24_simple1(&svgen_pwm24_1.Ta_1,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
//
// set_predel_dshim24_simple0(&svgen_pwm24_1.Tb_0,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
// set_predel_dshim24_simple1(&svgen_pwm24_1.Tb_1,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
//
// set_predel_dshim24_simple0(&svgen_pwm24_1.Tc_0,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
// set_predel_dshim24_simple1(&svgen_pwm24_1.Tc_1,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
//
// set_predel_dshim24_simple0(&svgen_pwm24_2.Ta_0,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
// set_predel_dshim24_simple1(&svgen_pwm24_2.Ta_1,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
//
// set_predel_dshim24_simple0(&svgen_pwm24_2.Tb_0,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
// set_predel_dshim24_simple1(&svgen_pwm24_2.Tb_1,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
//
// set_predel_dshim24_simple0(&svgen_pwm24_2.Tc_0,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
// set_predel_dshim24_simple1(&svgen_pwm24_2.Tc_1,VAR_PERIOD_MIN_XTICS,VAR_FREQ_PWM_XTICS);
*Uzad_out = Uq;
if (master==MODE_MASTER)
*tetta_out = uf_alg.tetta + add_tetta; // åùå ñäâèãàåìñÿ, ò.ê. â slave ïðèäåò ñ çàäåðæêîé íà îäèí òàêò øèìà èëè íà äâà?
else
*tetta_out = uf_alg.tetta;
*Kplus_out = Kplus;
}
#pragma CODE_SECTION(test_calc_vect_dq_pwm24_Ing,".v_24pwm_run");
void test_calc_vect_dq_pwm24_Ing(_iq Theta_zad,_iq Ud_zad, _iq Uq_zad,
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,
unsigned int master,
unsigned int n_bs,
_iq *Kplus_out,
_iq *Uzad_out )
{
_iq Kplus;
_iq Ud = 0;
_iq Uq = 0;
_iq Umod = 0;
_iq pwm_t;
DQ_TO_ALPHABETA dq_to_ab = DQ_TO_ALPHABETA_DEFAULTS;
static _iq max_Km = _IQ(MAX_ZADANIE_K_M);
static _iq max_Km_square = _IQ(MAX_ZADANIE_K_M * MAX_ZADANIE_K_M);
////////////////////////////////////////
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));
}
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;
////////////////////////////////////////
////////////////////////////////////////
if (master == MODE_MASTER)
{
// ìû master
uf_alg.tetta = Theta_zad;
Ud = Ud_zad;
Uq = Uq_zad; //_IQsat(Uzad_uf1,Uzad_max,0);
}
else if (master == MODE_SLAVE)
{
// ìû slave
uf_alg.tetta = Theta_zad;
Ud = Ud_zad;
Uq = Uq_zad; //_IQsat(master_Uzad_uf1,Uzad_max,0);
}
else
{
// ìû íåïîíÿòíî êòî!
Ud = 0;
Uq = 0;
uf_alg.tetta = 0;
}
////////////////////////////////////////
////////////////////////////////////////
uf_alg.Ud = Ud;
uf_alg.Uq = Uq;
if (uf_alg.tetta > CONST_IQ_2PI)
{
uf_alg.tetta -= CONST_IQ_2PI;
}
if (uf_alg.tetta < 0)
{
uf_alg.tetta += CONST_IQ_2PI;
}
if (n_bs == 0)
uf_alg.tetta_bs = uf_alg.tetta + uf_alg.winding_displacement_bs1;
else
uf_alg.tetta_bs = uf_alg.tetta + uf_alg.winding_displacement_bs2;
dq_to_ab.Tetta = uf_alg.tetta_bs;
dq_to_ab.Ud = Ud;
dq_to_ab.Uq = Uq;
dq_to_ab.calc2(&dq_to_ab);
svgen_dq_1.Ualpha = dq_to_ab.Ualpha;
svgen_dq_1.Ubeta = dq_to_ab.Ubeta;
////////////////////////////////////////
uf_alg.Ualpha = dq_to_ab.Ualpha;
uf_alg.Ubeta = dq_to_ab.Ubeta;
svgen_dq_1.calc(&svgen_dq_1);
uf_alg.svgen_dq_Ta = svgen_dq_1.Ta;
uf_alg.svgen_dq_Tb = svgen_dq_1.Tb;
uf_alg.svgen_dq_Tc = svgen_dq_1.Tc;
// 1
// a
pwm_t = correct_balance_uzpt_pwm24(svgen_dq_1.Ta, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24(&svgen_pwm24_1, &svgen_pwm24_1.Ta_0,
&svgen_pwm24_1.Ta_1,
&svgen_pwm24_1.Ta_imp, pwm_t);
// b
pwm_t = correct_balance_uzpt_pwm24(svgen_dq_1.Tb, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24(&svgen_pwm24_1, &svgen_pwm24_1.Tb_0,
&svgen_pwm24_1.Tb_1,
&svgen_pwm24_1.Tb_imp, pwm_t);
// c
pwm_t = correct_balance_uzpt_pwm24(svgen_dq_1.Tc, Kplus);
recalc_time_pwm_minimal_2_xilinx_pwm24(&svgen_pwm24_1, &svgen_pwm24_1.Tc_0,
&svgen_pwm24_1.Tc_1,
&svgen_pwm24_1.Tc_imp, pwm_t);
// 2 àíàëîãè÷íî 1 ò.ê. òóò ïàðàë. ðàáîòà â Ingeteam
svgen_pwm24_2.Ta_0 = svgen_pwm24_1.Ta_0;
svgen_pwm24_2.Ta_1 = svgen_pwm24_1.Ta_1;
svgen_pwm24_2.Tb_0 = svgen_pwm24_1.Tb_0;
svgen_pwm24_2.Tb_1 = svgen_pwm24_1.Tb_1;
svgen_pwm24_2.Tc_0 = svgen_pwm24_1.Tc_0;
svgen_pwm24_2.Tc_1 = svgen_pwm24_1.Tc_1;
//// a
// pwm_t = correct_balance_uzpt_pwm24(svgen_dq_1.Ta, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24(&svgen_pwm24_2, &svgen_pwm24_2.Ta_0,
// &svgen_pwm24_2.Ta_1,
// &svgen_pwm24_2.Ta_imp, pwm_t);
//// b
// pwm_t = correct_balance_uzpt_pwm24(svgen_dq_1.Tb, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24(&svgen_pwm24_2, &svgen_pwm24_2.Tb_0,
// &svgen_pwm24_2.Tb_1,
// &svgen_pwm24_2.Tb_imp, pwm_t);
//// c2
// pwm_t = correct_balance_uzpt_pwm24(svgen_dq_1.Tc, Kplus);
// recalc_time_pwm_minimal_2_xilinx_pwm24(&svgen_pwm24_2, &svgen_pwm24_2.Tc_0,
// &svgen_pwm24_2.Tc_1,
// &svgen_pwm24_2.Tc_imp, pwm_t);
////////////////////////////////////////
////////////////////////////////////////
}

View File

@ -0,0 +1,93 @@
/*
* uf_alg.h
*
* Created on: 10 ôåâð. 2020 ã.
* Author: yura
*/
#ifndef _UF_ALG_ING_H_
#define _UF_ALG_ING_H_
#include "svgen_mf.h"
#define CONST_IQ_05 8388608 //0.5
#define CONST_IQ_1 16777216 //1.0
/* Ãëîáàëüíàß ñòðóêòóðà UF ALG */
typedef struct
{
_iq tetta;
_iq tetta_bs;
_iq winding_displacement_bs1;
_iq winding_displacement_bs2;
_iq hz_to_angle;
_iq Kplus;
_iq Ud;
_iq Uq;
_iq Ualpha;
_iq Ubeta;
_iq svgen_dq_Ta;
_iq svgen_dq_Tb;
_iq svgen_dq_Tc;
} UF_ALG_VALUE;
#define UF_ALG_VALUE_DEFAULT {0,0,0,0,0,0,0,0,0,0,0,0,0}
extern UF_ALG_VALUE uf_alg ;
extern SVGENMF svgen_mf1;
extern SVGENMF svgen_mf2;
//void uf_const_f(_iq Fzad_uf1,_iq Fzad_uf2,_iq Uzad_uf1, _iq Uzad_uf2, int Revers,unsigned int enable_alg_u_disbalance);
void uf_const_f_24_Ing(_iq Fzad_uf1,_iq Fzad_uf2,_iq Uzad_uf1, _iq Uzad_uf2, unsigned int enable_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 *Kplus_out);
void uf_disbalance_uzpt(_iq Uzad_uf1, unsigned int disable_alg_u_disbalance, _iq kplus_u_disbalance, _iq k_u_disbalance,
_iq U_1, _iq U_2,
_iq Uzad_max,
_iq *Kplus_out);
void init_alpha_Ing(unsigned int bs);
void InitVariablesSvgen_Ing(unsigned int freq);
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,
unsigned int master,
unsigned int n_bs,
_iq *Kplus_out,
_iq *tetta_out,
_iq *Uzad_out);
void test_calc_vect_dq_pwm24_Ing(_iq Theta_zad,_iq Ud_zad, _iq Uq_zad,
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,
unsigned int master,
unsigned int n_bs,
_iq *Kplus_out,
_iq *Uzad_out);
#endif /* _UF_ALG_H_ */

View File

@ -0,0 +1,45 @@
/*=====================================================================================
File name: VHZPROF.C (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description: V/f Profile for Scalar Control of Induction Motor
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
-------------------------------------------------------------------------------------*/
#include "IQmathLib.h" // Include header for IQmath library
#include "vhzprof.h"
#include "math.h" // Include math libs
#include "dmctype.h"
//#include <stdlib.h>
void vhz_prof_calc(VHZPROF *v)
{
_iq VfSlope, AbsFreq;
// Take absolute frequency to allow the operation of both rotational directions
AbsFreq = labs(v->Freq);
if (AbsFreq <= v->LowFreq)
// Compute output voltage in profile #1
v->VoltOut = v->VoltMin;
else if ((AbsFreq > v->LowFreq)&(AbsFreq <= v->HighFreq))
{
// Compute slope of V/f profile
VfSlope = _IQdiv((v->VoltMax - v->VoltMin),(v->HighFreq - v->LowFreq));
// Compute output voltage in profile #2
v->VoltOut = v->VoltMin + _IQmpy(VfSlope,(AbsFreq-v->LowFreq));
}
else if ((AbsFreq > v->HighFreq)&(AbsFreq < v->FreqMax))
// Compute output voltage in profile #3
v->VoltOut = v->VoltMax;
}

View File

@ -0,0 +1,41 @@
/* =================================================================================
File name: VHZ_PROF.H (IQ version)
Originator: Digital Control Systems Group
Texas Instruments
Description:
Header file containing constants, data type definitions, and
function prototypes for the VHZPROF.
=====================================================================================
History:
-------------------------------------------------------------------------------------
04-15-2005 Version 3.20
------------------------------------------------------------------------------*/
#ifndef __VHZ_PROF_H__
#define __VHZ_PROF_H__
typedef struct { _iq Freq; // Input: Input Frequency (pu)
_iq VoltOut; // Output: Output voltage (pu)
_iq LowFreq; // Parameter: Low Frequency (pu)
_iq HighFreq; // Parameter: High Frequency at rated voltage (pu)
_iq FreqMax; // Parameter: Maximum Frequency (pu)
_iq VoltMax; // Parameter: Rated voltage (pu)
_iq VoltMin; // Parameter: Voltage at low Frequency range (pu)
void (*calc)(); // Pointer to calculation function
} VHZPROF;
typedef VHZPROF *VHZPROF_handle;
/*-----------------------------------------------------------------------------
Default initalizer for the VHZPROF object.
-----------------------------------------------------------------------------*/
#define VHZPROF_DEFAULTS { 0,0, \
0,0,0,0,0, \
(void (*)(Uint32))vhz_prof_calc }
/*------------------------------------------------------------------------------
Prototypes for the functions in VHZ_PROF.C
------------------------------------------------------------------------------*/
void vhz_prof_calc(VHZPROF_handle);
#endif // __VHZ_PROF_H__

View File

@ -0,0 +1,64 @@
/*
* word_structurs.h
*
* Created on: 5 èþí. 2020 ã.
* Author: Yura
*/
#ifndef SRC_LIBS_NIO12_WORD_STRUCTURS_H_
#define SRC_LIBS_NIO12_WORD_STRUCTURS_H_
////////////////////////////////////////////////////////////////////////////////
typedef union
{
struct
{
unsigned int bit0: 1;
unsigned int bit1: 1;
unsigned int bit2: 1;
unsigned int bit3: 1;
unsigned int bit4: 1;
unsigned int bit5: 1;
unsigned int bit6: 1;
unsigned int bit7: 1;
unsigned int bit8: 1;
unsigned int bit9: 1;
unsigned int bit10: 1;
unsigned int bit11: 1;
unsigned int bit12: 1;
unsigned int bit13: 1;
unsigned int bit14: 1;
unsigned int bit15: 1;
} bits; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè ïîáèòíî
int all; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè âìåñòå
} WORD_INT2BITS_STRUCT; // Ñòðóêòóðà ñëîâ ãîòîâà ñ ïîáèòîâûì äîñòóïîì
//////
////////////////////////////////////////////////////////////////////////////////
typedef union
{
struct
{
unsigned int bit0: 1;
unsigned int bit1: 1;
unsigned int bit2: 1;
unsigned int bit3: 1;
unsigned int bit4: 1;
unsigned int bit5: 1;
unsigned int bit6: 1;
unsigned int bit7: 1;
unsigned int bit8: 1;
unsigned int bit9: 1;
unsigned int bit10: 1;
unsigned int bit11: 1;
unsigned int bit12: 1;
unsigned int bit13: 1;
unsigned int bit14: 1;
unsigned int bit15: 1;
} bits; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè ïîáèòíî
unsigned int all; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè âìåñòå
} WORD_UINT2BITS_STRUCT; // Ñòðóêòóðà ñëîâ ãîòîâà ñ ïîáèòîâûì äîñòóïîì
//////
#endif /* SRC_LIBS_NIO12_WORD_STRUCTURS_H_ */

View File

@ -0,0 +1,143 @@
#include "CRC_Functions.h"
#pragma DATA_SECTION(crc_16_tab, ".slow_vars")
WORD crc_16_tab[] = {
0x0000, 0xc0c1, 0xc181, 0x0140, 0xc301, 0x03c0, 0x0280, 0xc241,
0xc601, 0x06c0, 0x0780, 0xc741, 0x0500, 0xc5c1, 0xc481, 0x0440,
0xcc01, 0x0cc0, 0x0d80, 0xcd41, 0x0f00, 0xcfc1, 0xce81, 0x0e40,
0x0a00, 0xcac1, 0xcb81, 0x0b40, 0xc901, 0x09c0, 0x0880, 0xc841,
0xd801, 0x18c0, 0x1980, 0xd941, 0x1b00, 0xdbc1, 0xda81, 0x1a40,
0x1e00, 0xdec1, 0xdf81, 0x1f40, 0xdd01, 0x1dc0, 0x1c80, 0xdc41,
0x1400, 0xd4c1, 0xd581, 0x1540, 0xd701, 0x17c0, 0x1680, 0xd641,
0xd201, 0x12c0, 0x1380, 0xd341, 0x1100, 0xd1c1, 0xd081, 0x1040,
0xf001, 0x30c0, 0x3180, 0xf141, 0x3300, 0xf3c1, 0xf281, 0x3240,
0x3600, 0xf6c1, 0xf781, 0x3740, 0xf501, 0x35c0, 0x3480, 0xf441,
0x3c00, 0xfcc1, 0xfd81, 0x3d40, 0xff01, 0x3fc0, 0x3e80, 0xfe41,
0xfa01, 0x3ac0, 0x3b80, 0xfb41, 0x3900, 0xf9c1, 0xf881, 0x3840,
0x2800, 0xe8c1, 0xe981, 0x2940, 0xeb01, 0x2bc0, 0x2a80, 0xea41,
0xee01, 0x2ec0, 0x2f80, 0xef41, 0x2d00, 0xedc1, 0xec81, 0x2c40,
0xe401, 0x24c0, 0x2580, 0xe541, 0x2700, 0xe7c1, 0xe681, 0x2640,
0x2200, 0xe2c1, 0xe381, 0x2340, 0xe101, 0x21c0, 0x2080, 0xe041,
0xa001, 0x60c0, 0x6180, 0xa141, 0x6300, 0xa3c1, 0xa281, 0x6240,
0x6600, 0xa6c1, 0xa781, 0x6740, 0xa501, 0x65c0, 0x6480, 0xa441,
0x6c00, 0xacc1, 0xad81, 0x6d40, 0xaf01, 0x6fc0, 0x6e80, 0xae41,
0xaa01, 0x6ac0, 0x6b80, 0xab41, 0x6900, 0xa9c1, 0xa881, 0x6840,
0x7800, 0xb8c1, 0xb981, 0x7940, 0xbb01, 0x7bc0, 0x7a80, 0xba41,
0xbe01, 0x7ec0, 0x7f80, 0xbf41, 0x7d00, 0xbdc1, 0xbc81, 0x7c40,
0xb401, 0x74c0, 0x7580, 0xb541, 0x7700, 0xb7c1, 0xb681, 0x7640,
0x7200, 0xb2c1, 0xb381, 0x7340, 0xb101, 0x71c0, 0x7080, 0xb041,
0x5000, 0x90c1, 0x9181, 0x5140, 0x9301, 0x53c0, 0x5280, 0x9241,
0x9601, 0x56c0, 0x5780, 0x9741, 0x5500, 0x95c1, 0x9481, 0x5440,
0x9c01, 0x5cc0, 0x5d80, 0x9d41, 0x5f00, 0x9fc1, 0x9e81, 0x5e40,
0x5a00, 0x9ac1, 0x9b81, 0x5b40, 0x9901, 0x59c0, 0x5880, 0x9841,
0x8801, 0x48c0, 0x4980, 0x8941, 0x4b00, 0x8bc1, 0x8a81, 0x4a40,
0x4e00, 0x8ec1, 0x8f81, 0x4f40, 0x8d01, 0x4dc0, 0x4c80, 0x8c41,
0x4400, 0x84c1, 0x8581, 0x4540, 0x8701, 0x47c0, 0x4680, 0x8641,
0x8201, 0x42c0, 0x4380, 0x8341, 0x4100, 0x81c1, 0x8081, 0x4040
};
unsigned char GetCRC8_Dallas1_WireReverse(unsigned char *DataArrIn, unsigned int DataLength)
{
unsigned char i, Data = 0, CRC = 0, CheckBit;
unsigned int ByteCnt = 0;
do
{
Data = DataArrIn[ByteCnt];
for(i = 0; i < 8; i++)
{
CheckBit = CRC ^ Data;
CheckBit &= 1;
CRC >>= 1;
Data >>= 1;
if(CheckBit == 1) CRC ^= 0x8C;
}
ByteCnt++;
}
while(ByteCnt < DataLength);
return CRC;
}
unsigned char GetCRC8_Dallas1_Wire(unsigned char *DataArrIn, unsigned int DataLength)
{
unsigned char CRC = 0x00;
unsigned int i;
while (DataLength--)
{
CRC ^= *(DataArrIn++);
for (i = 0; i < 8; i++) CRC = (CRC & 0x80 ? (CRC << 1) ^ 0x31 : CRC << 1) & 0x00FF;
}
return CRC;
}
unsigned int GetCRC16_IBM(unsigned int crc, unsigned int *buf, unsigned int size)
{
while(size--)
{
crc = (crc >> 8) ^ crc_16_tab[ (crc ^ *buf++) & 0xff ];
crc = crc & 0xffff;
}
return (crc & 0xffff);
}
unsigned int GetCRC16_IBM_v2(unsigned int crc, unsigned int *buf, unsigned int size)
{
unsigned int xor = 0;
while(size--)
{
// crc = (crc >> 8) ^ crc_16_tab[ (crc ^ *buf++) & 0xff ];
// crc = crc & 0xffff;
xor = ((*buf++) ^ crc) & 0xff;
crc >>= 8;
crc ^= crc_16_tab[xor];
}
return (crc & 0xffff);
}
unsigned int GetCRC16_B(unsigned int crc,unsigned int *buf,unsigned long size )
{
unsigned int x, dword, byte;
unsigned long i;
for (i = 0; i < size; i++)
{
x = i % 2;
dword = buf[i/2];
// dword = *buf;
if (x == 0)
{
byte = ((dword >> 8)&0xFF);
}
if (x == 1)
{
byte = (dword & 0xFF);
}
crc = (crc >> 8) ^ crc_16_tab[ (crc ^ (byte) ) & 0xff ];
crc = crc & 0xffff;
// crc = crc + ((byte) & 0xff);
}
return (crc & 0xffff);
}

View File

@ -0,0 +1,12 @@
#ifndef _CRC_FUNCTIONS_H
#define _CRC_FUNCTIONS_H
typedef unsigned short WORD;
unsigned int GetCRC16_IBM(unsigned int crc, unsigned int *buf, unsigned int size);
unsigned int GetCRC16_B(unsigned int crc,unsigned int *buf,unsigned long size);
unsigned char GetCRC8_Dallas1_WireReverse(unsigned char *DataArrIn, unsigned int DataLength);
unsigned char GetCRC8_Dallas1_Wire(unsigned char *DataArrIn, unsigned int DataLength);
unsigned int GetCRC16_IBM_v2(unsigned int crc, unsigned int *buf, unsigned int size);
#endif

View File

@ -0,0 +1,325 @@
#include "MemoryFunctions.h"
#define START_ADR_FLASH 0x100000
void write_xmemory(unsigned long addr, unsigned int data);
unsigned int flash_read_word(unsigned long adr);
void flash_reset();
unsigned char flash_toggle_bit(long adr)
{
unsigned int dq1,dq2,tog,tim;
unsigned long cicle;
cicle=0;
dq1 = flash_read_word(adr);
do
{
dq2= flash_read_word(adr);
tog = (dq1 & 0x40) + ( dq2 & 0x40);
if (tog!=0x40)
return 0;
dq1=dq2;
tim=dq2 & 0x20;
cicle++;
} while ((cicle!=26553500) && (tim==0));
dq1 = flash_read_word(adr);
dq2 = flash_read_word(adr);
tog = (dq1 & 0x40) + ( dq2 & 0x40);
if (tog!=0x40)
return 0;
flash_reset();
return 1;
}
#pragma CODE_SECTION(ReadMemory,".fast_run");
unsigned int ReadMemory(unsigned long addr)
{
return (*(volatile int *)(addr));
}
#pragma CODE_SECTION(WriteMemory,".fast_run");
void WriteMemory(unsigned long addr, unsigned int data)
{
(*(volatile int *)( addr )) = data;
}
unsigned char flash_erase_sector(unsigned long adr)
{
write_xmemory(0x555,0xaa);
write_xmemory(0x2aa,0x55);
write_xmemory(0x555,0x80);
write_xmemory(0x555,0xaa);
write_xmemory(0x2aa,0x55);
write_xmemory(adr,0x30);
return flash_toggle_bit(adr);
}
#pragma CODE_SECTION(write_xmemory,".fast_run");
void write_xmemory(unsigned long addr, unsigned int data)
{
(*(volatile int *)(START_ADR_FLASH+addr)) = data;
}
#pragma CODE_SECTION(read_xmemory,".fast_run");
unsigned int read_xmemory(unsigned long addr)
{
return (*(volatile int *)(START_ADR_FLASH+addr));
}
unsigned int flash_read_word(unsigned long adr)
{
return read_xmemory(adr);
}
void flash_reset()
{
write_xmemory(0,0xf0);
}
unsigned int flash_write_word(unsigned long adr, unsigned int dat)
{
unsigned int dq=0xffff;
if (dat!=dq)
{
write_xmemory(0x555,0xaa );
write_xmemory(0x2aa,0x55 );
write_xmemory(0x555,0xa0 );
write_xmemory(adr,dat);
dq=flash_toggle_bit(adr);
dq=flash_read_word(adr);
}
return (dq==dat);
}
unsigned int RunFlashData(unsigned long AdrFrom, unsigned long AdrTo, unsigned long Length,
unsigned int *cerr_out, unsigned int *repl_out, unsigned int *count_ok_out)
{
unsigned long adr_start,adr_end,f_s,f_e;
int i;
static char flash_tab[] = {
32,32,32,32,32,32,32,32,32,32,32,32,32,32,16,4,4,8
};
unsigned int d1,d2, d3, cerr=0, repl = 0, count_ok = 0;
unsigned long adr_out,adr_in, adr_out_s;
*cerr_out = 0;
*repl_out = 0;
*count_ok_out = 0;
flash_reset();
i=0;
adr_start=AdrTo-START_ADR_FLASH;
adr_end=adr_start+Length;
f_s=0;
f_e=0;
for (i=0;i<16;i++)
{
f_s=f_e;
f_e=f_s+(unsigned long)flash_tab[i]*1024;
if ( f_s<=adr_start && f_e>adr_start ) flash_erase_sector(f_s);
if ( f_s>adr_start && f_e<adr_end ) flash_erase_sector(f_s);
if ( f_s<adr_end && f_e>adr_end ) flash_erase_sector(f_s);
}
// i=flash_erase_sector(0x20000);
// i=flash_erase_sector(0x28000);
// i=flash_erase_sector(0x30000);
// i=flash_erase_sector(0x38000);
if (i!=0)
{
// error
// delay_loop();
}
//check clear flash?
adr_out_s=AdrTo-START_ADR_FLASH;
cerr=0;
adr_in=AdrFrom;
for (adr_out = 0; adr_out < Length; adr_out++)
{
d1=flash_read_word(adr_out+adr_out_s);
if (d1!=0xffff)
{
cerr++;
}
}
if (cerr)
{
*cerr_out = cerr;
*repl_out = 0;
*count_ok_out = 0;
return RETURN_FLASHED_NOT_CLEAR_1;
}
// end check clear flash
// ïèøåì âî flash
adr_out_s = AdrTo-START_ADR_FLASH;
cerr = 0;
adr_in = AdrFrom;
for (adr_out = 0; adr_out < Length; adr_out++)
{
d1=flash_read_word(adr_out+adr_out_s);
d3=ReadMemory(adr_in);
adr_in++;
if (d1==0xffff) // ïàìÿòü ÷èñòàÿ?
{
flash_write_word(adr_out+adr_out_s,d3);
d2=flash_read_word(adr_out+adr_out_s);
if (d2!=d3)
{
// âòîðàÿ ïîïûòêà
repl++;
if (d2==0xffff)
{
flash_write_word(adr_out+adr_out_s,d3);
d2=flash_read_word(adr_out+adr_out_s);
if (d2!=d3)
{
cerr++;
*cerr_out = cerr;
*repl_out = repl;
*count_ok_out = count_ok;
return RETURN_FLASHED_ERROR_AFTER_REPL;
}
else
count_ok++;
}
else
{
// ÷òî-òî çàïèñàëîñü, íî ñ îøèáêîé, íàäî áû îïÿòü ñòèðàòü ñåêòîð
cerr++;
*cerr_out = cerr;
*repl_out = repl;
*count_ok_out = count_ok;
return RETURN_FLASHED_ERROR_BEFORE_REPL_NOT_CLEAR;
}
}
else
count_ok++;
}
else
{
//íå ñòåðòà ïî÷åìó-òî! îøèáêà!
cerr++;
*cerr_out = cerr;
*repl_out = repl;
*count_ok_out = count_ok;
return RETURN_FLASHED_NOT_CLEAR_2;
}
}
*cerr_out = cerr;
*repl_out = repl;
*count_ok_out = count_ok;
if (cerr)
return RETURN_FLASHED_ERROR;
return RETURN_FLASHED_OK;
}
unsigned int VerifyFlashData(unsigned long AdrFrom, unsigned long AdrTo, unsigned long Length,
unsigned int *cerr_out, unsigned int *repl_out, unsigned int *count_ok_out)
{
unsigned long adr_start,adr_end,f_s,f_e;
int i;
volatile unsigned int d1,d2, d3, cerr=0, repl = 0, count_ok = 0;
unsigned long adr_out,adr_in, adr_out_s;
*cerr_out = 0;
*repl_out = 0;
*count_ok_out = 0;
i=0;
adr_start=AdrTo-START_ADR_FLASH;
adr_end=adr_start+Length;
f_s=0;
f_e=0;
// test flash
adr_out_s = AdrTo-START_ADR_FLASH;
cerr = 0;
adr_in = AdrFrom;
for (adr_out = 0; adr_out < Length; adr_out++)
{
d1=flash_read_word(adr_out+adr_out_s);
d3=ReadMemory(adr_in);
adr_in++;
repl++;
if (d1!=d3)
{
cerr++;
}
else
count_ok++;
}
*cerr_out = cerr;
*repl_out = count_ok;
*count_ok_out = count_ok;
if (cerr)
return RETURN_FLASHED_ERROR;
return RETURN_FLASHED_OK;
}

View File

@ -0,0 +1,36 @@
#ifndef _MEMORY_FUNCTIONS_H
#define _MEMORY_FUNCTIONS_H
enum {RETURN_FLASHED_OK=0,
RETURN_FLASHED_NOT_CLEAR_1,
RETURN_FLASHED_NOT_CLEAR_2,
RETURN_FLASHED_ERROR_AFTER_REPL,
RETURN_FLASHED_ERROR_BEFORE_REPL_NOT_CLEAR,
RETURN_FLASHED_ERROR
};
//#include "RS_Functions_modbus.h"
void WriteMemory(unsigned long addr, unsigned int data);
unsigned int ReadMemory(unsigned long addr);
//unsigned int RunFlashData(unsigned long AdrFrom,unsigned long AdrTo, unsigned long Length);
unsigned int RunFlashData(unsigned long AdrFrom, unsigned long AdrTo, unsigned long Length,
unsigned int *cerr_out, unsigned int *repl_out, unsigned int *count_ok_out);
unsigned int VerifyFlashData(unsigned long AdrFrom, unsigned long AdrTo, unsigned long Length,
unsigned int *cerr_out, unsigned int *repl_out, unsigned int *count_ok_out);
#define i_ReadMemory(addr) ReadMemory(addr)
#define i_WriteMemory(addr,data) WriteMemory(addr,data)
//#define i_ReadMemory(addr) (*(volatile int *)(addr))
//#define i_WriteMemory(addr,data) { (*(volatile int *)( addr )) = data; }
#endif

View File

@ -0,0 +1,98 @@
/*
* RS_Function_terminal.c
*
* Created on: 12 íîÿá. 2020 ã.
* Author: stud
*/
#include "RS_Function_terminal.h"
#include <message2.h>
#include <message2test.h>
#include "modbus_table_v2.h"
#include "options_table.h"
#include "DSP281x_Device.h"
#include "CRC_Functions.h"
#include "MemoryFunctions.h"
#include "RS_Functions.h"
#pragma DATA_SECTION(reply, ".slow_vars")
TMS_TO_TERMINAL_STRUCT reply = TMS_TO_TERMINAL_STRUCT_DEFAULT;
#pragma DATA_SECTION(reply_test_all, ".slow_vars")
TMS_TO_TERMINAL_TEST_ALL_STRUCT reply_test_all = TMS_TO_TERMINAL_TEST_ALL_STRUCT_DEFAULT;
void ReceiveCommandTestAll(RS_DATA_STRUCT *RS232_Arr)
{
unsigned int crc;
// int Data,Data1,Data2,Data3, Data4, DataM, tk1,tk2,tk3,tk0,period = 0, periodMiddle = 0, DataAnalog1, DataAnalog2, doubleImpulse, sinusImpulse;
// static unsigned int prevImp;
// const óêàçàòåëü íà ñòðóêòóðó ñòàíäàðòíîé êîìàíäû
CMD_TO_TMS_TEST_ALL_STRUCT* pcommand = (CMD_TO_TMS_TEST_ALL_STRUCT *)(RS232_Arr->RS_Header);
// íàñòðîèëè íà áóôåð ïðèåìà
// *(TMS_TO_TERMINAL_TEST_ALL_STRUCT*)RS232_Arr->buffer = reply_test_all; /* ?åîáõîäèìû ëåãêèå ïðèâåäåíèy */
// îòâåò, âûâîäèì äàííûå â òåðìèíàëêó
reply_test_all.head.Address = RS232_Arr->addr_recive;//CNTRL_ADDR;
reply_test_all.head.Number = CMD_RS232_TEST_ALL;
func_fill_answer_to_TMS_test(&reply_test_all, pcommand);
*(TMS_TO_TERMINAL_TEST_ALL_STRUCT*)RS232_Arr->buffer = reply_test_all; /* Íåîáõîäèìû ëåãêèå ïðèâåäåíèß */
crc = 0xffff;
crc = GetCRC16_IBM( crc, RS232_Arr->buffer, sizeof(TMS_TO_TERMINAL_TEST_ALL_STRUCT)-3);
reply_test_all.crc_lo = LOBYTE(crc);
reply_test_all.crc_hi = HIBYTE(crc);
// -êîïèðóåì â áóôåð äëy âåðíîñòè
*(TMS_TO_TERMINAL_TEST_ALL_STRUCT*)RS232_Arr->buffer = reply_test_all; // ?åîáõîäèìû ëåãêèå ïðèâåäåíèy
RS_Send(RS232_Arr,RS232_Arr->buffer, sizeof(TMS_TO_TERMINAL_TEST_ALL_STRUCT)+1);
return;
}
void ReceiveCommand(RS_DATA_STRUCT *RS232_Arr)
{
unsigned int crc;
// const óêàçàòåëü íà ñòðóêòóðó ñòàíäàðòíîé êîìàíäû
// íàñòðîèëè íà áóôåð ïðèåìà
//CMD_TO_TMS* const pcommand = (CMD_TO_TMS *)(RS232_Arr->RS_Header);
CMD_TO_TMS_STRUCT* pcommand = (CMD_TO_TMS_STRUCT *)(RS232_Arr->RS_Header);
// îòâåò, âûâîäèì äàííûå â òåðìèíàëêó
reply.head.Address = RS232_Arr->addr_recive;//CNTRL_ADDR;
reply.head.Number = CMD_RS232_STD;
// func_fill_answer_to_TMS(&reply, pcommand);
func_unpack_answer_from_TMS_RS232(pcommand);
func_pack_answer_to_TMS(&reply);
*(TMS_TO_TERMINAL_STRUCT*)RS232_Arr->buffer = reply; // Íåîáõîäèìû ëåãêèå ïðèâåäåíèy
crc = 0xffff;
crc = GetCRC16_IBM( crc, RS232_Arr->buffer, sizeof(TMS_TO_TERMINAL_STRUCT)-3);
reply.crc_lo = LOBYTE(crc);
reply.crc_hi = HIBYTE(crc);
// Ñêîïèðóåì â áóôåð äëy âåðíîñòè
*(TMS_TO_TERMINAL_STRUCT*)RS232_Arr->buffer = reply; // Íåîáõîäèìû ëåãêèå ïðèâåäåíèy
RS_Send(RS232_Arr,RS232_Arr->buffer, sizeof(TMS_TO_TERMINAL_STRUCT)+1);
return;
}

View File

@ -0,0 +1,605 @@
/*
* RS_Function_terminal.h
*
* Created on: 12 íîÿá. 2020 ã.
* Author: stud
*/
#ifndef SRC_XILINX_NIO12_RS_FUNCTION_TERMINAL_H_
#define SRC_XILINX_NIO12_RS_FUNCTION_TERMINAL_H_
#include "RS_Functions.h"
typedef struct
{
CHAR analog1_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
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; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog6_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog6_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
//
CHAR analog7_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog7_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog8_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog8_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog9_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog9_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog10_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog10_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog11_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog11_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog12_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog12_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog13_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog13_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog14_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog14_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog15_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
CHAR analog15_hi; // ñòàðøèé áàéò çàäàííîé ñêîðîñòè
} CMD_ANALOG_DATA_STRUCT;
typedef union
{
struct
{
unsigned int bit0: 1;
unsigned int bit1: 1;
unsigned int bit2: 1;
unsigned int bit3: 1;
unsigned int bit4: 1;
unsigned int bit5: 1;
unsigned int bit6: 1;
unsigned int bit7: 1;
} bit_data; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè ïîáèòíî
CHAR byte_data; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè âìåñòå
} CMD_DIGIT_BYTE_STRUCT; // Äèñêðåòíûå âåëè÷èíû
typedef struct
{
CMD_DIGIT_BYTE_STRUCT Byte01;
CMD_DIGIT_BYTE_STRUCT Byte02;
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
{
CHAR Address; // Àäðåñ êîíòðîëëåðà
CHAR Number; // Íîìåð êîìàíäû
} CMD_TMS_HEAD_STRUCT;
typedef struct
{
// Çàãîëîâîê
CMD_TMS_HEAD_STRUCT head;
// Àíàëîãîâûå âåëè÷èíû
CMD_ANALOG_DATA_STRUCT analog_data;
// Öèôðîâûå çíà÷åíèy
CMD_DIGIT_DATA_STRUCT digit_data;
// Êîíòðîëüíày ñóììà
CHAR crc_lo;
CHAR crc_hi;
// Äîïîëíèòåëüíûé áàéò
CHAR add_byte;
} CMD_TO_TMS_STRUCT;
typedef struct
{
CHAR Address; // Àäðåñ êîíòðîëëåðà
CHAR Number; // Íîìåð êîìàíäû
} CMD_TMS_HEAD_TEST_ALL_STRUCT;
typedef struct
{
CHAR analog1_lo; // ìëàäøèé áàéò çàäàííîé ñêîðîñòè
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
{
CMD_DIGIT_BYTE_STRUCT byte01;
CMD_DIGIT_BYTE_STRUCT byte02;
CMD_DIGIT_BYTE_STRUCT byte03;
CMD_DIGIT_BYTE_STRUCT byte04;
CMD_DIGIT_BYTE_STRUCT byte05;
CMD_DIGIT_BYTE_STRUCT byte06;
CMD_DIGIT_BYTE_STRUCT byte07;
CMD_DIGIT_BYTE_STRUCT byte08;
CMD_DIGIT_BYTE_STRUCT byte09;
CMD_DIGIT_BYTE_STRUCT byte10;
CMD_DIGIT_BYTE_STRUCT byte11;
CMD_DIGIT_BYTE_STRUCT byte12;
} CMD_DIGIT_DATA_TEST_ALL_STRUCT;
typedef struct
{
// Çàãîëîâîê
CMD_TMS_HEAD_TEST_ALL_STRUCT head;
// Àíàëîãîâûå âåëè÷èíû
CMD_ANALOG_DATA_TEST_ALL_STRUCT analog_data;
// Öèôðîâûå çíà÷åíèy
CMD_DIGIT_DATA_TEST_ALL_STRUCT digit_data;
// Êîíòðîëüíày ñóììà
CHAR crc_lo;
CHAR crc_hi;
// Äîïîëíèòåëüíûé áàéò
CHAR add_byte;
} CMD_TO_TMS_TEST_ALL_STRUCT;
typedef struct
{
CMD_DIGIT_BYTE_STRUCT byte01;
CMD_DIGIT_BYTE_STRUCT byte02;
CMD_DIGIT_BYTE_STRUCT byte03;
CMD_DIGIT_BYTE_STRUCT byte04;
CMD_DIGIT_BYTE_STRUCT byte05;
CMD_DIGIT_BYTE_STRUCT byte06;
CMD_DIGIT_BYTE_STRUCT byte07;
CMD_DIGIT_BYTE_STRUCT byte08;
CMD_DIGIT_BYTE_STRUCT byte09;
CMD_DIGIT_BYTE_STRUCT byte10;
CMD_DIGIT_BYTE_STRUCT byte11;
CMD_DIGIT_BYTE_STRUCT byte12;
CMD_DIGIT_BYTE_STRUCT byte13;
CMD_DIGIT_BYTE_STRUCT byte14;
CMD_DIGIT_BYTE_STRUCT byte15;
CMD_DIGIT_BYTE_STRUCT byte16;
CMD_DIGIT_BYTE_STRUCT byte17;
CMD_DIGIT_BYTE_STRUCT byte18;
CMD_DIGIT_BYTE_STRUCT byte19;
CMD_DIGIT_BYTE_STRUCT byte20;
CMD_DIGIT_BYTE_STRUCT byte21;
CMD_DIGIT_BYTE_STRUCT byte22;
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;
CMD_DIGIT_BYTE_STRUCT byte35;
CMD_DIGIT_BYTE_STRUCT byte36;
CMD_DIGIT_BYTE_STRUCT byte37;
CMD_DIGIT_BYTE_STRUCT byte38;
CMD_DIGIT_BYTE_STRUCT byte39;
CMD_DIGIT_BYTE_STRUCT byte40;
CMD_DIGIT_BYTE_STRUCT byte41;
CMD_DIGIT_BYTE_STRUCT byte42;
CMD_DIGIT_BYTE_STRUCT byte43;
CMD_DIGIT_BYTE_STRUCT byte44;
CMD_DIGIT_BYTE_STRUCT byte45;
CMD_DIGIT_BYTE_STRUCT byte46;
CMD_DIGIT_BYTE_STRUCT byte47;
CMD_DIGIT_BYTE_STRUCT byte48;
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; // Äèñêðåòíûå âåëè÷èíû ïîñûëêè îò ÑÓ
typedef struct
{
CHAR analog1_lo;
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;
CHAR analog6_lo;
CHAR analog6_hi;
CHAR analog7_lo;
CHAR analog7_hi;
CHAR analog8_lo;
CHAR analog8_hi;
CHAR analog9_lo;
CHAR analog9_hi;
CHAR analog10_lo;
CHAR analog10_hi;
CHAR analog11_lo;
CHAR analog11_hi;
CHAR analog12_lo;
CHAR analog12_hi;
CHAR analog13_lo;
CHAR analog13_hi;
CHAR analog14_lo;
CHAR analog14_hi;
CHAR analog15_lo;
CHAR analog15_hi;
CHAR analog16_lo;
CHAR analog16_hi;
CHAR analog17_lo;
CHAR analog17_hi;
CHAR analog18_lo;
CHAR analog18_hi;
CHAR analog19_lo;
CHAR analog19_hi;
CHAR analog20_lo;
CHAR analog20_hi;
CHAR analog21_lo;
CHAR analog21_hi;
CHAR analog22_lo;
CHAR analog22_hi;
CHAR analog23_lo;
CHAR analog23_hi;
CHAR analog24_lo;
CHAR analog24_hi;
CHAR analog25_lo;
CHAR analog25_hi;
CHAR analog26_lo;
CHAR analog26_hi;
CHAR analog27_lo;
CHAR analog27_hi;
CHAR analog28_lo;
CHAR analog28_hi;
CHAR analog29_lo;
CHAR analog29_hi;
CHAR analog30_lo;
CHAR analog30_hi;
CHAR analog31_lo;
CHAR analog31_hi;
CHAR analog32_lo;
CHAR analog32_hi;
CHAR analog33_lo;
CHAR analog33_hi;
CHAR analog34_lo;
CHAR analog34_hi;
CHAR analog35_lo;
CHAR analog35_hi;
CHAR analog36_lo;
CHAR analog36_hi;
CHAR analog37_lo;
CHAR analog37_hi;
CHAR analog38_lo;
CHAR analog38_hi;
CHAR analog39_lo;
CHAR analog39_hi;
CHAR analog40_lo;
CHAR analog40_hi;
CHAR analog41_lo;
CHAR analog41_hi;
CHAR analog42_lo;
CHAR analog42_hi;
CHAR analog43_lo;
CHAR analog43_hi;
CHAR analog44_lo;
CHAR analog44_hi;
CHAR analog45_lo;
CHAR analog45_hi;
CHAR analog46_lo;
CHAR analog46_hi;
CHAR analog47_lo;
CHAR analog47_hi;
CHAR analog48_lo;
CHAR analog48_hi;
CHAR analog49_lo;
CHAR analog49_hi;
CHAR analog50_lo;
CHAR analog50_hi;
CHAR analog51_lo;
CHAR analog51_hi;
CHAR analog52_lo;
CHAR analog52_hi;
CHAR analog53_lo;
CHAR analog53_hi;
CHAR analog54_lo;
CHAR analog54_hi;
CHAR analog55_lo;
CHAR analog55_hi;
CHAR analog56_lo;
CHAR analog56_hi;
CHAR analog57_lo;
CHAR analog57_hi;
CHAR analog58_lo;
CHAR analog58_hi;
CHAR analog59_lo;
CHAR analog59_hi;
CHAR analog60_lo;
CHAR analog60_hi;
CHAR analog61_lo;
CHAR analog61_hi;
CHAR analog62_lo;
CHAR analog62_hi;
CHAR analog63_lo;
CHAR analog63_hi;
CHAR analog64_lo;
CHAR analog64_hi;
CHAR analog65_lo;
CHAR analog65_hi;
CHAR analog66_lo;
CHAR analog66_hi;
CHAR analog67_lo;
CHAR analog67_hi;
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;
typedef struct
{
// Çàãîëîâîê
CMD_TMS_HEAD_STRUCT head;
// Öèôðîâûå çíà÷åíèy
ANS_DIGIT_DATA_TO_TERMINAL_STRUCT digit_data;
// Àíàëîãîâûå âåëè÷èíû
TMS_ANALOG_DATA_STRUCT analog_data;
// Êîíòðîëüíày ñóììà
CHAR crc_lo;
CHAR crc_hi;
// Äîïîëíèòåëüíûé áàéò
CHAR add_byte;
} TMS_TO_TERMINAL_STRUCT;
#define TMS_TO_TERMINAL_STRUCT_DEFAULT {{0}, {0}, {0}, 0, 0, 0}
typedef struct
{
CMD_DIGIT_BYTE_STRUCT byte01;
CMD_DIGIT_BYTE_STRUCT byte02;
CMD_DIGIT_BYTE_STRUCT byte03;
CMD_DIGIT_BYTE_STRUCT byte04;
CMD_DIGIT_BYTE_STRUCT byte05;
CMD_DIGIT_BYTE_STRUCT byte06;
CMD_DIGIT_BYTE_STRUCT byte07;
CMD_DIGIT_BYTE_STRUCT byte08;
CMD_DIGIT_BYTE_STRUCT byte09;
CMD_DIGIT_BYTE_STRUCT byte10;
CMD_DIGIT_BYTE_STRUCT byte11;
CMD_DIGIT_BYTE_STRUCT byte12;
CMD_DIGIT_BYTE_STRUCT byte13;
CMD_DIGIT_BYTE_STRUCT byte14;
CMD_DIGIT_BYTE_STRUCT byte15;
CMD_DIGIT_BYTE_STRUCT byte16;
CMD_DIGIT_BYTE_STRUCT byte17;
CMD_DIGIT_BYTE_STRUCT byte18;
CMD_DIGIT_BYTE_STRUCT byte19;
CMD_DIGIT_BYTE_STRUCT byte20;
CMD_DIGIT_BYTE_STRUCT byte21;
CMD_DIGIT_BYTE_STRUCT byte22;
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
{
CHAR analog1_lo;
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;
CHAR analog6_lo;
CHAR analog6_hi;
CHAR analog7_lo;
CHAR analog7_hi;
CHAR analog8_lo;
CHAR analog8_hi;
CHAR analog9_lo;
CHAR analog9_hi;
CHAR analog10_lo;
CHAR analog10_hi;
CHAR analog11_lo;
CHAR analog11_hi;
CHAR analog12_lo;
CHAR analog12_hi;
CHAR analog13_lo;
CHAR analog13_hi;
CHAR analog14_lo;
CHAR analog14_hi;
CHAR analog15_lo;
CHAR analog15_hi;
CHAR analog16_lo;
CHAR analog16_hi;
CHAR analog17_lo;
CHAR analog17_hi;
CHAR analog18_lo;
CHAR analog18_hi;
CHAR analog19_lo;
CHAR analog19_hi;
CHAR analog20_lo;
CHAR analog20_hi;
CHAR analog21_lo;
CHAR analog21_hi;
CHAR analog22_lo;
CHAR analog22_hi;
CHAR analog23_lo;
CHAR analog23_hi;
CHAR analog24_lo;
CHAR analog24_hi;
} TMS_ANALOG_DATA_TEST_ALL_STRUCT;
typedef struct
{
// Çàãîëîâîê
CMD_TMS_HEAD_TEST_ALL_STRUCT head;
// Öèôðîâûå çíà÷åíèy
ANS_DIGIT_DATA_TO_TERMINAL_TEST_ALL_STRUCT digit_data;
// Àíàëîãîâûå âåëè÷èíû
TMS_ANALOG_DATA_TEST_ALL_STRUCT analog_data;
// Êîíòðîëüíày ñóììà
CHAR crc_lo;
CHAR crc_hi;
// Äîïîëíèòåëüíûé áàéò
CHAR add_byte;
//Óêàçàòåëü íà ìàññèâ äàííûõ èç TMS
// unsigned int pcommand;
//Ôóíêöèó ôîðìèðîâàíèó îòâåòà
// void (*fill_answer)();
} TMS_TO_TERMINAL_TEST_ALL_STRUCT;
void ReceiveCommandTestAll(RS_DATA_STRUCT *RS232_Arr);
void ReceiveCommand(RS_DATA_STRUCT *RS232_Arr);
extern TMS_TO_TERMINAL_TEST_ALL_STRUCT reply_test_all;
extern TMS_TO_TERMINAL_STRUCT reply;
#endif /* SRC_XILINX_NIO12_RS_FUNCTION_TERMINAL_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,142 @@
#ifndef _RS_FUNCTIONS_H
#define _RS_FUNCTIONS_H
#define MAX_RECEIVE_LENGTH 254
#define MAX_SEND_LENGTH 400 //266 //254
#define CMD_RS232_MODBUS_1 1
#define CMD_RS232_MODBUS_3 3
#define CMD_RS232_MODBUS_4 4
#define CMD_RS232_MODBUS_5 5
#define CMD_RS232_MODBUS_6 6
#define CMD_RS232_MODBUS_15 15
#define CMD_RS232_MODBUS_16 16
#define RS_TIME_OUT 6000
#define RS_TIME_OUT_MPU 6000//6000 // îæèäàíèå îòâåòà îò ÌÏÓ
#define RS_TIME_OUT_HMI 1000
#define RS_TIME_OUT_MAX 10000
#define RS_TIME_OUT_LOST 1000
typedef unsigned char CHAR;
// Message RS declaration
typedef struct {
unsigned int commnumber; // Íîìåð ïîðòà
unsigned long RS_Length; // Äëèíà ïàêåòà
unsigned int *pRS_RecvPtr; // Áóôåð ïðèåìà
unsigned int *pRS_SendPtr; // Áóôåð ïîñûëêè
unsigned int *pRS_SendPtr_stage1; // Áóôåð ïîñûëêè
unsigned int *pRS_SendPtr_stage2; // Áóôåð ïîñûëêè
unsigned int *pRecvPtr;
unsigned int RS_PrevCmd; // Ïðåäûäóùàß êîììàíäà
unsigned int RS_Cmd; // Òåêóùàß êîììàíäà
unsigned int RS_Header[MAX_RECEIVE_LENGTH]; // Çàãîëîâîê
unsigned int flag_TIMEOUT_to_Send; // Ôëàã îæèäàíèß òàéìàóòà íà îòñûëêó
unsigned int flag_TIMEOUT_to_Receive; // Ôëàã îæèäàíèß òàéìàóòà íà ïðèåì
unsigned int RS_DataReady; // Ôëàã ãîòîâíîñòè RS äàííûõ
unsigned int buffer[MAX_SEND_LENGTH]; // Áóôåð äëß îòñûëêè ïî RS
unsigned int buffer_stage1[8]; // Áóôåð äëß îòñûëêè ïî RS
// unsigned int buffer_stage2[8]; // Áóôåð äëß îòñûëêè ïî RS
unsigned int addr_answer; // àäðåñ êóäà îòâå÷àòü â ðåæèìå âåäóùåãî
unsigned int addr_recive;// àäðåñ ïî êîòîðîìó íàñ çàïðîñèëè
unsigned int flag_LEADING; // Ôëàã ðåæèìà êîíòðîëëåðà (ïî óìîë÷àíèþ âåäîìûé)
unsigned long RS_RecvLen;
unsigned long RS_SLength; // Äëèíà ïàêåòà äëß ïîñûëêè
unsigned long RS_SendLen; // Êîëè÷åñòâî áàéò óæå ïåðåäàëè
unsigned long RS_SLength_stage1; // Äëèíà ïàêåòà äëß ïîñûëêè
unsigned long RS_SLength_stage2; // Äëèíà ïàêåòà äëß ïîñûëêè
unsigned int time_wait_rs_out;
unsigned int time_wait_rs_out_mpu;
unsigned int time_wait_rs_lost; // ñëèøêîì áîëüøàÿ ïàóçà ìåæäó áàéòàìè - åñòü ïîòåðÿ!!!
char RS_SendBlockMode; /* Ðåæèì ïåðåäà÷è */
char RS_SendBlockMode_stage1; /* Ðåæèì ïåðåäà÷è */
char RS_SendBlockMode_stage2; /* Ðåæèì ïåðåäà÷è */
char RS_Flag9bit; /* äëß RS485???????? */
int BS_LoadOK;/** Ôëàã óñïåøíîñòè ïðèåìà áëîêà */
int RS_FlagBegin;
int RS_HeaderCnt;
int RS_FlagSkiping;
int RS_DataReadyAnswer; // ôëàã, ÷òî ìû ïîëó÷èëè îòâåò íà ñâîé çàïðîñ, åñëè ìû ìàñòåð
int RS_DataReadyAnswerAnalyze; // ôëàã, ÷òî ìû ïîëó÷èëè îòâåò íà ñâîé çàïðîñ, åñëè ìû ìàñòåð è îáðàáîòàëè åãî
int RS_DataSended; // ôëàã, ÷òî ìû îòïðàâèëè ñâîé çàïðîñ, æäåì îòâåò è ìû ìàñòåð
int RS_DataWillSend; // ôëàã, ÷òî ìû ïîäãîòîâèëè ñâîé çàïðîñ è ñåé÷àñ íà÷íåì åãî ïåðåäàâàòü è ìû ìàñòåð
int RS_DataReadyRequest; // ôëàã, ÷òî ìû ïîëó÷èëè çàïðîñ, åñëè ìû ñëåéâ
int RS_DataReadyFullUpdate; // ôëàã, ÷òî ìû ïîëó÷èëè îòâåòû è ìàññèâ ïîëíîñòüþ îáíîâèëñÿ
int RS_OnTransmitedData ; // ôëàã ÷òî ìû åùå ïåðåäàåì çàïðîøåííûå äàííûå
int current_tx_stage;
int cmd_tx_stage;
unsigned int count_recive_ok; // ïðèíÿòî ïîñûëîê ñ âàëèäíûì crc,
unsigned int count_recive_error_crc; // îøèáîê crc
unsigned int count_recive_dirty; // ïðèíÿòî ïîñûëîê äî ðàñ÷åòà crc, ñîâïàëà òîëüêî äëèíà è êîä êîìàíäû
unsigned int count_recive_bad; // ïðèíÿòî ïîñûëîê c íåïðàâèëüíûì ôîðìàòîì
unsigned int count_recive_bytes_all; // ïðèíÿòî âñåãî áàéò
unsigned int count_recive_bytes_skipped; // ïðîïóùåíî âñåãî áàéò
unsigned int count_recive_cmd_skipped; // ïðîïóùåíî âñåãî ïîñûëîê
unsigned int count_recive_rxerror; // îøèáêè ïî ïðåðûâàíèþ
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 TMS_TO_TERMINAL_TEST_ALL_STRUCT_DEFAULT {{0}, {0}, {0}, 0, 0, 0}
enum {
CMD_RS232_LOAD = 51, CMD_RS232_UPLOAD, CMD_RS232_RUN, CMD_RS232_XFLASH, CMD_RS232_TFLASH,
CMD_RS232_PEEK, CMD_RS232_POKE, CMD_RS232_INITLOAD, CMD_RS232_INIT,CMD_RS232_EXTEND,
CMD_RS232_VECTOR = 61, CMD_RS232_IMPULSE, CMD_RS232_STD = 65, CMD_RS232_TEST_ALL, CMD_RS232_STD_ANS,
CMD_RS232_LAST
};
enum {
false = 0, true
};
#define RS_LEN_CMD CMD_RS232_LAST
//extern RS_DATA_STRUCT RS232_A, RS232_B;
extern RS_DATA_STRUCT rs_a,rs_b;
int RS_Send(RS_DATA_STRUCT *rs_arr,unsigned int *pBuf,unsigned long len);
void RS232_WorkingWith(unsigned int enable_rs_a, unsigned int enable_rs_b, unsigned int enable_int_timeout);
void RS232_TuneUp(unsigned long speed_baud_a, unsigned long speed_baud_b);
void inc_RS_timeout_cicle(void);
void resetup_rs_on_timeout_lost(int rsp);
void resetup_rs(RS_DATA_STRUCT *rs_arr);
void resetup_mpu_rs(RS_DATA_STRUCT *rs_arr);
int test_rs_live(RS_DATA_STRUCT *rs_arr);
void RS_SetControllerLeading(RS_DATA_STRUCT *RS232_Arr,int bool);
void RS_SetAdrAnswerController(RS_DATA_STRUCT *RS232_Arr,int set_addr_answer);
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;
#endif

View File

@ -0,0 +1,328 @@
#include "RS_modbus_svu.h"
#include <message2.h>
#include <message2test.h>
#include "modbus_table_v2.h"
#include "options_table.h"
#include "DSP281x_Device.h"
#include "CRC_Functions.h"
#include "MemoryFunctions.h"
#include "RS_Functions.h"
int err_modbus3 = 1;
int err_modbus16 = 1;
int cmd_3_or_16 = 0;
int err_send_log_16 = 0; //Switch between command 3 and 16
unsigned int flag_send_answer_rs = 0; //This flag enables fast answer to SVU when values changed
unsigned int adr_read_from_modbus3 = 0;
unsigned int flag_received_first_mess_from_MPU = 0;
void ReceiveCommandModbus3(RS_DATA_STRUCT *RS232_Arr)
{
// Êîíòðîëüíày ñóììà
unsigned int crc, Address_MB, Length_MB, i/*, Data*/;
// int buf_out[200];
/* ïîëó÷èëè íà÷àëüíûé àäðåñ ÷òåíèy. */
Address_MB =(RS232_Arr->RS_Header[2] << 8) | RS232_Arr->RS_Header[3];
/* ïîëó÷èëè êîëè÷åñòâî ñëîâ äàííûõ */
Length_MB = (RS232_Arr->RS_Header[4] << 8 ) | RS232_Arr->RS_Header[5];
/////////////////////////////////////////////////
// Îòñûëêà
/* Ïîñ÷èòàëè êîíòðîëüíóþ ñóììó ïåðåä ñàìîé ïîñûëêîé */
// f.RScount = SECOND*3;
RS232_Arr->buffer[0] = RS232_Arr->addr_recive; //CNTRL_ADDR;
RS232_Arr->buffer[1] = CMD_RS232_MODBUS_3;
RS232_Arr->buffer[2] = Length_MB*2;
for (i=0;i<Length_MB;i++)
{
if (Address_MB>=ADR_MODBUS_TABLE && Address_MB<0xe00)
{
RS232_Arr->buffer[3+i*2 ]=modbus_table_rs_out[Address_MB-ADR_MODBUS_TABLE+i].byte.HB;
RS232_Arr->buffer[3+i*2+1]=modbus_table_rs_out[Address_MB-ADR_MODBUS_TABLE+i].byte.LB;
}
if (Address_MB>=0xe00 && Address_MB<0xf00)
{
RS232_Arr->buffer[3+i*2 ]=options_controller[Address_MB-0xe00+i].byte.HB;
RS232_Arr->buffer[3+i*2+1]=options_controller[Address_MB-0xe00+i].byte.LB;
}
}
crc = 0xffff;
crc = GetCRC16_IBM(crc, RS232_Arr->buffer, Length_MB*2+3);
RS232_Arr->buffer[Length_MB*2+3] = LOBYTE(crc);
RS232_Arr->buffer[Length_MB*2+4] = HIBYTE(crc);
RS232_Arr->buffer[Length_MB*2+5] = 0;
RS232_Arr->buffer[Length_MB*2+6] = 0;
RS_Send(RS232_Arr,RS232_Arr->buffer, Length_MB*2+7);
return;
}
/***************************************************************/
/***************************************************************/
/* Çàïðîñ äàííûõ ïî ïðîòîêîëó ModBus - êîìàíäà 3
×òåíèå ß÷ååê äàííûõ */
/***************************************************************/
/***************************************************************/
void SendCommandModbus3(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start,unsigned int count_word)
{
// Êîíòðîëüíàß ñóììà
unsigned int crc; //, Address_MB, Length_MB, i, Data;
// int buf_out[200];
// int buf_in[200];
// rs_arr->buffer[0]=
rs_arr->buffer[0] = LOBYTE(adr_contr);
rs_arr->buffer[1] = CMD_RS232_MODBUS_3;
rs_arr->buffer[2] = HIBYTE(adr_start);
rs_arr->buffer[3] = LOBYTE(adr_start);
rs_arr->buffer[4] = 0;
rs_arr->buffer[5] = LOBYTE(count_word);
crc = 0xffff;
crc = GetCRC16_IBM( crc, rs_arr->buffer, 6);
// crc = get_crc_ccitt( crc, rs_arr->buffer, 6);
rs_arr->buffer[6] = LOBYTE(crc);
rs_arr->buffer[7] = HIBYTE(crc);
rs_arr->buffer[8] = 0;
rs_arr->buffer[9] = 0;
RS_Send(rs_arr,rs_arr->buffer, 11);
/* æäåì îòâåòà */
if (adr_contr>0 && adr_contr<0xff)
{
RS_Len[CMD_RS232_MODBUS_3]=5+count_word*2;
adr_read_from_modbus3=adr_start;
RS_SetControllerLeading(rs_arr,true);
RS_SetAdrAnswerController(rs_arr,adr_contr);
}
return;
}
void ReceiveCommandModbus16(RS_DATA_STRUCT *RS232_Arr)
{
// Êîíòðîëüíày ñóììà
unsigned int crc, Address_MB, Length_MB, Bytecnt_MB, i/*, Data1,Data2,Quantity*/;
int /*Data,*/i1,i2;
/* ïîëó÷èëè íà÷àëüíûé àäðåñ ÷òåíèy. */
Address_MB = RS232_Arr->RS_Header[3] | ( RS232_Arr->RS_Header[2] << 8);
/* ïîëó÷èëè quantity. */
//Quantity = RS232_Arr->RS_Header[5] | ( RS232_Arr->RS_Header[4] << 8);
/* ïîëó÷èëè êîëè÷åñòâî áàéò äàííûõ */
// Length_MB = (RS232_Arr->RS_Header[4] << 8 ) | RS232_Arr->RS_Header[5];
Bytecnt_MB = RS232_Arr->RS_Header[6];
Length_MB = Bytecnt_MB>>1;
for (i=0;i<Length_MB;i++)
{
if (Address_MB>=ADR_MODBUS_TABLE && Address_MB<0xe00)
{
RS232_Arr->buffer[3+i*2 ]=modbus_table_rs_out[Address_MB-ADR_MODBUS_TABLE+i].byte.HB;
RS232_Arr->buffer[3+i*2+1]=modbus_table_rs_out[Address_MB-ADR_MODBUS_TABLE+i].byte.LB;
}
if (Address_MB>=0xe00 && Address_MB<0xf00)
{
options_controller[Address_MB-0xe00+i].byte.HB=RS232_Arr->RS_Header[7+i*2 ];
options_controller[Address_MB-0xe00+i].byte.LB=RS232_Arr->RS_Header[7+i*2+1];
}
}
if (Address_MB>=0xe00 && Address_MB<0xf00)
{
i1 = options_controller[0].all;
i2 = options_controller[1].all;
store_data_flash(options_controller,sizeof(options_controller));
SetCntrlAddr(i1, i2); /* Óñòàíîâêà àäðåñà êîíòðîëëåðà */
}
/////////////////////////////////////////////////
// Îòñûëêà
// Ïîñ÷èòàëè êîíòðîëüíóþ ñóììó ïåðåä ñàìîé ïîñûëêîé
RS232_Arr->buffer[0] = RS232_Arr->addr_recive;
RS232_Arr->buffer[1] = CMD_RS232_MODBUS_16;
RS232_Arr->buffer[2] = HIBYTE(Address_MB);
RS232_Arr->buffer[3] = LOBYTE(Address_MB);
RS232_Arr->buffer[4] = 0;
RS232_Arr->buffer[5] = 2;
crc = 0xffff;
crc = GetCRC16_IBM( crc, RS232_Arr->buffer, 6);
RS232_Arr->buffer[6] = LOBYTE(crc);
RS232_Arr->buffer[7] = HIBYTE(crc);
RS232_Arr->buffer[8] = 0;
RS232_Arr->buffer[9] = 0;
RS_Send(RS232_Arr,RS232_Arr->buffer, 10);
return;
}
/***************************************************************/
/***************************************************************/
/***************************************************************/
/* Ïåðåäà÷à äàííûõ ïî ïðîòîêîëó ModBus - êîìàíäà 16
Ïåðåäà÷à äàííûõ */
/***************************************************************/
/***************************************************************/
/***************************************************************/
void SendCommandModbus16(RS_DATA_STRUCT *rs_arr,int adr_contr, unsigned int adr_start,unsigned int count_word)
{
// Êîíòðîëüíàß ñóììà
unsigned int crc, Address_MB, i; //, Length_MB; //, Bytecnt_MB, Data1,Data2;
// int Data, digital, ust_I, ust_Time;
//Length_MB = count_word;
Address_MB = adr_start;
// Îòñûëêà
// Ïîñ÷èòàëè êîíòðîëüíóþ ñóììó ïåðåä ñàìîé ïîñûëêîé
rs_arr->buffer[0] = adr_contr;
rs_arr->buffer[1] = CMD_RS232_MODBUS_16;
rs_arr->buffer[2] = HIBYTE(adr_start);
rs_arr->buffer[3] = LOBYTE(adr_start);
rs_arr->buffer[4] = HIBYTE(count_word);
rs_arr->buffer[5] = LOBYTE(count_word);
rs_arr->buffer[6] = LOBYTE(count_word*2);
for (i=0;i<count_word;i++)
{
rs_arr->buffer[7+i*2 ]=modbus_table_rs_out[Address_MB-ADR_MODBUS_TABLE+i].byte.HB;
rs_arr->buffer[7+i*2+1]=modbus_table_rs_out[Address_MB-ADR_MODBUS_TABLE+i].byte.LB;//LOBYTE(buffer_out_data[Address_MB+i]);
}
crc = 0xffff;
// crc = get_crc_ccitt(crc, rs_arr->buffer, Length_MB*2+7);
crc = GetCRC16_IBM(crc, rs_arr->buffer, (unsigned long)(count_word*2+7));
rs_arr->buffer[count_word*2+7] = LOBYTE(crc);
rs_arr->buffer[count_word*2+8] = HIBYTE(crc);
rs_arr->buffer[count_word*2+9] = 0;
rs_arr->buffer[count_word*2+10] = 0;
RS_Send(rs_arr,rs_arr->buffer,( count_word*2+10+2));
// æäåì îòâåòà
if (adr_contr>0 && adr_contr<0xff)
{
RS_Len[CMD_RS232_MODBUS_16]=8;
RS_SetControllerLeading(rs_arr,true);
RS_SetAdrAnswerController(rs_arr,adr_contr);
}
}
void ReceiveAnswerCommandModbus3(RS_DATA_STRUCT *RS232_Arr)
{
unsigned int Address_MB, Length_MB, i;
MODBUS_REG_STRUCT elementData;
/* ïîëó÷èëè íà÷àëüíûé àäðåñ ÷òåíèß. */
Address_MB = adr_read_from_modbus3;
/* ïîëó÷èëè êîëè÷åñòâî ñëîâ äàííûõ */
Length_MB = RS232_Arr->RS_Header[2] >> 1;
/////////////////////////////////////////////////
// Îòñûëêà
/* Ïîñ÷èòàëè êîíòðîëüíóþ ñóììó ïåðåä ñàìîé ïîñûëêîé */
for (i=0;i<Length_MB;i++)
{
elementData.byte.HB = RS232_Arr->RS_Header[3+i*2];
elementData.byte.LB = RS232_Arr->RS_Header[3+i*2+1];
if (elementData.all != modbus_table_rs_in[Address_MB-ADR_MODBUS_TABLE+i].all) {
flag_send_answer_rs = 1;
}
modbus_table_rs_in[Address_MB-ADR_MODBUS_TABLE+i].all = elementData.all;
// modbus_table_rs_in[Address_MB-ADR_MODBUS_TABLE+i].byte.HB=RS232_Arr->RS_Header[3+i*2];
// modbus_table_rs_in[Address_MB-ADR_MODBUS_TABLE+i].byte.LB=RS232_Arr->RS_Header[3+i*2+1];
//Commented, because of out table can be rewrited before new value had been sent to SVO
modbus_table_rs_out[Address_MB-ADR_MODBUS_TABLE+i].all = modbus_table_rs_in[Address_MB-ADR_MODBUS_TABLE+i].all;
}
RS_SetControllerLeading(RS232_Arr,false);
RS_SetAdrAnswerController(RS232_Arr, 0);
err_modbus3=0;
cmd_3_or_16=1;
flag_received_first_mess_from_MPU=1;
return;
}
void ReceiveAnswerCommandModbus16(RS_DATA_STRUCT *RS232_Arr)
{
// Êîíòðîëüíàß ñóììà
//unsigned int crc, Address_MB, Length_MB, Bytecnt_MB/*, i, Data1,Data2*/;
//int Data, digital, ust_I, ust_Time;
/* ïîëó÷èëè íà÷àëüíûé àäðåñ ÷òåíèß. */
//Address_MB = RS232_Arr->RS_Header[3] | ( RS232_Arr->RS_Header[2] << 8);
/* ïîëó÷èëè êîëè÷åñòâî ñëîâ äàííûõ */
//Length_MB = (RS232_Arr->RS_Header[4] << 8 ) | RS232_Arr->RS_Header[5];
//Bytecnt_MB = RS232_Arr->RS_Header[6];
RS_SetAdrAnswerController(RS232_Arr,0);
RS_SetControllerLeading(RS232_Arr,false);
err_modbus16 = 0;
cmd_3_or_16 = 0;
flag_received_first_mess_from_MPU=1;
return;
}

View File

@ -0,0 +1,27 @@
#ifndef _RS_MODBUS_SVU_H
#define _RS_MODBUS_SVU_H
#include "RS_Functions.h"
void ReceiveCommandModbus3(RS_DATA_STRUCT *RS232_Arr);
void ReceiveCommandModbus16(RS_DATA_STRUCT *RS232_Arr);
void SendCommandModbus3(RS_DATA_STRUCT *rs_arr, int adr_contr, unsigned int adr_start,unsigned int count_word);
void SendCommandModbus16(RS_DATA_STRUCT *rs_arr,int adr_contr, unsigned int adr_start,unsigned int count_word);
void ReceiveAnswerCommandModbus3(RS_DATA_STRUCT *RS232_Arr);
void ReceiveAnswerCommandModbus16(RS_DATA_STRUCT *RS232_Arr);
extern int err_modbus3;
extern int err_modbus16;
extern int cmd_3_or_16;
extern int err_send_log_16;
extern unsigned int flag_received_first_mess_from_MPU;
extern unsigned int flag_send_answer_rs;
extern unsigned int adr_read_from_modbus3;
#endif

View File

@ -0,0 +1,90 @@
#ifndef _SPARTAN2E_ADR_H
#define _SPARTAN2E_ADR_H
// EEPROM
#define ADR_CONTR_REG_FOR_WRITE 0x2020
#define ADR_CONTR_REG_FOR_READ 0x2028
//serial bus
#define ADR_SERIAL_BUS_DATA_WRITE 0x200A
#define ADR_SERIAL_BUS_CMD 0x200B
#define ADR_SERIAL_BUS_DATA_READ 0x200F
//Er workith
#define ADR_BUS_ERROR_READ 0x2012
#define ADR_ERRORS_TOTAL_INFO 0x2026
//parallel bus
#define ADR_PARALLEL_BUS_CMD 0x200C
#define ADR_PARALLEL_BUS_ADR_TABLE 0x200D
#define ADR_PARALLEL_BUS_SET_TABLE 0x200E
//async bus
#define ADR_ASYNC_BUS_TABLE 0x2029
//build, test
#define ADR_CONTROLLER_BUILD 0x2014
#define ADR_XTEST_REG 0x2013
// adr free block in memory TMS
#define ADR_FIRST_FREE 0x2040
#define ADR_LAST_FREE 0x207F
//hwp
#define ADR_HWP_SERVICE_0 0x2009
#define ADR_HWP_SERVICE_1 0x2008
#define ADR_HWP_DATA_RECEVED_0 0x2010
#define ADR_HWP_DATA_RECEVED_1 0x2011
#define ADR_HWP_TEST_TIMER 0x2027
//sensor rotor
#define ADR_SENSOR_S1_T_PERIOD 0x2015
#define ADR_SENSOR_S1_COUNT_IMPULS 0x2016
#define ADR_SENSOR_S2_T_PERIOD 0x2017
#define ADR_SENSOR_S2_COUNT_IMPULS 0x2018
#define ADR_SENSOR_CMD 0x2019
#define ADR_SENSOR_S1_T_PERIOD_LOW_ONE_IMPULS 0x2021
#define ADR_SENSOR_S1_T_PERIOD_HIGH_ONE_IMPULS 0x2022
#define ADR_SENSOR_S2_T_PERIOD_LOW_ONE_IMPULS 0x2023
#define ADR_SENSOR_S2_T_PERIOD_HIGH_ONE_IMPULS 0x2024
//pwm
#define ADR_PWM_WDOG 0x2025
#define ADR_PWM_DIRECT 0x2000
#define ADR_PWM_DIRECT2 0x2030
#define ADR_PWM_DRIVE_MODE 0x2001
#define ADR_PWM_DEAD_TIME 0x2002
#define ADR_PWM_KEY_NUMBER 0x2003
#define ADR_PWM_PERIOD 0x2004
#define ADR_PWM_SAW_DIRECT 0x2005
#define ADR_PWM_START_STOP 0x2006
#define ADR_PWM_TIMING 0x2007
#define ADR_SAW_REQUEST 0x2031
#define ADR_SAW_VALUE 0x2032
#define ADR_TK_MASK_0 0x2033
#define ADR_TK_MASK_1 0x2034
#define ADR_PWM_IT_TYPE 0x2035
//optical bus
#define SI_OPTICS_WORD_TO_SEND_1 0x2036
#define SI_OPTICS_WORD_TO_SEND_2 0x2037
#define SI_OPTICS_WORD_TO_SEND_3 0x2038
#define SI_OPTICS_WORD_TO_SEND_4 0x2039
#endif

View File

@ -0,0 +1,896 @@
#include <project.h>
#include "DSP281x_Examples.h" // DSP281x Examples Include File
#include "DSP281x_SWPrioritizedIsrLevels.h" // DSP281x Examples Include File
#include "DSP281x_Device.h"
#include "MemoryFunctions.h"
#include "Spartan2E_Adr.h"
//#include "xerror.h"
//#include "SpaceVectorPWM.h"
//#include "v_pwm24_v2.h"
//#include "PWMTools.h"
#define SelectLoadXilinx() WriteOper(0,0,0,1)
//#define TypeAccess_Is_SerialBus 21
#define dat_xilinx_line_do(bitb) \
GpioDataRegs.GPEDAT.bit.GPIOE0=bitb
#define setup_xilinx_line_do_on() \
GpioMuxRegs.GPEDIR.bit.GPIOE0=1;\
GpioDataRegs.GPEDAT.bit.GPIOE0=1
#define reset_xilinx() WriteOper(1,1,0,1)
#define XSEEPROM_WRITE_REPEAT 3
#define XSEEPROM_READ_REPEAT 3
#define XSEEPROM_MAX_ERROR_CONSECUTIVE_FRAME 20 // threshold
#define XSEEPROM_MIN_LENTH 7 // max 7 => 1 word = 2 byte
#define XSEEPROM_MAX_ERROR_CONSECUTIVE_BREAK (XSEEPROM_MAX_ERROR_CONSECUTIVE_FRAME + 10)
#define xseeprom_pause { }
#pragma DATA_SECTION(xeeprom_controll_fast,".fast_vars");
unsigned int xeeprom_controll_fast;
//XSerial_bus XSerial_bus0;
//Xmemory_uni Xmemory_uni0;
//XSerial_bus_stats XSerial_bus_stats0;
#pragma DATA_SECTION(Controll, ".fast_vars");
XControll_reg Controll;
unsigned int xeeprom_controll_store;
void write_bit_xilinx(unsigned char bitb);
int xseeprom_read_all(unsigned int Mode_is_Verify, XSeeprom_t * Ptr);
int xseeprom_write_all(XSeeprom_t * Ptr);
void xseeprom_adr(unsigned int adr);
//unsigned int xseeprom_case_xilinx (void);
void xseeprom_delay(void);
void xseeprom_init(void);
void xControll_wr();
unsigned int xseeprom_read_byte(unsigned int use_ack);
void xseeprom_set_mode_ON (unsigned int set_mode);
void xseeprom_start(void);
void xseeprom_stop(void);
void xseeprom_undo (void);
unsigned int xseeprom_write_byte(unsigned int byte);
void xseeprom_clk (unsigned int clk);
unsigned int xseeprom_din (void);
void xseeprom_dout (unsigned int data);
void xseeprom_mode_wr (unsigned int mode);
void ResetPeriphPlane();
unsigned int time = 0;
void write_byte_xilinx(unsigned char bx)
{
int i;
for (i=0;i<=7;i++)
write_bit_xilinx( (bx >> i) & 1);
}
void write_bit_xilinx(unsigned char bitb)
{
pause_1000(1);
EALLOW;
GpioDataRegs.GPBDAT.bit.GPIOB8=1;
dat_xilinx_line_do(bitb);
pause_1000(1);
GpioDataRegs.GPBDAT.bit.GPIOB8=0;
pause_1000(1);
GpioDataRegs.GPBDAT.bit.GPIOB8=1;
EDIS;
}
void setup_xilinx_line()
{
EALLOW;
GpioMuxRegs.GPBMUX.bit.CAP4Q1_GPIOB8=0;
GpioMuxRegs.GPAMUX.bit.CAP2Q2_GPIOA9=0;
GpioMuxRegs.GPBDIR.bit.GPIOB8=1;
GpioMuxRegs.GPADIR.bit.GPIOA9=0;
GpioDataRegs.GPBDAT.bit.GPIOB8=1;
// init line
GpioMuxRegs.GPEMUX.bit.XNMI_XINT13_GPIOE2=0; // as io
GpioMuxRegs.GPEDIR.bit.GPIOE2 = 0; // as input
setup_xilinx_line_do_on();
EDIS;
}
unsigned int read_init_xilinx()
{
unsigned int i;
EALLOW;
i=GpioDataRegs.GPEDAT.bit.GPIOE2;
EDIS;
return (i);
}
unsigned int read_done_xilinx()
{
unsigned int i;
EALLOW;
i=GpioDataRegs.GPADAT.bit.GPIOA9;
EDIS;
return (i);
}
long xverify_remote_eeprom(unsigned int adr_device, unsigned long adr,
unsigned long adr_eeprom, unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error )
{
int i;
static XSeeprom_t rom;
unsigned long repeat_er=0;
unsigned int er_wr=0;
unsigned int er_rd=0;
rom.Adr_device=adr_device;
rom.Adr=adr;
rom.Adr_seeprom=adr_eeprom;
rom.size=size;
if (er_wr)
return 0;
for (i=0; i<XSEEPROM_WRITE_REPEAT; i++) {
er_rd=xseeprom_read_all(1,&rom);
repeat_er+=rom.repeat_error;
if((rom.repeat_error==0) && (er_rd==0))
break;
}
*ok_write=rom.ok_write;
*repeat_error=repeat_er;
*write_error=((unsigned long)(rom.write_error<<8)) | ((unsigned long)(er_wr & 0x000f)) | ((unsigned long)(er_rd<<4 & 0x00f0));
if (rom.write_error != 0)
xerror(xseeprom_er_ID(3),(void *)0);
if(er_rd!=0)
xerror(xseeprom_er_ID(2),(void *)0);
return 0;
}
long xread_remote_eeprom(unsigned int adr_device, unsigned long adr_eeprom,
unsigned long adr, unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error ){
int i;
static XSeeprom_t rom;
unsigned int er_wr=0;
unsigned int er_rd=0;
unsigned long repeat_er=0;
rom.Adr_device=adr_device;
rom.Adr=adr;
rom.Adr_seeprom=adr_eeprom;
rom.size=size;
for (i=0; i<XSEEPROM_WRITE_REPEAT; i++) {
er_rd=xseeprom_read_all(0,&rom);
repeat_er+=rom.repeat_error;
if((rom.repeat_error==0) && (er_rd==0))
break;
}
*ok_write=rom.ok_write;
*repeat_error=repeat_er;
*write_error=(unsigned long)((er_wr & 0x000f) | (er_rd<<4 & 0x00f0));
if(er_rd!=0)
xerror(xseeprom_er_ID(2),(void *)0);
return 0;
}
int xflash_remote_eeprom(unsigned int adr_device, unsigned long adr,
unsigned long adr_eeprom, unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error )
{
int i;
static XSeeprom_t rom;
unsigned long repeat_er=0;
unsigned int er_wr=0;
unsigned int er_rd=0;
unsigned int old_started=0;
rom.Adr_device=adr_device;
rom.Adr=adr;
rom.Adr_seeprom=adr_eeprom;
rom.size=size;
old_started = x_parallel_bus_project.flags.bit.started;
project_stop_parallel_bus();
xseeprom_set_mode_ON(1); // on work with Spartan200E
for (i=0; i<XSEEPROM_WRITE_REPEAT; i++) {
er_wr=xseeprom_write_all(&rom);
repeat_er+=rom.repeat_error;
if((rom.repeat_error==0) && (er_wr==0))
break;
}
*ok_write=rom.ok_write;
*repeat_error=repeat_er;
*write_error=(unsigned long)((er_wr & 0x000f) | (er_rd<<4 & 0x00f0));
if(er_wr)
return xerror(xseeprom_er_ID(1),(void *)0);
// if (er_wr)
// return 0;
for (i=0; i<XSEEPROM_WRITE_REPEAT; i++) {
er_rd=xseeprom_read_all(1,&rom);
repeat_er+=rom.repeat_error;
if((rom.repeat_error==0) && (er_rd==0))
break;
}
xseeprom_set_mode_ON(0);
*ok_write=rom.ok_write;
*repeat_error=repeat_er;
*write_error=((unsigned long)(rom.write_error<<8)) | ((unsigned long)(er_wr & 0x000f)) | ((unsigned long)(er_rd<<4 & 0x00f0));
if(er_rd)
xerror(xseeprom_er_ID(2),(void *)0);
if (rom.write_error)
xerror(xseeprom_er_ID(3),(void *)0);
project_reload_all_plates(WITHOUT_RESET_ALL_PLATES_NO_STOP_ERROR);//wait_start_cds + load_cfg
i_WriteMemory(ADR_BUS_ERROR_READ, 0);
if(i_ReadMemory(ADR_ERRORS_TOTAL_INFO)) //Åñëè íà ëèíèßõ îñòàëèñü îøèáêè.
{
// xerror(main_er_ID(1),(void *)0);
}
i_WriteMemory(ADR_CONTR_REG_FOR_WRITE, 0xffff);
if (old_started)
project_start_parallel_bus();
return 0; // no error
}
int load_xilinx_new(unsigned long adr,unsigned long size)
{
unsigned int wx;
unsigned long adr_x;
unsigned long adr_int;
unsigned int done_line;
volatile unsigned int Value;
setup_xilinx_line();
reset_xilinx();
pause_1000(100);
// controll levels on line INIT and DONE
Value=read_init_xilinx(); // there must be level '0'
if(Value != 0)
return xerror(xtools_er_ID(1),(void *)0);
Value=read_done_xilinx(); // there must be level '0'
if(Value != 0)
return xerror(xtools_er_ID(2),(void *)0);
SelectLoadXilinx();
pause_1000(100);
Value=read_init_xilinx(); // there must be level '1'
if(Value != 1)
return xerror(xtools_er_ID(1),(void *)0);
// down peripheral frequency
// Clk_mode_store=XintfRegs.XINTCNF2.bit.CLKMODE;
// xfrequency_peripheral_is_slow(1);
adr_int= size+1-10;
// fast part of loading
for (adr_x=0;adr_x<adr_int;adr_x++)
{
wx=i_ReadMemory(adr_x+adr);
write_byte_xilinx( (wx>>8) & 0xff);
write_byte_xilinx( wx & 0xff);
}
// slow part of loading
adr_x=adr_int;
wx=i_ReadMemory(adr_x+adr);
write_byte_xilinx( (wx>>8) & 0xff);
pause_1000(10000);
write_byte_xilinx( wx & 0xff);
pause_1000(10000);
adr_int++;
// final part of loading
for (adr_x=adr_int;adr_x<(size+1);adr_x++)
{
unsigned int bx;
int i;
done_line=read_done_xilinx();
if(done_line==1)
break;
wx=i_ReadMemory(adr_x+adr);
bx=(wx>>8) & 0xff;
for (i=0;i<=7;i++)
{
write_bit_xilinx( (bx >> i) & 1);
done_line=read_done_xilinx();
if(done_line==1)
break;
}
if(done_line==1)
break;
wx=i_ReadMemory(adr_x+adr);
bx= wx & 0xff;
for (i=0;i<=7;i++)
{
write_bit_xilinx( (bx >> i) & 1);
done_line=read_done_xilinx();
if(done_line==1)
break;
}
if(done_line==1)
break;
}
// configure line DO as input
// EALLOW;
// setup_xilinx_line_do_off();
// EDIS;
// activation part of loading
// restore peripheral frequency
// xfrequency_peripheral_is_slow(Clk_mode_store);
// DONE activate on clock 2
write_bit_xilinx(1); // clock 3, activate GWE
write_bit_xilinx(1); // clock 4, activate GSR
write_bit_xilinx(1); // clock 5, activate GTS. Led is work.
write_bit_xilinx(1); // clock 6, activate DLL
write_bit_xilinx(0); // clock 7
write_bit_xilinx(1);
pause_1000(100);
write_bit_xilinx(0);
pause_1000(100);
// controll line DONE
Value=read_done_xilinx(); // there must be level '1'
if(Value != 1)
return xerror(xtools_er_ID(2),(void *)0);
// pause for DLL in Xilinx
pause_1000(10000);
return 0;
}
int xseeprom_write_all(XSeeprom_t * Ptr)
{
union XSeeprom_command_reg command;
unsigned int data;
unsigned int i;
unsigned int er=0;
unsigned long er_ack=0;
unsigned int er_for_one_pack=0;
unsigned int er_consecutive=0;
unsigned long adr_x=Ptr->Adr;
unsigned long adr_eeprom=Ptr->Adr_seeprom;
unsigned int count_word=128;
unsigned int wx;
command.bit.bit7=1;
command.bit.bit6=0;
command.bit.bit5=1;
command.bit.bit4=0;
command.bit.bit3=0;
command.bit.A1=1;
command.bit.WR0=0;
Ptr->ok_write=0;
Ptr->repeat_error=0;
Ptr->write_error=0;
xseeprom_init();
pause_1000(100);
xseeprom_adr(Ptr->Adr_device);
// xseeprom_set_mode_ON(1);
xeeprom_controll_fast=Controll.all;
pause_1000(100);
while ((adr_x-Ptr->Adr)<(Ptr->size)) { // while size
er=0;
for(;;){
Led2_Toggle();
xseeprom_start();
command.bit.P0=(adr_eeprom>>15 & 0x0001);
er=xseeprom_write_byte(command.all);
if(er)
break;
data=adr_eeprom>>7 & 0x00ff;
er=xseeprom_write_byte(data);
if(er)
break;
data=adr_eeprom<<1 & 0x00ff;
er=xseeprom_write_byte(data);
break;
}
i=0;
while ( (i<count_word) && (er == 0) && ((adr_x+i-Ptr->Adr)<(Ptr->size)) && ((adr_eeprom<<1 & 0x00ff)+2*i < 0x00ff) ) {
wx=i_ReadMemory(adr_x+i);
er=xseeprom_write_byte(wx>>8);
if(er)
break;
er=xseeprom_write_byte(wx);
if(er)
break;
i+=1;
}
xseeprom_stop();
xseeprom_delay();
if (er == 0) {
adr_x+=i;
adr_eeprom+=i;
Ptr->ok_write+=i;
er_consecutive=0;
} else {
er_consecutive++;
er_ack++;
if (er_consecutive > XSEEPROM_MAX_ERROR_CONSECUTIVE_FRAME) {
if (er_for_one_pack < XSEEPROM_MIN_LENTH) {
er_for_one_pack +=1;
er_consecutive=0;
}
}
Led1_Toggle();
}
switch (er_for_one_pack) {
case 0 : count_word = 128; break;
case 1 : count_word = 64; break;
case 2 : count_word = 32; break;
case 3 : count_word = 16; break;
case 4 : count_word = 8; break;
case 5 : count_word = 4; break;
case 6 : count_word = 2; break;
case 7 : count_word = 1; break;
default : break;
}
Ptr->repeat_error=er_ack;
if(er_consecutive > XSEEPROM_MAX_ERROR_CONSECUTIVE_BREAK) {
xseeprom_undo();
return(4);
}
} // while size
xseeprom_undo();
return 0;
}
int xseeprom_read_all(unsigned int Mode_is_Verify, XSeeprom_t * Ptr)
{
union XSeeprom_command_reg command;
unsigned int data;
// unsigned int i;
unsigned long i;
unsigned int er;
unsigned long er_ack=0;
unsigned int er_consecutive=0;
unsigned long adr_x=Ptr->Adr;
unsigned long adr_eeprom=Ptr->Adr_seeprom;
unsigned int count_word=128;
unsigned int data_rd;
unsigned int wx;
command.bit.bit7=1;
command.bit.bit6=0;
command.bit.bit5=1;
command.bit.bit4=0;
command.bit.bit3=0;
command.bit.A1=1;
Ptr->ok_write=0;
Ptr->repeat_error=0;
Ptr->write_error=0;
xseeprom_init();
xseeprom_adr(Ptr->Adr_device);
// xseeprom_set_mode_ON(1);
xeeprom_controll_fast=Controll.all;
pause_1000(100);
while ((adr_x-Ptr->Adr)<(Ptr->size)) { // while size
er=0;
for(;;){
Led2_Toggle();
xseeprom_start();
command.bit.P0=(adr_eeprom>>15 & 0x0001);
command.bit.WR0=0;
er=xseeprom_write_byte(command.all);
if(er)
break;
data=adr_eeprom>>7 & 0x00ff;
er=xseeprom_write_byte(data);
if(er)
break;
data=adr_eeprom<<1 & 0x00ff;
er=xseeprom_write_byte(data);
if(er)
break;
xseeprom_start();
command.bit.WR0=1;
er=xseeprom_write_byte(command.all);
break;
}
i=0;
while ( (i<count_word) && (er == 0) && ((adr_x-Ptr->Adr)<(Ptr->size)) && (( adr_eeprom<<1 & 0x00ff)+2*i < 0x00ff) ) {
data_rd=xseeprom_read_byte(1);
data_rd<<=8;
if( ((i+1)!=count_word) && ((adr_x-Ptr->Adr)<(Ptr->size-1)) && ((adr_eeprom<<1 & 0x00ff)+2*i+1 < 0x00ff) )
data_rd|=xseeprom_read_byte(1); // use ack
else
data_rd|=xseeprom_read_byte(0); // don't use ack
if(Mode_is_Verify==0)
{
i_WriteMemory((adr_x),data_rd);
}
else {
wx=i_ReadMemory(adr_x);
if(wx!=data_rd)
Ptr->write_error++;
}
i++;
adr_x++;
}
xseeprom_stop();
// xseeprom_delay();
if (er == 0) {
adr_eeprom+=i;
Ptr->ok_write+=i;
er_consecutive=0;
} else {
er_consecutive++;
er_ack++;
Led1_Toggle();
}
Ptr->repeat_error=er_ack;
if(er_consecutive > XSEEPROM_MAX_ERROR_CONSECUTIVE_BREAK) {
xseeprom_undo();
return(4);
}
} // while size
ResetPeriphPlane();
xseeprom_undo();
return 0;
}
void xseeprom_adr(unsigned int adr)
{
Controll.bit.line_P7_4_Sorce_Is_Tms=1;
Controll.bit.line_P7_4_Is=adr;
xControll_wr();
}
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;
// Controll.bit.RemotePlane_Is_Reset = 1;
xControll_wr();
pause_1000(10000);
// Controll.bit.RemotePlane_Is_Reset = 0;
Controll.bit.line_P7_4_Is = 0x0;
xControll_wr();
}
void xseeprom_init(void)
{
xeeprom_controll_store=Controll.all;
Controll.bit.line_CLKS_Sorce_Is_Tms=1;
Controll.bit.line_CLKS_Is=1;
Controll.bit.line_ER0_OUT_Sorce_Is_Tms=1;
Controll.bit.line_ER0_OUT_Is=1;
Controll.bit.line_P7_4_Sorce_Is_Tms=1;
Controll.bit.line_P7_4_Is=0xf;
Controll.bit.line_Z_ER0_OUT_Is=0; // read
Controll.bit.line_SET_MODE_Is=0; // off
// áóôåð îòêðûëè íà âûõîä
Controll.bit.OE_BUF_Is_ON=0;//1;
// ñíßò ñáðîñ ñ ïåðèôåðèéíûõ ïëàò
Controll.bit.RemotePlane_Is_Reset=0;
xControll_wr();
}
void xControll_wr()
{
i_WriteMemory(ADR_CONTR_REG_FOR_WRITE, Controll.all);
}
/*
unsigned int xseeprom_case_xilinx (void) {
xinput_new_uni_rd_status(&Xinput_new_uni_tms0);
return Xinput_new_uni_tms0.ChanalsPtr.ChanalPtr[XINPUT_NEW_TMS0_NUMBER_LINE_CASE_XILINX].rd_status;
}
*/
unsigned int xseeprom_read_byte(unsigned int use_ack){
int i;
unsigned int data=0;
xseeprom_dout(1);
xseeprom_mode_wr(0);
for (i=7;i>=0;i--)
{
xseeprom_pause
xseeprom_clk(1);
xseeprom_pause
data=data<<1|(xseeprom_din() & 0x0001);
xseeprom_clk(0);
xseeprom_pause
}
pause_1000(10);
xseeprom_mode_wr(1);
xseeprom_dout(!use_ack); // ack
xseeprom_pause
xseeprom_clk(1);
xseeprom_pause
xseeprom_clk(0);
xseeprom_pause
xseeprom_dout(1);
xseeprom_mode_wr(0);
pause_1000(10);
return data;
}
void xseeprom_set_mode_ON (unsigned int set_mode) {
Controll.bit.line_SET_MODE_Is=~set_mode;
xControll_wr();
}
void xseeprom_start(void) {
xseeprom_clk(1);
xseeprom_dout(1);
xseeprom_mode_wr(1);
xseeprom_pause
xseeprom_dout(0); // start
xseeprom_pause
xseeprom_clk(0);
xseeprom_pause
}
void xseeprom_stop(void) {
xseeprom_mode_wr(1);
xseeprom_dout(0);
pause_1000(10);
xseeprom_clk(1);
pause_1000(10);
xseeprom_dout(1);
pause_1000(10);
}
void xseeprom_undo (void){
Controll.all=xeeprom_controll_store;
Controll.bit.OE_BUF_Is_ON=1;
xControll_wr();
}
unsigned int xseeprom_write_byte(unsigned int byte){
int i;
unsigned int ack;
xseeprom_mode_wr(1);
for (i=7;i>=0;i--)
{
xseeprom_dout((byte >> i) & 1);
xseeprom_pause
xseeprom_clk(1);
xseeprom_pause
xseeprom_clk(0);
xseeprom_pause
}
xseeprom_dout(1);
xseeprom_mode_wr(0);
pause_1000(10);
xseeprom_pause
xseeprom_clk(1);
pause_1000(10);
xseeprom_pause
ack=xseeprom_din();
xseeprom_clk(0);
xseeprom_pause
pause_1000(10);
/*
// xseeprom_dout(1);
xseeprom_mode_wr(0);
pause_1000(10);
// xseeprom_mode_wr(0);
xseeprom_dout(1);
xseeprom_pause
xseeprom_clk(1);
xseeprom_pause
ack=xseeprom_din();
xseeprom_clk(0);
xseeprom_pause
pause_1000(10);
*/
return ack; // '0' - ok!
}
void xseeprom_clk (unsigned int clk) {
xeeprom_controll_fast&=0xfdff;
xeeprom_controll_fast|=(clk<<9 & 0x0200);
i_WriteMemory(ADR_CONTR_REG_FOR_WRITE,xeeprom_controll_fast);
}
unsigned int xseeprom_din (void) {
return (i_ReadMemory(ADR_CONTR_REG_FOR_READ)>>15 & 0x0001);
}
void xseeprom_dout (unsigned int data) {
xeeprom_controll_fast&=0xff7f;
xeeprom_controll_fast|=(data<<7 & 0x0080);
i_WriteMemory(ADR_CONTR_REG_FOR_WRITE,xeeprom_controll_fast);
}
void xseeprom_mode_wr (unsigned int mode) { // '1' - write, '0' - read
xeeprom_controll_fast&=0xffef;
xeeprom_controll_fast|=(mode<<4 & 0x0010);
i_WriteMemory(ADR_CONTR_REG_FOR_WRITE,xeeprom_controll_fast);
}
/*********************** example ******************************************
* i=xilinx_live_smart(0x5aaa);
* i=i|xilinx_live_smart(0x0000)
***************************************************************************/
unsigned int xilinx_live_smart(unsigned int d) // dout(15:0) = din(11:8) & din(15:12) & not din(7:0);
{
unsigned int dout;
unsigned int d_rd;
i_WriteMemory(ADR_XTEST_REG,d);
dout = ~d;
d_rd = i_ReadMemory(ADR_XTEST_REG);
if (d_rd!=dout)
return 1;
return 0;
}
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
int enable_er0_control(void)
{
return xilinx_live_smart(0x5AA5);
}
int test_xilinx_live(void)
{
unsigned int i;
//test xilinx controller on read/write operation
for(i=0;i<10000;i++)
if(xilinx_live_smart(i))
return xerror(main_er_ID(1),(void *)0);
return 0;
}
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,264 @@
#ifndef _SPARTAN2E_FUNCTIONS_H
#define _SPARTAN2E_FUNCTIONS_H
#include "DSP281x_Device.h"
#define SIZE_XILINX200 90126 // count words
struct XControll_reg_bit {
unsigned int OE_BUF_Is_ON:1;
unsigned int RemotePlane_Is_Reset:1;
unsigned int Int_for_XNMI_XINT13_ON:1;
unsigned int Int_for_XINT1_XBIO_ON:1;
unsigned int line_Z_ER0_OUT_Is:1;
unsigned int line_SET_MODE_Is:1;
unsigned int line_ER0_OUT_Sorce_Is_Tms:1;
unsigned int line_ER0_OUT_Is:1;
unsigned int line_CLKS_Sorce_Is_Tms:1;
unsigned int line_CLKS_Is:1;
unsigned int line_P7_4_Sorce_Is_Tms:1;
unsigned int line_P7_4_Is:4; // 4 bits
unsigned int line_ER0_IN_Is:1; // WR has no effect
};
typedef union {
unsigned int all;
struct XControll_reg_bit bit;
} XControll_reg;
union XSeeprom_command_reg {
unsigned int all;
struct {
unsigned int WR0:1;
unsigned int P0:1;
unsigned int A1:1;
unsigned int bit3:1;
unsigned int bit4:1;
unsigned int bit5:1;
unsigned int bit6:1;
unsigned int bit7:1;
} bit;
};
struct XSerial_bus_config_bit {
unsigned int Use_Config:1;
unsigned int Number_of_Frequency_is:3;
unsigned int Use_Timer:1;
unsigned int Range_CountTimer:4;
unsigned int Use_Filtr_on_din:1;
unsigned int Use_only_fast_Filtr_on_din:1;
unsigned int Use_Tweaking:1;
unsigned int Use_compensation_delay_on_Tweaking:1;
unsigned int Use_SyncRdWr:1;
unsigned int reserve_bits:2; // unused 2 bits
};
union XSerial_bus_config_reg {
unsigned int all;
struct XSerial_bus_config_bit bit;
};
struct XSerial_bus_intc_din_bit {
unsigned int State_Is_Idle:1;
unsigned int Error_CRC:1;
unsigned int Error_Comand:1;
unsigned int Timeout_Is_Complete:1;
unsigned int Mode_Is_Config:1;
unsigned int rezerv:3;
};
typedef volatile union {
unsigned int all;
struct XSerial_bus_intc_din_bit bit;
} XSerial_bus_intc_din_reg;
struct XSerial_bus_adr_bit {
unsigned int AdrPlane:4;
unsigned int reserve_bits:3; // unused 3 bits
unsigned int RdWR:1; // '0' - WR, '1' - RD
unsigned int AdrReg:8;
};
union XSerial_bus_adr_reg {
unsigned int all;
struct XSerial_bus_adr_bit bit;
};
typedef struct {
unsigned int TypeAccess;
unsigned int AdrPlane;
unsigned int AdrReg;
unsigned int DataWr;
unsigned int DataRd;
} Xmemory_uni;
typedef volatile struct {
unsigned int BaseAddress; // Base address of registers //
unsigned int DataWr; // Data for write to selected register //
unsigned int DataRd; // Reading data from selected register //
union XSerial_bus_adr_reg Adr;
XSerial_bus_intc_din_reg ISR;
union XSerial_bus_config_reg Config;
unsigned int IsReady:1; // Device is initialized and ready //
} XSerial_bus;
struct XSeeprom_s {
unsigned int Adr_device;
unsigned long Adr;
unsigned long Adr_seeprom;
unsigned long size;
unsigned long ok_write;
unsigned long write_error;
unsigned long repeat_error;
};
typedef volatile struct XSeeprom_s XSeeprom_t;
struct XSerial_bus_intc_mer_bit {
unsigned int Master_Enable:1;
unsigned int Hardware_Int_Enable:1;
};
union XSerial_bus_intc_mer_reg {
unsigned int all;
struct XSerial_bus_intc_mer_bit bit;
};
struct XSerial_bus_INTC {
XSerial_bus_intc_din_reg ISR;
XSerial_bus_intc_din_reg IER;
XSerial_bus_intc_din_reg IPR;
union XSerial_bus_intc_mer_reg MER;
};
struct XSerial_Tweaking_Data {
unsigned int Tweaking_tr_line:4;
unsigned int Tweaking_rec_line:4;
};
/*
struct XSerial_bus_Config_Data {
unsigned int Constant_for_Timer;
unsigned int Number_Wait_State_for_TrRec:4;
unsigned int Number_Wait_State_for_Pause:4;
struct XSerial_Tweaking_Data Tweaking_chanal[8];
unsigned int Delay_clk_for_Tr:7;
unsigned int Delay_clk_for_Rec:7;
unsigned int Use_fast_Filtr:1;
unsigned int Use_fast_Transmit:1;
unsigned int Tweaking_tbuf_en:4;
};
*/
/*
typedef volatile struct {
unsigned int PlaneIsLive; // For selected DelayLine chanal is visible: QualityTrRec = 100%, bit per chanal
unsigned int CountErrors; // count errors transmit-recieve
XSerial_bus *Bus;
struct XSerial_bus_INTC INTC;
struct XSerial_bus_Config_Data Config_Data;
unsigned int Number_Chanal;
} XSerial_bus_stats;
*/
/*
struct PARALLEL_BITS { // bits description
Uint16 res0:1; // 0
Uint16 res1:1; // 1
Uint16 res2:1; // 2
Uint16 res3:1; // 3
Uint16 res4:1; // 4
Uint16 res5:1; // 5
Uint16 res6:1; // 6
Uint16 res7:1; // 7
Uint16 res8:1; // 8
Uint16 res9:1; // 9
Uint16 res10:1; // 10
Uint16 res11:1; // 11
Uint16 res12:1; // 12
Uint16 res13:1; // 13
Uint16 res14:1; // 14
Uint16 res15:1; // 15
};
struct PARALLEL_STATUS_BITS { // bits description
Uint16 err_crc:1; // 0
Uint16 not_ready:1; // 1
Uint16 res2:1; // 2
Uint16 res3:1; // 3
Uint16 res4:1; // 4
Uint16 res5:1; // 5
Uint16 res6:1; // 6
Uint16 res7:1; // 7
Uint16 res8:1; // 8
Uint16 res9:1; // 9
Uint16 res10:1; // 10
Uint16 res11:1; // 11
Uint16 res12:1; // 12
Uint16 res13:1; // 13
Uint16 res14:1; // 14
Uint16 res15:1; // 15
};
union PARALLEL1_REG {
Uint16 all;
struct PARALLEL_BITS bit;
};
union PARALLEL2_REG {
Uint16 all;
struct PARALLEL_BITS bit;
};
union PARALLEL3_REG {
Uint16 all;
struct PARALLEL_BITS bit;
};
union PARALLEL4_REG {
Uint16 all;
struct PARALLEL_BITS bit;
};
union PARALLEL5_REG {
Uint16 all;
struct PARALLEL_BITS bit;
};
union PARALLEL_STATUS_REG {
Uint16 all;
struct PARALLEL_STATUS_BITS bit;
};
typedef volatile struct { // bits description
union PARALLEL1_REG reg1;
union PARALLEL2_REG reg2;
union PARALLEL3_REG reg3;
union PARALLEL4_REG reg4;
union PARALLEL5_REG reg5;
union PARALLEL_STATUS_REG status;
} PARALLEL_REGS;
*/
int load_xilinx_new(unsigned long adr,unsigned long size);
int xflash_remote_eeprom(unsigned int adr_device, unsigned long adr,
unsigned long adr_eeprom, unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error );
long xread_remote_eeprom(unsigned int adr_device, unsigned long adr_eeprom,
unsigned long adr, unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error );
long xverify_remote_eeprom(unsigned int adr_device, unsigned long adr,
unsigned long adr_eeprom, unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error );
int test_xilinx_live(void);
int enable_er0_control(void);
void ResetNPeriphPlane(unsigned int np);
#endif

View File

@ -0,0 +1,340 @@
#include "TuneUpPlane.h"
#include "DSP281x_Examples.h"
#include "DSP281x_Device.h"
#include "DSP281x_Xintf.h"
#define SelectWorkWithFlash() WriteOper(0,0,0,0)
#define SelectStrob67_ForFlash() WriteOper(1,0,1,0)
unsigned int cl_led1 = 0;
unsigned int cl_led2 = 0;
void SetupOperLine();
#pragma CODE_SECTION(Led1_Toggle,".fast_run");
#pragma CODE_SECTION(Led2_Toggle,".fast_run");
#pragma CODE_SECTION(i_led2_on_off,".fast_run");
void i_led2_on_off(int i)
{
EALLOW;
if (i) GpioDataRegs.GPDSET.bit.GPIOD6=1;
else GpioDataRegs.GPDCLEAR.bit.GPIOD6=1;
EDIS;
}
#pragma CODE_SECTION(i_led1_on_off,".fast_run");
void i_led1_on_off(int i)
{
EALLOW;
if (i) GpioDataRegs.GPASET.bit.GPIOA10=1;
else GpioDataRegs.GPACLEAR.bit.GPIOA10=1;
EDIS;
}
//#pragma CODE_SECTION(i_led2_on_off_special,".fast_run");
//void i_led2_on_off_special(int i)
//{
// EALLOW;
//
// if (i) GpioDataRegs.GPDSET.bit.GPIOD6=1;
// else GpioDataRegs.GPDCLEAR.bit.GPIOD6=1;
//
//
// EDIS;
//}
#pragma CODE_SECTION(i_led1_on_off_special,".fast_run");
void i_led1_on_off_special(int i)
{
EALLOW;
if (i)
{
GpioDataRegs.GPASET.bit.GPIOA10=1;
cl_led1++;
}
else
{
if (cl_led1)
cl_led1--;
if (cl_led1 == 0)
GpioDataRegs.GPACLEAR.bit.GPIOA10=1;
}
EDIS;
}
#pragma CODE_SECTION(i_led2_on_off_special,".fast_run");
void i_led2_on_off_special(int i)
{
EALLOW;
if (i)
{
GpioDataRegs.GPDSET.bit.GPIOD6=1;
cl_led2++;
}
else
{
if (cl_led2)
cl_led2--;
if (cl_led2 == 0)
GpioDataRegs.GPDCLEAR.bit.GPIOD6=1;
}
EDIS;
}
void Led1_Toggle()
{
EALLOW;
GpioDataRegs.GPATOGGLE.bit.GPIOA10=1;
EDIS;
}
void Led2_Toggle()
{
EALLOW;
GpioDataRegs.GPDTOGGLE.bit.GPIOD6=1;
EDIS;
}
void SetupLedsLine()
{
EALLOW;
GpioMuxRegs.GPDMUX.bit.T4CTRIP_SOCB_GPIOD6 = 0;
GpioDataRegs.GPDDAT.bit.GPIOD6 = 0;
GpioMuxRegs.GPDDIR.bit.GPIOD6 = 1;
GpioMuxRegs.GPAMUX.bit.CAP3QI1_GPIOA10 = 0;
GpioDataRegs.GPADAT.bit.GPIOA10 = 0;
GpioMuxRegs.GPADIR.bit.GPIOA10 = 1;
EDIS;
}
#pragma CODE_SECTION(pause_1000,".fast_run");
void pause_1000(unsigned long t)
{
unsigned long i;
t = t >> 1;
for (i = 0; i < t; i++)
{
DSP28x_usDelay(40L);
}
}
//Xilinx Zone
void XintfZone0_Timing(void)
{
// Zone 0------------------------------------
// When using ready, ACTIVE must be 1 or greater
// Lead must always be 1 or greater
// Zone write timing
XintfRegs.XTIMING0.bit.XWRLEAD = 3;//2;
XintfRegs.XTIMING0.bit.XWRACTIVE = 5;//2;//1; // 1
XintfRegs.XTIMING0.bit.XWRTRAIL = 1;//0;
// Zone read timing
XintfRegs.XTIMING0.bit.XRDLEAD = 3;
XintfRegs.XTIMING0.bit.XRDACTIVE = 5;//1
XintfRegs.XTIMING0.bit.XRDTRAIL = 1;//1
// do not double all Zone read/write lead/active/trail timing
XintfRegs.XTIMING0.bit.X2TIMING = 0;
// Zone will not sample READY
XintfRegs.XTIMING0.bit.USEREADY = 0;//1;
XintfRegs.XTIMING0.bit.READYMODE = 0;//1;
// Size must be 1,1 - other values are reserved
XintfRegs.XTIMING0.bit.XSIZE = 3;
//Force a pipeline flush to ensure that the write to
//the last register configured occurs before returning.
asm(" RPT #7 || NOP");
}
void XintfZone6_And7_Timing(void)
{
// All Zones---------------------------------
// Timing for all zones based on XTIMCLK = SYSCLKOUT/2
XintfRegs.XINTCNF2.bit.XTIMCLK = 1;
// Buffer up to 0 writes
XintfRegs.XINTCNF2.bit.WRBUFF = 0;
// XCLKOUT is enabled
XintfRegs.XINTCNF2.bit.CLKOFF = 0;
// XCLKOUT = XTIMCLK
#ifdef XLOW_FREQUENCY_MODE
XintfRegs.XINTCNF2.bit.CLKMODE = 1;
#else
XintfRegs.XINTCNF2.bit.CLKMODE = 0;
#endif
XintfRegs.XINTCNF2.bit.MPNMC = 0;
// Zone 6------------------------------------
// When using ready, ACTIVE must be 1 or greater
// Lead must always be 1 or greater
// Zone write timing
XintfRegs.XTIMING6.bit.XWRLEAD = 3;
XintfRegs.XTIMING6.bit.XWRACTIVE = 7;
XintfRegs.XTIMING6.bit.XWRTRAIL = 3;
// Zone read timing
XintfRegs.XTIMING6.bit.XRDLEAD = 3;
XintfRegs.XTIMING6.bit.XRDACTIVE = 7;//3;
XintfRegs.XTIMING6.bit.XRDTRAIL = 3;
// do not double all Zone read/write lead/active/trail timing
XintfRegs.XTIMING6.bit.X2TIMING = 0;
// Zone will not sample READY
XintfRegs.XTIMING6.bit.USEREADY = 0;//1;
XintfRegs.XTIMING6.bit.READYMODE = 0;//1;
// Size must be 1,1 - other values are reserved
XintfRegs.XTIMING6.bit.XSIZE = 3;
// Zone 7------------------------------------
// When using ready, ACTIVE must be 1 or greater
// Lead must always be 1 or greater
// Zone write timing
XintfRegs.XTIMING7.bit.XWRLEAD = 3;
XintfRegs.XTIMING7.bit.XWRACTIVE = 7;
XintfRegs.XTIMING7.bit.XWRTRAIL = 3;
// Zone read timing
XintfRegs.XTIMING7.bit.XRDLEAD = 3;
XintfRegs.XTIMING7.bit.XRDACTIVE = 3;
XintfRegs.XTIMING7.bit.XRDTRAIL = 3;
// don't double all Zone read/write lead/active/trail timing
XintfRegs.XTIMING7.bit.X2TIMING = 0;
// Zone will not sample XREADY signal
XintfRegs.XTIMING7.bit.USEREADY = 0;
XintfRegs.XTIMING7.bit.READYMODE = 0;
// Size must be 1,1 - other values are reserved
XintfRegs.XTIMING7.bit.XSIZE = 3;
//Force a pipeline flush to ensure that the write to
//the last register configured occurs before returning.
asm(" RPT #7 || NOP");
}
void XintfZone2_Timing(void)
{
// All Zones---------------------------------
// Timing for all zones based on XTIMCLK = SYSCLKOUT/2
XintfRegs.XINTCNF2.bit.XTIMCLK = 1;
// Buffer up to 0 writes
XintfRegs.XINTCNF2.bit.WRBUFF = 0;
// XCLKOUT is enabled
XintfRegs.XINTCNF2.bit.CLKOFF = 0;
// XCLKOUT = XTIMCLK
XintfRegs.XINTCNF2.bit.CLKMODE = 0;
XintfRegs.XINTCNF2.bit.MPNMC = 0;
// Zone 6------------------------------------
// When using ready, ACTIVE must be 1 or greater
// 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;
// Zone read timing
XintfRegs.XTIMING2.bit.XRDLEAD = 2;
XintfRegs.XTIMING2.bit.XRDACTIVE = 3; //1;
XintfRegs.XTIMING2.bit.XRDTRAIL = 1;//2;//0;
// do not double all Zone read/write lead/active/trail timing
XintfRegs.XTIMING2.bit.X2TIMING = 0;
// Zone will not sample READY
XintfRegs.XTIMING2.bit.USEREADY = 0;//1;
XintfRegs.XTIMING2.bit.READYMODE = 0;//1;
// Size must be 1,1 - other values are reserved
XintfRegs.XTIMING2.bit.XSIZE = 3;
//Force a pipeline flush to ensure that the write to
//the last register configured occurs before returning.
asm(" RPT #7 || NOP");
}
void FlashInit()
{
SetupOperLine();
SelectStrob67_ForFlash();
XintfZone6_And7_Timing();
SelectWorkWithFlash();
}
void SetupOperLine()
{
EALLOW;
GpioMuxRegs.GPAMUX.bit.C1TRIP_GPIOA13=0;
GpioMuxRegs.GPAMUX.bit.C2TRIP_GPIOA14=0;
GpioMuxRegs.GPAMUX.bit.C3TRIP_GPIOA15=0;
GpioMuxRegs.GPBMUX.bit.C4TRIP_GPIOB13=0;
GpioMuxRegs.GPBMUX.bit.C6TRIP_GPIOB15=0;
GpioMuxRegs.GPADIR.bit.GPIOA13=1;
GpioMuxRegs.GPADIR.bit.GPIOA14=1;
GpioMuxRegs.GPADIR.bit.GPIOA15=1;
GpioMuxRegs.GPBDIR.bit.GPIOB13=1;
GpioMuxRegs.GPBDIR.bit.GPIOB15=1;
GpioMuxRegs.GPAQUAL.all=0;
GpioMuxRegs.GPBQUAL.all=0;
EDIS;
WriteOper(1,1,1,1);
}
void WriteOper(unsigned char oper_mode1,unsigned char oper_mode2, unsigned char oper_mode3, unsigned char oper_mode4)
{
EALLOW;
GpioDataRegs.GPADAT.bit.GPIOA13=oper_mode1;
GpioDataRegs.GPADAT.bit.GPIOA14=oper_mode2;
GpioDataRegs.GPADAT.bit.GPIOA15=oper_mode3;
GpioDataRegs.GPBDAT.bit.GPIOB13=oper_mode4;
asm(" NOP");
GpioDataRegs.GPBDAT.bit.GPIOB15=0;
asm(" NOP");
asm(" NOP");
asm(" NOP");
GpioDataRegs.GPBDAT.bit.GPIOB15=1;
asm(" NOP");
asm(" NOP");
asm(" NOP");
GpioDataRegs.GPBDAT.bit.GPIOB15=0;
asm(" NOP");
asm(" NOP");
asm(" NOP");
EDIS;
}

View File

@ -0,0 +1,38 @@
#ifndef _TUNE_UP_PLANE_H
#define _TUNE_UP_PLANE_H
#include "DSP281x_Device.h"
void WriteOper(unsigned char oper_mode1,unsigned char oper_mode2, unsigned char oper_mode3, unsigned char oper_mode4);
void pause_1000(unsigned long t);
void XintfZone0_Timing(void);
void XintfZone6_And7_Timing(void);
void XintfZone2_Timing(void);
void FlashInit();
//extern void DSP28x_usDelay(long LoopCount);
void Led1_Toggle();
void Led2_Toggle();
void i_led2_on_off(int i);
void i_led1_on_off(int i);
void i_led2_on_off_special(int i);
void i_led1_on_off_special(int i);
#define i_led1_on() {EALLOW;GpioDataRegs.GPASET.bit.GPIOA10 = 1;EDIS;}
#define i_led1_off() {EALLOW;GpioDataRegs.GPACLEAR.bit.GPIOA10 = 1;;EDIS;}
#define i_led2_on() {EALLOW;GpioDataRegs.GPDSET.bit.GPIOD6 = 1;EDIS;}
#define i_led2_off() {EALLOW;GpioDataRegs.GPDCLEAR.bit.GPIOD6 = 1;;EDIS;}
#define i_led1_toggle() {EALLOW; GpioDataRegs.GPATOGGLE.bit.GPIOA10 = 1; EDIS;}
#define i_led2_toggle() {EALLOW; GpioDataRegs.GPDTOGGLE.bit.GPIOD6 = 1; EDIS;}
void SetupLedsLine();
#endif

View File

@ -0,0 +1,39 @@
#ifndef _MODBUS_STRUCT_H
#define _MODBUS_STRUCT_H
//#include "RS_Functions.h"
struct MODBUS_WORD_STRUCT { // bit description
unsigned int LB:8; // 16:23 High word low byte
unsigned int HB:8; // 24:31 High word high byte
};
struct MODBUS_BITS_STRUCT { // bit description
unsigned int bit0: 1;
unsigned int bit1: 1;
unsigned int bit2: 1;
unsigned int bit3: 1;
unsigned int bit4: 1;
unsigned int bit5: 1;
unsigned int bit6: 1;
unsigned int bit7: 1;
unsigned int bit8: 1;
unsigned int bit9: 1;
unsigned int bit10: 1;
unsigned int bit11: 1;
unsigned int bit12: 1;
unsigned int bit13: 1;
unsigned int bit14: 1;
unsigned int bit15: 1;
};
typedef union {
//unsigned int all;
int all;
struct MODBUS_BITS_STRUCT bit;
struct MODBUS_WORD_STRUCT byte;
} MODBUS_REG_STRUCT;
#endif

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

View 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

View File

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

View File

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

11
Inu/Src/N12_Xilinx/xHWP.c Normal file
View File

@ -0,0 +1,11 @@
#include "xHWP.h"
#include "DSP281x_Examples.h"
#include "DSP281x_Device.h"
#include "x_parallel_bus.h"
#include "xerror.h"

View File

@ -0,0 +1,6 @@
#ifndef _XHWP_H
#define _XHWP_H
#endif

View File

@ -0,0 +1,561 @@
#include "xPeriphSP6_loader.h"
#include "DSP281x_Examples.h"
#include "DSP281x_Device.h"
#include "MemoryFunctions.h"
#include "Spartan2E_Adr.h"
#include "Spartan2E_Functions.h"
#include "TuneUpPlane.h"
#include "x_parallel_bus.h"
#include "xp_project.h"
Byte byte; //used 8 most significant bits
Word word;
ControlReg controlReg;
volatile AddrToSent addrToSent;
WordToReverse wordToReverse;
WordReversed wordReversed;
volatile int fail = 0;
volatile unsigned long length = 0;
volatile int tryNumb = 0;
int manufactorerAndProductID = 0;
static int countInMemWrite = 0;
void initState(int adr_device){
controlReg.all = 0x0000;
controlReg.bit.cs = 1;
controlReg.bit.rw = 1;
controlReg.bit.plane_addr = adr_device;
controlReg.bit.clock = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void sendByte(void){
int bitCnt = 8;
controlReg.bit.clock = 0;
controlReg.bit.data = byte.bit.data;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
while (bitCnt > 0) {
if (controlReg.bit.clock == 1) {
controlReg.bit.clock = 0;
controlReg.bit.data = byte.bit.data;
// bitCnt--;
} else {
controlReg.bit.clock = 1;
byte.all = byte.all << 1;
bitCnt--;
}
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
}
void sendWord(void){
int bitCnt = 16;
controlReg.bit.clock = 0;
controlReg.bit.data = word.bit.data;
// controlReg.bit.data = word.bit.dataReceived;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
while (bitCnt > 0) {
if (controlReg.bit.clock == 1) {
controlReg.bit.clock = 0;
// controlReg.bit.data = word.bit.dataReceived;
controlReg.bit.data = word.bit.data;
} else {
controlReg.bit.clock = 1;
// word.all = word.all >> 1;
word.all = word.all << 1;
bitCnt--;
}
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
}
void readByte(void){
int bitCnt = 8;
controlReg.bit.clock = 0;
controlReg.bit.rw = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
// byte.all = 0x0000;
while (bitCnt > 0) {
if (controlReg.bit.clock == 1) {
byte.all = byte.all << 1;
controlReg.all = i_ReadMemory(ADR_CONTR_REG_FOR_READ);
byte.bit.dataReceived = controlReg.bit.eeprom_read;
controlReg.bit.clock = 0;
bitCnt--;
} else {
controlReg.all = i_ReadMemory(ADR_CONTR_REG_FOR_READ);
controlReg.bit.clock = 1;
}
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
}
void readWord(void){
int bitCnt = 16;
word.all = 0x0000;
while (bitCnt > 0) {
if (controlReg.bit.clock == 1) {
word.all = word.all << 1;
// word.all = word.all >> 1;
controlReg.all = i_ReadMemory(ADR_CONTR_REG_FOR_READ);
word.bit.dataReceived = controlReg.bit.eeprom_read;
// word.bit.data = controlReg.bit.eeprom_read;
controlReg.bit.clock = 0;
bitCnt--;
} else {
controlReg.all = i_ReadMemory(ADR_CONTR_REG_FOR_READ);
controlReg.bit.clock = 1;
}
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
}
void WREN(void) {
controlReg.bit.cs = 0;
byte.all= 0x0600;
sendByte();
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
controlReg.bit.cs = 1;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void WRDI(void) {
controlReg.bit.cs = 0;
byte.all= 0x0400;
sendByte();
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
controlReg.bit.cs = 1;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void WRSR(void) {
controlReg.bit.cs = 0;
byte.all= 0x0100;
sendByte();
byte.all= 0x0200;
sendByte();
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
controlReg.bit.cs = 1;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void RDSR(void) {
controlReg.bit.cs = 0;
controlReg.bit.rw = 1;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
byte.all= 0x0500;
sendByte();
readByte();
controlReg.bit.cs = 1;
controlReg.bit.rw = 1;
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void RDID(void) {
controlReg.bit.cs = 0;
controlReg.bit.rw = 1;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
if (manufactorerAndProductID == 0)
byte.all = 0x1500;
else
byte.all = 0x9F00;
sendByte();
readByte();
controlReg.bit.cs = 1;
controlReg.bit.rw = 1;
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void ERASE(void) {
controlReg.bit.cs = 0;
if (manufactorerAndProductID == 0)
byte.all = 0x6200;
else
byte.all = 0xC700;
sendByte();
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
controlReg.bit.cs = 1;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void READ(void) {
controlReg.bit.cs = 0;
byte.all= 0x0300;
sendByte();
}
void PROGRAM(void) {
controlReg.bit.cs = 0;
byte.all= 0x0200;
sendByte();
}
void ADDR3bytes(FlashAddr flashAddr) {
int bitCnt = 24;
addrToSent.all= flashAddr.all;
addrToSent.all= addrToSent.all << 8;
controlReg.bit.clock = 0;
controlReg.bit.data = addrToSent.bit.data;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
while (bitCnt > 0) {
if (controlReg.bit.clock == 1) {
controlReg.bit.clock = 0;
controlReg.bit.data = addrToSent.bit.data;
// bitCnt--;
} else {
controlReg.bit.clock = 1;
addrToSent.all = addrToSent.all << 1;
bitCnt--;
}
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
}
void DataW256Bytes(volatile unsigned long addrToRead) {
unsigned long WordNum = 0;
while (WordNum < 128) {
wordToReverse.all= i_ReadMemory(addrToRead + WordNum);
wordReversed.bit.bit0 = wordToReverse.bit.bit7;
wordReversed.bit.bit1 = wordToReverse.bit.bit6;
wordReversed.bit.bit2 = wordToReverse.bit.bit5;
wordReversed.bit.bit3 = wordToReverse.bit.bit4;
wordReversed.bit.bit4 = wordToReverse.bit.bit3;
wordReversed.bit.bit5 = wordToReverse.bit.bit2;
wordReversed.bit.bit6 = wordToReverse.bit.bit1;
wordReversed.bit.bit7 = wordToReverse.bit.bit0;
wordReversed.bit.bit8 = wordToReverse.bit.bit15;
wordReversed.bit.bit9 = wordToReverse.bit.bit14;
wordReversed.bit.bit10 = wordToReverse.bit.bit13;
wordReversed.bit.bit11 = wordToReverse.bit.bit12;
wordReversed.bit.bit12 = wordToReverse.bit.bit11;
wordReversed.bit.bit13 = wordToReverse.bit.bit10;
wordReversed.bit.bit14 = wordToReverse.bit.bit9;
wordReversed.bit.bit15 = wordToReverse.bit.bit8;
word.all= wordReversed.all;
sendWord();
WordNum++;
}
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
controlReg.bit.cs = 1;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void DataR256Bytes(volatile unsigned long addrToRead) {
unsigned long WordNum = 0;
controlReg.bit.clock = 0;
controlReg.bit.rw = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
while (WordNum < 128) {
if ((addrToRead + WordNum) <= length) {
readWord();
wordToReverse.all= i_ReadMemory(addrToRead + WordNum);
wordReversed.bit.bit0 = wordToReverse.bit.bit7;
wordReversed.bit.bit1 = wordToReverse.bit.bit6;
wordReversed.bit.bit2 = wordToReverse.bit.bit5;
wordReversed.bit.bit3 = wordToReverse.bit.bit4;
wordReversed.bit.bit4 = wordToReverse.bit.bit3;
wordReversed.bit.bit5 = wordToReverse.bit.bit2;
wordReversed.bit.bit6 = wordToReverse.bit.bit1;
wordReversed.bit.bit7 = wordToReverse.bit.bit0;
wordReversed.bit.bit8 = wordToReverse.bit.bit15;
wordReversed.bit.bit9 = wordToReverse.bit.bit14;
wordReversed.bit.bit10 = wordToReverse.bit.bit13;
wordReversed.bit.bit11 = wordToReverse.bit.bit12;
wordReversed.bit.bit12 = wordToReverse.bit.bit11;
wordReversed.bit.bit13 = wordToReverse.bit.bit10;
wordReversed.bit.bit14 = wordToReverse.bit.bit9;
wordReversed.bit.bit15 = wordToReverse.bit.bit8;
if (word.all != wordReversed.all) {
fail++;
WordNum =128;
} else {
fail = 0;
}
WordNum++;
} else {
// flashAddr.bit.addr2 = 0xFF;
WordNum =128; //finish flash writing
}
}
controlReg.bit.cs = 1;
controlReg.bit.rw = 1;
controlReg.bit.clock = 0;
controlReg.bit.data = 0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, controlReg.all);
}
void memWrite (unsigned int adr_device, volatile unsigned long adr,
volatile unsigned long adr_eeprom, volatile unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error )
{
/////////**********************
/////////before start procedure
/////////**********************
volatile int failNumb = 0;
volatile int checkNumb = 0;
volatile unsigned long addrToRead = 0;
volatile FlashAddr flashAddr;
Led1_Toggle();
Led2_Toggle();
*ok_write= size;
countInMemWrite++;
failNumb = 0;
checkNumb = 0;
addrToRead = adr;
length = size + addrToRead;
addrToRead = adr +8;
*write_error = 0;
*repeat_error = 0;
project.stop_parallel_bus();
initState(adr_device);
WREN();
manufactorerAndProductID = 0;
RDID();
if (byte.all != 0x1F00) {
manufactorerAndProductID = 1;
RDID();
if ((byte.all != 0x2000) && (byte.all != 0xEF00)) *write_error = 5; //TODO: make defines with flash ID NAMES
}
WREN();
WRSR();
RDSR();
while (byte.all > 0) {
if (checkNumb < 3) {
DELAY_US(150);
RDSR(); //check that flash is not busy
// byte.all = 1; // for test!
if (failNumb > 1000) {
// if (failNumb > 30000) { //1000 // for test!
WREN();
WRSR();
RDSR();
failNumb = 0;
checkNumb++;
}
failNumb++;
} else {
*write_error = 1;
*ok_write= 0;
failNumb = 1000;
byte.all = 0x0000;
tryNumb++;
}
}
// failNumb = 1000; // for test!
if (failNumb < 1000) {
failNumb = 0;
checkNumb = 0;
WREN();
ERASE();
RDSR();
while (byte.all > 0) {
DELAY_US(70000);
RDSR(); //check that flash is not busy
if (failNumb > 1000) {
*ok_write= 0;
*write_error = 2;
byte.all = 0x0000;
tryNumb++;
}
failNumb++;
}
}
if (failNumb < 1000) {
failNumb = 0;
flashAddr.all = 0;
/////////**********************
/////////before start procedure finished
/////////**********************
while (flashAddr.bit.addr2 < 0x08){
WREN();
PROGRAM();
ADDR3bytes(flashAddr);
DataW256Bytes(addrToRead);
RDSR();
Led1_Toggle();
failNumb = 0;
checkNumb = 0;
while (byte.all != 0x0000){
if (byte.all != 0x0200) {
if (checkNumb < 30) {
DELAY_US(3500);
RDSR(); //check that flash is not busy
checkNumb++;
} else {
byte.all = 0x0200;
}
} else { //programming the page not completed, it's still "data ready"
if (failNumb < 20) {
WREN();
PROGRAM(); //complete procedure again
ADDR3bytes(flashAddr);
DataW256Bytes(addrToRead);
RDSR();
checkNumb = 0;
failNumb++;
} else {
*ok_write= addrToRead - adr-8;
*write_error = 3;
byte.all = 0x0000;
flashAddr.bit.addr2 = 0x08;
tryNumb++;
// asm (" ESTOP0"); //for save flash life
}
}
}
if (failNumb < 20){
READ();
ADDR3bytes(flashAddr);
DataR256Bytes(addrToRead);
Led2_Toggle();
if (fail ==0) { //if page written correctly, go to the next
if (flashAddr.bit.addr1 < 0xff) {
flashAddr.bit.addr1++;
} else {
flashAddr.bit.addr1 = 0;
flashAddr.bit.addr2++;
}
addrToRead += 0x00000080;
} else if (fail > 7) {
*ok_write= addrToRead - adr - 8;
*write_error = 4;
*repeat_error = fail;
flashAddr.bit.addr2 = 0x08;
tryNumb++;
// asm (" ESTOP0"); //for save flash life
}
}
}
if ((*write_error != 0) && (tryNumb < 3) && (countInMemWrite < 3)) {
memWrite (adr_device, adr, adr_eeprom, size, ok_write, write_error, repeat_error );
}
countInMemWrite = 0;
}
tryNumb =0;
WriteMemory(ADR_CONTR_REG_FOR_WRITE, 0xffff);
WriteMemory(ADR_CONTR_REG_FOR_READ, 0xffff);
project.reload_all_plates_without_reset_no_stop_error();// wait_start_cds + load_cfg
WriteMemory(ADR_BUS_ERROR_READ, 0);
if(i_ReadMemory(ADR_ERRORS_TOTAL_INFO)) //Åñëè íà ëèíèßõ îñòàëèñü îøèáêè.
{
xerror(main_er_ID(3),(void *)0);
}
project.start_parallel_bus();
}

View File

@ -0,0 +1,133 @@
#ifndef _XPERIPHSP6_LOADER_H
#define _XPERIPHSP6_LOADER_H
typedef union{
unsigned int all;
struct{
unsigned int loader_on:1;
unsigned int cs:1;
unsigned int reserved0:2;
unsigned int rw:1;
unsigned int mode:1;
unsigned int reserved1:1;
unsigned int data:1;
unsigned int reserved2:1;
unsigned int clock:1;
unsigned int reserved3:1;
unsigned int plane_addr:4;
unsigned int eeprom_read:1;
}bit;
}ControlReg;
typedef union{
unsigned long all;
struct{
unsigned int addr0:8;
unsigned int addr1:8;
unsigned int addr2:8;
unsigned int reserved:8;
}bit;
}FlashAddr;
typedef union{
unsigned long all;
struct{
unsigned int reserved:16;
unsigned int reserved1:15;
unsigned int data:1;
}bit;
}AddrToSent;
typedef union{
unsigned int all;
struct{
unsigned int reserved0:8;
unsigned int dataReceived:1;
unsigned int reserved1:6;
unsigned int data:1;
}bit;
}Byte;
typedef union{
unsigned int all;
struct{
unsigned int dataReceived:1;
unsigned int reserved1:14;
unsigned int data:1;
}bit;
}Word;
typedef union{
unsigned int all;
struct{
unsigned int bit0:1;
unsigned int bit1:1;
unsigned int bit2:1;
unsigned int bit3:1;
unsigned int bit4:1;
unsigned int bit5:1;
unsigned int bit6:1;
unsigned int bit7:1;
unsigned int bit8:1;
unsigned int bit9:1;
unsigned int bit10:1;
unsigned int bit11:1;
unsigned int bit12:1;
unsigned int bit13:1;
unsigned int bit14:1;
unsigned int bit15:1;
}bit;
}WordToReverse;
typedef union{
unsigned int all;
struct{
unsigned int bit0:1;
unsigned int bit1:1;
unsigned int bit2:1;
unsigned int bit3:1;
unsigned int bit4:1;
unsigned int bit5:1;
unsigned int bit6:1;
unsigned int bit7:1;
unsigned int bit8:1;
unsigned int bit9:1;
unsigned int bit10:1;
unsigned int bit11:1;
unsigned int bit12:1;
unsigned int bit13:1;
unsigned int bit14:1;
unsigned int bit15:1;
}bit;
}WordReversed;
void memWrite (unsigned int adr_device, volatile unsigned long adr,
volatile unsigned long adr_eeprom, volatile unsigned long size, unsigned long *ok_write,
unsigned long *write_error, unsigned long *repeat_error );
void RDID(void);
void RDSR(void);
void WREN(void);
void WRDI(void);
void WRSR(void);
void RDSR(void);
void ERASE(void);
void READ(void);
void PROGRAM(void);
#endif

View File

@ -0,0 +1,111 @@
#ifndef X_BASIC_TYPES_H /* prevent circular inclusions */
#define X_BASIC_TYPES_H /* by using protection macros */
#ifndef TRUE
#define TRUE 1
#endif
#ifndef FALSE
#define FALSE 0
#endif
#ifndef NULL
#define NULL 0
#endif
/*-----------------------------------------------------------------------------
Define the types
-----------------------------------------------------------------------------*/
typedef signed char Int8;
typedef signed int Int16;
typedef signed long Int32;
typedef signed long long Int64;
typedef unsigned char UInt8;
typedef unsigned int UInt16;
typedef unsigned long UInt32;
typedef unsigned long long UInt64;
#ifndef real
typedef float real;
#endif
typedef enum {
component_NotReady = 0x1, // íå ãîòîâ, íå áûëî èíèòà è íå áûëî îáìåíà
component_Ready = 0x2, // ãîòîâ, ïðîøåë ïðîâåðêó íà îáìåí ïî øèíå
component_Started = 0x4, // ïåðåõîäíîé ðåæèì, èíèò áûë, íî îáìåíà åùå íåò, ïîñëå íåñêîëüêèõ íåóäà÷íûõ ïîïûòîê îáìåíà ïîëó÷èì ïåðåõîä â component_Error
component_Error = 0x8, // îøèáêà èëè íå ïðîøåë âíóòðåííèé òåñò.
component_Detected = 0x10, // ïëàòà îáíàðóæåíà, íî îáìåí ñ íåé îòêëþ÷åí â íàñòðîéêàõ ïðîåêòà. Òîëüêî ïðè çàïóñêå ïîèñêà ÂÑÅÕ ïëàò.
component_NotFinded = 0x20, // ïëàòà âêëþ÷åíà â íàñòðîéêàõ ïðîåêòà, íî íå áûëà îáíàðóæåíà ïðè ñòàðòå ïðîãðàììû.
component_NotDetected = 0x40, // ïëàòà íå îáíàðóæåíà, è îáìåí ñ íåé îòêëþ÷åí â íàñòðîéêàõ ïðîåêòà. Òîëüêî ïðè çàïóñêå ïîèñêà ÂÑÅÕ ïëàò.
component_ErrorSBus = 0x80, // íåò îáìåíà ïî SBUS
component_ErrorPBus = 0x100 // àâàðèÿ ïî PBUS
} T_component_status;
typedef enum {
local_status_NotReady = 0x1, // íå ãîòîâ, íå áûëî èíèòà è íå áûëî îáìåíà
local_status_Ok = 0x2, // Íåò îøèáîê
local_status_Error = 0x4 // åñòü îøèáêè.
} T_local_status;
typedef enum {
status_Success = 0,
status_Failed = 1
} T_status_ReturnType;
//typedef UInt16 T_Status;
#define HiWord(l)((UInt16)(((UInt32)(l)>>16)&0xFFFF))
#define LoWord(l)((UInt16)( (UInt32)(l) &0xFFFF))
#define HiByte(w)((UInt8)(((UInt16)(w)>>8)&0xFF))
#define LoByte(w)((UInt8)( (UInt16)(w) &0xFF))
#define Byte3(l)((UInt8)(((UInt32)(l)>>24)&0xFF))
#define Byte2(l)((UInt8)(((UInt32)(l)>>16)&0xFF))
#define Byte1(l)((UInt8)(((UInt32)(l)>> 8)&0xFF))
#define Byte0(l)((UInt8)( (UInt32)(l) &0xFF))
#define Bit_UInt32(bit_index, value) ((UInt32)((((UInt32)(value)) >> (bit_index)) & 0x01))
#define UInt16_Byte0(c) ((((UInt16)(c)) << 0) & 0x00ff)
#define UInt16_Byte1(c) ((((UInt16)(c)) << 8) & 0xff00)
#define UInt32_Byte0(c) ((((UInt32)(c)) << 0) & 0x000000ff)
#define UInt32_Byte1(c) ((((UInt32)(c)) << 8) & 0x0000ff00)
#define UInt32_Byte2(c) ((((UInt32)(c)) << 16) & 0x00ff0000)
#define UInt32_Byte3(c) ((((UInt32)(c)) << 24) & 0xff000000)
#define UInt32_LoWord(w) ((((UInt32)(w)) << 0) & 0x0000ffff)
#define UInt32_HiWord(w) ((((UInt32)(w)) << 16) & 0xffff0000)
#define UInt16_Bit(index, value) ((((UInt16)(value)) & 0x0001) << (index))
#define UInt32_Bit(index, value) ((((UInt32)(value)) & 0x00000001) << (index))
#define X_ASSERT_ESTOP0(useit) \
{ \
if(useit == TRUE) \
{ \
X_Stop(); \
asm (" ESTOP0"); \
} \
}
/*------------------------------------------------------------------------------
Prototypes for the functions in x_basic_types.c
------------------------------------------------------------------------------*/
void X_Stop();
#endif

View File

@ -0,0 +1,218 @@
#include "x_int13.h"
#include <281xEvTimersInit.h>
#include <project.h>
#include "DSP281x_Examples.h" // DSP281x Examples Include File
#include "DSP281x_SWPrioritizedIsrLevels.h" // DSP281x Examples Include File
#include "DSP281x_Device.h"
#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;
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////
//unsigned int enable_profile_led1_pwm = 1;
//unsigned int enable_profile_led2_pwm = 1;
int InitXilinxSpartan2E(void (*int_handler)())
{
int err;
project.controller.status = component_NotReady;
err = load_xilinx_new(0x130000, SIZE_XILINX200);
if (err)
return err;
err = test_xilinx_live();
#ifdef ENABLE_XINTC_INT13
if (int_handler)
XIntcInterruptSetup(int_handler);
else
err = 1;
#endif
if (err == 0)
project.controller.status = component_Ready;
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)
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);
#endif
EINT;
// Insert ISR Code here.......
// i_led2_on_off(1);
// IER &= 0xEFFF;
if (project.controller.write.setup.bit.use_int13 == 1)
{
// EnableInterrupts();
//Îñòàíàâëèâàåì ïðåðûâàíèå, â êîòîðîì ïðîèçâîäèì ðàñ÷¸òû, èç-çà êîòîðûõ ïëàâàëî ïðåðûâàíèå ØÈÌ
// stop_eva_timer1();
if(int13_handler)
{
int13_handler();
}
//Çàïóñêàåì îáðàòíî
//// start_eva_timer1();
// DINT;
//
// IFR &= 0xefff; // î÷èñòèì åñëè âäðóã ïðåðûâàíèå óæå ïðèøëî!
// IER |= M_INT13;
}
else
{
// IFR &= 0xefff; // î÷èñòèì åñëè âäðóã ïðåðûâàíèå óæå ïðèøëî!
// IER |= M_INT13;
}
// EnableInterrupts();
// c = IFR; // & 0x0100
// if (c)
// {
// count_lost_interrupt++;
// IFR &= 0xfeff; // î÷èñòèì åñëè âäðóã ïðåðûâàíèå óæå ïðèøëî!
// }
// EnableInterrupts();
// i_led2_on_off(0);
// IFR &= 0xfeff; // î÷èñòèì åñëè âäðóã ïðåðûâàíèå óæå ïðèøëî!
// EINT;
#if (_ENABLE_INTERRUPT_PROFILE_LED1)
if (profile_interrupt.for_led1.bits.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);
#endif
}
int XIntcInterruptSetup(void (*int_handler)())
{
int result = 0;
EALLOW;
GpioMuxRegs.GPEMUX.bit.XNMI_XINT13_GPIOE2=1;
// GpioMuxRegs.GPEDIR.bit.GPIOE2 = 0;
// GpioDataRegs.GPESET.bit.GPIOE2 = 1;
PieVectTable.XINT13=&XIntc_INT13_Handler;
int13_handler = int_handler;
// PieCtrlRegs.PIECRTL.bit.
XIntruptRegs.XNMICR.bit.POLARITY=0;
XIntruptRegs.XNMICR.bit.SELECT=1;
XIntruptRegs.XNMICR.bit.ENABLE=0;
// Enable interrupt 13
// IER |= M_INT13;
project.controller.read.status.bit.int13_inited = 1;
// EDIS;
// EnableInterrupts();
/*
* Start the interrupt controller in simulation mode.
*/
// result = XIntc_Start(Ptr, intc_mode_is_Sim); // sim mode
// if (!(result == status_Success))
return result;
// return status_Success;
}
void start_int13_interrupt(void)
{
// Enable interrupt 13
IER |= M_INT13;
}
void stop_int13_interrupt(void)
{
// Disable interrupt 13
// IER &= ~(M_INT13);
IER &= MINT13; // Set "global" priority
}

View File

@ -0,0 +1,36 @@
#ifndef _X_INT13_H
#define _X_INT13_H
#include <project_setup.h>
#if(C_PROJECT_TYPE==PROJECT_22220)
#define ENABLE_XINTC_INT13 1
#endif
#if(C_PROJECT_TYPE==PROJECT_BALZAM)
#define ENABLE_XINTC_INT13 1
#endif
#if(C_PROJECT_TYPE==PROJECT_23550)
#define ENABLE_XINTC_INT13 1
#endif
//////////////////////////////////////////
int InitXilinxSpartan2E(void (*int_handler)());
int XIntcInterruptSetup(void (*int_handler)());
void start_int13_interrupt(void);
void stop_int13_interrupt(void);
#endif

View File

@ -0,0 +1,238 @@
#include "x_parallel_bus.h"
#include "MemoryFunctions.h"
#include "Spartan2E_Adr.h"
#include "Spartan2E_Functions.h"
#include "xp_controller.h"
#include "xerror.h"
X_PARALLEL_BUS x_parallel_bus_project = X_PARALLEL_BUS_DEFAULTS;
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_run_cmd(X_PARALLEL_BUS *v)
{
volatile unsigned int d_wr;
d_wr = ( (v->flags.bit.cmd_start & 0x1) << 15 ) | ( (v->setup.setup_error_count_read & 0xf) << 8 ) | ((v->setup.size_table - 1) & 0xff);
WriteMemory(ADR_PARALLEL_BUS_CMD, d_wr);
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_clear_table(X_PARALLEL_BUS *v)
{
v->setup.size_table = -1;
v->setup.free_table = -1;
v->flags.bit.cmd_start = 1;
x_parallel_bus_run_cmd(v);
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
int x_parallel_bus_check_free_table(X_PARALLEL_BUS *v)
{
if ( (v->setup.size_table + v->setup.tms_adr_data_start) <= v->setup.tms_adr_data_finish)
{
return 1;
}
return 0;
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_add_table(X_PARALLEL_BUS *v)
{
volatile unsigned int d_wr;
if (v->flags.bit.started)
{
v->stop(v);
}
// if (v->setup.size_table != 0)
// v->setup.size_table++;
if ( (v->setup.size_table + v->setup.tms_adr_data_start) > v->setup.tms_adr_data_finish)
{
// ìåñòà â òàáëèöå íåòó!!!
xerror(xparall_bus_er_ID(1),(void *)0);
return;
}
d_wr = v->setup.size_table & 0xff;
WriteMemory(ADR_PARALLEL_BUS_ADR_TABLE, d_wr);
d_wr = ( (v->slave_addr & 0xf) << 12 ) | ( (v->reg_addr & 0xf) << 8 ) | (( (v->setup.tms_adr_data_start & 0xff) + v->setup.size_table) & 0xff);
WriteMemory(ADR_PARALLEL_BUS_SET_TABLE, d_wr);
v->setup.free_table = (v->setup.tms_adr_data_finish - v->setup.tms_adr_data_start) - v->setup.size_table;
// x_parallel_bus_run_cmd(v);
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_start(X_PARALLEL_BUS *v)
{
if (v->setup.size_table != 0)
{
v->flags.bit.error = 0;
v->flags.bit.cmd_start = 1;
v->flags.bit.was_started = 0;
x_parallel_bus_run_cmd(v);
v->flags.bit.started = 1;
}
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_stop(X_PARALLEL_BUS *v)
{
v->flags.bit.cmd_start = 0;
x_parallel_bus_run_cmd(v);
v->flags.bit.started = 0;
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_restart(X_PARALLEL_BUS *v)
{
v->flags.bit.cmd_start = 0;
x_parallel_bus_run_cmd(v);
v->flags.bit.started = 0;
v->flags.bit.error = 0;
v->flags.bit.cmd_start = 1;
x_parallel_bus_run_cmd(v);
v->flags.bit.started = 1;
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_init(X_PARALLEL_BUS *v)
{
if (v->flags.bit.init)
return;
v->setup.size_table = 0;//-1;
v->setup.tms_adr_data_start = ADR_FIRST_FREE;
v->setup.tms_adr_data_finish = ADR_LAST_FREE;
v->setup.setup_error_count_read = MAX_WAIT_ERROR_PARALLEL_BUS;
v->setup.free_table = v->setup.tms_adr_data_finish - v->setup.tms_adr_data_start;
v->flags.all = 0;
v->slave_addr = 0;
v->reg_addr = 0;
v->error_count_start = 0;
v->count_read = 0;
v->stop(v);
v->flags.bit.init = 1;
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
void x_parallel_bus_read_status(X_PARALLEL_BUS *v)
{
// volatile unsigned int d_rd;
static unsigned int prev_error = 0;
T_controller_read r_c;
// check prev status?
if (v->flags.bit.error)
return;
// read status bus
r_c.errors_buses.all = i_ReadMemory(ADR_BUS_ERROR_READ);
v->flags.bit.count_error = r_c.errors_buses.bit.count_error_pbus;// ((d_rd >> 8) & 0xf);
v->flags.bit.slave_addr_error = r_c.errors_buses.bit.slave_addr_error; // ((d_rd >> 4) & 0xf);
if ( v->flags.bit.count_error >= v->setup.setup_error_count_read )
{
v->flags.bit.error = 1;
}
else
v->flags.bit.error = 0;
if ((prev_error != v->flags.bit.error ) && (v->flags.bit.error))
{
v->error_count_start++;
if (v->flags.bit.started)
{
v->flags.bit.was_started = 1;
x_parallel_bus_stop(v);
}
}
prev_error = v->flags.bit.error;
if ( v->flags.bit.started && (v->flags.bit.error == 0))
v->count_read++;
}
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////
//
////////////////////////////////////////////////////////////////
#pragma CODE_SECTION(x_parallel_bus_read_one_data,".fast_run");
void x_parallel_bus_read_one_data(X_PARALLEL_BUS *v)
{
// read data from parallel bus
v->data_table_read = i_ReadMemory(ADR_FIRST_FREE + v->adr_table_read);
}
////////////////////////////////////////////////////////////////

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