diff --git a/APP_Framework/Framework/connection/4g/adapter_4g.c b/APP_Framework/Framework/connection/4g/adapter_4g.c index a0a96cd62..765840810 100644 --- a/APP_Framework/Framework/connection/4g/adapter_4g.c +++ b/APP_Framework/Framework/connection/4g/adapter_4g.c @@ -110,7 +110,9 @@ int Adapter4GTest(void) return 0; } -// SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0)|SHELL_CMD_DISABLE_RETURN, Adapter4GTest, Adapter4GTest, show adapter 4G information); -#ifdef ADD_RTTHREAD_FETURES -MSH_CMD_EXPORT(Adapter4GTestRTThread,a 4G adpter sample); + +#ifdef ADD_RTTHREAD_FETURES +MSH_CMD_EXPORT(Adapter4GTest,a EC200T adpter sample); +#else +SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0)|SHELL_CMD_DISABLE_RETURN, Adapter4GTest, Adapter4GTest, show adapter 4G information); #endif \ No newline at end of file diff --git a/APP_Framework/Framework/connection/bluetooth/adapter_bluetooth.c b/APP_Framework/Framework/connection/bluetooth/adapter_bluetooth.c index 03d116376..2f72ba2e2 100644 --- a/APP_Framework/Framework/connection/bluetooth/adapter_bluetooth.c +++ b/APP_Framework/Framework/connection/bluetooth/adapter_bluetooth.c @@ -82,7 +82,7 @@ int AdapterBlueToothInit(void) int AdapterBlueToothTest(void) { const char *bluetooth_msg = "BT Adapter Test"; - char bluetooth_recv_msg[128]; + char bluetooth_recv_msg[128]={0}; int len; int baud_rate = BAUD_RATE_9600; @@ -92,7 +92,7 @@ int AdapterBlueToothTest(void) AdapterDeviceOpen(adapter); //if bluetooth master and slave have already match, no need to AdapterDeviceControl and AdapterDeviceConnect - AdapterDeviceControl(adapter, OPE_INT, &baud_rate); + AdapterDeviceControl(adapter, OPE_INT, &baud_rate); //AdapterDeviceConnect(adapter, adapter->net_role, NULL, NULL, 0); len = strlen(bluetooth_msg); @@ -100,6 +100,7 @@ int AdapterBlueToothTest(void) while (1) { AdapterDeviceRecv(adapter, bluetooth_recv_msg, 8); printf("bluetooth_recv_msg %s\n", bluetooth_recv_msg); + AdapterDeviceSend(adapter, bluetooth_msg, len); printf("send %s after recv\n", bluetooth_msg); PrivTaskDelay(1000); diff --git a/APP_Framework/Framework/connection/bluetooth/hc08/Kconfig b/APP_Framework/Framework/connection/bluetooth/hc08/Kconfig index 6e1f3f0fe..f7c0e5ec8 100644 --- a/APP_Framework/Framework/connection/bluetooth/hc08/Kconfig +++ b/APP_Framework/Framework/connection/bluetooth/hc08/Kconfig @@ -55,9 +55,30 @@ if ADD_NUTTX_FETURES endif if ADD_RTTHREAD_FETURES - config ADAPTER_HC08_DRIVER - string "HC08 device uart driver path" - default "/dev/uart4" + config ADAPTER_HC08_RECV_BUFFER_SIZE + int "HC08 recv data buffer size" + default "128" + config ADAPTER_HC08_WORK_ROLE string "HC08 work role M(MASTER) or S(SLAVER)" + default "M" + + config ADAPTER_HC08_DRIVER_EXTUART + bool "Using extra uart to support bluetooth" + default n + + config ADAPTER_HC08_DRIVER + string "HC08 device uart driver path" + default "/dev/dev2" + depends on !ADAPTER_HC08_DRIVER_EXTUART + + if ADAPTER_HC08_DRIVER_EXTUART + config ADAPTER_HC08_DRIVER + string "HC08 device extra uart driver path" + default "/dev/dev2" + + config ADAPTER_HC08_DRIVER_EXT_PORT + int "if HC08 device using extuart, choose port" + default "2" + endif endif diff --git a/APP_Framework/Framework/connection/bluetooth/hc08/hc08.c b/APP_Framework/Framework/connection/bluetooth/hc08/hc08.c index 1798d5e2f..a7054a56a 100644 --- a/APP_Framework/Framework/connection/bluetooth/hc08/hc08.c +++ b/APP_Framework/Framework/connection/bluetooth/hc08/hc08.c @@ -189,6 +189,30 @@ static int Hc08AtConfigure(ATAgentType agent, enum Hc08AtCmd hc08_at_cmd, void * AtSetReplyCharNum(agent, 13); ATOrderSend(agent, REPLY_TIME_OUT, reply, cmd_str); reply_ok_flag = 0; + break; + case HC08_AT_CMD_GET_SUUID: + AtSetReplyCharNum(agent, 13); + ATOrderSend(agent, REPLY_TIME_OUT, reply, HC08_GET_SUUID_CMD); + reply_ok_flag = 0; + break; + case HC08_AT_CMD_SET_SUUID: + luuid = *(unsigned int *)param; + sprintf(cmd_str, HC08_SET_SUUID_CMD, luuid); + AtSetReplyCharNum(agent, 13); + ATOrderSend(agent, REPLY_TIME_OUT, reply, cmd_str); + reply_ok_flag = 0; + break; + case HC08_AT_CMD_GET_TUUID: + AtSetReplyCharNum(agent, 13); + ATOrderSend(agent, REPLY_TIME_OUT, reply, HC08_GET_TUUID_CMD); + reply_ok_flag = 0; + break; + case HC08_AT_CMD_SET_TUUID: + luuid = *(unsigned int *)param; + sprintf(cmd_str, HC08_SET_TUUID_CMD, luuid); + AtSetReplyCharNum(agent, 13); + ATOrderSend(agent, REPLY_TIME_OUT, reply, cmd_str); + reply_ok_flag = 0; break; default: printf("hc08 do not support no.%d cmd\n", hc08_at_cmd); @@ -310,7 +334,8 @@ static int Hc08Ioctl(struct Adapter *adapter, int cmd, void *args) return 0; } -#else + +#else static int Hc08Ioctl(struct Adapter *adapter, int cmd, void *args) { if (OPE_INT != cmd) { @@ -362,27 +387,45 @@ static int Hc08Ioctl(struct Adapter *adapter, int cmd, void *args) } PrivTaskDelay(500); - + #ifdef ADD_RTTHREAD_FETURES //Step3 : show hc08 device info, hc08_get send "AT+RX" response device info - // char device_info[HC08_RESP_DEFAULT_SIZE * 2] = {0}; - // if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_GET_DEVICE_INFO, NULL, device_info) < 0) { - // return -1; - // } - + char device_info[HC08_RESP_DEFAULT_SIZE * 2] = {0}; + if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_GET_DEVICE_INFO, NULL, device_info) < 0) { + return -1; + } + #endif //Step4 : set LUUID銆丼UUID銆乀UUID, slave and master need to have same uuid param luuid = 1234; - if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_SET_LUUID, &luuid, NULL) < 0) { + if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_SET_LUUID, &luuid, NULL) < 0) { return -1; } if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_GET_LUUID, NULL, NULL) < 0) { return -1; } + #ifdef ADD_RTTHREAD_FETURES + uint32_t suuid=1234; + if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_SET_SUUID, &luuid, NULL) < 0) { + return -1; + } + if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_GET_SUUID, NULL, NULL) < 0) { + return -1; + } + uint32_t tuuid=1234; + if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_SET_TUUID, &tuuid, NULL) < 0) { + return -1; + } + + if (Hc08AtConfigure(adapter->agent, HC08_AT_CMD_GET_TUUID, NULL, NULL) < 0) { + return -1; + } + #endif ADAPTER_DEBUG("Hc08 ioctl done\n"); return 0; } + #endif static int Hc08SetAddr(struct Adapter *adapter, const char *ip, const char *gateway, const char *netmask) diff --git a/APP_Framework/Framework/connection/lora/adapter_lora.c b/APP_Framework/Framework/connection/lora/adapter_lora.c index 3c296ccf8..2e848ef35 100644 --- a/APP_Framework/Framework/connection/lora/adapter_lora.c +++ b/APP_Framework/Framework/connection/lora/adapter_lora.c @@ -924,8 +924,8 @@ static pthread_t lora_client_data_task; int AdapterLoraTest(void) { - struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_LORA_NAME); - + struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_LORA_NAME); + AdapterDeviceOpen(adapter); //create lora gateway task @@ -979,6 +979,9 @@ int AdapterLoraTest(void) return 0; } +#ifdef ADD_RTTHREAD_FETURES +MSH_CMD_EXPORT(AdapterLoraTest,a Lora adpter sample); +#endif #ifdef ADD_XIZI_FETURES SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0)|SHELL_CMD_DISABLE_RETURN, AdapterLoraTest, AdapterLoraTest, show adapter lora information); #endif diff --git a/APP_Framework/Framework/connection/lora/e220/Kconfig b/APP_Framework/Framework/connection/lora/e220/Kconfig index 322b307c8..aec5daab6 100644 --- a/APP_Framework/Framework/connection/lora/e220/Kconfig +++ b/APP_Framework/Framework/connection/lora/e220/Kconfig @@ -64,5 +64,34 @@ if ADD_NUTTX_FETURES endif if ADD_RTTHREAD_FETURES + config ADAPTER_E220_M0 + int "E220 M0 pin number" + default "11" + config ADAPTER_E220_M1 + int "E220 M1 pin number" + default "9" + + config ADAPTER_E220_PIN_DRIVER + string "E220 device pin driver path" + default "/dev/dev3" + + config ADAPTER_E220_DRIVER_EXTUART + bool "Using extra uart to support lora" + default y + + config ADAPTER_E220_DRIVER + string "E220 device uart driver path" + default "/dev/dev3" + depends on !ADAPTER_E220_DRIVER_EXTUART + + if ADAPTER_E220_DRIVER_EXTUART + config ADAPTER_E220_DRIVER + string "E220 device extra uart driver path" + default "/dev/dev3" + + config ADAPTER_E220_DRIVER_EXT_PORT + int "if E220 device using extuart, choose port" + default "3" + endif endif diff --git a/APP_Framework/Framework/connection/lora/e220/SConscript b/APP_Framework/Framework/connection/lora/e220/SConscript new file mode 100644 index 000000000..8ad6e9cc3 --- /dev/null +++ b/APP_Framework/Framework/connection/lora/e220/SConscript @@ -0,0 +1,10 @@ +from building import * +import os + +cwd = GetCurrentDir() +src = [] +if GetDepend(['ADAPTER_E220']): + src += ['e220.c'] +group = DefineGroup('connection lora e220', src, depend = [], CPPPATH = [cwd]) + +Return('group') \ No newline at end of file diff --git a/APP_Framework/Framework/connection/lora/e220/e220.c b/APP_Framework/Framework/connection/lora/e220/e220.c index 9f4f75d72..7715df01b 100644 --- a/APP_Framework/Framework/connection/lora/e220/e220.c +++ b/APP_Framework/Framework/connection/lora/e220/e220.c @@ -21,7 +21,11 @@ #include #define E220_GATEWAY_ADDRESS 0xFFFF +#ifdef ADD_RTTHREAD_FETURES +#define E220_CHANNEL 0x02 +#else #define E220_CHANNEL 0x05 +#endif #ifdef AS_LORA_GATEWAY_ROLE #define E220_ADDRESS E220_GATEWAY_ADDRESS @@ -31,7 +35,11 @@ #define E220_ADDRESS ADAPTER_LORA_NET_ROLE_ID #endif +#ifdef ADD_RTTHREAD_FETURES +#define E220_UART_BAUD_RATE 9600 +#else #define E220_UART_BAUD_RATE 115200 +#endif enum E220LoraMode { @@ -265,13 +273,16 @@ static int E220SetRegisterParam(struct Adapter *adapter, uint16 address, uint8 c buffer[10] = 0; //low-cipher ret = PrivWrite(adapter->fd, (void *)buffer, 11); + if(ret < 0){ printf("E220SetRegisterParam send failed %d!\n", ret); } - PrivRead(adapter->fd, buffer, 11); - E220LoraModeConfig(DATA_TRANSFER_MODE); + PrivRead(adapter->fd, buffer, 11); + E220LoraModeConfig(DATA_TRANSFER_MODE); + + PrivTaskDelay(1000); return 0; @@ -337,6 +348,59 @@ static int E220Open(struct Adapter *adapter) return 0; } #else +#ifdef ADD_RTTHREAD_FETURES +static int E220Open(struct Adapter *adapter) +{ + /*step1: open e220 uart port*/ + adapter->fd = PrivOpen(ADAPTER_E220_DRIVER, O_RDWR); + if (adapter->fd < 0) { + printf("E220Open get uart %s fd error\n", ADAPTER_E220_DRIVER); + return -1; + } + + struct SerialDataCfg cfg; + memset(&cfg, 0 ,sizeof(struct SerialDataCfg)); + + cfg.serial_baud_rate = BAUD_RATE_9600; + cfg.serial_data_bits = DATA_BITS_8; + cfg.serial_stop_bits = STOP_BITS_1; + cfg.serial_parity_mode = PARITY_NONE; + cfg.serial_bit_order = BIT_ORDER_LSB; + cfg.serial_invert_mode = NRZ_NORMAL; + cfg.serial_buffer_size = SERIAL_RB_BUFSZ; + + /*aiit board use ch438, so it needs more serial configuration*/ +#ifdef ADAPTER_E220_DRIVER_EXTUART + cfg.ext_uart_no = ADAPTER_E220_DRIVER_EXT_PORT; + cfg.port_configure = PORT_CFG_INIT; +#endif + +#ifdef AS_LORA_GATEWAY_ROLE + //serial receive timeout 10s + cfg.serial_timeout = 10000; +#endif + +#ifdef AS_LORA_CLIENT_ROLE + //serial receive wait forever + cfg.serial_timeout = -1; +#endif + + struct PrivIoctlCfg ioctl_cfg; + ioctl_cfg.ioctl_driver_type = SERIAL_TYPE; + ioctl_cfg.args = &cfg; + + PrivIoctl(adapter->fd, OPE_INT, &ioctl_cfg); + + cfg.serial_baud_rate = E220_UART_BAUD_RATE; + ioctl_cfg.args = &cfg; + + PrivIoctl(adapter->fd, OPE_INT, &ioctl_cfg); + + ADAPTER_DEBUG("E220Open done\n"); + + return 0; +} +#else static int E220Open(struct Adapter *adapter) { /*step1: open e220 uart port*/ @@ -392,6 +456,7 @@ static int E220Open(struct Adapter *adapter) return 0; } #endif +#endif /** * @description: Close E220 uart function @@ -473,7 +538,7 @@ static int E220Send(struct Adapter *adapter, const void *buf, size_t len) */ static int E220Recv(struct Adapter *adapter, void *buf, size_t len) { - int recv_len, recv_len_continue; + int recv_len=0, recv_len_continue=0; uint8 *recv_buf = PrivMalloc(len); @@ -559,7 +624,46 @@ static void LoraOpen(void) E220Open(adapter); } +MSH_CMD_EXPORT(LoraOpen,Lora open test sample); +#ifdef ADD_RTTHREAD_FETURES +static void LoraRead(void *parameter) +{ + int RevLen; + int i, cnt = 0; + + uint8 buffer[256]; + + memset(buffer, 0, 256); + + struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_LORA_NAME); + if (NULL == adapter) { + printf("LoraRead find lora adapter error\n"); + return; + } + + while (1) + { + printf("ready to read lora data\n"); + + RevLen = E220Recv(adapter, buffer, 6); + if (RevLen) { + printf("lora get data %u\n", RevLen); + for (i = 0; i < RevLen; i ++) { + printf("i %u data 0x%x\n", i, buffer[i]); + } + + memset(buffer, 0, 256); + + PrivTaskDelay(1000); + + cnt ++; + E220Send(adapter, &cnt, 1); + } + } +} +MSH_CMD_EXPORT(LoraRead,Lora read test sample); +#else static void LoraRead(void *parameter) { int RevLen; @@ -595,6 +699,8 @@ static void LoraRead(void *parameter) } } } +#endif + #ifdef ADD_XIZI_FETURES static void LoraTest(void) @@ -668,3 +774,41 @@ void E220LoraSend(int argc, char *argv[]) } } #endif + +#ifdef ADD_RTTHREAD_FETURES + +static void LoraReadStart(void) +{ + int ret; + + LoraOpen(); + + rt_thread_t tid= rt_thread_create("LoraReadStart", LoraRead, RT_NULL,2048,10,5); + if(tid!=RT_NULL){ + rt_thread_startup(tid); + }else{ + rt_kprintf("LoraReadStart task_lora_read failed \r\n"); + return; + } + +} +MSH_CMD_EXPORT(LoraReadStart,Lora read task start sample); +#define E22400T_M1_PIN (11U) +#define E22400T_M0_PIN (9U) +static void LoraSend(int argc, char *argv[]) +{ + int8_t cmd[10]={0xFF,0xFF,0x02,0xAA,0XBB,0xCC}; //sned AA BB CC to address 01 channel05 + LoraOpen(); + struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_LORA_NAME); + if (NULL == adapter) { + printf("LoraRead find lora adapter error\n"); + return; + } + rt_pin_mode (E22400T_M1_PIN, PIN_MODE_OUTPUT); + rt_pin_mode (E22400T_M0_PIN, PIN_MODE_OUTPUT); + rt_pin_write(E22400T_M1_PIN, PIN_LOW); + rt_pin_write(E22400T_M0_PIN, PIN_HIGH); + E220Send(adapter, cmd, 6); +} +MSH_CMD_EXPORT(LoraSend,Lora send sample); +#endif \ No newline at end of file diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/applications/main.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/applications/main.c index 4c54c8355..56e528716 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/applications/main.c +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/applications/main.c @@ -13,22 +13,21 @@ #include #include "drv_gpio.h" #include - +#include "fsl_gpio.h" +#include "board/hardware/ch438/ch438.h" /* defined the LED pin: GPIO1_IO9 */ #define LED0_PIN GET_PIN(1,9) - +extern int FrameworkInit(void); int main(void) -{ +{ /* set LED0 pin mode to output */ rt_pin_mode(LED0_PIN, PIN_MODE_OUTPUT); rt_kprintf("XIUOS xidatong build %s %s\n",__DATE__,__TIME__); - while (1) - { - rt_pin_write(LED0_PIN, PIN_HIGH); - rt_thread_mdelay(500); - rt_pin_write(LED0_PIN, PIN_LOW); - rt_thread_mdelay(500); - } + FrameworkInit(); + while (1) + { + rt_thread_mdelay(5000); + } } #ifdef BSP_USING_SDRAM diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/Kconfig b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/Kconfig index c06392967..267083666 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/Kconfig +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/Kconfig @@ -229,7 +229,44 @@ menu "Onboard Peripheral Drivers" config BSP_USB1_HOST bool "Enable USB1 Host" default n + + config BSP_USING_RT_THREAD_HC08 + bool "Enable Bluetooth" + default n + menuconfig BSP_USING_CH438 + bool "Enable CH438" + if BSP_USING_CH438 + config CONFIG_CH438_EXTUART0 + bool "Enable CH438_EXTUART0" + default n + config CONFIG_CH438_EXTUART1 + bool "Enable CH438_EXTUART1" + default n + config CONFIG_CH438_EXTUART2 + bool "Enable CH438_EXTUART2" + default n + config CONFIG_CH438_EXTUART3 + bool "Enable CH438_EXTUART3" + default n + config CONFIG_CH438_EXTUART4 + bool "Enable CH438_EXTUART4" + default n + config CONFIG_CH438_EXTUART5 + bool "Enable CH438_EXTUART5" + default n + config CONFIG_CH438_EXTUART6 + bool "Enable CH438_EXTUART6" + default n + config CONFIG_CH438_EXTUART7 + bool "Enable CH438_EXTUART7" + default n + config CH438_INT_PORT + int "ch438 Interrupt Port deafult 3" + range 0 7 + default 3 + endif + menuconfig BSP_USING_ETH bool "Enable Ethernet" select RT_USING_NETDEV diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/board.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/board.c index 48db851df..68f13bd1e 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/board.c +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/board.c @@ -1091,7 +1091,15 @@ void rt_hw_board_init() void rt_hw_us_delay(rt_uint32_t usec) { - ; + rt_uint32_t start, now, delta, reload, us_tick; + start = SysTick->VAL; + reload = SysTick->LOAD; + us_tick = SystemCoreClock / 1000000UL; + do { + now = SysTick->VAL; + delta = start > now ? start - now : reload + start - now; + } while(delta < us_tick * usec); + } static int reboot(void) diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/hardware/ch438/ch438.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/hardware/ch438/ch438.c new file mode 100644 index 000000000..4b5b21688 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/board/hardware/ch438/ch438.c @@ -0,0 +1,1323 @@ +/* +* Copyright (c) 2020 AIIT XUOS Lab +* XiOS is licensed under Mulan PSL v2. +* You can use this software according to the terms and conditions of the Mulan PSL v2. +* You may obtain a copy of Mulan PSL v2 at: +* http://license.coscl.org.cn/MulanPSL2 +* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND, +* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT, +* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE. +* See the Mulan PSL v2 for more details. +*/ + +/** + * @file .c + * @brief imxrt board sd card automount + * @version 1.0 + * @author AIIT XUOS Lab + * @date 2022.06.30 + */ + +#include "ch438.h" +#include + +#ifdef BSP_USING_CH438 + +#define RT (0U) // If config this macro ,we can use rt gpio for ch438 us + +/* This array shows whether the current serial port is selected */ +static bool const g_uart_selected[CH438PORTNUM] = +{ +#ifdef CONFIG_CH438_EXTUART0 + [0] = true, +#endif +#ifdef CONFIG_CH438_EXTUART1 + [1] = true, +#endif +#ifdef CONFIG_CH438_EXTUART2 + [2] = true, +#endif +#ifdef CONFIG_CH438_EXTUART3 + [3] = true, +#endif +#ifdef CONFIG_CH438_EXTUART4 + [4] = true, +#endif +#ifdef CONFIG_CH438_EXTUART5 + [5] = true, +#endif +#ifdef CONFIG_CH438_EXTUART6 + [6] = true, +#endif +#ifdef CONFIG_CH438_EXTUART7 + [7] = true, +#endif +}; + + +/* rt-thread sem and serial definition */ +struct rt_serial_device *extuart_serial_parm[CH438PORTNUM]; +static rt_sem_t rx_sem[CH438PORTNUM]={RT_NULL}; +char * sem[CH438PORTNUM]={"sem0","sem1","sem2","sem3","sem4","sem5","sem6","sem7"}; +/* rt-thread workqueue*/ +struct rt_workqueue* rq; +/* there is data available on the corresponding port */ +static volatile bool done[CH438PORTNUM] = {false,false,false,false,false,false,false,false}; + +/* Eight port data buffer */ +static uint8_t buff[CH438PORTNUM][CH438_BUFFSIZE]; + +/* the value of interrupt number of SSR register */ +static uint8_t Interruptnum[CH438PORTNUM] = {0x01,0x02,0x04,0x08,0x10,0x20,0x40,0x80,}; + +/* Offset address of serial port number */ +static uint8_t offsetadd[CH438PORTNUM] = {0x00,0x10,0x20,0x30,0x08,0x18,0x28,0x38,}; + + +const struct rt_uart_ops ch438_ops={ + rt_ch438_configure, + rt_ch438_control, + rt_ch438_putc, + rt_ch438_getc, + RT_NULL +}; + + +void Config_Interrupt(void){ + gpio_pin_config_t int_config = { + kGPIO_DigitalInput, + 0, + kGPIO_IntFallingEdge, + }; + GPIO_PinInit(CH438_CTL_GPIO, CH438_INT_PIN, &int_config); + /* Enable GPIO pin interrupt */ + GPIO_PortEnableInterrupts(CH438_CTL_GPIO, 1U << CH438_INT_PIN); +} + + +static void Ch438Irq(void * parameter) +{ + rt_uint8_t gInterruptStatus; + rt_uint8_t port = 0; + struct rt_serial_device *serial = (struct rt_serial_device *)parameter; + /* multi irq may happen*/ + gInterruptStatus = ReadCH438Data(REG_SSR_ADDR); + port=CH438_INT_PORT; + rt_hw_serial_isr(extuart_serial_parm[port], RT_SERIAL_EVENT_RX_IND); +} + + +static rt_err_t rt_ch438_configure(struct rt_serial_device *serial, struct serial_configure *cfg) +{ + rt_uint32_t baud_rate = cfg->baud_rate; + rt_uint16_t port = cfg->reserved; + CH438PortInit(port, baud_rate); + return RT_EOK; +} + +static rt_err_t rt_ch438_control(struct rt_serial_device *serial, int cmd, void *arg) +{ + rt_uint16_t ext_uart_no = serial->config.reserved; + static rt_uint16_t register_flag = 0; + + switch (cmd) + { + case RT_DEVICE_CTRL_CLR_INT: + if(1 == register_flag) + { + /* Close interrupt of CH438 */ + /* GPIO3_3 INT*/ + rt_pin_irq_enable(CH438_INT, PIN_IRQ_DISABLE ); + register_flag = 0; + }break; + case RT_DEVICE_CTRL_SET_INT: + if(0 == register_flag) + { + rt_pin_mode(CH438_INT, PIN_MODE_INPUT_PULLUP); + rt_pin_attach_irq(CH438_INT, PIN_IRQ_MODE_FALLING,Ch438Irq,(void *)serial); + rt_pin_irq_enable(CH438_INT, PIN_IRQ_ENABLE); + register_flag = 1; + }break; + } + return (RT_EOK); +} + +static int rt_ch438_putc(struct rt_serial_device *serial, char c) +{ + uint16_t ext_uart_no = serial->config.reserved; + rt_uint8_t REG_LSR_ADDR,REG_THR_ADDR; + + REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR; + REG_THR_ADDR = offsetadd[ext_uart_no] | REG_THR0_ADDR; + rt_thread_mdelay(5); + if((ReadCH438Data( REG_LSR_ADDR ) & BIT_LSR_TEMT) != 0) + { + + WriteCH438Block( REG_THR_ADDR, 1, &c ); + return 1; + } else { + return 0; + } + +} + + +static int rt_ch438_getc(struct rt_serial_device *serial) +{ + + rt_uint8_t dat = 0; + rt_uint8_t REG_LSR_ADDR,REG_RBR_ADDR; + uint16_t ext_uart_no = serial->config.reserved;///< get extern uart port + + REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR; + REG_RBR_ADDR = offsetadd[ext_uart_no] | REG_RBR0_ADDR; + rt_thread_mdelay(5); + if((ReadCH438Data(REG_LSR_ADDR) & BIT_LSR_DATARDY) == 0x01) + { + dat = ReadCH438Data( REG_RBR_ADDR ); + if(dat >= 0) + return dat; + }else{ + return -1; + } + +} + + +int rt_hw_ch438_init(void) +{ + struct rt_serial_device *extserial; + struct device_uart *extuart; + struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT; + rt_err_t ret; + #ifdef CONFIG_CH438_EXTUART0 + static struct rt_serial_device extserial0; + + extserial = &extserial0; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 115200; + extserial->config.reserved = 0; ///< extern uart port + + extuart_serial_parm[0] = &extserial0; + + ret = rt_hw_serial_register(extserial, + "dev0", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev0 register failed.\n"); + } + #endif + #ifdef CONFIG_CH438_EXTUART1 + static struct rt_serial_device extserial1; + + extserial = &extserial1; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 115200; + extserial->config.reserved = 1; ///< extern uart port + + extuart_serial_parm[1] = &extserial1; + + ret = rt_hw_serial_register(extserial, + "dev1", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev1 register failed.\n"); + } + #endif + #ifdef CONFIG_CH438_EXTUART2 + static struct rt_serial_device extserial2; + + extserial = &extserial2; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 9600; + extserial->config.reserved = 2; ///< extern uart port + + extuart_serial_parm[2] = &extserial2; + + ret = rt_hw_serial_register(extserial, + "dev2", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev2 register failed.\n"); + } + rt_kprintf("extuart_dev2 register succeed.\n"); + #endif + #ifdef CONFIG_CH438_EXTUART3 + static struct rt_serial_device extserial3; + + extserial = &extserial3; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 9600; + extserial->config.reserved = 3; ///< extern uart port + + ret = rt_hw_serial_register(extserial, + "dev3", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev3 register failed.\n"); + } + + extuart_serial_parm[3] = &extserial3; + #endif + #ifdef CONFIG_CH438_EXTUART4 + static struct rt_serial_device extserial4; + + extserial = &extserial4; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 9600; + extserial->config.reserved = 4; ///< extern uart port + + ret = rt_hw_serial_register(extserial, + "dev4", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev4 register failed.\n"); + } + + extuart_serial_parm[4] = &extserial4; + #endif + #ifdef CONFIG_CH438_EXTUART5 + static struct rt_serial_device extserial5; + + extserial = &extserial5; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 115200; + extserial->config.reserved = 5; ///< extern uart port + + ret = rt_hw_serial_register(extserial, + "dev5", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev5 register failed.\n"); + } + + extuart_serial_parm[5] = &extserial5; + #endif + #ifdef CONFIG_CH438_EXTUART6 + static struct rt_serial_device extserial6; + + extserial = &extserial6; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 57600; + extserial->config.reserved = 6; ///< extern uart port + + ret = rt_hw_serial_register(extserial, + "dev6", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev6 register failed.\n"); + } + + extuart_serial_parm[6] = &extserial6; + #endif + #ifdef CONFIG_CH438_EXTUART7 + static struct rt_serial_device extserial7; + + extserial = &extserial7; + extserial->ops = &ch438_ops; + extserial->config = config; + extserial->config.baud_rate = 9600; + extserial->config.reserved = 7; ///< extern uart port + + ret = rt_hw_serial_register(extserial, + "dev7", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + extuart); + if(ret < 0){ + rt_kprintf("extuart_dev7 register failed.\n"); + } + rt_kprintf("extuart_dev7 register succeed.\n"); + extuart_serial_parm[7] = &extserial7; + #endif + Ch438InitDefault(); + + return 0; + +} +INIT_DEVICE_EXPORT(rt_hw_ch438_init); + + +void up_udelay(void) +{ + volatile uint32_t i = 0; + for (i = 0; i < EXAMPLE_DELAY_COUNT; ++i) + { + __asm("NOP"); /* delay */ + } +} + +void up_mdelay(uint32_t time){ + + while(time--){ + udelay(1000); + } +} +/**************************************************************************** + * Name: CH438SetOutput + * + * Description: + * Configure pin mode to output + * + ****************************************************************************/ +static void CH438SetOutput(void) +{ + gpio_pin_config_t ch438_d0_config ={kGPIO_DigitalOutput, 0, kGPIO_NoIntmode}; + GPIO_PinInit(CH438_D_GPIO,CH438_D0_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D1_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D2_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D3_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D4_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D5_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D6_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D7_PIN,&ch438_d0_config); + +} + +/**************************************************************************** + * Name: CH438SetInput + * + * Description: + * Configure pin mode to input + * + ****************************************************************************/ +static void CH438SetInput(void) +{ + gpio_pin_config_t ch438_d0_config ={kGPIO_DigitalInput, 0, kGPIO_NoIntmode}; + GPIO_PinInit(CH438_D_GPIO,CH438_D0_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D1_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D2_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D3_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D4_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D5_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D6_PIN,&ch438_d0_config); + GPIO_PinInit(CH438_D_GPIO,CH438_D7_PIN,&ch438_d0_config); + +} +//#define ADAPTER_ZIGBEE_E18 +/**************************************************************************** + * Name: ReadCH438Data + * + * Description: + * Read data from ch438 address + * + ****************************************************************************/ +static uint8_t ReadCH438Data(uint8_t addr) +{ + uint8_t dat = 0; + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NWR_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NRD_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_ALE_PIN,PIN_HIGH); + + + CH438SetOutput(); + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(10); + #else + udelay(1); + #endif + if(addr &0x80) GPIO_PinWrite(CH438_D_GPIO,CH438_D7_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D7_PIN,PIN_LOW); + if(addr &0x40) GPIO_PinWrite(CH438_D_GPIO,CH438_D6_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D6_PIN,PIN_LOW); + if(addr &0x20) GPIO_PinWrite(CH438_D_GPIO,CH438_D5_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D5_PIN,PIN_LOW); + if(addr &0x10) GPIO_PinWrite(CH438_D_GPIO,CH438_D4_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D4_PIN,PIN_LOW); + if(addr &0x08) GPIO_PinWrite(CH438_D_GPIO,CH438_D3_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D3_PIN,PIN_LOW); + if(addr &0x04) GPIO_PinWrite(CH438_D_GPIO,CH438_D2_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D2_PIN,PIN_LOW); + if(addr &0x02) GPIO_PinWrite(CH438_D_GPIO,CH438_D1_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D1_PIN,PIN_LOW); + if(addr &0x01) GPIO_PinWrite(CH438_D_GPIO,CH438_D0_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D0_PIN,PIN_LOW); + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(10); + #else + udelay(1); + #endif + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_ALE_PIN,PIN_LOW); + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(10); + #else + udelay(1); + #endif + + CH438SetInput(); + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(10); + #else + udelay(1); + #endif + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NRD_PIN,PIN_LOW); + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(10); + #else + udelay(1); + #endif + + + if (GPIO_PinRead(CH438_D_GPIO,CH438_D7_PIN)) dat |= 0x80; + if (GPIO_PinRead(CH438_D_GPIO,CH438_D6_PIN)) dat |= 0x40; + if (GPIO_PinRead(CH438_D_GPIO,CH438_D5_PIN)) dat |= 0x20; + if (GPIO_PinRead(CH438_D_GPIO,CH438_D4_PIN)) dat |= 0x10; + if (GPIO_PinRead(CH438_D_GPIO,CH438_D3_PIN)) dat |= 0x08; + if (GPIO_PinRead(CH438_D_GPIO,CH438_D2_PIN)) dat |= 0x04; + if (GPIO_PinRead(CH438_D_GPIO,CH438_D1_PIN)) dat |= 0x02; + if (GPIO_PinRead(CH438_D_GPIO,CH438_D0_PIN)) dat |= 0x01; + + + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NRD_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_ALE_PIN,PIN_HIGH); + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(10); + #else + udelay(1); + #endif + + + return dat; +} + +/**************************************************************************** + * Name: WriteCH438Data + * + * Description: + * write data to ch438 address + * + ****************************************************************************/ +static void WriteCH438Data(uint8_t addr, const uint8_t dat) +{ + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_ALE_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NRD_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NWR_PIN,PIN_HIGH); + + + CH438SetOutput(); + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(100); + #else + udelay(1); + #endif + + + if(addr &0x80) GPIO_PinWrite(CH438_D_GPIO,CH438_D7_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D7_PIN,PIN_LOW); + if(addr &0x40) GPIO_PinWrite(CH438_D_GPIO,CH438_D6_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D6_PIN,PIN_LOW); + if(addr &0x20) GPIO_PinWrite(CH438_D_GPIO,CH438_D5_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D5_PIN,PIN_LOW); + if(addr &0x10) GPIO_PinWrite(CH438_D_GPIO,CH438_D4_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D4_PIN,PIN_LOW); + if(addr &0x08) GPIO_PinWrite(CH438_D_GPIO,CH438_D3_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D3_PIN,PIN_LOW); + if(addr &0x04) GPIO_PinWrite(CH438_D_GPIO,CH438_D2_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D2_PIN,PIN_LOW); + if(addr &0x02) GPIO_PinWrite(CH438_D_GPIO,CH438_D1_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D1_PIN,PIN_LOW); + if(addr &0x01) GPIO_PinWrite(CH438_D_GPIO,CH438_D0_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D0_PIN,PIN_LOW); + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(100); + #else + udelay(1); + #endif + + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_ALE_PIN,PIN_LOW); + + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(100); + #else + udelay(1); + #endif + + + if(dat &0x80) GPIO_PinWrite(CH438_D_GPIO,CH438_D7_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D7_PIN,PIN_LOW); + if(dat &0x40) GPIO_PinWrite(CH438_D_GPIO,CH438_D6_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D6_PIN,PIN_LOW); + if(dat &0x20) GPIO_PinWrite(CH438_D_GPIO,CH438_D5_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D5_PIN,PIN_LOW); + if(dat &0x10) GPIO_PinWrite(CH438_D_GPIO,CH438_D4_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D4_PIN,PIN_LOW); + if(dat &0x08) GPIO_PinWrite(CH438_D_GPIO,CH438_D3_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D3_PIN,PIN_LOW); + if(dat &0x04) GPIO_PinWrite(CH438_D_GPIO,CH438_D2_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D2_PIN,PIN_LOW); + if(dat &0x02) GPIO_PinWrite(CH438_D_GPIO,CH438_D1_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D1_PIN,PIN_LOW); + if(dat &0x01) GPIO_PinWrite(CH438_D_GPIO,CH438_D0_PIN,PIN_HIGH); else GPIO_PinWrite(CH438_D_GPIO,CH438_D0_PIN,PIN_LOW); + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(100); + #else + udelay(1); + #endif + + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NWR_PIN,PIN_LOW); + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(100); + #else + udelay(1); + #endif + + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NWR_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_ALE_PIN,PIN_HIGH); + + + #ifdef ADAPTER_ZIGBEE_E18 + udelay(100); + #else + udelay(1); + #endif + + CH438SetInput(); + + return; +} + +/**************************************************************************** + * Name: WriteCH438Block + * + * Description: + * Write data block from ch438 address + * + ****************************************************************************/ +static void WriteCH438Block(uint8_t mAddr, uint8_t mLen, const uint8_t *mBuf) +{ + while(mLen--) + WriteCH438Data(mAddr, *mBuf++); +} + +/**************************************************************************** + * Name: CH438UARTSend + * + * Description: + * Enable FIFO mode, which is used for ch438 serial port to send multi byte data, + * with a maximum of 128 bytes of data sent at a time + * + ****************************************************************************/ +static void Ch438UartSend(uint8_t ext_uart_no, const uint8_t *Data, uint16_t Num) +{ + uint8_t REG_LSR_ADDR,REG_THR_ADDR; + REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR; + REG_THR_ADDR = offsetadd[ext_uart_no] | REG_THR0_ADDR; + + while(1) + { + while((ReadCH438Data(REG_LSR_ADDR) & BIT_LSR_TEMT) == 0); /* wait for sending data done, THR and TSR is NULL */ + if(Num <= 128) + { + WriteCH438Block(REG_THR_ADDR, Num, Data); + break; + } + else + { + WriteCH438Block(REG_THR_ADDR, 128, Data); + Num -= 128; + Data += 128; + } + } + +} + +/**************************************************************************** + * Name: CH438UARTRcv + * + * Description: + * Disable FIFO mode for ch438 serial port to receive multi byte data + * + ****************************************************************************/ +uint8_t CH438UARTRcv(uint8_t ext_uart_no, uint8_t *buf, size_t size) +{ + uint8_t rcv_num = 0; + uint8_t dat = 0; + uint8_t REG_LSR_ADDR,REG_RBR_ADDR; + uint8_t *read_buffer; + size_t buffer_index = 0; + + read_buffer = buf; + + REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR; + REG_RBR_ADDR = offsetadd[ext_uart_no] | REG_RBR0_ADDR; + + /* Wait for the data to be ready */ + int count=0; + while ((ReadCH438Data(REG_LSR_ADDR) & BIT_LSR_DATARDY) == 0){ + } + while (((ReadCH438Data(REG_LSR_ADDR) & BIT_LSR_DATARDY) == 0x01) && (size != 0)) + { count++; + if(1==count){ + rt_thread_mdelay(5000); + } + rt_thread_mdelay(5); + dat = ReadCH438Data(REG_RBR_ADDR); + *read_buffer = dat; + read_buffer++; + buffer_index++; + if (255 == buffer_index) { + buffer_index = 0; + read_buffer = buf; + } + + ++rcv_num; + --size; + } + + return rcv_num; +} + +/**************************************************************************** + * Name: ImxrtCH438Init + * + * Description: + * ch438 initialization + * + ****************************************************************************/ +static void ImxrtCH438Init(void) +{ + CH438SetOutput(); + gpio_pin_config_t ch438_ctl_config ={kGPIO_DigitalOutput, 0, kGPIO_NoIntmode}; + GPIO_PinInit(CH438_CTL_GPIO,CH438_NWR_PIN,&ch438_ctl_config); + GPIO_PinInit(CH438_CTL_GPIO,CH438_NRD_PIN,&ch438_ctl_config); + GPIO_PinInit(CH438_CTL_GPIO,CH438_ALE_PIN,&ch438_ctl_config); + + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NWR_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_NRD_PIN,PIN_HIGH); + GPIO_PinWrite(CH438_CTL_GPIO,CH438_ALE_PIN,PIN_HIGH); +} + +/**************************************************************************** + * Name: CH438PortInit + * + * Description: + * ch438 port initialization + * + ****************************************************************************/ +static void CH438PortInit(uint8_t ext_uart_no, uint32_t baud_rate) +{ + uint32_t div; + uint8_t DLL,DLM,dlab; + uint8_t REG_LCR_ADDR; + uint8_t REG_DLL_ADDR; + uint8_t REG_DLM_ADDR; + uint8_t REG_IER_ADDR; + uint8_t REG_MCR_ADDR; + uint8_t REG_FCR_ADDR; + + REG_LCR_ADDR = offsetadd[ext_uart_no] | REG_LCR0_ADDR; + REG_DLL_ADDR = offsetadd[ext_uart_no] | REG_DLL0_ADDR; + REG_DLM_ADDR = offsetadd[ext_uart_no] | REG_DLM0_ADDR; + REG_IER_ADDR = offsetadd[ext_uart_no] | REG_IER0_ADDR; + REG_MCR_ADDR = offsetadd[ext_uart_no] | REG_MCR0_ADDR; + REG_FCR_ADDR = offsetadd[ext_uart_no] | REG_FCR0_ADDR; + + /* reset the uart */ + WriteCH438Data(REG_IER_ADDR, BIT_IER_RESET); + up_mdelay(50); + + dlab = ReadCH438Data(REG_IER_ADDR); + dlab &= 0xDF; + WriteCH438Data(REG_IER_ADDR, dlab); + + /* set LCR register DLAB bit 1 */ + dlab = ReadCH438Data(REG_LCR_ADDR); + dlab |= 0x80; + WriteCH438Data(REG_LCR_ADDR, dlab); + + div = (Fpclk >> 4) / baud_rate; + DLM = div >> 8; + DLL = div & 0xff; + + /* set bps */ + WriteCH438Data(REG_DLL_ADDR, DLL); + WriteCH438Data(REG_DLM_ADDR, DLM); + + /* set FIFO mode, 112 bytes */ + WriteCH438Data(REG_FCR_ADDR, BIT_FCR_RECVTG1 | BIT_FCR_RECVTG0 | BIT_FCR_FIFOEN); + + /* 8 bit word size, 1 bit stop bit, no crc */ + WriteCH438Data(REG_LCR_ADDR, BIT_LCR_WORDSZ1 | BIT_LCR_WORDSZ0); + + /* enable interrupt */ + WriteCH438Data(REG_IER_ADDR, BIT_IER_IERECV); + + /* allow interrupt output, DTR and RTS is 1 */ + WriteCH438Data(REG_MCR_ADDR, BIT_MCR_OUT2); + + /* release the data in FIFO */ + WriteCH438Data(REG_FCR_ADDR, ReadCH438Data(REG_FCR_ADDR)| BIT_FCR_TFIFORST); +} +/**************************************************************************** + * Name: ImxrtCh438ReadData + * + * Description: + * Read data from ch438 port + * + ****************************************************************************/ +static int ImxrtCh438WriteData(uint8_t ext_uart_no, const uint8_t *write_buffer, size_t size) +{ + int write_len, write_len_continue; + int i, write_index; + if(write_buffer == NULL){ + return ERROR; + } + + write_len = size; + write_len_continue = size; + + if(write_len > 256) + { + if(0 == write_len % 256) + { + write_index = write_len / 256; + for(i = 0; i < write_index; i ++) + { + Ch438UartSend(ext_uart_no, write_buffer + i * 256, 256); + } + } + else + { + write_index = 0; + while(write_len_continue > 256) + { + Ch438UartSend(ext_uart_no, write_buffer + write_index * 256, 256); + write_index++; + write_len_continue = write_len - write_index * 256; + } + Ch438UartSend(ext_uart_no, write_buffer + write_index * 256, write_len_continue); + } + } + else + { + Ch438UartSend(ext_uart_no, write_buffer, write_len); + } + + return OK; +} + +/**************************************************************************** + * Name: ImxrtCh438ReadData + * + * Description: + * Read data from ch438 port + * + ****************************************************************************/ +static size_t ImxrtCh438ReadData(uint8_t ext_uart_no, size_t size) +{ + size_t RevLen = 0; + uint8_t InterruptStatus; + uint8_t REG_IIR_ADDR; + uint8_t REG_LSR_ADDR; + uint8_t REG_MSR_ADDR; + + REG_IIR_ADDR = offsetadd[ext_uart_no] | REG_IIR0_ADDR; + REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR; + REG_MSR_ADDR = offsetadd[ext_uart_no] | REG_MSR0_ADDR; + /* Read the interrupt status of the serial port */ + InterruptStatus = ReadCH438Data(REG_IIR_ADDR) & 0x0f; + rt_kprintf("InterruptStatus is %d\n", InterruptStatus); + + switch(InterruptStatus) + { + case INT_NOINT: /* no interrupt */ + break; + case INT_THR_EMPTY: /* the transmit hold register is not interrupted */ + break; + case INT_RCV_OVERTIME: /* receive data timeout interrupt */ + case INT_RCV_SUCCESS: /* receive data available interrupt */ + RevLen = CH438UARTRcv(ext_uart_no, buff[ext_uart_no], size); + break; + case INT_RCV_LINES: /* receive line status interrupt */ + ReadCH438Data(REG_LSR_ADDR); + break; + case INT_MODEM_CHANGE: /* modem input change interrupt */ + ReadCH438Data(REG_MSR_ADDR); + break; + default: + break; + } + + return RevLen; +} + +/**************************************************************************** + * Name: Ch438InitDefault + * + * Description: + * Ch438 default initialization function + * + ****************************************************************************/ +static void Ch438InitDefault(void) +{ + /*Dynamically create semaphores */ + semaphoreChInit(); + + ImxrtCH438Init(); + +/* If a port is checked, the port will be initialized. Otherwise, the interrupt of the port will be disabled. */ + +#ifdef CONFIG_CH438_EXTUART0 + CH438PortInit(0, CONFIG_CH438_EXTUART0_BAUD); +#else + WriteCH438Data(REG_IER0_ADDR, 0x00); +#endif + +#ifdef CONFIG_CH438_EXTUART1 + CH438PortInit(1, CONFIG_CH438_EXTUART1_BAUD); +#else + WriteCH438Data(REG_IER1_ADDR, 0x00); +#endif + +#ifdef CONFIG_CH438_EXTUART2 + CH438PortInit(2, CONFIG_CH438_EXTUART2_BAUD); +#else + WriteCH438Data(REG_IER2_ADDR, 0x00); +#endif + +#ifdef CONFIG_CH438_EXTUART3 + CH438PortInit(3, CONFIG_CH438_EXTUART3_BAUD); +#else + WriteCH438Data(REG_IER3_ADDR, 0x00); +#endif + +#ifdef CONFIG_CH438_EXTUART4 + CH438PortInit(4, CONFIG_CH438_EXTUART4_BAUD); +#else + WriteCH438Data(REG_IER4_ADDR, 0x00); +#endif + +#ifdef CONFIG_CH438_EXTUART5 + CH438PortInit(5, CONFIG_CH438_EXTUART5_BAUD); +#else + WriteCH438Data(REG_IER5_ADDR, 0x00); +#endif + +#ifdef CONFIG_CH438_EXTUART6 + CH438PortInit(6, CONFIG_CH438_EXTUART6_BAUD); +#else + WriteCH438Data(REG_IER6_ADDR, 0x00); +#endif + +#ifdef CONFIG_CH438_EXTUART7 + CH438PortInit(7, CONFIG_CH438_EXTUART7_BAUD); +#else + WriteCH438Data(REG_IER7_ADDR, 0x00); +#endif + + up_mdelay(10); + +} +/**************************************************************************** + * Name: static void getChInterruptStatus( void *arg) + * + * Description: + * read Interrupt register of ch438 + * + ****************************************************************************/ + +static int getCh438InterruptStatus(void ){ + uint8_t gChInterruptStatus=0; /*Interrupt register status*/ + uint8_t i=7; + gChInterruptStatus=ReadCH438Data(REG_SSR_ADDR); + rt_kprintf("gChInterruptStatus: %x",gChInterruptStatus); + if(gChInterruptStatus){ + for(i=0;i +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include "fsl_gpio.h" +#include "drv_gpio.h" +#include "MIMXRT1052.h" + + +/*self define*/ +/* output pin */ +#define CH438_D_GPIO GPIO1 +#define ZIGBEE_GPIO GPIO2 +#define CH438_CTL_GPIO GPIO3 + +#define CH438_INT_IRQ GPIO3_Combined_0_15_IRQn +#define CH438_INT_IRQ_HANDLER GPIO3_Combined_0_15_IRQHandler + +/* ch438 ctl pin */ +#define CH438_NWR 68 +#define CH438_NRD 69 +#define CH438_ALE 66 +#define CH438_INT 67 + +/* ch438 r/w pin*/ +#define CH438_D0 25 +#define CH438_D1 24 +#define CH438_D2 20 +#define CH438_D3 21 +#define CH438_D4 31 +#define CH438_D5 28 +#define CH438_D6 30 +#define CH438_D7 29 + + +#ifdef CONFIG_CH438_EXTUART0 +#define EXTU_UART_0 "dev0" +#endif + +#ifdef CONFIG_CH438_EXTUART1 +#define EXTU_UART_1 "dev1" +#endif + +#ifdef CONFIG_CH438_EXTUART2 +#define EXTU_UART_2 "dev2" +#endif + +#ifdef CONFIG_CH438_EXTUART3 +#define EXTU_UART_3 "dev3" +#endif + +#ifdef CONFIG_CH438_EXTUART4 +#define EXTU_UART_4 "dev4" +#endif + +#ifdef CONFIG_CH438_EXTUART5 +#define EXTU_UART_5 "dev5" +#endif + +#ifdef CONFIG_CH438_EXTUART6 +#define EXTU_UART_6 "dev6" +#endif + +#ifdef CONFIG_CH438_EXTUART7 +#define EXTU_UART_7 "dev7" +#endif + + +#define ZIGBEE_MODE_PIN (11U) + +#define CH438_D0_PIN (25U) +#define CH438_D1_PIN (24U) +#define CH438_D2_PIN (20U) +#define CH438_D3_PIN (21U) +#define CH438_D4_PIN (31U) +#define CH438_D5_PIN (28U) +#define CH438_D6_PIN (30U) +#define CH438_D7_PIN (29U) + +#define CH438_NWR_PIN (4U) +#define CH438_NRD_PIN (5U) +#define CH438_ALE_PIN (2U) +#define CH438_INT_PIN (3U) + +#define EXAMPLE_DELAY_COUNT 5000 +#define CH438PORTNUM 8 +#define CH438_BUFFSIZE 256 +#define CH438_INCREMENT MSEC2TICK(33) + +#define CONFIG_CH438_EXTUART0_BAUD 115200 +#define CONFIG_CH438_EXTUART1_BAUD 115200 +#define CONFIG_CH438_EXTUART2_BAUD 9600 +#define CONFIG_CH438_EXTUART3_BAUD 9600 +#define CONFIG_CH438_EXTUART4_BAUD 115200 +#define CONFIG_CH438_EXTUART5_BAUD 115200 +#define CONFIG_CH438_EXTUART6_BAUD 115200 +#define CONFIG_CH438_EXTUART7_BAUD 9600 +#define OK 0 +#define ERROR 1 + +/* chip definition */ +/* CH438serial port0 register address */ + +#define REG_RBR0_ADDR 0x00 /* serial port0receive buffer register address */ +#define REG_THR0_ADDR 0x00 /* serial port0send hold register address */ +#define REG_IER0_ADDR 0x01 /* serial port0interrupt enable register address */ +#define REG_IIR0_ADDR 0x02 /* serial port0interrupt identifies register address */ +#define REG_FCR0_ADDR 0x02 /* serial port0FIFO controls register address */ +#define REG_LCR0_ADDR 0x03 /* serial port0circuit control register address */ +#define REG_MCR0_ADDR 0x04 /* serial port0MODEM controls register address */ +#define REG_LSR0_ADDR 0x05 /* serial port0line status register address */ +#define REG_MSR0_ADDR 0x06 /* serial port0address of MODEM status register */ +#define REG_SCR0_ADDR 0x07 /* serial port0the user can define the register address */ +#define REG_DLL0_ADDR 0x00 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM0_ADDR 0x01 /* Baud rate divisor latch high 8-bit byte address */ + + +/* CH438serial port1 register address */ + +#define REG_RBR1_ADDR 0x10 /* serial port1receive buffer register address */ +#define REG_THR1_ADDR 0x10 /* serial port1send hold register address */ +#define REG_IER1_ADDR 0x11 /* serial port1interrupt enable register address */ +#define REG_IIR1_ADDR 0x12 /* serial port1interrupt identifies register address */ +#define REG_FCR1_ADDR 0x12 /* serial port1FIFO controls register address */ +#define REG_LCR1_ADDR 0x13 /* serial port1circuit control register address */ +#define REG_MCR1_ADDR 0x14 /* serial port1MODEM controls register address */ +#define REG_LSR1_ADDR 0x15 /* serial port1line status register address */ +#define REG_MSR1_ADDR 0x16 /* serial port1address of MODEM status register */ +#define REG_SCR1_ADDR 0x17 /* serial port1the user can define the register address */ +#define REG_DLL1_ADDR 0x10 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM1_ADDR 0x11 /* Baud rate divisor latch high 8-bit byte address */ + + +/* CH438serial port2 register address */ + +#define REG_RBR2_ADDR 0x20 /* serial port2receive buffer register address */ +#define REG_THR2_ADDR 0x20 /* serial port2send hold register address */ +#define REG_IER2_ADDR 0x21 /* serial port2interrupt enable register address */ +#define REG_IIR2_ADDR 0x22 /* serial port2interrupt identifies register address */ +#define REG_FCR2_ADDR 0x22 /* serial port2FIFO controls register address */ +#define REG_LCR2_ADDR 0x23 /* serial port2circuit control register address */ +#define REG_MCR2_ADDR 0x24 /* serial port2MODEM controls register address */ +#define REG_LSR2_ADDR 0x25 /* serial port2line status register address */ +#define REG_MSR2_ADDR 0x26 /* serial port2address of MODEM status register */ +#define REG_SCR2_ADDR 0x27 /* serial port2the user can define the register address */ +#define REG_DLL2_ADDR 0x20 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM2_ADDR 0x21 /* Baud rate divisor latch high 8-bit byte address */ + + +/* CH438serial port3 register address */ + +#define REG_RBR3_ADDR 0x30 /* serial port3receive buffer register address */ +#define REG_THR3_ADDR 0x30 /* serial port3send hold register address */ +#define REG_IER3_ADDR 0x31 /* serial port3interrupt enable register address */ +#define REG_IIR3_ADDR 0x32 /* serial port3interrupt identifies register address */ +#define REG_FCR3_ADDR 0x32 /* serial port3FIFO controls register address */ +#define REG_LCR3_ADDR 0x33 /* serial port3circuit control register address */ +#define REG_MCR3_ADDR 0x34 /* serial port3MODEM controls register address */ +#define REG_LSR3_ADDR 0x35 /* serial port3line status register address */ +#define REG_MSR3_ADDR 0x36 /* serial port3address of MODEM status register */ +#define REG_SCR3_ADDR 0x37 /* serial port3the user can define the register address */ +#define REG_DLL3_ADDR 0x30 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM3_ADDR 0x31 /* Baud rate divisor latch high 8-bit byte address */ + + +/* CH438serial port4 register address */ + +#define REG_RBR4_ADDR 0x08 /* serial port4receive buffer register address */ +#define REG_THR4_ADDR 0x08 /* serial port4send hold register address */ +#define REG_IER4_ADDR 0x09 /* serial port4interrupt enable register address */ +#define REG_IIR4_ADDR 0x0A /* serial port4interrupt identifies register address */ +#define REG_FCR4_ADDR 0x0A /* serial port4FIFO controls register address */ +#define REG_LCR4_ADDR 0x0B /* serial port4circuit control register address */ +#define REG_MCR4_ADDR 0x0C /* serial port4MODEM controls register address */ +#define REG_LSR4_ADDR 0x0D /* serial port4line status register address */ +#define REG_MSR4_ADDR 0x0E /* serial port4address of MODEM status register */ +#define REG_SCR4_ADDR 0x0F /* serial port4the user can define the register address */ +#define REG_DLL4_ADDR 0x08 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM4_ADDR 0x09 /* Baud rate divisor latch high 8-bit byte address */ + + +/* CH438serial port5 register address */ + +#define REG_RBR5_ADDR 0x18 /* serial port5receive buffer register address */ +#define REG_THR5_ADDR 0x18 /* serial port5send hold register address */ +#define REG_IER5_ADDR 0x19 /* serial port5interrupt enable register address */ +#define REG_IIR5_ADDR 0x1A /* serial port5interrupt identifies register address */ +#define REG_FCR5_ADDR 0x1A /* serial port5FIFO controls register address */ +#define REG_LCR5_ADDR 0x1B /* serial port5circuit control register address */ +#define REG_MCR5_ADDR 0x1C /* serial port5MODEM controls register address */ +#define REG_LSR5_ADDR 0x1D /* serial port5line status register address */ +#define REG_MSR5_ADDR 0x1E /* serial port5address of MODEM status register */ +#define REG_SCR5_ADDR 0x1F /* serial port5the user can define the register address */ +#define REG_DLL5_ADDR 0x18 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM5_ADDR 0x19 /* Baud rate divisor latch high 8-bit byte address */ + + +/* CH438serial port6 register address */ + +#define REG_RBR6_ADDR 0x28 /* serial port6receive buffer register address */ +#define REG_THR6_ADDR 0x28 /* serial port6send hold register address */ +#define REG_IER6_ADDR 0x29 /* serial port6interrupt enable register address */ +#define REG_IIR6_ADDR 0x2A /* serial port6interrupt identifies register address */ +#define REG_FCR6_ADDR 0x2A /* serial port6FIFO controls register address */ +#define REG_LCR6_ADDR 0x2B /* serial port6circuit control register address */ +#define REG_MCR6_ADDR 0x2C /* serial port6MODEM controls register address */ +#define REG_LSR6_ADDR 0x2D /* serial port6line status register address */ +#define REG_MSR6_ADDR 0x2E /* serial port6address of MODEM status register */ +#define REG_SCR6_ADDR 0x2F /* serial port6the user can define the register address */ +#define REG_DLL6_ADDR 0x28 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM6_ADDR 0x29 /* Baud rate divisor latch high 8-bit byte address */ + + +/* CH438serial port7 register address */ + +#define REG_RBR7_ADDR 0x38 /* serial port7receive buffer register address */ +#define REG_THR7_ADDR 0x38 /* serial port7send hold register address */ +#define REG_IER7_ADDR 0x39 /* serial port7interrupt enable register address */ +#define REG_IIR7_ADDR 0x3A /* serial port7interrupt identifies register address */ +#define REG_FCR7_ADDR 0x3A /* serial port7FIFO controls register address */ +#define REG_LCR7_ADDR 0x3B /* serial port7circuit control register address */ +#define REG_MCR7_ADDR 0x3C /* serial port7MODEM controls register address */ +#define REG_LSR7_ADDR 0x3D /* serial port7line status register address */ +#define REG_MSR7_ADDR 0x3E /* serial port7address of MODEM status register */ +#define REG_SCR7_ADDR 0x3F /* serial port7the user can define the register address */ +#define REG_DLL7_ADDR 0x38 /* Baud rate divisor latch low 8-bit byte address */ +#define REG_DLM7_ADDR 0x39 /* Baud rate divisor latch high 8-bit byte address */ + + +#define REG_SSR_ADDR 0x4F /* pecial status register address */ + + +/* IER register bit */ + +#define BIT_IER_RESET 0x80 /* The bit is 1 soft reset serial port */ +#define BIT_IER_LOWPOWER 0x40 /* The bit is 1 close serial port internal reference clock */ +#define BIT_IER_SLP 0x20 /* serial port0 is SLP, 1 close clock vibrator */ +#define BIT_IER1_CK2X 0x20 /* serial port1 is CK2X, 1 force the external clock signal after 2 times as internal */ +#define BIT_IER_IEMODEM 0x08 /* The bit is 1 allows MODEM input status to interrupt */ +#define BIT_IER_IELINES 0x04 /* The bit is 1 allow receiving line status to be interrupted */ +#define BIT_IER_IETHRE 0x02 /* The bit is 1 allows the send hold register to break in mid-air */ +#define BIT_IER_IERECV 0x01 /* The bit is 1 allows receiving data interrupts */ + +/* IIR register bit */ + +#define BIT_IIR_FIFOENS1 0x80 +#define BIT_IIR_FIFOENS0 0x40 /* The two is 1 said use FIFO */ + +/* Interrupt type: 0001 has no interrupt, 0110 receiving line status is interrupted, 0100 receiving data can be interrupted, +1100 received data timeout interrupt, 0010THR register air interrupt, 0000MODEM input change interrupt */ +#define BIT_IIR_IID3 0x08 +#define BIT_IIR_IID2 0x04 +#define BIT_IIR_IID1 0x02 +#define BIT_IIR_NOINT 0x01 + +/* FCR register bit */ + +/* Trigger point: 00 corresponds to 1 byte, 01 corresponds to 16 bytes, 10 corresponds to 64 bytes, 11 corresponds to 112 bytes */ +#define BIT_FCR_RECVTG1 0x80 /* Set the trigger point for FIFO interruption and automatic hardware flow control */ +#define BIT_FCR_RECVTG0 0x40 /* Set the trigger point for FIFO interruption and automatic hardware flow control */ + +#define BIT_FCR_TFIFORST 0x04 /* The bit is 1 empty the data sent in FIFO */ +#define BIT_FCR_RFIFORST 0x02 /* The bit is 1 empty the data sent in FIFO */ +#define BIT_FCR_FIFOEN 0x01 /* The bit is 1 use FIFO, 0 disable FIFO */ + +/* LCR register bit */ + +#define BIT_LCR_DLAB 0x80 /* To access DLL, DLM, 0 to access RBR/THR/IER */ +#define BIT_LCR_BREAKEN 0x40 /* 1 forces a BREAK line interval*/ + +/* Set the check format: when PAREN is 1, 00 odd check, 01 even check, 10 MARK (set 1), 11 blank (SPACE, clear 0) */ +#define BIT_LCR_PARMODE1 0x20 /* Sets the parity bit format */ +#define BIT_LCR_PARMODE0 0x10 /* Sets the parity bit format */ + +#define BIT_LCR_PAREN 0x08 /* A value of 1 allows you to generate and receive parity bits when sending */ +#define BIT_LCR_STOPBIT 0x04 /* If is 1, then two stop bits, is 0, a stop bit */ + +/* Set word length: 00 for 5 data bits, 01 for 6 data bits, 10 for 7 data bits and 11 for 8 data bits */ +#define BIT_LCR_WORDSZ1 0x02 /* Set the word length length */ +#define BIT_LCR_WORDSZ0 0x01 + +/* MCR register bit */ + +#define BIT_MCR_AFE 0x20 /* For 1 allows automatic flow control of CTS and RTS hardware */ +#define BIT_MCR_LOOP 0x10 /* Is the test mode of 1 enabling internal loop */ +#define BIT_MCR_OUT2 0x08 /* 1 Allows an interrupt request for the serial port output */ +#define BIT_MCR_OUT1 0x04 /* The MODEM control bit defined for the user */ +#define BIT_MCR_RTS 0x02 /* The bit is 1 RTS pin output effective */ +#define BIT_MCR_DTR 0x01 /* The bit is 1 DTR pin output effective */ + +/* LSR register bit */ + +#define BIT_LSR_RFIFOERR 0x80 /* 1 said There is at least one error in receiving FIFO */ +#define BIT_LSR_TEMT 0x40 /* 1 said THR and TSR are empty */ +#define BIT_LSR_THRE 0x20 /* 1 said THR is empty*/ +#define BIT_LSR_BREAKINT 0x10 /* The bit is 1 said the BREAK line interval was detected*/ +#define BIT_LSR_FRAMEERR 0x08 /* The bit is 1 said error reading data frame */ +#define BIT_LSR_PARERR 0x04 /* The bit is 1 said parity error */ +#define BIT_LSR_OVERR 0x02 /* 1 said receive FIFO buffer overflow */ +#define BIT_LSR_DATARDY 0x01 /* The bit is 1 said receive data received in FIFO */ + +/* MSR register bit */ + +#define BIT_MSR_DCD 0x80 /* The bit is 1 said DCD pin effective */ +#define BIT_MSR_RI 0x40 /* The bit is 1 said RI pin effective */ +#define BIT_MSR_DSR 0x20 /* The bit is 1 said DSR pin effective */ +#define BIT_MSR_CTS 0x10 /* The bit is 1 said CTS pin effective */ +#define BIT_MSR_DDCD 0x08 /* The bit is 1 said DCD pin The input state has changed */ +#define BIT_MSR_TERI 0x04 /* The bit is 1 said RI pin The input state has changed */ +#define BIT_MSR_DDSR 0x02 /* The bit is 1 said DSR pin The input state has changed */ +#define BIT_MSR_DCTS 0x01 /* The bit is 1 said CTS pin The input state has changed */ + +/* Interrupt status code */ + +#define INT_NOINT 0x01 /* There is no interruption */ +#define INT_THR_EMPTY 0x02 /* THR empty interruption */ +#define INT_RCV_OVERTIME 0x0C /* Receive timeout interrupt */ +#define INT_RCV_SUCCESS 0x04 /* Interrupts are available to receive data */ +#define INT_RCV_LINES 0x06 /* Receiving line status interrupted */ +#define INT_MODEM_CHANGE 0x00 /* MODEM input changes interrupt */ + +#define CH438_IIR_FIFOS_ENABLED 0xC0 /* use FIFO */ + +#define Fpclk 1843200 /* Define the internal clock frequency*/ + +/* For Interrupt */ +unsigned char CH438_CheckIIR(uint32_t iiraddr); /* Config serial port1interrupt identifies register function */ +void CH438_INTConfig(uint32_t ieraddr,uint32_t iiraddr,uint32_t mcraddr); /* Serial interrupt enable function */ +void Disable_Interrupt(void); /* Disable EXTI interrupt*/ +void Config_Interrupt(void); /* Config EXTI interrupt*/ + +/* For RT-Thread Config */ +static void Ch438Irq(void *parameter); +static rt_err_t rt_ch438_configure(struct rt_serial_device *serial, struct serial_configure *cfg); +static rt_err_t rt_ch438_control(struct rt_serial_device *serial, int cmd, void *arg); +static int rt_ch438_putc(struct rt_serial_device *serial, char c); +static int rt_ch438_getc(struct rt_serial_device *serial); +int rt_hw_ch438_init(void); + +int semaphoreChInit(void); + +/* Delay */ +void up_udelay(void); +void up_mdelay(uint32_t time); + +void udelay(unsigned long usecs); +/* CH438 Config */ +static void CH438SetOutput(void); +static void CH438SetInput(void); +static uint8_t ReadCH438Data(uint8_t addr); +static void WriteCH438Data(uint8_t addr, const uint8_t dat); +static void WriteCH438Block(uint8_t mAddr, uint8_t mLen, const uint8_t *mBuf); +static void Ch438UartSend(uint8_t ext_uart_no, const uint8_t *Data, uint16_t Num); +uint8_t CH438UARTRcv(uint8_t ext_uart_no, uint8_t *buf, size_t size); +static void ImxrtCH438Init(void); +static void CH438PortInit(uint8_t ext_uart_no, uint32_t baud_rate); +static int ImxrtCh438WriteData(uint8_t ext_uart_no, const uint8_t *write_buffer, size_t size); +static size_t ImxrtCh438ReadData(uint8_t ext_uart_no, size_t size); +static void Ch438InitDefault(void); + +static int getCh438InterruptStatus(void ); +/* CH438 Test Function */ +void CH438Test(void); +void HC08Test(void); +void ZigBeeTest(void); +void CH438Init(void); +#endif \ No newline at end of file diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鍒濆鍖栨垚鍔.PNG b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鍒濆鍖栨垚鍔.PNG new file mode 100644 index 000000000..e7adbfa06 Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鍒濆鍖栨垚鍔.PNG differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鍙戦佹暟鎹垚鍔.PNG b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鍙戦佹暟鎹垚鍔.PNG new file mode 100644 index 000000000..976075d98 Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鍙戦佹暟鎹垚鍔.PNG differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鎴愬姛鎺ユ敹鏁版嵁.PNG b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鎴愬姛鎺ユ敹鏁版嵁.PNG new file mode 100644 index 000000000..0f2d0dd94 Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Bluetooth/浠庢満钃濈墮鎴愬姛鎺ユ敹鏁版嵁.PNG differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/CH438/zigbee base ch438 receive.png b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/CH438/zigbee base ch438 receive.png new file mode 100644 index 000000000..72acb8cc4 Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/CH438/zigbee base ch438 receive.png differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Lora/lora receive.PNG b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Lora/lora receive.PNG new file mode 100644 index 000000000..2650a4ede Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Lora/lora receive.PNG differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Lora/lora send.PNG b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Lora/lora send.PNG new file mode 100644 index 000000000..595a26157 Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-arm32/test_photo/Lora/lora send.PNG differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/.config b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/.config index 829ff9017..e12d40794 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/.config +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/.config @@ -28,7 +28,9 @@ CONFIG_RT_USING_IDLE_HOOK=y CONFIG_RT_IDLE_HOOK_LIST_SIZE=4 CONFIG_IDLE_THREAD_STACK_SIZE=4096 CONFIG_SYSTEM_THREAD_STACK_SIZE=4096 -# CONFIG_RT_USING_TIMER_SOFT is not set +CONFIG_RT_USING_TIMER_SOFT=y +CONFIG_RT_TIMER_THREAD_PRIO=4 +CONFIG_RT_TIMER_THREAD_STACK_SIZE=2048 # # kservice optimization @@ -231,12 +233,23 @@ CONFIG_RT_LIBC_DEFAULT_TIMEZONE=8 # # Socket abstraction layer # -# CONFIG_RT_USING_SAL is not set +CONFIG_RT_USING_SAL=y +CONFIG_SAL_INTERNET_CHECK=y +# CONFIG_SAL_USING_POSIX is not set +CONFIG_SAL_SOCKETS_NUM=16 # # Network interface device # -# CONFIG_RT_USING_NETDEV is not set +CONFIG_RT_USING_NETDEV=y +CONFIG_NETDEV_USING_IFCONFIG=y +CONFIG_NETDEV_USING_PING=y +CONFIG_NETDEV_USING_NETSTAT=y +CONFIG_NETDEV_USING_AUTO_DEFAULT=y +# CONFIG_NETDEV_USING_IPV6 is not set +CONFIG_NETDEV_IPV4=1 +CONFIG_NETDEV_IPV6=0 +# CONFIG_NETDEV_IPV6_SCOPES is not set # # light weight TCP/IP stack @@ -280,25 +293,20 @@ CONFIG_BSP_USING_UART_HS=y # CONFIG_BSP_USING_UART2 is not set # CONFIG_BSP_USING_UART3 is not set # CONFIG_BSP_USING_I2C1 is not set -# CONFIG_BSP_USING_SPI1 is not set +CONFIG_BSP_USING_SPI1=y +CONFIG_BSP_SPI1_CLK_PIN=9 +CONFIG_BSP_SPI1_D0_PIN=11 +CONFIG_BSP_SPI1_D1_PIN=10 +CONFIG_BSP_SPI1_USING_SS0=y +CONFIG_BSP_SPI1_SS0_PIN=12 +# CONFIG_BSP_SPI1_USING_SS1 is not set +# CONFIG_BSP_SPI1_USING_SS2 is not set +# CONFIG_BSP_SPI1_USING_SS3 is not set # # Onboard Peripheral Drivers # -CONFIG_BSP_USING_LCD=y -CONFIG_BSP_LCD_CS_PIN=41 -CONFIG_BSP_LCD_WR_PIN=38 -CONFIG_BSP_LCD_DC_PIN=39 -CONFIG_BSP_LCD_RST_PIN=37 -CONFIG_BSP_LCD_BACKLIGHT_PIN=-1 -CONFIG_BSP_LCD_BACKLIGHT_ACTIVE_LOW=y -# CONFIG_BSP_LCD_BACKLIGHT_ACTIVE_HIGH is not set -CONFIG_BSP_LCD_CLK_FREQ=15000000 -# CONFIG_BSP_BOARD_KD233 is not set -CONFIG_BSP_BOARD_K210_OPENMV_TEST=y -# CONFIG_BSP_BOARD_USER is not set -CONFIG_BSP_LCD_X_MAX=480 -CONFIG_BSP_LCD_Y_MAX=272 +# CONFIG_BSP_USING_LCD is not set # CONFIG_BSP_USING_CH438 is not set # @@ -318,6 +326,23 @@ CONFIG_PKG_KENDRYTE_SDK_VERNUM=0x0055 # CONFIG_DRV_USING_OV2640 is not set # CONFIG_DRV_USING_HS300X is not set # CONFIG_DRV_USING_SX1278 is not set +CONFIG_PKG_USING_WIZNET=y +CONFIG_PKG_WIZNET_PATH="/packages/iot/wiznet" +CONFIG_WIZ_USING_W5500=y +# CONFIG_WIZNET_DEVICE_EXTERN_CONFIG is not set + +# +# WIZnet device configure +# +CONFIG_WIZ_SPI_DEVICE="spi10" +CONFIG_WIZ_RST_PIN=13 +CONFIG_WIZ_IRQ_PIN=14 +CONFIG_WIZ_USING_DHCP=y +CONFIG_WIZ_USING_PING=y +# CONFIG_WIZ_DEBUG is not set +# CONFIG_PKG_USING_WIZNET_V200 is not set +CONFIG_PKG_USING_WIZNET_LATEST_VERSION=y +CONFIG_PKG_WIZNET_VER="latest" # # APP_Framework diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/SConscript b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/SConscript index c583d3016..0c762e3fe 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/SConscript +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/SConscript @@ -1,9 +1,23 @@ from building import * cwd = GetCurrentDir() -src = Glob('*.c') + Glob('*.cpp') +src = [ + 'main.c' +] CPPPATH = [cwd] +## 璁剧疆 lcd_test.c 鐨勪緷璧栧畯 +if GetDepend('BSP_USING_LCD'): + src += ['lcd_test.c'] + +## 璁剧疆 tcp_client.c 鍜 tcp_server.c 鐨勪緷璧栧畯 +if GetDepend('PKG_USING_WIZNET'): + src += ['tcp_client.c'] + src += ['tcp_server.c'] + group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH) Return('group') + + + diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/main.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/main.c index 5b51e4275..cf701b92a 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/main.c +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/main.c @@ -21,11 +21,11 @@ #include #include #include -#define LED_G 12 +//#define LED_G 12 int main(void) { - rt_pin_mode(LED_G, PIN_MODE_OUTPUT); + //rt_pin_mode(LED_G, PIN_MODE_OUTPUT); rt_thread_mdelay(100); char info1[25] ={0}; char info2[25] ={0}; @@ -39,10 +39,10 @@ int main(void) #endif while(1) { - rt_pin_write(LED_G, PIN_HIGH); - rt_thread_mdelay(500); - rt_pin_write(LED_G, PIN_LOW); + //rt_pin_write(LED_G, PIN_HIGH); rt_thread_mdelay(500); + //rt_pin_write(LED_G, PIN_LOW); + //rt_thread_mdelay(500); } return 0; } diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_client.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_client.c new file mode 100644 index 000000000..f5548502d --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_client.c @@ -0,0 +1,144 @@ +/* + * 绋嬪簭娓呭崟锛歵cp 瀹㈡埛绔 + * + * 杩欐槸涓涓 tcp 瀹㈡埛绔殑渚嬬▼ + * 瀵煎嚭 tcpclient 鍛戒护鍒版帶鍒剁粓绔 + * 鍛戒护璋冪敤鏍煎紡锛歵cpclient URL PORT + * URL锛氭湇鍔″櫒鍦板潃 PORT:锛氱鍙e彿 + * 绋嬪簭鍔熻兘锛氭帴鏀跺苟鏄剧ず浠庢湇鍔$鍙戦佽繃鏉ョ殑淇℃伅锛屾帴鏀跺埌寮澶存槸 'q' 鎴 'Q' 鐨勪俊鎭鍑虹▼搴 + * Created by Ybeichen on 2022/7/28. +*/ + +#include "tcp_client.h" +#include +#include /* 浣跨敤BSD socket锛岄渶瑕佸寘鍚玸ocket.h澶存枃浠 */ +#include +#include + +#define BUFSZ 1024 + +static const char send_data[] = "This is TCP Client from RT-Thread."; /* 鍙戦佺敤鍒扮殑鏁版嵁 */ +static void tcp_client(int argc, char **argv) +{ + int ret; + char *recv_data; + struct hostent *host; + int sock, bytes_received; + struct sockaddr_in server_addr; + const char *url; + int port; + + if (argc < 3) + { + rt_kprintf("Usage: tcp_client URL PORT\n"); + rt_kprintf("Like: tcp_client 192.168.12.44 5000\n"); + return ; + } + + url = argv[1]; + port = strtoul(argv[2], 0, 10); + + /* 閫氳繃鍑芥暟鍏ュ彛鍙傛暟url鑾峰緱host鍦板潃锛堝鏋滄槸鍩熷悕锛屼細鍋氬煙鍚嶈В鏋愶級 */ + host = gethostbyname(url); + + /* 鍒嗛厤鐢ㄤ簬瀛樻斁鎺ユ敹鏁版嵁鐨勭紦鍐 */ + recv_data = rt_malloc(BUFSZ); + if (recv_data == RT_NULL) + { + rt_kprintf("No memory\n"); + return; + } + + /* 鍒涘缓涓涓猻ocket锛岀被鍨嬫槸SOCKET_STREAM锛孴CP绫诲瀷 */ + if ((sock = socket(AF_WIZ, SOCK_STREAM, 0)) == -1) + { + /* 鍒涘缓socket澶辫触 */ + rt_kprintf("Socket error\n"); + + /* 閲婃斁宸插垎閰嶇殑鎺ユ敹缂撳啿 */ + rt_free(recv_data); + return; + } + + /* 鍒濆鍖栭杩炴帴鐨勬湇鍔$鍦板潃 */ + server_addr.sin_family = AF_WIZ; + server_addr.sin_port = htons(port); + server_addr.sin_addr = *((struct in_addr *)host->h_addr); + rt_memset(&(server_addr.sin_zero), 0, sizeof(server_addr.sin_zero)); + + /* 杩炴帴鍒版湇鍔$ */ + if (connect(sock, (struct sockaddr *)&server_addr, sizeof(struct sockaddr)) == -1) + { + /* 杩炴帴澶辫触 */ + rt_kprintf("Connect fail!\n"); + closesocket(sock); + + /*閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + return; + } + + while (1) + { + /* 浠巗ock杩炴帴涓帴鏀舵渶澶UFSZ - 1瀛楄妭鏁版嵁 */ + bytes_received = recv(sock, recv_data, BUFSZ - 1, 0); + if (bytes_received < 0) + { + /* 鎺ユ敹澶辫触锛屽叧闂繖涓繛鎺 */ + closesocket(sock); + rt_kprintf("\nreceived error,close the socket.\r\n"); + + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + break; + } + else if (bytes_received == 0) + { + /* 榛樿 recv 涓洪樆濉炴ā寮忥紝姝ゆ椂鏀跺埌0璁や负杩炴帴鍑洪敊锛屽叧闂繖涓繛鎺 */ + closesocket(sock); + rt_kprintf("\nreceived error,close the socket.\r\n"); + + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + break; + } + + /* 鏈夋帴鏀跺埌鏁版嵁锛屾妸鏈娓呴浂 */ + recv_data[bytes_received] = '\0'; + + if (strncmp(recv_data, "q", 1) == 0 || strncmp(recv_data, "Q", 1) == 0) + { + /* 濡傛灉鏄瀛楁瘝鏄痲鎴朡锛屽叧闂繖涓繛鎺 */ + closesocket(sock); + rt_kprintf("\n got a 'q' or 'Q',close the socket.\r\n"); + + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + break; + } + else + { + /* 鍦ㄦ帶鍒剁粓绔樉绀烘敹鍒扮殑鏁版嵁 */ + rt_kprintf("\nReceived data = %s ", recv_data); + } + + /* 鍙戦佹暟鎹埌sock杩炴帴 */ + ret = send(sock, send_data, strlen(send_data), 0); + if (ret < 0) + { + /* 鎺ユ敹澶辫触锛屽叧闂繖涓繛鎺 */ + closesocket(sock); + rt_kprintf("\nsend error,close the socket.\r\n"); + + rt_free(recv_data); + break; + } + else if (ret == 0) + { + /* 鎵撳嵃send鍑芥暟杩斿洖鍊间负0鐨勮鍛婁俊鎭 */ + rt_kprintf("\n Send warning,send function return 0.\r\n"); + } + } + return; +} +MSH_CMD_EXPORT(tcp_client, a tcp client sample); \ No newline at end of file diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_client.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_client.h new file mode 100644 index 000000000..2afa1818a --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_client.h @@ -0,0 +1,11 @@ +// +// Created by Y鍖楄景 on 2022/7/28. +// + +#ifndef RT_THREAD_FUSION_XIUOS_TCP_CLIENT_H +#define RT_THREAD_FUSION_XIUOS_TCP_CLIENT_H + +static void tcpclient(int argc, char **argv); + +#endif //RT_THREAD_FUSION_XIUOS_TCP_CLIENT_H + diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_server.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_server.c new file mode 100644 index 000000000..287881827 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_server.c @@ -0,0 +1,174 @@ +/* +* 绋嬪簭娓呭崟锛歵cp 鏈嶅姟绔 + * + * 杩欐槸涓涓 tcp 鏈嶅姟绔殑渚嬬▼ + * 瀵煎嚭 tcp_server 鍛戒护鍒版帶鍒剁粓绔 + * 鍛戒护璋冪敤鏍煎紡锛歵cp_server + * 鏃犲弬鏁 + * 绋嬪簭鍔熻兘锛氫綔涓轰竴涓湇鍔$锛屾帴鏀跺苟鏄剧ず瀹㈡埛绔彂鏉ョ殑鏁版嵁 锛屾帴鏀跺埌 exit 閫鍑虹▼搴 + * Created by Ybeichen on 2022/7/28. +*/ + +#include "tcp_server.h" +#include +#include /* 浣跨敤BSD socket锛岄渶瑕佸寘鍚玸ocket.h澶存枃浠 */ +#include "netdb.h" +#include +#include + +#define BUFSZ (2048) +static int port = 5000; +static int is_running = 0; /* 鍋滄鏍囧織 */ +static const char send_data[] = "This is TCP Server from RT-Thread."; /* 鍙戦佺敤鍒扮殑鏁版嵁 */ + +static void tcp_server(void *argr) +{ + char *recv_data; /* 鐢ㄤ簬鎺ユ敹鐨勬寚閽堬紝鍚庨潰浼氬仛涓娆″姩鎬佸垎閰嶄互璇锋眰鍙敤鍐呭瓨 */ + socklen_t sin_size; + int sock, connected, bytes_received; + struct sockaddr_in server_addr, client_addr; + int ret; + + recv_data = rt_malloc(BUFSZ + 1); /* 鍒嗛厤鎺ユ敹鐢ㄧ殑鏁版嵁缂撳啿 */ + if (recv_data == RT_NULL) + { + rt_kprintf("No memory\n"); + return; + } + + /* 鍒涘缓涓涓猻ocket锛岀被鍨嬫槸SOCKET_STREAM锛孴CP绫诲瀷 */ + if ((sock = socket(AF_WIZ, SOCK_STREAM, IPPROTO_TCP)) == -1) + { + /* 鍒涘缓socket澶辫触 */ + rt_kprintf("Socket error\n"); + + /* 閲婃斁宸插垎閰嶇殑鎺ユ敹缂撳啿 */ + rt_free(recv_data); + return; + } + + /* 鍒濆鍖栨湰鍦版湇鍔$鍦板潃 */ + server_addr.sin_family = AF_WIZ; + server_addr.sin_port = htons(port); /* 鏈嶅姟绔伐浣滅殑绔彛 */ + server_addr.sin_addr.s_addr = INADDR_ANY; + rt_memset(&(server_addr.sin_zero), 0, sizeof(server_addr.sin_zero)); + + /* 缁戝畾socket鍒版湇鍔$鍦板潃 */ + if (bind(sock, (struct sockaddr *)&server_addr, sizeof(struct sockaddr)) == -1) + { + /* 缁戝畾澶辫触 */ + rt_kprintf("Unable to bind\n"); + + /* 閲婃斁宸插垎閰嶇殑鎺ユ敹缂撳啿 */ + rt_free(recv_data); + return; + } + + /* 鍦╯ocket涓婅繘琛岀洃鍚 */ + if (listen(sock, 5) == -1) + { + rt_kprintf("Listen error\n"); + + /* release recv buffer */ + rt_free(recv_data); + return; + } + + rt_kprintf("\nTCPServer Waiting for client on port %d...\n", port); + + is_running=1; + while (is_running) + { + + /* 鎺ュ彈涓涓鎴风杩炴帴socket鐨勮姹傦紝杩欎釜鍑芥暟璋冪敤鏄樆濉炲紡鐨 */ + connected = accept(sock, (struct sockaddr *)&client_addr, (socklen_t *)sizeof(struct sockaddr_in)); + /* 杩斿洖鐨勬槸杩炴帴鎴愬姛鐨剆ocket */ + if (connected < 0) + { + rt_kprintf("accept connection failed! errno = %d\n", errno); + /* release recv buffer */ + rt_free(recv_data); + continue; + } + + /* 鎺ュ彈杩斿洖鐨刢lient_addr鎸囧悜浜嗗鎴风鐨勫湴鍧淇℃伅 */ + rt_kprintf("I got a connection from (%s , %d)\n", + inet_ntoa(client_addr.sin_addr), ntohs(client_addr.sin_port)); + + /* 瀹㈡埛绔繛鎺ョ殑澶勭悊 */ + while (is_running) + { + /* 鍙戦佹暟鎹埌connected socket */ + ret = send(connected, send_data, strlen(send_data), 0); + if (ret < 0) + { + /* 鍙戦佸け璐ワ紝鍏抽棴杩欎釜杩炴帴 */ + rt_kprintf("\nsend error,close the socket.\r\n"); + closesocket(connected); + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + break; + } + else if (ret == 0) + { + /* 鎵撳嵃send鍑芥暟杩斿洖鍊间负0鐨勮鍛婁俊鎭 */ + rt_kprintf("\n Send warning,send function return 0.\r\n"); + + } + + /* 浠巆onnected socket涓帴鏀舵暟鎹紝鎺ユ敹buffer鏄1024澶у皬锛屼絾骞朵笉涓瀹氳兘澶熸敹鍒1024澶у皬鐨勬暟鎹 */ + bytes_received = recv(connected, recv_data, BUFSZ, 0); + if (bytes_received < 0) + { + /* 鎺ユ敹澶辫触锛屽叧闂繖涓猚onnected socket */ + rt_kprintf("\nReceived error, close the connect.\r\n"); + closesocket(connected); + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + break; + } + else if (bytes_received == 0) + { + /* 鎵撳嵃recv鍑芥暟杩斿洖鍊间负0鐨勮鍛婁俊鎭 */ + rt_kprintf("\nReceived warning,recv function return 0.\r\n"); + closesocket(connected); + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + break; + } + + /* 鏈夋帴鏀跺埌鏁版嵁锛屾妸鏈娓呴浂 */ + recv_data[bytes_received] = '\0'; + if (strncmp(recv_data, "q", 1) == 0 || strncmp(recv_data, "Q", 1) == 0) + { + /* 濡傛灉鏄瀛楁瘝鏄痲鎴朡锛屽叧闂繖涓繛鎺 */ + rt_kprintf("\nGot a 'q' or 'Q', close the connect.\r\n"); + closesocket(connected); + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + break; + } + else if (strcmp(recv_data, "exit") == 0) + { + /* 濡傛灉鎺ユ敹鐨勬槸exit锛屽垯鍏抽棴鏁翠釜鏈嶅姟绔 */ + closesocket(connected); + is_running=0; + break; + } + else + { + /* 鍦ㄦ帶鍒剁粓绔樉绀烘敹鍒扮殑鏁版嵁 */ + rt_kprintf("RECEIVED DATA = %s \n", recv_data); + } + } + } + + /* 閫鍑烘湇鍔 */ + closesocket(sock); + + /* 閲婃斁鎺ユ敹缂撳啿 */ + rt_free(recv_data); + + return; +} +MSH_CMD_EXPORT(tcp_server, a tcp server sample); \ No newline at end of file diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_server.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_server.h new file mode 100644 index 000000000..6b00ba1e3 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/applications/tcp_server.h @@ -0,0 +1,11 @@ +// +// Created by Y鍖楄景 on 2022/7/28. +// + +#ifndef RT_THREAD_FUSION_XIUOS_TCP_SERVER_H +#define RT_THREAD_FUSION_XIUOS_TCP_SERVER_H + +static void tcp_server(void *argr); + +#endif //RT_THREAD_FUSION_XIUOS_TCP_SERVER_H + diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/rtconfig.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/rtconfig.h index f66495531..eee446b17 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/rtconfig.h +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/rtconfig.h @@ -25,6 +25,9 @@ #define RT_IDLE_HOOK_LIST_SIZE 4 #define IDLE_THREAD_STACK_SIZE 4096 #define SYSTEM_THREAD_STACK_SIZE 4096 +#define RT_USING_TIMER_SOFT +#define RT_TIMER_THREAD_PRIO 4 +#define RT_TIMER_THREAD_STACK_SIZE 2048 /* kservice optimization */ @@ -143,9 +146,19 @@ /* Socket abstraction layer */ +#define RT_USING_SAL +#define SAL_INTERNET_CHECK +#define SAL_SOCKETS_NUM 16 /* Network interface device */ +#define RT_USING_NETDEV +#define NETDEV_USING_IFCONFIG +#define NETDEV_USING_PING +#define NETDEV_USING_NETSTAT +#define NETDEV_USING_AUTO_DEFAULT +#define NETDEV_IPV4 1 +#define NETDEV_IPV6 0 /* light weight TCP/IP stack */ @@ -168,20 +181,15 @@ #define __STACKSIZE__ 4096 #define BSP_USING_UART_HS +#define BSP_USING_SPI1 +#define BSP_SPI1_CLK_PIN 9 +#define BSP_SPI1_D0_PIN 11 +#define BSP_SPI1_D1_PIN 10 +#define BSP_SPI1_USING_SS0 +#define BSP_SPI1_SS0_PIN 12 /* Onboard Peripheral Drivers */ -#define BSP_USING_LCD -#define BSP_LCD_CS_PIN 41 -#define BSP_LCD_WR_PIN 38 -#define BSP_LCD_DC_PIN 39 -#define BSP_LCD_RST_PIN 37 -#define BSP_LCD_BACKLIGHT_PIN -1 -#define BSP_LCD_BACKLIGHT_ACTIVE_LOW -#define BSP_LCD_CLK_FREQ 15000000 -#define BSP_BOARD_K210_OPENMV_TEST -#define BSP_LCD_X_MAX 272 -#define BSP_LCD_Y_MAX 480 /* Kendryte SDK Config */ @@ -192,6 +200,17 @@ /* More Drivers */ +#define PKG_USING_WIZNET +#define WIZ_USING_W5500 + +/* WIZnet device configure */ + +#define WIZ_SPI_DEVICE "spi10" +#define WIZ_RST_PIN 13 +#define WIZ_IRQ_PIN 14 +#define WIZ_USING_DHCP +#define WIZ_USING_PING +#define PKG_USING_WIZNET_LATEST_VERSION /* APP_Framework */ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/tcp_client.png b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/tcp_client.png new file mode 100644 index 000000000..4038ac35a Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/tcp_client.png differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/tcp_server.png b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/tcp_server.png new file mode 100644 index 000000000..08eb3436f Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/tcp_server.png differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/w5500.png b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/w5500.png new file mode 100644 index 000000000..dece93598 Binary files /dev/null and b/Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/test/w5500.png differ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/Kconfig b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/Kconfig index 4bae294f6..bd708394c 100644 --- a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/Kconfig +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/Kconfig @@ -4,4 +4,5 @@ source "$RT_Thread_DIR/app_match_rt-thread/rw007/Kconfig" source "$RT_Thread_DIR/app_match_rt-thread/ov2640/Kconfig" source "$RT_Thread_DIR/app_match_rt-thread/hs300x/Kconfig" source "$RT_Thread_DIR/app_match_rt-thread/sx1278/Kconfig" +source "$RT_Thread_DIR/app_match_rt-thread/wiznet/Kconfig" endmenu diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/Kconfig b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/Kconfig new file mode 100644 index 000000000..018e8dace --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/Kconfig @@ -0,0 +1,112 @@ + +# Kconfig file for package wiznet +menuconfig PKG_USING_WIZNET + bool "WIZnet: WIZnet TCP/IP chips SAL framework implement" + default n + select RT_USING_PIN + select RT_USING_SPI + select RT_USING_LIBC if RT_VER_NUM < 0x40100 + select RT_USING_SAL + select RT_USING_TIMER_SOFT + +if PKG_USING_WIZNET + + config PKG_WIZNET_PATH + string + default "/packages/iot/wiznet" + + choice + prompt "WIZnet device type" + default WIZ_USING_W5500 + help + Select the wiznet type + + config WIZ_USING_W5500 + bool "W5500" + + endchoice + + config WIZNET_DEVICE_EXTERN_CONFIG + bool + default n + + if !WIZNET_DEVICE_EXTERN_CONFIG + menu "WIZnet device configure" + + config WIZ_SPI_DEVICE + string "SPI device name" + default "spi10" + + config WIZ_RST_PIN + int "Reset PIN number" + default 10 + + config WIZ_IRQ_PIN + int "IRQ PIN number" + default 11 + endmenu + endif + + config WIZ_USING_DHCP + bool "Enable alloc IP address through DHCP" + default y + + if !WIZ_USING_DHCP + + menu "WIZnet network configure" + + config WIZ_IPADDR + string "IPv4: IP address" + default 192.168.1.10 + + config WIZ_GWADDR + string "IPv4: Gateway address" + default 192.168.1.1 + + config WIZ_MSKADDR + string "IPv4: Mask address" + default 255.255.255.0 + + endmenu + + endif + + config WIZ_USING_PING + bool "Enable Ping utility" + default y + + config WIZ_DEBUG + bool "Enable debug log output" + default n + + choice + prompt "Version" + default PKG_USING_WIZNET_V110 if ((RT_VER_NUM < 0x30103) || (RT_VER_NUM = 0x40000)) + default PKG_USING_WIZNET_LATEST_VERSION + help + Select the wiznet version + + config PKG_USING_WIZNET_V200 + bool "v2.0.0" + + if ((RT_VER_NUM < 0x30103) || (RT_VER_NUM = 0x40000)) + config PKG_USING_WIZNET_V110 + bool "v1.1.0" + + config PKG_USING_WIZNET_V100 + bool "v1.0.0" + endif + + config PKG_USING_WIZNET_LATEST_VERSION + bool "latest" + + endchoice + + config PKG_WIZNET_VER + string + default "v2.0.0" if PKG_USING_WIZNET_V200 + default "v1.1.0" if PKG_USING_WIZNET_V110 + default "v1.0.0" if PKG_USING_WIZNET_V100 + default "latest" if PKG_USING_WIZNET_LATEST_VERSION + +endif diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/LICENSE b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/LICENSE new file mode 100644 index 000000000..261eeb9e9 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/README.md b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/README.md new file mode 100644 index 000000000..ff5bf80f7 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/README.md @@ -0,0 +1,164 @@ +# WIZnet + +[涓枃椤礭(README_ZH.md) | English + +## 1. Introduction + +The WIZnet software package is a porting implementation of RT-Thread based on the WIZnet official website [ioLibrary_Driver](https://github.com/Wiznet/ioLibrary_Driver) code base, and currently only supports W5500 devices. On the basis of the original code library function, this software package docks with the RT-Thread SAL socket abstraction layer, realizes the support for standard BSD Socket APIs, is perfectly compatible with a variety of software packages and network functions, and improves the compatibility of WIZnet devices. + +### 1.1 Directory structure + +The WIZnet software package directory structure is as follows: + +``` +wiznet +鈹溾攢鈹鈹inc // RT_Thread transplant header file +鈹溾攢鈹鈹iolibrary // WIZnet official library file +鈹 鈹斺攢鈹鈹Ethernet // WIZnet official Socket APIs and WIZCHIP driver +鈹 鈹 鈹斺攢鈹鈹W5500 // WIZCHIP driver +鈹 鈹 wizchip_conf.c // Socket configuration file +鈹 鈹 wizchip_socket.c // Socket APIs file +鈹 鈹斺攢鈹鈹Internet // WIZnet official network function realization +鈹 鈹 鈹斺攢鈹鈹DHCP // DHCP function implementation +鈹 鈹斺攢鈹鈹鈹鈹鈹鈹DNS // DNS function realization +鈹溾攢鈹鈹src // RT_Thread transplant source code file +鈹 鈹斺攢鈹鈹wiz_af_inet.c // WIZnet BSD Socket registered to SAL +鈹 鈹 wiz_device.c // WIZnet device initialization +鈹 鈹 wiz_ping.c // WIZnet device Ping command realization +鈹 鈹 wiz_socket.c // WIZnet BSD Socket APIs implementation +鈹 鈹斺攢鈹鈹wiz.c // WIZnet initialization (device initialization, network initialization) +鈹 LICENSE // package license +鈹 README.md // Software package instructions +鈹斺攢鈹鈹SConscript // RT-Thread default build script +``` + + +### 1.2 License + +The WIZnet software package complies with the Apache-2.0 license, see the LICENSE file for details. + +### 1.3 Dependency + +- RT-Thread 4.0.1+ +- SAL component +- netdev component +- SPI driver: WIZnet devices use SPI for data communication, which requires the support of the system SPI driver framework; +- PIN driver: used to handle device reset and interrupt pins; + +## 2. Get the software package + +To use the WIZnet software package, you need to select it in the RT-Thread package management. The specific path is as follows: + +```shell +WIZnet: WIZnet TCP/IP chips SAL framework implement + WIZnet device type (W5500) ---> + WIZnet device configure ---> + (spi30) SPI device name + (10) Reset PIN number + (11) IRQ PIN number + [] Enable alloc IP address through DHCP + WIZnet network configure ---> + (192.168.1.10) IPv4: IP address + (192.168.1.1) IPv4: Gateway address + (255.255.255.0) IPv4: Mask address + [] Enable Ping utility + [] Enable debug log output + Version (latest) ---> +``` + +**WIZnet device type**: Configure the supported device type (currently only supports W5500 devices) + +**WIZnet device configure**: configure the parameters of the device used + +- **SPI device name**: Configure the name of the device using SPI (note that it needs to be set to **non-SPI bus device**) + +- **Reset PIN number**: Configure the reset pin number connected to the device (modified according to the actual pin number used) + +- **IRQ PIN number**: Configure the interrupt pin number of the device connection (same as above) + +**Enable alloc IP address through DHCP**: Configure whether to use DHCP to allocate IP addresses (enabled by default) + +**WIZnet network configure**: If you do not enable the DHCP function, you need to configure the statically connected IP address, gateway and subnet mask + +**Enable Ping utility**: Configure to enable Ping command (enabled by default) + +**Enable debug log output**: Configure to enable debug log display + +**Version**: software package version selection + +## 3. Use the software package + +The initialization function of WIZnet software package is as follows: + +```c +int wiz_init(void); +``` + +This function supports component initialization. If the automatic component initialization function is enabled, the application layer does not need to call this function. The main functions of the function are: + +- Set the default MAC address; +- Device configuration and initialization (configure SPI device, configure reset and interrupt pins); +- Network configuration and initialization (DHCP allocation of IP address, configuration of socket parameters); +- Register the implemented BSD Socket APIs to the SAL socket abstraction layer to complete WIZnet device adaptation; + +Each WIZnet device needs a unique MAC address. The user can call the following function in the application layer program to set the MAC address of the WIZnet device. If this function is not called, the device will use the default MAC address. The default MAC address is `00-E0-81 -DC-53-1A` (Note: If there are devices with the same MAC address in the same LAN, it may cause the device network to be abnormal). + +```c +int wiz_set_mac(const char *mac); +``` + +After the device is powered on and initialized, the device's MAC address is successfully set, and then you can enter the command `wiz_ifconfig` in FinSH to view the device's IP address, MAC address and other network information, as shown below: + +```shell +msh />ifconfig +network interface device: W5500 (Default) ## Device name +MTU: 1472 ## Network maximum transmission unit +MAC: 00 e0 81 dc 53 1a ## Device MAC address +FLAGS: UP LINK_UP INTERNET_UP ## Device flag +ip address: 192.168.12.26 ## Device IP address +gw address: 192.168.10.1 ## Device gateway address +net mask: 255.255.0.0 ## Device subnet mask +dns server #0: 192.168.10.1 ## DNS server address 0 +dns server #1: 0.0.0.0 ## DNS server address 1 +``` + +After obtaining the IP address successfully, if the Ping command function is enabled, you can enter the command `ping + domain name address` in FinSH to test the network connection status, as shown below: + +```shell +msh />wiz_ping baidu.com +32 bytes from 220.181.57.216 icmp_seq=0 ttl=128 time=31 ticks +32 bytes from 220.181.57.216 icmp_seq=1 ttl=128 time=31 ticks +32 bytes from 220.181.57.216 icmp_seq=2 ttl=128 time=32 ticks +32 bytes from 220.181.57.216 icmp_seq=3 ttl=128 time=32 ticks +``` + +The normal test of the `ping` command indicates that the WIZnet device is successfully connected to the network, and then you can use the standard BSD Socket APIs abstracted by SAL (Socket Abstraction Layer) for network development (MQTT, HTTP, MbedTLS, NTP, Iperf, etc.), WIZnet software package The supported protocol cluster types are: the primary protocol cluster is **AF_WIZ**, and the secondary protocol cluster is **AF_INET** (for specific differences and usage, please refer to [SAL Programming Guide](https://www.rt-thread.org/document/site/submodules/rtthread-manual-doc/zh/1chapters/13-chapter_sal/) ). + +## 4. Common problems + +- Assertion problem during SPI device initialization + + ```shell + (wiz_device->parent.type == RT_Device_Class_SPIDevice) assertion failed at function:wiz_spi_init, line number:126 + ``` + + The above assertion problem occurs. The possible reason is that the name of the SPI device used by WIZnet in ENV is incorrectly filled. Please distinguish the relationship between SPI DEVICE and SPI BUS. If there is no SPI device or only SPI bus device in the BSP project, you need to manually mount the SPI device to the SPI bus in the driver and correctly configure the SPI device name used in the WIZnet software package. + +- The latest version of WIZnet software package has been supported as a server server mode (not supported before V1.1.0). + +- WIZNet software package initialization error ```[E/wiz.dev] You should attach [wiznet] into SPI bus firstly.``` error is caused by not mounting the winzet device to the SPI bus; please refer to the wiz_init function Note to solve the problem of package initialization failure. + +- When using the previous code in the RT-Thread repository, please compare ```[components/net/sal_socket/src/sal_socket.c]```, especially about the content of [PR](https://github.com/RT-Thread/rt-thread/pull/3534/files), pay attention to the content of sal_closesocket . When you always fail to apply for socket(-1), please make sure that the RT-Thread code you are using is the same as the [PR](https://github.com/RT-Thread/rt-thread/pull/3534 /files). + +- When applying for a socket, the error is ```0x22```. Note that the development branch of wiznet is in the master version or a version greater than V1.1.0. Please pay attention to the execution order of ```wiz_socket_init()```, because the ```sal_check_netdev_internet_up``` networking detection function will actively apply for a socket to determine whether the w5500 has network capabilities, and network status changes will cause ```sal_check_netdev_internet_up``` was called, causing ```0x22``` error. + + +## 5. Matters needing attention + +- When obtaining the software package, you need to pay attention to the correct configuration of the SPI device name, reset pin number and interrupt pin number used; +- After the initialization is complete, it is recommended to use the `wiz_set_mac()` function to set the device MAC address to prevent conflicts with the default MAC address; + +## 6. Contact & Thanks + +- Maintenance: RT-Thread development team +- Homepage: https://github.com/RT-Thread-packages/wiznet diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/README_ZH.md b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/README_ZH.md new file mode 100644 index 000000000..de52d88a6 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/README_ZH.md @@ -0,0 +1,167 @@ +# WIZnet + +涓枃椤 | [English](README.md) + +## 1銆佷粙缁 + +WIZnet 杞欢鍖呮槸 RT-Thread 鍩轰簬 WIZnet 瀹樼綉 [ioLibrary_Driver](https://github.com/Wiznet/ioLibrary_Driver) 浠g爜搴撶殑绉绘瀹炵幇锛岀洰鍓嶅彧鏀寔 W5500 璁惧銆傝杞欢鍖呭湪鍘熶唬鐮佸簱鍔熻兘鐨勫熀纭涓婏紝瀵规帴 RT-Thread SAL 濂楁帴瀛楁娊璞″眰锛屽疄鐜板鏍囧噯 BSD Socket APIs 鐨勬敮鎸侊紝瀹岀編鐨勫吋瀹瑰绉嶈蒋浠跺寘鍜岀綉缁滃姛鑳藉疄鐜帮紝鎻愰珮 WIZnet 璁惧鍏煎鎬с + +### 1.1 鐩綍缁撴瀯 + +WIZnet 杞欢鍖呯洰褰曠粨鏋勫涓嬫墍绀猴細 + +``` +wiznet +鈹溾攢鈹鈹inc // RT_Thread 绉绘澶存枃浠 +鈹溾攢鈹鈹iolibrary // WIZnet 瀹樻柟搴撴枃浠 +鈹 鈹斺攢鈹鈹Ethernet // WIZnet 瀹樻柟 Socket APIs 鍜 WIZCHIP 椹卞姩 +鈹 鈹 鈹斺攢鈹鈹W5500 // WIZCHIP 椹卞姩 +鈹 鈹 wizchip_conf.c // Socket 閰嶇疆鏂囦欢 +鈹 鈹 wizchip_socket.c // Socket APIs 鏂囦欢 +鈹 鈹斺攢鈹鈹Internet // WIZnet 瀹樻柟缃戠粶鍔熻兘瀹炵幇 +鈹 鈹 鈹斺攢鈹鈹DHCP // DHCP 鍔熻兘瀹炵幇 +鈹 鈹斺攢鈹鈹鈹鈹鈹鈹DNS // DNS 鍔熻兘瀹炵幇 +鈹溾攢鈹鈹src // RT_Thread 绉绘婧愮爜鏂囦欢 +鈹 鈹斺攢鈹鈹wiz_af_inet.c // WIZnet BSD Socket 娉ㄥ唽鍒 SAL +鈹 鈹 wiz_device.c // WIZnet 璁惧鍒濆鍖 +鈹 鈹 wiz_ping.c // WIZnet 璁惧 Ping 鍛戒护瀹炵幇 +鈹 鈹 wiz_socket.c // WIZnet BSD Socket APIs 瀹炵幇 +鈹 鈹斺攢鈹鈹wiz.c // WIZnet 鍒濆鍖栵紙璁惧鍒濆鍖栥佺綉缁滃垵濮嬪寲锛 +鈹 LICENSE // 杞欢鍖呰鍙瘉 +鈹 README.md // 杞欢鍖呬娇鐢ㄨ鏄 +鈹斺攢鈹鈹SConscript // RT-Thread 榛樿鐨勬瀯寤鸿剼鏈 +``` + + +### 1.2 璁稿彲璇 + +WIZnet 杞欢鍖呴伒寰 Apache-2.0 璁稿彲锛岃瑙 LICENSE 鏂囦欢銆 + +### 1.3 渚濊禆 + +- RT-Thread 4.0.1+ +- SAL 缁勪欢 +- netdev 缁勪欢 +- SPI 椹卞姩锛歐IZnet 璁惧浣跨敤 SPI 杩涜鏁版嵁閫氳锛岄渶瑕佺郴缁 SPI 椹卞姩妗嗘灦鏀寔锛 +- PIN 椹卞姩锛氱敤浜庡鐞嗚澶囧浣嶅拰涓柇寮曡剼锛 + +## 2銆佽幏鍙栬蒋浠跺寘 + +浣跨敤 WIZnet 杞欢鍖呴渶瑕佸湪 RT-Thread 鐨勫寘绠$悊涓変腑瀹冿紝鍏蜂綋璺緞濡備笅锛 + +```shell +WIZnet: WIZnet TCP/IP chips SAL framework implement + WIZnet device type (W5500) ---> + WIZnet device configure ---> + (spi30) SPI device name + (10) Reset PIN number + (11) IRQ PIN number + [ ] Enable alloc IP address through DHCP + WIZnet network configure ---> + (192.168.1.10) IPv4: IP address + (192.168.1.1) IPv4: Gateway address + (255.255.255.0) IPv4: Mask address + [ ] Enable Ping utility + [ ] Enable debug log output + Version (latest) ---> +``` + +**WIZnet device type** 锛氶厤缃敮鎸佺殑璁惧绫诲瀷锛堢洰鍓嶅彧鏀寔 W5500 璁惧 锛 + +**WIZnet device configure** 锛氶厤缃娇鐢ㄨ澶囩殑鍙傛暟 + +- **SPI device name**锛氶厤缃娇鐢 SPI 鐨勮澶囧悕绉帮紙娉ㄦ剰闇璁剧疆涓**闈 SPI 鎬荤嚎璁惧**锛 + +- **Reset PIN number**锛氶厤缃澶囪繛鎺ョ殑澶嶄綅寮曡剼鍙凤紙鏍规嵁瀹為檯浣跨敤寮曡剼鍙蜂慨鏀癸級 + +- **IRQ PIN number**锛氶厤缃澶囪繛鎺ョ殑涓柇寮曡剼鍙凤紙鍚屼笂锛 + +**Enable alloc IP address through DHCP**锛 閰嶇疆鏄惁浣跨敤 DHCP 鍒嗛厤 IP 鍦板潃锛堥粯璁ゅ紑鍚級 + +**WIZnet network configure**锛氬鏋滀笉寮鍚 DHCP 鍔熻兘锛岄渶瑕侀厤缃潤鎬佽繛鎺ョ殑 IP 鍦板潃銆佺綉鍏冲拰瀛愮綉鎺╃爜 + +**Enable Ping utility**锛 閰嶇疆寮鍚 Ping 鍛戒护 锛堥粯璁ゅ紑鍚級 + +**Enable debug log output**锛氶厤缃紑鍚皟璇曟棩蹇楁樉绀 + +**Version**锛氳蒋浠跺寘鐗堟湰閫夋嫨 + +## 3銆佷娇鐢ㄨ蒋浠跺寘 + +WIZnet 杞欢鍖呭垵濮嬪寲鍑芥暟濡備笅鎵绀猴細 + +```c +int wiz_init锛坴oid锛夛紱 +``` + +璇ュ嚱鏁版敮鎸佺粍浠跺垵濮嬪寲锛屽鏋滃紑鍚粍浠惰嚜鍔ㄥ垵濮嬪寲鍔熻兘锛屽垯搴旂敤灞傛棤闇鍦ㄨ皟鐢ㄨ鍑芥暟 锛屽嚱鏁颁富瑕佸畬鎴愬姛鑳芥湁锛 + +- 璁剧疆榛樿 MAC 鍦板潃锛 + +- 璁惧閰嶇疆鍜屽垵濮嬪寲锛堥厤缃 SPI 璁惧锛岄厤缃浣嶅拰涓柇寮曡剼锛夛紱 + +- 缃戠粶閰嶇疆鍜屽垵濮嬪寲锛圖HCP 鍒嗛厤 IP 鍦板潃锛岄厤缃 socket 鍙傛暟 锛夛紱 + +- 娉ㄥ唽瀹炵幇鐨 BSD Socket APIs 鍒 SAL 濂楁帴瀛楁娊璞″眰涓紝瀹屾垚 WIZnet 璁惧閫傞厤锛 + +姣忎釜 WIZnet 璁惧闇瑕佸敮涓鐨 MAC 鍦板潃锛岀敤鎴峰彲浠ュ湪搴旂敤灞傜▼搴忎腑璋冪敤濡備笅鍑芥暟璁剧疆 WIZnet 璁惧 MAC 鍦板潃锛屽鏋滀笉璋冪敤璇ュ嚱鏁帮紝璁惧灏嗕娇鐢ㄩ粯璁ょ殑 MAC 鍦板潃锛岄粯璁 MAC 鍦板潃涓 `00-E0-81-DC-53-1A`锛堟敞鎰忥細鍚屼竴涓眬鍩熺綉涓鏋滃瓨鍦ㄧ浉鍚 MAC 鍦板潃鐨勮澶囷紝鍙兘瀵艰嚧璁惧缃戠粶寮傚父锛 銆 + +```c +int wiz_set_mac(const char *mac); +``` + +璁惧涓婄數鍒濆鍖栧畬鎴愶紝璁剧疆璁惧 MAC 鍦板潃鎴愬姛锛岀劧鍚庡彲浠ュ湪 FinSH 涓緭鍏ュ懡浠 `wiz_ifconfig` 鏌ョ湅璁惧 IP 鍦板潃銆丮AC 鍦板潃绛夌綉缁滀俊鎭紝濡備笅鎵绀猴細 + +```shell +msh />ifconfig +network interface device: W5500 (Default) ## 璁惧鍚嶇О +MTU: 1472 ## 缃戠粶鏈澶т紶杈撳崟鍏 +MAC: 00 e0 81 dc 53 1a ## 璁惧 MAC 鍦板潃 +FLAGS: UP LINK_UP INTERNET_UP ## 璁惧鏍囧織 +ip address: 192.168.12.26 ## 璁惧 IP 鍦板潃 +gw address: 192.168.10.1 ## 璁惧缃戝叧鍦板潃 +net mask : 255.255.0.0 ## 璁惧瀛愮綉鎺╃爜 +dns server #0: 192.168.10.1 ## 鍩熷悕瑙f瀽鏈嶅姟鍣ㄥ湴鍧0 +dns server #1: 0.0.0.0 ## 鍩熷悕瑙f瀽鏈嶅姟鍣ㄥ湴鍧1 +``` + +鑾峰彇 IP 鍦板潃鎴愬姛涔嬪悗锛屽鏋滃紑鍚 Ping 鍛戒护鍔熻兘锛屽彲浠ュ湪 FinSH 涓緭鍏ュ懡浠 `ping + 鍩熷悕鍦板潃` 娴嬭瘯缃戠粶杩炴帴鐘舵侊紝 濡備笅鎵绀猴細 + +```shell +msh />wiz_ping baidu.com +32 bytes from 220.181.57.216 icmp_seq=0 ttl=128 time=31 ticks +32 bytes from 220.181.57.216 icmp_seq=1 ttl=128 time=31 ticks +32 bytes from 220.181.57.216 icmp_seq=2 ttl=128 time=32 ticks +32 bytes from 220.181.57.216 icmp_seq=3 ttl=128 time=32 ticks +``` + +`ping` 鍛戒护娴嬭瘯姝e父璇存槑 WIZnet 璁惧缃戠粶杩炴帴鎴愬姛锛屼箣鍚庡彲浠ヤ娇鐢 SAL锛堝鎺ュ瓧鎶借薄灞傦級 鎶借薄鍑烘潵鐨勬爣鍑 BSD Socket APIs 杩涜缃戠粶寮鍙戯紙MQTT銆丠TTP銆丮bedTLS銆丯TP銆両perf 绛夛級锛學IZnet 杞欢鍖呮敮鎸佺殑鍗忚绨囩被鍨嬩负锛氫富鍗忚绨囦负 **AF_WIZ**銆佹鍗忚绨囦负 **AF_INET**锛堝叿浣撳尯鍒拰浣跨敤鏂瑰紡鍙煡鐪 [SAL 缂栫▼鎸囧崡](https://www.rt-thread.org/document/site/submodules/rtthread-manual-doc/zh/1chapters/13-chapter_sal/) 锛夈 + +## 4銆佸父瑙侀棶棰 + +- SPI 璁惧鍒濆鍖栨椂鏂█闂 + + ```shell + (wiz_device->parent.type == RT_Device_Class_SPIDevice) assertion failed at function:wiz_spi_init, line number:126 + ``` + + 鍑虹幇涓婅堪鏂█闂锛屽彲鑳藉師鍥犳槸 ENV 涓厤缃 WIZnet 浣跨敤鐨 SPI 璁惧鍚嶇О濉啓涓嶆纭紝璇峰尯鍒 SPI DEVICE 涓 SPI BUS 鐨勫叧绯汇傚鏋 BSP 宸ョ▼涓病鏈 SPI 璁惧鎴栬呭彧鏈 SPI 鎬荤嚎璁惧锛岄渶瑕佹墜鍔ㄥ湪椹卞姩涓寕杞 SPI 璁惧鍒 SPI 鎬荤嚎锛屽苟姝g‘閰嶇疆 WIZnet 杞欢鍖呬腑浣跨敤鐨 SPI 璁惧鍚嶇О銆 + +- WIZnet 杞欢鍖呮渶鏂扮増鏈凡鏀寔浣滀负 server 鏈嶅姟鍣ㄦā寮忥紙V1.1.0 鐗堟湰涔嬪墠涓嶆敮鎸侊級銆 + +- WIZNet 杞欢鍖呭垵濮嬪寲鍑虹幇 ```[E/wiz.dev] You should attach [wiznet] into SPI bus firstly.```閿欒锛屾槸鍥犱负娌℃湁鎸傝浇 winzet 璁惧鍒 SPI 鎬荤嚎瀵艰嚧鐨勶紱璇峰弬鑰 wiz_init 鍑芥暟涓殑娉ㄩ噴锛岃В鍐宠蒋浠跺寘鍒濆鍖栧け璐ョ殑闂銆 + +- 鍦ㄤ娇鐢 RT-Thread 浠撳簱鐨勬棦寰浠g爜鏃讹紝璇锋瘮瀵 ```[components/net/sal_socket/src/sal_socket.c]```鐨勫唴瀹癸紝灏ゅ叾鏄叧浜庢澶 [PR](https://github.com/RT-Thread/rt-thread/pull/3534/files) 鐨勫唴瀹癸紝娉ㄦ剰 sal_closesocket 鐨勫唴瀹广傚綋浣犳绘槸鐢宠 socket(-1) 澶辫触鏃讹紝璇风‘淇濅綘鎵浣跨敤鐨 RT-Thread 鐨勪唬鐮佹槸涓庤 [PR](https://github.com/RT-Thread/rt-thread/pull/3534/files) 鐨勬剰鍥剧浉绗﹀悎鐨勩 + +- 褰撳嚭鐜扮敵璇 socket 鏃堕敊璇负 ```0x22``` 閿欒锛屾敞鎰 wiznet 鐨勫紑鍙戝垎鏀浜 master 鐗堟湰鎴栬呭ぇ浜 V1.1.0 鐨勭増鏈傝鐣欐剰 ```wiz_socket_init()``` 鐨勬墽琛岄『搴忥紝鍥犱负 ```sal_check_netdev_internet_up``` 鑱旂綉妫娴嬪嚱鏁帮紝浼氫富鍔ㄧ敵璇 socket 浠ュ垽鏂 w5500 鏄惁鍏锋湁缃戠粶鑳藉姏锛岃岀綉缁滅姸鎬佸彉鏇翠細瀵艰嚧 ```sal_check_netdev_internet_up``` 琚皟鐢紝閫犳垚 ```0x22``` 閿欒銆 + + +## 5銆佹敞鎰忎簨椤 + +- 鑾峰彇杞欢鍖呮椂锛岄渶瑕佹敞鎰忔纭厤缃娇鐢ㄧ殑 SPI 璁惧鍚嶇О銆佸浣嶅紩鑴氬彿鍜屼腑鏂紩鑴氬彿锛 +- 鍒濆鍖栧畬鎴愪箣鍚庯紝寤鸿浣跨敤 `wiz_set_mac()` 鍑芥暟璁剧疆璁惧 MAC 鍦板潃锛岄槻姝娇鐢ㄩ粯璁 MAC 鍦板潃浜х敓鍐茬獊锛 + +## 6銆佽仈绯绘柟寮 & 鎰熻阿 + +- 缁存姢锛歊T-Thread 寮鍙戝洟闃 +- 涓婚〉锛歨ttps://github.com/RT-Thread-packages/wiznet diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/SConscript b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/SConscript new file mode 100644 index 000000000..ebcfeef47 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/SConscript @@ -0,0 +1,34 @@ +from building import * + +cwd = GetCurrentDir() + +src = Split(''' +src/wiz_af_inet.c +src/wiz_device.c +src/wiz_socket.c +src/wiz.c +''') + +if GetDepend(['WIZ_USING_PING']): + src += Glob('src/wiz_ping.c') + +src += Glob('ioLibrary/Ethernet/*.c') +src += Glob('ioLibrary/Internet/DNS/*.c') + +if GetDepend(['WIZ_USING_DHCP']): + src += Glob('ioLibrary/Internet/DHCP/*.c') + +if GetDepend(['WIZ_USING_W5500']): + src += Glob('ioLibrary/Ethernet/W5500/*.c') + +CPPPATH = [ +cwd + '/inc', +cwd + '/ioLibrary', +cwd + '/ioLibrary/Ethernet', +cwd + '/ioLibrary/Ethernet/W5500', +cwd + '/ioLibrary/Internet', +] + +group = DefineGroup('WIZnet', src, depend = ['PKG_USING_WIZNET'], CPPPATH = CPPPATH) + +Return('group') diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/inc/wiz.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/inc/wiz.h new file mode 100644 index 000000000..5c4e4bc63 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/inc/wiz.h @@ -0,0 +1,40 @@ +/* + * Copyright (c) 2006-2022, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2018-09-26 chenyong first version + */ + +#ifndef __WIZ_H__ +#define __WIZ_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#define WIZ_SW_VERSION "2.1.0" +#define WIZ_SW_VERSION_NUM 0x020100 + +#ifndef WIZ_SOCKETS_NUM +#define WIZ_SOCKETS_NUM 8 +#endif + +#ifndef WIZ_RX_MBOX_NUM +#define WIZ_RX_MBOX_NUM 10 +#endif + +/* WIZnet set chip MAC address */ +void wiz_user_config_mac(char *mac_buf, rt_uint8_t buf_len); +/* WIZnet initialize device and network */ +int wiz_init(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __WIZ_H__ */ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/inc/wiz_socket.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/inc/wiz_socket.h new file mode 100644 index 000000000..4886be0ec --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/inc/wiz_socket.h @@ -0,0 +1,116 @@ +/* + * Copyright (c) 2006-2022, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2018-09-26 chenyong first version + */ + +#ifndef __WIZ_SOCKET_H__ +#define __WIZ_SOCKET_H__ + +#include +#include +#include + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* WIZnet socket magic word */ +#define WIZ_SOCKET_MAGIC 0x3120 + +/* WIZnet Socket address family */ +#ifndef AF_WIZ +#define AF_WIZ 46 +#endif + +struct wiz_socket; +/* A callback prototype to inform about events for wiznet socket */ +typedef void (* wiz_socket_callback)(struct wiz_socket *conn, int event, uint16_t len); + +struct wiz_clnt_info +{ + int socket; + int state; + rt_slist_t list; +}; + +struct wiz_svr_info +{ + int backlog; + rt_timer_t conn_tmr; + rt_mailbox_t conn_mbox; + rt_slist_t clnt_list; +}; + +struct wiz_socket +{ + /* WIZnet socket magic word */ + uint32_t magic; + + int socket; + uint16_t port; + /* type of the WIZnet socket (TCP, UDP or RAW) */ + uint8_t type; + /* current state of the WIZnet socket */ + uint8_t state; + /* receive semaphore, received data release semaphore */ + rt_sem_t recv_notice; + rt_mutex_t recv_lock; + + /* timeout to wait for send or receive data in milliseconds */ + int32_t recv_timeout; + int32_t send_timeout; + + /* A callback function that is informed about events for this AT socket */ + wiz_socket_callback callback; + + struct sockaddr *remote_addr; + /* number of times data was received, set by event_callback() */ + uint16_t rcvevent; + /* number of times data was ACKed (free send buffer), set by event_callback() */ + uint16_t sendevent; + /* error happened for this socket, set by event_callback() */ + uint16_t errevent; + + /* server socket information */ + struct wiz_svr_info *svr_info; + +#ifdef SAL_USING_POSIX + rt_wqueue_t wait_head; +#endif +}; + +int wiz_socket(int domain, int type, int protocol); +int wiz_closesocket(int socket); +int wiz_shutdown(int socket, int how); +int wiz_listen(int socket, int backlog); +int wiz_bind(int socket, const struct sockaddr *name, socklen_t namelen); +int wiz_connect(int socket, const struct sockaddr *name, socklen_t namelen); +int wiz_accept(int socket, struct sockaddr *addr, socklen_t *addrlen); +int wiz_sendto(int socket, const void *dwiza, size_t size, int flags, const struct sockaddr *to, socklen_t tolen); +int wiz_send(int socket, const void *dwiza, size_t size, int flags); +int wiz_recvfrom(int socket, void *mem, size_t len, int flags, struct sockaddr *from, socklen_t *fromlen); +int wiz_recv(int socket, void *mem, size_t len, int flags); +int wiz_getsockopt(int socket, int level, int optname, void *optval, socklen_t *optlen); +int wiz_setsockopt(int socket, int level, int optname, const void *optval, socklen_t optlen); +struct hostent *wiz_gethostbyname(const char *name); +int wiz_getaddrinfo(const char *nodename, const char *servname, const struct addrinfo *hints, struct addrinfo **res); +void wiz_freeaddrinfo(struct addrinfo *ai); + +/* get WIZnet socket object */ +struct wiz_socket *wiz_get_socket(int socket); +/* WIZnet chip TCP/IP protocol register */ +int wiz_inet_init(void); + +#ifdef __cplusplus + } +#endif + +#endif /* __WIZ_SOCKET_H__ */ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/W5500/w5500.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/W5500/w5500.c new file mode 100644 index 000000000..68d4cb8be --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/W5500/w5500.c @@ -0,0 +1,267 @@ +//***************************************************************************** +// +//! \file w5500.c +//! \brief W5500 HAL Interface. +//! \version 1.0.2 +//! \date 2013/10/21 +//! \par Revision history +//! <2015/02/05> Notice +//! The version history is not updated after this point. +//! Download the latest version directly from GitHub. Please visit the our GitHub repository for ioLibrary. +//! >> https://github.com/Wiznet/ioLibrary_Driver +//! <2014/05/01> V1.0.2 +//! 1. Implicit type casting -> Explicit type casting. Refer to M20140501 +//! Fixed the problem on porting into under 32bit MCU +//! Issued by Mathias ClauBen, wizwiki forum ID Think01 and bobh +//! Thank for your interesting and serious advices. +//! <2013/12/20> V1.0.1 +//! 1. Remove warning +//! 2. WIZCHIP_READ_BUF WIZCHIP_WRITE_BUF in case _WIZCHIP_IO_MODE_SPI_FDM_ +//! for loop optimized(removed). refer to M20131220 +//! <2013/10/21> 1st Release +//! \author MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** +//#include +#include "w5500.h" + +#define _W5500_SPI_VDM_OP_ 0x00 +#define _W5500_SPI_FDM_OP_LEN1_ 0x01 +#define _W5500_SPI_FDM_OP_LEN2_ 0x02 +#define _W5500_SPI_FDM_OP_LEN4_ 0x03 + +#if (_WIZCHIP_ == 5500) +//////////////////////////////////////////////////// + +uint8_t WIZCHIP_READ(uint32_t AddrSel) +{ + uint8_t ret; + uint8_t spi_data[3]; + + WIZCHIP_CRITICAL_ENTER(); + WIZCHIP.CS._select(); + + AddrSel |= (_W5500_SPI_READ_ | _W5500_SPI_VDM_OP_); + + if(!WIZCHIP.IF.SPI._read_burst || !WIZCHIP.IF.SPI._write_burst) // byte operation + { + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x00FF0000) >> 16); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x0000FF00) >> 8); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x000000FF) >> 0); + } + else // burst operation + { + spi_data[0] = (AddrSel & 0x00FF0000) >> 16; + spi_data[1] = (AddrSel & 0x0000FF00) >> 8; + spi_data[2] = (AddrSel & 0x000000FF) >> 0; + WIZCHIP.IF.SPI._write_burst(spi_data, 3); + } + ret = WIZCHIP.IF.SPI._read_byte(); + + WIZCHIP.CS._deselect(); + WIZCHIP_CRITICAL_EXIT(); + return ret; +} + +void WIZCHIP_WRITE(uint32_t AddrSel, uint8_t wb ) +{ + uint8_t spi_data[4]; + + WIZCHIP_CRITICAL_ENTER(); + WIZCHIP.CS._select(); + + AddrSel |= (_W5500_SPI_WRITE_ | _W5500_SPI_VDM_OP_); + + //if(!WIZCHIP.IF.SPI._read_burst || !WIZCHIP.IF.SPI._write_burst) // byte operation + if(!WIZCHIP.IF.SPI._write_burst) // byte operation + { + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x00FF0000) >> 16); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x0000FF00) >> 8); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x000000FF) >> 0); + WIZCHIP.IF.SPI._write_byte(wb); + } + else // burst operation + { + spi_data[0] = (AddrSel & 0x00FF0000) >> 16; + spi_data[1] = (AddrSel & 0x0000FF00) >> 8; + spi_data[2] = (AddrSel & 0x000000FF) >> 0; + spi_data[3] = wb; + WIZCHIP.IF.SPI._write_burst(spi_data, 4); + } + + WIZCHIP.CS._deselect(); + WIZCHIP_CRITICAL_EXIT(); +} + +void WIZCHIP_READ_BUF (uint32_t AddrSel, uint8_t* pBuf, uint16_t len) +{ + uint8_t spi_data[3]; + uint16_t i; + + WIZCHIP_CRITICAL_ENTER(); + WIZCHIP.CS._select(); + + AddrSel |= (_W5500_SPI_READ_ | _W5500_SPI_VDM_OP_); + + if(!WIZCHIP.IF.SPI._read_burst || !WIZCHIP.IF.SPI._write_burst) // byte operation + { + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x00FF0000) >> 16); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x0000FF00) >> 8); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x000000FF) >> 0); + for(i = 0; i < len; i++) + pBuf[i] = WIZCHIP.IF.SPI._read_byte(); + } + else // burst operation + { + spi_data[0] = (AddrSel & 0x00FF0000) >> 16; + spi_data[1] = (AddrSel & 0x0000FF00) >> 8; + spi_data[2] = (AddrSel & 0x000000FF) >> 0; + WIZCHIP.IF.SPI._write_burst(spi_data, 3); + WIZCHIP.IF.SPI._read_burst(pBuf, len); + } + + WIZCHIP.CS._deselect(); + WIZCHIP_CRITICAL_EXIT(); +} + +void WIZCHIP_WRITE_BUF(uint32_t AddrSel, uint8_t* pBuf, uint16_t len) +{ + uint8_t spi_data[3]; + uint16_t i; + + WIZCHIP_CRITICAL_ENTER(); + WIZCHIP.CS._select(); + + AddrSel |= (_W5500_SPI_WRITE_ | _W5500_SPI_VDM_OP_); + + if(!WIZCHIP.IF.SPI._write_burst) // byte operation + { + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x00FF0000) >> 16); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x0000FF00) >> 8); + WIZCHIP.IF.SPI._write_byte((AddrSel & 0x000000FF) >> 0); + for(i = 0; i < len; i++) + WIZCHIP.IF.SPI._write_byte(pBuf[i]); + } + else // burst operation + { + spi_data[0] = (AddrSel & 0x00FF0000) >> 16; + spi_data[1] = (AddrSel & 0x0000FF00) >> 8; + spi_data[2] = (AddrSel & 0x000000FF) >> 0; + WIZCHIP.IF.SPI._write_burst(spi_data, 3); + WIZCHIP.IF.SPI._write_burst(pBuf, len); + } + + WIZCHIP.CS._deselect(); + WIZCHIP_CRITICAL_EXIT(); +} + + +uint16_t getSn_TX_FSR(uint8_t sn) +{ + uint16_t val=0,val1=0; + + do + { + val1 = WIZCHIP_READ(Sn_TX_FSR(sn)); + val1 = (val1 << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_TX_FSR(sn),1)); + if (val1 != 0) + { + val = WIZCHIP_READ(Sn_TX_FSR(sn)); + val = (val << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_TX_FSR(sn),1)); + } + }while (val != val1); + return val; +} + + +uint16_t getSn_RX_RSR(uint8_t sn) +{ + uint16_t val=0,val1=0; + + do + { + val1 = WIZCHIP_READ(Sn_RX_RSR(sn)); + val1 = (val1 << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_RX_RSR(sn),1)); + if (val1 != 0) + { + val = WIZCHIP_READ(Sn_RX_RSR(sn)); + val = (val << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_RX_RSR(sn),1)); + } + }while (val != val1); + return val; +} + +void wiz_send_data(uint8_t sn, uint8_t *wizdata, uint16_t len) +{ + uint16_t ptr = 0; + uint32_t addrsel = 0; + + if(len == 0) return; + ptr = getSn_TX_WR(sn); + //M20140501 : implict type casting -> explict type casting + //addrsel = (ptr << 8) + (WIZCHIP_TXBUF_BLOCK(sn) << 3); + addrsel = ((uint32_t)ptr << 8) + (WIZCHIP_TXBUF_BLOCK(sn) << 3); + // + WIZCHIP_WRITE_BUF(addrsel,wizdata, len); + + ptr += len; + setSn_TX_WR(sn,ptr); +} + +void wiz_recv_data(uint8_t sn, uint8_t *wizdata, uint16_t len) +{ + uint16_t ptr = 0; + uint32_t addrsel = 0; + + if(len == 0) return; + ptr = getSn_RX_RD(sn); + //M20140501 : implict type casting -> explict type casting + //addrsel = ((ptr << 8) + (WIZCHIP_RXBUF_BLOCK(sn) << 3); + addrsel = ((uint32_t)ptr << 8) + (WIZCHIP_RXBUF_BLOCK(sn) << 3); + // + WIZCHIP_READ_BUF(addrsel, wizdata, len); + ptr += len; + + setSn_RX_RD(sn,ptr); +} + + +void wiz_recv_ignore(uint8_t sn, uint16_t len) +{ + uint16_t ptr = 0; + + ptr = getSn_RX_RD(sn); + ptr += len; + setSn_RX_RD(sn,ptr); +} + +#endif diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/W5500/w5500.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/W5500/w5500.h new file mode 100644 index 000000000..3afc16e9c --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/W5500/w5500.h @@ -0,0 +1,2163 @@ +//***************************************************************************** +// +//! \file w5500.h +//! \brief W5500 HAL Header File. +//! \version 1.0.0 +//! \date 2013/10/21 +//! \par Revision history +//! <2015/02/05> Notice +//! The version history is not updated after this point. +//! Download the latest version directly from GitHub. Please visit the our GitHub repository for ioLibrary. +//! >> https://github.com/Wiznet/ioLibrary_Driver +//! <2013/10/21> 1st Release +//! \author MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** + +// + +#ifndef _W5500_H_ +#define _W5500_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include "wizchip_conf.h" + +/// @cond DOXY_APPLY_CODE +#if (_WIZCHIP_ == 5500) +/// @endcond + +#define _W5500_IO_BASE_ 0x00000000 + +#define _W5500_SPI_READ_ (0x00 << 2) //< SPI interface Read operation in Control Phase +#define _W5500_SPI_WRITE_ (0x01 << 2) //< SPI interface Write operation in Control Phase + +#define WIZCHIP_CREG_BLOCK 0x00 //< Common register block +#define WIZCHIP_SREG_BLOCK(N) (1+4*N) //< Socket N register block +#define WIZCHIP_TXBUF_BLOCK(N) (2+4*N) //< Socket N Tx buffer address block +#define WIZCHIP_RXBUF_BLOCK(N) (3+4*N) //< Socket N Rx buffer address block + +#define WIZCHIP_OFFSET_INC(ADDR, N) (ADDR + (N<<8)) //< Increase offset address + + +/////////////////////////////////////// +// Definition For Legacy Chip Driver // +/////////////////////////////////////// +#define IINCHIP_READ(ADDR) WIZCHIP_READ(ADDR) ///< The defined for legacy chip driver +#define IINCHIP_WRITE(ADDR,VAL) WIZCHIP_WRITE(ADDR,VAL) ///< The defined for legacy chip driver +#define IINCHIP_READ_BUF(ADDR,BUF,LEN) WIZCHIP_READ_BUF(ADDR,BUF,LEN) ///< The defined for legacy chip driver +#define IINCHIP_WRITE_BUF(ADDR,BUF,LEN) WIZCHIP_WRITE(ADDR,BUF,LEN) ///< The defined for legacy chip driver + +////////////////////////////// +//-------------------------- defgroup --------------------------------- +/** + * @defgroup W5500 W5500 + * + * @brief WHIZCHIP register defines and I/O functions of @b W5500. + * + * - @ref WIZCHIP_register : @ref Common_register_group and @ref Socket_register_group + * - @ref WIZCHIP_IO_Functions : @ref Basic_IO_function, @ref Common_register_access_function and @ref Socket_register_access_function + */ + + +/** + * @defgroup WIZCHIP_register WIZCHIP register + * @ingroup W5500 + * + * @brief WHIZCHIP register defines register group of @b W5500. + * + * - @ref Common_register_group : Common register group + * - @ref Socket_register_group : \c SOCKET n register group + */ + + +/** + * @defgroup WIZCHIP_IO_Functions WIZCHIP I/O functions + * @ingroup W5500 + * + * @brief This supports the basic I/O functions for @ref WIZCHIP_register. + * + * - Basic I/O function \n + * WIZCHIP_READ(), WIZCHIP_WRITE(), WIZCHIP_READ_BUF(), WIZCHIP_WRITE_BUF() \n\n + * + * - @ref Common_register_group access functions \n + * -# @b Mode \n + * getMR(), setMR() + * -# @b Interrupt \n + * getIR(), setIR(), getIMR(), setIMR(), getSIR(), setSIR(), getSIMR(), setSIMR(), getINTLEVEL(), setINTLEVEL() + * -# Network Information \n + * getSHAR(), setSHAR(), getGAR(), setGAR(), getSUBR(), setSUBR(), getSIPR(), setSIPR() + * -# @b Retransmission \n + * getRCR(), setRCR(), getRTR(), setRTR() + * -# @b PPPoE \n + * getPTIMER(), setPTIMER(), getPMAGIC(), getPMAGIC(), getPSID(), setPSID(), getPHAR(), setPHAR(), getPMRU(), setPMRU() + * -# ICMP packet \n + * getUIPR(), getUPORTR() + * -# @b etc. \n + * getPHYCFGR(), setPHYCFGR(), getVERSIONR() \n\n + * + * - \ref Socket_register_group access functions \n + * -# SOCKET control \n + * getSn_MR(), setSn_MR(), getSn_CR(), setSn_CR(), getSn_IMR(), setSn_IMR(), getSn_IR(), setSn_IR() + * -# SOCKET information \n + * getSn_SR(), getSn_DHAR(), setSn_DHAR(), getSn_PORT(), setSn_PORT(), getSn_DIPR(), setSn_DIPR(), getSn_DPORT(), setSn_DPORT() + * getSn_MSSR(), setSn_MSSR() + * -# SOCKET communication \n + * getSn_RXBUF_SIZE(), setSn_RXBUF_SIZE(), getSn_TXBUF_SIZE(), setSn_TXBUF_SIZE() \n + * getSn_TX_RD(), getSn_TX_WR(), setSn_TX_WR() \n + * getSn_RX_RD(), setSn_RX_RD(), getSn_RX_WR() \n + * getSn_TX_FSR(), getSn_RX_RSR(), getSn_KPALVTR(), setSn_KPALVTR() + * -# IP header field \n + * getSn_FRAG(), setSn_FRAG(), getSn_TOS(), setSn_TOS() \n + * getSn_TTL(), setSn_TTL() + */ + + + +/** + * @defgroup Common_register_group Common register + * @ingroup WIZCHIP_register + * + * @brief Common register group\n + * It set the basic for the networking\n + * It set the configuration such as interrupt, network information, ICMP, etc. + * @details + * @sa MR : Mode register. + * @sa GAR, SUBR, SHAR, SIPR + * @sa INTLEVEL, IR, IMR, SIR, SIMR : Interrupt. + * @sa _RTR_, _RCR_ : Data retransmission. + * @sa PTIMER, PMAGIC, PHAR, PSID, PMRU : PPPoE. + * @sa UIPR, UPORTR : ICMP message. + * @sa PHYCFGR, VERSIONR : etc. + */ + + + +/** + * @defgroup Socket_register_group Socket register + * @ingroup WIZCHIP_register + * + * @brief Socket register group.\n + * Socket register configures and control SOCKETn which is necessary to data communication. + * @details + * @sa Sn_MR, Sn_CR, Sn_IR, Sn_IMR : SOCKETn Control + * @sa Sn_SR, Sn_PORT, Sn_DHAR, Sn_DIPR, Sn_DPORT : SOCKETn Information + * @sa Sn_MSSR, Sn_TOS, Sn_TTL, Sn_KPALVTR, Sn_FRAG : Internet protocol. + * @sa Sn_RXBUF_SIZE, Sn_TXBUF_SIZE, Sn_TX_FSR, Sn_TX_RD, Sn_TX_WR, Sn_RX_RSR, Sn_RX_RD, Sn_RX_WR : Data communication + */ + + + + /** + * @defgroup Basic_IO_function Basic I/O function + * @ingroup WIZCHIP_IO_Functions + * @brief These are basic input/output functions to read values from register or write values to register. + */ + +/** + * @defgroup Common_register_access_function Common register access functions + * @ingroup WIZCHIP_IO_Functions + * @brief These are functions to access common registers. + */ + +/** + * @defgroup Socket_register_access_function Socket register access functions + * @ingroup WIZCHIP_IO_Functions + * @brief These are functions to access socket registers. + */ + +//------------------------------- defgroup end -------------------------------------------- +//----------------------------- W5500 Common Registers IOMAP ----------------------------- +/** + * @ingroup Common_register_group + * @brief Mode Register address(R/W)\n + * @ref MR is used for S/W reset, ping block mode, PPPoE mode and etc. + * @details Each bit of @ref MR defined as follows. + * + * + * + *
7 6 5 4 3 2 1 0
RST Reserved WOL PB PPPoE Reserved FARP Reserved
+ * - \ref MR_RST : Reset + * - \ref MR_WOL : Wake on LAN + * - \ref MR_PB : Ping block + * - \ref MR_PPPOE : PPPoE mode + * - \ref MR_FARP : Force ARP mode + */ +#define MR (_W5500_IO_BASE_ + (0x0000 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Gateway IP Register address(R/W) + * @details @ref GAR configures the default gateway address. + */ +#define GAR (_W5500_IO_BASE_ + (0x0001 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Subnet mask Register address(R/W) + * @details @ref SUBR configures the subnet mask address. + */ +#define SUBR (_W5500_IO_BASE_ + (0x0005 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Source MAC Register address(R/W) + * @details @ref SHAR configures the source hardware address. + */ +#define SHAR (_W5500_IO_BASE_ + (0x0009 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Source IP Register address(R/W) + * @details @ref SIPR configures the source IP address. + */ +#define SIPR (_W5500_IO_BASE_ + (0x000F << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Set Interrupt low level timer register address(R/W) + * @details @ref INTLEVEL configures the Interrupt Assert Time. + */ +#define INTLEVEL (_W5500_IO_BASE_ + (0x0013 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Interrupt Register(R/W) + * @details @ref IR indicates the interrupt status. Each bit of @ref IR will be still until the bit will be written to by the host. + * If @ref IR is not equal to x00 INTn PIN is asserted to low until it is x00\n\n + * Each bit of @ref IR defined as follows. + * + * + * + *
7 6 5 4 3 2 1 0
CONFLICT UNREACH PPPoE MP Reserved Reserved Reserved Reserved
+ * - \ref IR_CONFLICT : IP conflict + * - \ref IR_UNREACH : Destination unreachable + * - \ref IR_PPPoE : PPPoE connection close + * - \ref IR_MP : Magic packet + */ +#define IR (_W5500_IO_BASE_ + (0x0015 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Interrupt mask register(R/W) + * @details @ref _IMR_ is used to mask interrupts. Each bit of @ref _IMR_ corresponds to each bit of @ref IR. + * When a bit of @ref _IMR_ is and the corresponding bit of @ref IR is an interrupt will be issued. In other words, + * if a bit of @ref _IMR_ is an interrupt will not be issued even if the corresponding bit of @ref IR is \n\n + * Each bit of @ref _IMR_ defined as the following. + * + * + * + *
7 6 5 4 3 2 1 0
IM_IR7 IM_IR6 IM_IR5 IM_IR4 Reserved Reserved Reserved Reserved
+ * - \ref IM_IR7 : IP Conflict Interrupt Mask + * - \ref IM_IR6 : Destination unreachable Interrupt Mask + * - \ref IM_IR5 : PPPoE Close Interrupt Mask + * - \ref IM_IR4 : Magic Packet Interrupt Mask + */ +//M20150401 : Rename SYMBOE ( Re-define error in a compile) +//#define IMR (_W5500_IO_BASE_ + (0x0016 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +#define _IMR_ (_W5500_IO_BASE_ + (0x0016 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Socket Interrupt Register(R/W) + * @details @ref SIR indicates the interrupt status of Socket.\n + * Each bit of @ref SIR be still until @ref Sn_IR is cleared by the host.\n + * If @ref Sn_IR is not equal to x00 the n-th bit of @ref SIR is and INTn PIN is asserted until @ref SIR is x00 */ +#define SIR (_W5500_IO_BASE_ + (0x0017 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Socket Interrupt Mask Register(R/W) + * @details Each bit of @ref SIMR corresponds to each bit of @ref SIR. + * When a bit of @ref SIMR is and the corresponding bit of @ref SIR is Interrupt will be issued. + * In other words, if a bit of @ref SIMR is an interrupt will be not issued even if the corresponding bit of @ref SIR is + */ +#define SIMR (_W5500_IO_BASE_ + (0x0018 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Timeout register address( 1 is 100us )(R/W) + * @details @ref _RTR_ configures the retransmission timeout period. The unit of timeout period is 100us and the default of @ref _RTR_ is x07D0. + * And so the default timeout period is 200ms(100us X 2000). During the time configured by @ref _RTR_, W5500 waits for the peer response + * to the packet that is transmitted by \ref Sn_CR (CONNECT, DISCON, CLOSE, SEND, SEND_MAC, SEND_KEEP command). + * If the peer does not respond within the @ref _RTR_ time, W5500 retransmits the packet or issues timeout. + */ +//M20150401 : Rename SYMBOE ( Re-define error in a compile) +//#define RTR (_W5500_IO_BASE_ + (0x0019 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +#define _RTR_ (_W5500_IO_BASE_ + (0x0019 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Retry count register(R/W) + * @details @ref _RCR_ configures the number of time of retransmission. + * When retransmission occurs as many as ref _RCR_+1 Timeout interrupt is issued (@ref Sn_IR_TIMEOUT = '1'). + */ +//M20150401 : Rename SYMBOE ( Re-define error in a compile) +//#define RCR (_W5500_IO_BASE_ + (0x001B << 8) + (WIZCHIP_CREG_BLOCK << 3)) +#define _RCR_ (_W5500_IO_BASE_ + (0x001B << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief PPP LCP Request Timer register in PPPoE mode(R/W) + * @details @ref PTIMER configures the time for sending LCP echo request. The unit of time is 25ms. + */ +#define PTIMER (_W5500_IO_BASE_ + (0x001C << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief PPP LCP Magic number register in PPPoE mode(R/W) + * @details @ref PMAGIC configures the 4bytes magic number to be used in LCP negotiation. + */ +#define PMAGIC (_W5500_IO_BASE_ + (0x001D << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief PPP Destination MAC Register address(R/W) + * @details @ref PHAR configures the PPPoE server hardware address that is acquired during PPPoE connection process. + */ +#define PHAR (_W5500_IO_BASE_ + (0x001E << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief PPP Session Identification Register(R/W) + * @details @ref PSID configures the PPPoE sever session ID acquired during PPPoE connection process. + */ +#define PSID (_W5500_IO_BASE_ + (0x0024 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief PPP Maximum Segment Size(MSS) register(R/W) + * @details @ref PMRU configures the maximum receive unit of PPPoE. + */ +#define PMRU (_W5500_IO_BASE_ + (0x0026 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Unreachable IP register address in UDP mode(R) + * @details W5500 receives an ICMP packet(Destination port unreachable) when data is sent to a port number + * which socket is not open and @ref IR_UNREACH bit of @ref IR becomes and @ref UIPR & @ref UPORTR indicates + * the destination IP address & port number respectively. + */ +#define UIPR (_W5500_IO_BASE_ + (0x0028 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief Unreachable Port register address in UDP mode(R) + * @details W5500 receives an ICMP packet(Destination port unreachable) when data is sent to a port number + * which socket is not open and @ref IR_UNREACH bit of @ref IR becomes and @ref UIPR & @ref UPORTR + * indicates the destination IP address & port number respectively. + */ +#define UPORTR (_W5500_IO_BASE_ + (0x002C << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief PHY Status Register(R/W) + * @details @ref PHYCFGR configures PHY operation mode and resets PHY. In addition, @ref PHYCFGR indicates the status of PHY such as duplex, Speed, Link. + */ +#define PHYCFGR (_W5500_IO_BASE_ + (0x002E << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +// Reserved (_W5500_IO_BASE_ + (0x002F << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0030 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0031 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0032 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0033 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0034 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0035 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0036 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0037 << 8) + (WIZCHIP_CREG_BLOCK << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0038 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + +/** + * @ingroup Common_register_group + * @brief chip version register address(R) + * @details @ref VERSIONR always indicates the W5500 version as @b 0x04. + */ +#define VERSIONR (_W5500_IO_BASE_ + (0x0039 << 8) + (WIZCHIP_CREG_BLOCK << 3)) + + +//----------------------------- W5500 Socket Registers IOMAP ----------------------------- +/** + * @ingroup Socket_register_group + * @brief socket Mode register(R/W) + * @details @ref Sn_MR configures the option or protocol type of Socket n.\n\n + * Each bit of @ref Sn_MR defined as the following. + * + * + * + *
7 6 5 4 3 2 1 0
MULTI/MFEN BCASTB ND/MC/MMB UCASTB/MIP6B Protocol[3] Protocol[2] Protocol[1] Protocol[0]
+ * - @ref Sn_MR_MULTI : Support UDP Multicasting + * - @ref Sn_MR_BCASTB : Broadcast block in UDP Multicasting + * - @ref Sn_MR_ND : No Delayed Ack(TCP) flag + * - @ref Sn_MR_MC : IGMP version used in UDP mulitcasting + * - @ref Sn_MR_MMB : Multicast Blocking in @ref Sn_MR_MACRAW mode + * - @ref Sn_MR_UCASTB : Unicast Block in UDP Multicating + * - @ref Sn_MR_MIP6B : IPv6 packet Blocking in @ref Sn_MR_MACRAW mode + * - Protocol + * + * + * + * + * + * + *
Protocol[3] Protocol[2] Protocol[1] Protocol[0] @b Meaning
0 0 0 0 Closed
0 0 0 1 TCP
0 0 1 0 UDP
0 1 0 0 MACRAW
+ * - @ref Sn_MR_MACRAW : MAC LAYER RAW SOCK \n + * - @ref Sn_MR_UDP : UDP + * - @ref Sn_MR_TCP : TCP + * - @ref Sn_MR_CLOSE : Unused socket + * @note MACRAW mode should be only used in Socket 0. + */ +#define Sn_MR(N) (_W5500_IO_BASE_ + (0x0000 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Socket command register(R/W) + * @details This is used to set the command for Socket n such as OPEN, CLOSE, CONNECT, LISTEN, SEND, and RECEIVE.\n + * After W5500 accepts the command, the @ref Sn_CR register is automatically cleared to 0x00. + * Even though @ref Sn_CR is cleared to 0x00, the command is still being processed.\n + * To check whether the command is completed or not, please check the @ref Sn_IR or @ref Sn_SR. + * - @ref Sn_CR_OPEN : Initialize or open socket. + * - @ref Sn_CR_LISTEN : Wait connection request in TCP mode(Server mode) + * - @ref Sn_CR_CONNECT : Send connection request in TCP mode(Client mode) + * - @ref Sn_CR_DISCON : Send closing request in TCP mode. + * - @ref Sn_CR_CLOSE : Close socket. + * - @ref Sn_CR_SEND : Update TX buffer pointer and send data. + * - @ref Sn_CR_SEND_MAC : Send data with MAC address, so without ARP process. + * - @ref Sn_CR_SEND_KEEP : Send keep alive message. + * - @ref Sn_CR_RECV : Update RX buffer pointer and receive data. + */ +#define Sn_CR(N) (_W5500_IO_BASE_ + (0x0001 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Socket interrupt register(R) + * @details @ref Sn_IR indicates the status of Socket Interrupt such as establishment, termination, receiving data, timeout).\n + * When an interrupt occurs and the corresponding bit of @ref Sn_IMR is the corresponding bit of @ref Sn_IR becomes \n + * In order to clear the @ref Sn_IR bit, the host should write the bit to \n + * + * + * + *
7 6 5 4 3 2 1 0
Reserved Reserved Reserved SEND_OK TIMEOUT RECV DISCON CON
+ * - \ref Sn_IR_SENDOK : SEND_OK Interrupt + * - \ref Sn_IR_TIMEOUT : TIMEOUT Interrupt + * - \ref Sn_IR_RECV : RECV Interrupt + * - \ref Sn_IR_DISCON : DISCON Interrupt + * - \ref Sn_IR_CON : CON Interrupt + */ +#define Sn_IR(N) (_W5500_IO_BASE_ + (0x0002 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Socket status register(R) + * @details @ref Sn_SR indicates the status of Socket n.\n + * The status of Socket n is changed by @ref Sn_CR or some special control packet as SYN, FIN packet in TCP. + * @par Normal status + * - @ref SOCK_CLOSED : Closed + * - @ref SOCK_INIT : Initiate state + * - @ref SOCK_LISTEN : Listen state + * - @ref SOCK_ESTABLISHED : Success to connect + * - @ref SOCK_CLOSE_WAIT : Closing state + * - @ref SOCK_UDP : UDP socket + * - @ref SOCK_MACRAW : MAC raw mode socket + *@par Temporary status during changing the status of Socket n. + * - @ref SOCK_SYNSENT : This indicates Socket n sent the connect-request packet (SYN packet) to a peer. + * - @ref SOCK_SYNRECV : It indicates Socket n successfully received the connect-request packet (SYN packet) from a peer. + * - @ref SOCK_FIN_WAIT : Connection state + * - @ref SOCK_CLOSING : Closing state + * - @ref SOCK_TIME_WAIT : Closing state + * - @ref SOCK_LAST_ACK : Closing state + */ +#define Sn_SR(N) (_W5500_IO_BASE_ + (0x0003 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief source port register(R/W) + * @details @ref Sn_PORT configures the source port number of Socket n. + * It is valid when Socket n is used in TCP/UDP mode. It should be set before OPEN command is ordered. + */ +#define Sn_PORT(N) (_W5500_IO_BASE_ + (0x0004 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Peer MAC register address(R/W) + * @details @ref Sn_DHAR configures the destination hardware address of Socket n when using SEND_MAC command in UDP mode or + * it indicates that it is acquired in ARP-process by CONNECT/SEND command. + */ +#define Sn_DHAR(N) (_W5500_IO_BASE_ + (0x0006 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Peer IP register address(R/W) + * @details @ref Sn_DIPR configures or indicates the destination IP address of Socket n. It is valid when Socket n is used in TCP/UDP mode. + * In TCP client mode, it configures an IP address of TCP serverbefore CONNECT command. + * In TCP server mode, it indicates an IP address of TCP clientafter successfully establishing connection. + * In UDP mode, it configures an IP address of peer to be received the UDP packet by SEND or SEND_MAC command. + */ +#define Sn_DIPR(N) (_W5500_IO_BASE_ + (0x000C << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Peer port register address(R/W) + * @details @ref Sn_DPORT configures or indicates the destination port number of Socket n. It is valid when Socket n is used in TCP/UDP mode. + * In TCP clientmode, it configures the listen port number of TCP serverbefore CONNECT command. + * In TCP Servermode, it indicates the port number of TCP client after successfully establishing connection. + * In UDP mode, it configures the port number of peer to be transmitted the UDP packet by SEND/SEND_MAC command. + */ +#define Sn_DPORT(N) (_W5500_IO_BASE_ + (0x0010 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Maximum Segment Size(Sn_MSSR0) register address(R/W) + * @details @ref Sn_MSSR configures or indicates the MTU(Maximum Transfer Unit) of Socket n. + */ +#define Sn_MSSR(N) (_W5500_IO_BASE_ + (0x0012 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +// Reserved (_W5500_IO_BASE_ + (0x0014 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief IP Type of Service(TOS) Register(R/W) + * @details @ref Sn_TOS configures the TOS(Type Of Service field in IP Header) of Socket n. + * It is set before OPEN command. + */ +#define Sn_TOS(N) (_W5500_IO_BASE_ + (0x0015 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +/** + * @ingroup Socket_register_group + * @brief IP Time to live(TTL) Register(R/W) + * @details @ref Sn_TTL configures the TTL(Time To Live field in IP header) of Socket n. + * It is set before OPEN command. + */ +#define Sn_TTL(N) (_W5500_IO_BASE_ + (0x0016 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0017 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0018 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +// Reserved (_W5500_IO_BASE_ + (0x0019 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +// Reserved (_W5500_IO_BASE_ + (0x001A << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +// Reserved (_W5500_IO_BASE_ + (0x001B << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +// Reserved (_W5500_IO_BASE_ + (0x001C << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) +// Reserved (_W5500_IO_BASE_ + (0x001D << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Receive memory size register(R/W) + * @details @ref Sn_RXBUF_SIZE configures the RX buffer block size of Socket n. + * Socket n RX Buffer Block size can be configured with 1,2,4,8, and 16 Kbytes. + * If a different size is configured, the data cannot be normally received from a peer. + * Although Socket n RX Buffer Block size is initially configured to 2Kbytes, + * user can re-configure its size using @ref Sn_RXBUF_SIZE. The total sum of @ref Sn_RXBUF_SIZE can not be exceed 16Kbytes. + * When exceeded, the data reception error is occurred. + */ +#define Sn_RXBUF_SIZE(N) (_W5500_IO_BASE_ + (0x001E << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Transmit memory size register(R/W) + * @details @ref Sn_TXBUF_SIZE configures the TX buffer block size of Socket n. Socket n TX Buffer Block size can be configured with 1,2,4,8, and 16 Kbytes. + * If a different size is configured, the data can锟絫 be normally transmitted to a peer. + * Although Socket n TX Buffer Block size is initially configured to 2Kbytes, + * user can be re-configure its size using @ref Sn_TXBUF_SIZE. The total sum of @ref Sn_TXBUF_SIZE can not be exceed 16Kbytes. + * When exceeded, the data transmission error is occurred. + */ +#define Sn_TXBUF_SIZE(N) (_W5500_IO_BASE_ + (0x001F << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Transmit free memory size register(R) + * @details @ref Sn_TX_FSR indicates the free size of Socket n TX Buffer Block. It is initialized to the configured size by @ref Sn_TXBUF_SIZE. + * Data bigger than @ref Sn_TX_FSR should not be saved in the Socket n TX Buffer because the bigger data overwrites the previous saved data not yet sent. + * Therefore, check before saving the data to the Socket n TX Buffer, and if data is equal or smaller than its checked size, + * transmit the data with SEND/SEND_MAC command after saving the data in Socket n TX buffer. But, if data is bigger than its checked size, + * transmit the data after dividing into the checked size and saving in the Socket n TX buffer. + */ +#define Sn_TX_FSR(N) (_W5500_IO_BASE_ + (0x0020 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Transmit memory read pointer register address(R) + * @details @ref Sn_TX_RD is initialized by OPEN command. However, if Sn_MR(P[3:0]) is TCP mode(001, it is re-initialized while connecting with TCP. + * After its initialization, it is auto-increased by SEND command. + * SEND command transmits the saved data from the current @ref Sn_TX_RD to the @ref Sn_TX_WR in the Socket n TX Buffer. + * After transmitting the saved data, the SEND command increases the @ref Sn_TX_RD as same as the @ref Sn_TX_WR. + * If its increment value exceeds the maximum value 0xFFFF, (greater than 0x10000 and the carry bit occurs), + * then the carry bit is ignored and will automatically update with the lower 16bits value. + */ +#define Sn_TX_RD(N) (_W5500_IO_BASE_ + (0x0022 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Transmit memory write pointer register address(R/W) + * @details @ref Sn_TX_WR is initialized by OPEN command. However, if Sn_MR(P[3:0]) is TCP mode(001, it is re-initialized while connecting with TCP.\n + * It should be read or be updated like as follows.\n + * 1. Read the starting address for saving the transmitting data.\n + * 2. Save the transmitting data from the starting address of Socket n TX buffer.\n + * 3. After saving the transmitting data, update @ref Sn_TX_WR to the increased value as many as transmitting data size. + * If the increment value exceeds the maximum value 0xFFFF(greater than 0x10000 and the carry bit occurs), + * then the carry bit is ignored and will automatically update with the lower 16bits value.\n + * 4. Transmit the saved data in Socket n TX Buffer by using SEND/SEND command + */ +#define Sn_TX_WR(N) (_W5500_IO_BASE_ + (0x0024 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Received data size register(R) + * @details @ref Sn_RX_RSR indicates the data size received and saved in Socket n RX Buffer. + * @ref Sn_RX_RSR does not exceed the @ref Sn_RXBUF_SIZE and is calculated as the difference between + * 锟絊ocket n RX Write Pointer (@ref Sn_RX_WR)and 锟絊ocket n RX Read Pointer (@ref Sn_RX_RD) + */ +#define Sn_RX_RSR(N) (_W5500_IO_BASE_ + (0x0026 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Read point of Receive memory(R/W) + * @details @ref Sn_RX_RD is initialized by OPEN command. Make sure to be read or updated as follows.\n + * 1. Read the starting save address of the received data.\n + * 2. Read data from the starting address of Socket n RX Buffer.\n + * 3. After reading the received data, Update @ref Sn_RX_RD to the increased value as many as the reading size. + * If the increment value exceeds the maximum value 0xFFFF, that is, is greater than 0x10000 and the carry bit occurs, + * update with the lower 16bits value ignored the carry bit.\n + * 4. Order RECV command is for notifying the updated @ref Sn_RX_RD to W5500. + */ +#define Sn_RX_RD(N) (_W5500_IO_BASE_ + (0x0028 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Write point of Receive memory(R) + * @details @ref Sn_RX_WR is initialized by OPEN command and it is auto-increased by the data reception. + * If the increased value exceeds the maximum value 0xFFFF, (greater than 0x10000 and the carry bit occurs), + * then the carry bit is ignored and will automatically update with the lower 16bits value. + */ +#define Sn_RX_WR(N) (_W5500_IO_BASE_ + (0x002A << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief socket interrupt mask register(R) + * @details @ref Sn_IMR masks the interrupt of Socket n. + * Each bit corresponds to each bit of @ref Sn_IR. When a Socket n Interrupt is occurred and the corresponding bit of @ref Sn_IMR is + * the corresponding bit of @ref Sn_IR becomes When both the corresponding bit of @ref Sn_IMR and @ref Sn_IR are and the n-th bit of @ref IR is + * Host is interrupted by asserted INTn PIN to low. + */ +#define Sn_IMR(N) (_W5500_IO_BASE_ + (0x002C << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Fragment field value in IP header register(R/W) + * @details @ref Sn_FRAG configures the FRAG(Fragment field in IP header). + */ +#define Sn_FRAG(N) (_W5500_IO_BASE_ + (0x002D << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +/** + * @ingroup Socket_register_group + * @brief Keep Alive Timer register(R/W) + * @details @ref Sn_KPALVTR configures the transmitting timer of 锟終EEP ALIVE(KA)packet of SOCKETn. It is valid only in TCP mode, + * and ignored in other modes. The time unit is 5s. + * KA packet is transmittable after @ref Sn_SR is changed to SOCK_ESTABLISHED and after the data is transmitted or received to/from a peer at least once. + * In case of '@ref Sn_KPALVTR > 0', W5500 automatically transmits KA packet after time-period for checking the TCP connection (Auto-keepalive-process). + * In case of '@ref Sn_KPALVTR = 0', Auto-keep-alive-process will not operate, + * and KA packet can be transmitted by SEND_KEEP command by the host (Manual-keep-alive-process). + * Manual-keep-alive-process is ignored in case of '@ref Sn_KPALVTR > 0'. + */ +#define Sn_KPALVTR(N) (_W5500_IO_BASE_ + (0x002F << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + +//#define Sn_TSR(N) (_W5500_IO_BASE_ + (0x0030 << 8) + (WIZCHIP_SREG_BLOCK(N) << 3)) + + +//----------------------------- W5500 Register values ----------------------------- + +/* MODE register values */ +/** + * @brief Reset + * @details If this bit is All internal registers will be initialized. It will be automatically cleared as after S/W reset. + */ +#define MR_RST 0x80 + +/** + * @brief Wake on LAN + * @details 0 : Disable WOL mode\n + * 1 : Enable WOL mode\n + * If WOL mode is enabled and the received magic packet over UDP has been normally processed, the Interrupt PIN (INTn) asserts to low. + * When using WOL mode, the UDP Socket should be opened with any source port number. (Refer to Socket n Mode Register (@ref Sn_MR) for opening Socket.) + * @note The magic packet over UDP supported by W5500 consists of 6 bytes synchronization stream (xFFFFFFFFFFFF and + * 16 times Target MAC address stream in UDP payload. The options such like password are ignored. You can use any UDP source port number for WOL mode. + */ +#define MR_WOL 0x20 + +/** + * @brief Ping block + * @details 0 : Disable Ping block\n + * 1 : Enable Ping block\n + * If the bit is it blocks the response to a ping request. + */ +#define MR_PB 0x10 + +/** + * @brief Enable PPPoE + * @details 0 : DisablePPPoE mode\n + * 1 : EnablePPPoE mode\n + * If you use ADSL, this bit should be + */ +#define MR_PPPOE 0x08 + +/** + * @brief Enable UDP_FORCE_ARP CHECHK + * @details 0 : Disable Force ARP mode\n + * 1 : Enable Force ARP mode\n + * In Force ARP mode, It forces on sending ARP Request whenever data is sent. + */ +#define MR_FARP 0x02 + +/* IR register values */ +/** + * @brief Check IP conflict. + * @details Bit is set as when own source IP address is same with the sender IP address in the received ARP request. + */ +#define IR_CONFLICT 0x80 + +/** + * @brief Get the destination unreachable message in UDP sending. + * @details When receiving the ICMP (Destination port unreachable) packet, this bit is set as + * When this bit is Destination Information such as IP address and Port number may be checked with the corresponding @ref UIPR & @ref UPORTR. + */ +#define IR_UNREACH 0x40 + +/** + * @brief Get the PPPoE close message. + * @details When PPPoE is disconnected during PPPoE mode, this bit is set. + */ +#define IR_PPPoE 0x20 + +/** + * @brief Get the magic packet interrupt. + * @details When WOL mode is enabled and receives the magic packet over UDP, this bit is set. + */ +#define IR_MP 0x10 + + +/* PHYCFGR register value */ +#define PHYCFGR_RST ~(1<<7) //< For PHY reset, must operate AND mask. +#define PHYCFGR_OPMD (1<<6) // Configre PHY with OPMDC value +#define PHYCFGR_OPMDC_ALLA (7<<3) +#define PHYCFGR_OPMDC_PDOWN (6<<3) +#define PHYCFGR_OPMDC_NA (5<<3) +#define PHYCFGR_OPMDC_100FA (4<<3) +#define PHYCFGR_OPMDC_100F (3<<3) +#define PHYCFGR_OPMDC_100H (2<<3) +#define PHYCFGR_OPMDC_10F (1<<3) +#define PHYCFGR_OPMDC_10H (0<<3) +#define PHYCFGR_DPX_FULL (1<<2) +#define PHYCFGR_DPX_HALF (0<<2) +#define PHYCFGR_SPD_100 (1<<1) +#define PHYCFGR_SPD_10 (0<<1) +#define PHYCFGR_LNK_ON (1<<0) +#define PHYCFGR_LNK_OFF (0<<0) + +/* IMR register values */ +/** + * @brief IP Conflict Interrupt Mask. + * @details 0: Disable IP Conflict Interrupt\n + * 1: Enable IP Conflict Interrupt + */ +#define IM_IR7 0x80 + +/** + * @brief Destination unreachable Interrupt Mask. + * @details 0: Disable Destination unreachable Interrupt\n + * 1: Enable Destination unreachable Interrupt + */ +#define IM_IR6 0x40 + +/** + * @brief PPPoE Close Interrupt Mask. + * @details 0: Disable PPPoE Close Interrupt\n + * 1: Enable PPPoE Close Interrupt + */ +#define IM_IR5 0x20 + +/** + * @brief Magic Packet Interrupt Mask. + * @details 0: Disable Magic Packet Interrupt\n + * 1: Enable Magic Packet Interrupt + */ +#define IM_IR4 0x10 + +/* Sn_MR Default values */ +/** + * @brief Support UDP Multicasting + * @details 0 : disable Multicasting\n + * 1 : enable Multicasting\n + * This bit is applied only during UDP mode(P[3:0] = 010.\n + * To use multicasting, @ref Sn_DIPR & @ref Sn_DPORT should be respectively configured with the multicast group IP address & port number + * before Socket n is opened by OPEN command of @ref Sn_CR. + */ +#define Sn_MR_MULTI 0x80 + +/** + * @brief Broadcast block in UDP Multicasting. + * @details 0 : disable Broadcast Blocking\n + * 1 : enable Broadcast Blocking\n + * This bit blocks to receive broadcasting packet during UDP mode(P[3:0] = 010.\m + * In addition, This bit does when MACRAW mode(P[3:0] = 100 + */ +#define Sn_MR_BCASTB 0x40 + +/** + * @brief No Delayed Ack(TCP), Multicast flag + * @details 0 : Disable No Delayed ACK option\n + * 1 : Enable No Delayed ACK option\n + * This bit is applied only during TCP mode (P[3:0] = 001.\n + * When this bit is It sends the ACK packet without delay as soon as a Data packet is received from a peer.\n + * When this bit is It sends the ACK packet after waiting for the timeout time configured by @ref _RTR_. + */ +#define Sn_MR_ND 0x20 + +/** + * @brief Unicast Block in UDP Multicasting + * @details 0 : disable Unicast Blocking\n + * 1 : enable Unicast Blocking\n + * This bit blocks receiving the unicast packet during UDP mode(P[3:0] = 010 and MULTI = + */ +#define Sn_MR_UCASTB 0x10 + +/** + * @brief MAC LAYER RAW SOCK + * @details This configures the protocol mode of Socket n. + * @note MACRAW mode should be only used in Socket 0. + */ +#define Sn_MR_MACRAW 0x04 + +#define Sn_MR_IPRAW 0x03 /**< IP LAYER RAW SOCK */ + +/** + * @brief UDP + * @details This configures the protocol mode of Socket n. + */ +#define Sn_MR_UDP 0x02 + +/** + * @brief TCP + * @details This configures the protocol mode of Socket n. + */ +#define Sn_MR_TCP 0x01 + +/** + * @brief Unused socket + * @details This configures the protocol mode of Socket n. + */ +#define Sn_MR_CLOSE 0x00 + +/* Sn_MR values used with Sn_MR_MACRAW */ +/** + * @brief MAC filter enable in @ref Sn_MR_MACRAW mode + * @details 0 : disable MAC Filtering\n + * 1 : enable MAC Filtering\n + * This bit is applied only during MACRAW mode(P[3:0] = 100.\n + * When set as W5500 can only receive broadcasting packet or packet sent to itself. + * When this bit is W5500 can receive all packets on Ethernet. + * If user wants to implement Hybrid TCP/IP stack, + * it is recommended that this bit is set as for reducing host overhead to process the all received packets. + */ +#define Sn_MR_MFEN Sn_MR_MULTI + +/** + * @brief Multicast Blocking in @ref Sn_MR_MACRAW mode + * @details 0 : using IGMP version 2\n + * 1 : using IGMP version 1\n + * This bit is applied only during UDP mode(P[3:0] = 010 and MULTI = + * It configures the version for IGMP messages (Join/Leave/Report). + */ +#define Sn_MR_MMB Sn_MR_ND + +/** + * @brief IPv6 packet Blocking in @ref Sn_MR_MACRAW mode + * @details 0 : disable IPv6 Blocking\n + * 1 : enable IPv6 Blocking\n + * This bit is applied only during MACRAW mode (P[3:0] = 100. It blocks to receiving the IPv6 packet. + */ +#define Sn_MR_MIP6B Sn_MR_UCASTB + +/* Sn_MR value used with Sn_MR_UDP & Sn_MR_MULTI */ +/** + * @brief IGMP version used in UDP mulitcasting + * @details 0 : disable Multicast Blocking\n + * 1 : enable Multicast Blocking\n + * This bit is applied only when MACRAW mode(P[3:0] = 100. It blocks to receive the packet with multicast MAC address. + */ +#define Sn_MR_MC Sn_MR_ND + +/* Sn_MR alternate values */ +/** + * @brief For Berkeley Socket API + */ +#define SOCK_STREAM Sn_MR_TCP + +/** + * @brief For Berkeley Socket API + */ +#define SOCK_DGRAM Sn_MR_UDP + + +/* Sn_CR values */ +/** + * @brief Initialize or open socket + * @details Socket n is initialized and opened according to the protocol selected in Sn_MR(P3:P0). + * The table below shows the value of @ref Sn_SR corresponding to @ref Sn_MR.\n + * + * + * + * + * + * + *
\b Sn_MR (P[3:0]) \b Sn_SR
Sn_MR_CLOSE (000)
Sn_MR_TCP (001) SOCK_INIT (0x13)
Sn_MR_UDP (010) SOCK_UDP (0x22)
S0_MR_MACRAW (100) SOCK_MACRAW (0x02)
+ */ +#define Sn_CR_OPEN 0x01 + +/** + * @brief Wait connection request in TCP mode(Server mode) + * @details This is valid only in TCP mode (\ref Sn_MR(P3:P0) = \ref Sn_MR_TCP). + * In this mode, Socket n operates as a TCP serverand waits for connection-request (SYN packet) from any TCP client + * The @ref Sn_SR changes the state from \ref SOCK_INIT to \ref SOCKET_LISTEN. + * When a TCP clientconnection request is successfully established, + * the @ref Sn_SR changes from SOCK_LISTEN to SOCK_ESTABLISHED and the @ref Sn_IR(0) becomes + * But when a TCP clientconnection request is failed, @ref Sn_IR(3) becomes and the status of @ref Sn_SR changes to SOCK_CLOSED. + */ +#define Sn_CR_LISTEN 0x02 + +/** + * @brief Send connection request in TCP mode(Client mode) + * @details To connect, a connect-request (SYN packet) is sent to TCP serverconfigured by @ref Sn_DIPR & Sn_DPORT(destination address & port). + * If the connect-request is successful, the @ref Sn_SR is changed to @ref SOCK_ESTABLISHED and the Sn_IR(0) becomes \n\n + * The connect-request fails in the following three cases.\n + * 1. When a @b ARPTO occurs (@ref Sn_IR[3] = ) because destination hardware address is not acquired through the ARP-process.\n + * 2. When a @b SYN/ACK packet is not received and @b TCPTO (Sn_IR(3) = )\n + * 3. When a @b RST packet is received instead of a @b SYN/ACK packet. In these cases, @ref Sn_SR is changed to @ref SOCK_CLOSED. + * @note This is valid only in TCP mode and operates when Socket n acts as TCP client + */ +#define Sn_CR_CONNECT 0x04 + +/** + * @brief Send closing request in TCP mode + * @details Regardless of TCP serveror TCP client the DISCON command processes the disconnect-process (b>Active closeor Passive close.\n + * @par Active close + * it transmits disconnect-request(FIN packet) to the connected peer\n + * @par Passive close + * When FIN packet is received from peer, a FIN packet is replied back to the peer.\n + * @details When the disconnect-process is successful (that is, FIN/ACK packet is received successfully), @ref Sn_SR is changed to @ref SOCK_CLOSED.\n + * Otherwise, TCPTO occurs (\ref Sn_IR(3)='1') and then @ref Sn_SR is changed to @ref SOCK_CLOSED. + * @note Valid only in TCP mode. + */ +#define Sn_CR_DISCON 0x08 + +/** + * @brief Close socket + * @details Sn_SR is changed to @ref SOCK_CLOSED. + */ +#define Sn_CR_CLOSE 0x10 + +/** + * @brief Update TX buffer pointer and send data + * @details SEND transmits all the data in the Socket n TX buffer.\n + * For more details, please refer to Socket n TX Free Size Register (@ref Sn_TX_FSR), Socket n, + * TX Write Pointer Register(@ref Sn_TX_WR), and Socket n TX Read Pointer Register(@ref Sn_TX_RD). + */ +#define Sn_CR_SEND 0x20 + +/** + * @brief Send data with MAC address, so without ARP process + * @details The basic operation is same as SEND.\n + * Normally SEND transmits data after destination hardware address is acquired by the automatic ARP-process(Address Resolution Protocol).\n + * But SEND_MAC transmits data without the automatic ARP-process.\n + * In this case, the destination hardware address is acquired from @ref Sn_DHAR configured by host, instead of APR-process. + * @note Valid only in UDP mode. + */ +#define Sn_CR_SEND_MAC 0x21 + +/** + * @brief Send keep alive message + * @details It checks the connection status by sending 1byte keep-alive packet.\n + * If the peer can not respond to the keep-alive packet during timeout time, the connection is terminated and the timeout interrupt will occur. + * @note Valid only in TCP mode. + */ +#define Sn_CR_SEND_KEEP 0x22 + +/** + * @brief Update RX buffer pointer and receive data + * @details RECV completes the processing of the received data in Socket n RX Buffer by using a RX read pointer register (@ref Sn_RX_RD).\n + * For more details, refer to Socket n RX Received Size Register (@ref Sn_RX_RSR), Socket n RX Write Pointer Register (@ref Sn_RX_WR), + * and Socket n RX Read Pointer Register (@ref Sn_RX_RD). + */ +#define Sn_CR_RECV 0x40 + +/* Sn_IR values */ +/** + * @brief SEND_OK Interrupt + * @details This is issued when SEND command is completed. + */ +#define Sn_IR_SENDOK 0x10 + +/** + * @brief TIMEOUT Interrupt + * @details This is issued when ARPTO or TCPTO occurs. + */ +#define Sn_IR_TIMEOUT 0x08 + +/** + * @brief RECV Interrupt + * @details This is issued whenever data is received from a peer. + */ +#define Sn_IR_RECV 0x04 + +/** + * @brief DISCON Interrupt + * @details This is issued when FIN or FIN/ACK packet is received from a peer. + */ +#define Sn_IR_DISCON 0x02 + +/** + * @brief CON Interrupt + * @details This is issued one time when the connection with peer is successful and then @ref Sn_SR is changed to @ref SOCK_ESTABLISHED. + */ +#define Sn_IR_CON 0x01 + +/* Sn_SR values */ +/** + * @brief Closed + * @details This indicates that Socket n is released.\n + * When DICON, CLOSE command is ordered, or when a timeout occurs, it is changed to @ref SOCK_CLOSED regardless of previous status. + */ +#define SOCK_CLOSED 0x00 + +/** + * @brief Initiate state + * @details This indicates Socket n is opened with TCP mode.\n + * It is changed to @ref SOCK_INIT when @ref Sn_MR(P[3:0]) = 001 and OPEN command is ordered.\n + * After @ref SOCK_INIT, user can use LISTEN /CONNECT command. + */ +#define SOCK_INIT 0x13 + +/** + * @brief Listen state + * @details This indicates Socket n is operating as TCP servermode and waiting for connection-request (SYN packet) from a peer TCP client.\n + * It will change to @ref SOCK_ESTALBLISHED when the connection-request is successfully accepted.\n + * Otherwise it will change to @ref SOCK_CLOSED after TCPTO @ref Sn_IR(TIMEOUT) = '1') is occurred. + */ +#define SOCK_LISTEN 0x14 + +/** + * @brief Connection state + * @details This indicates Socket n sent the connect-request packet (SYN packet) to a peer.\n + * It is temporarily shown when @ref Sn_SR is changed from @ref SOCK_INIT to @ref SOCK_ESTABLISHED by CONNECT command.\n + * If connect-accept(SYN/ACK packet) is received from the peer at SOCK_SYNSENT, it changes to @ref SOCK_ESTABLISHED.\n + * Otherwise, it changes to @ref SOCK_CLOSED after TCPTO (@ref Sn_IR[TIMEOUT] = '1') is occurred. + */ +#define SOCK_SYNSENT 0x15 + +/** + * @brief Connection state + * @details It indicates Socket n successfully received the connect-request packet (SYN packet) from a peer.\n + * If socket n sends the response (SYN/ACK packet) to the peer successfully, it changes to @ref SOCK_ESTABLISHED. \n + * If not, it changes to @ref SOCK_CLOSED after timeout (@ref Sn_IR[TIMEOUT] = '1') is occurred. + */ +#define SOCK_SYNRECV 0x16 + +/** + * @brief Success to connect + * @details This indicates the status of the connection of Socket n.\n + * It changes to @ref SOCK_ESTABLISHED when the TCP SERVERprocessed the SYN packet from the TCP CLIENTduring @ref SOCK_LISTEN, or + * when the CONNECT command is successful.\n + * During @ref SOCK_ESTABLISHED, DATA packet can be transferred using SEND or RECV command. + */ +#define SOCK_ESTABLISHED 0x17 + +/** + * @brief Closing state + * @details These indicate Socket n is closing.\n + * These are shown in disconnect-process such as active-close and passive-close.\n + * When Disconnect-process is successfully completed, or when timeout occurs, these change to @ref SOCK_CLOSED. + */ +#define SOCK_FIN_WAIT 0x18 + +/** + * @brief Closing state + * @details These indicate Socket n is closing.\n + * These are shown in disconnect-process such as active-close and passive-close.\n + * When Disconnect-process is successfully completed, or when timeout occurs, these change to @ref SOCK_CLOSED. + */ +#define SOCK_CLOSING 0x1A + +/** + * @brief Closing state + * @details These indicate Socket n is closing.\n + * These are shown in disconnect-process such as active-close and passive-close.\n + * When Disconnect-process is successfully completed, or when timeout occurs, these change to @ref SOCK_CLOSED. + */ +#define SOCK_TIME_WAIT 0x1B + +/** + * @brief Closing state + * @details This indicates Socket n received the disconnect-request (FIN packet) from the connected peer.\n + * This is half-closing status, and data can be transferred.\n + * For full-closing, DISCON command is used. But For just-closing, CLOSE command is used. + */ +#define SOCK_CLOSE_WAIT 0x1C + +/** + * @brief Closing state + * @details This indicates Socket n is waiting for the response (FIN/ACK packet) to the disconnect-request (FIN packet) by passive-close.\n + * It changes to @ref SOCK_CLOSED when Socket n received the response successfully, or when timeout(@ref Sn_IR[TIMEOUT] = '1') is occurred. + */ +#define SOCK_LAST_ACK 0x1D + +/** + * @brief UDP socket + * @details This indicates Socket n is opened in UDP mode(@ref Sn_MR(P[3:0]) = '010').\n + * It changes to SOCK_UDP when @ref Sn_MR(P[3:0]) = '010' and @ref Sn_CR_OPEN command is ordered.\n + * Unlike TCP mode, data can be transfered without the connection-process. + */ +#define SOCK_UDP 0x22 + +#define SOCK_IPRAW 0x32 /**< IP raw mode socket */ + +/** + * @brief MAC raw mode socket + * @details This indicates Socket 0 is opened in MACRAW mode (S0_MR(P[3:0]) = 100and is valid only in Socket 0.\n + * It changes to SOCK_MACRAW when S0_MR(P[3:0] = 100and OPEN command is ordered.\n + * Like UDP mode socket, MACRAW mode Socket 0 can transfer a MAC packet (Ethernet frame) without the connection-process. + */ +#define SOCK_MACRAW 0x42 + +//#define SOCK_PPPOE 0x5F + +/* IP PROTOCOL */ +#define IPPROTO_IP 0 //< Dummy for IP +#define IPPROTO_ICMP 1 //< Control message protocol +#define IPPROTO_IGMP 2 //< Internet group management protocol +#define IPPROTO_GGP 3 //< Gateway^2 (deprecated) +#define IPPROTO_TCP 6 //< TCP +#define IPPROTO_PUP 12 //< PUP +#define IPPROTO_UDP 17 //< UDP +#define IPPROTO_IDP 22 //< XNS idp +#define IPPROTO_ND 77 //< UNOFFICIAL net disk protocol +#define IPPROTO_RAW 255 //< Raw IP packet + + +/** + * @brief Enter a critical section + * + * @details It is provided to protect your shared code which are executed without distribution. \n \n + * + * In non-OS environment, It can be just implemented by disabling whole interrupt.\n + * In OS environment, You can replace it to critical section api supported by OS. + * + * \sa WIZCHIP_READ(), WIZCHIP_WRITE(), WIZCHIP_READ_BUF(), WIZCHIP_WRITE_BUF() + * \sa WIZCHIP_CRITICAL_EXIT() + */ +#define WIZCHIP_CRITICAL_ENTER() WIZCHIP.CRIS._enter() + +#ifdef _exit +#undef _exit +#endif + +/** + * @brief Exit a critical section + * + * @details It is provided to protect your shared code which are executed without distribution. \n\n + * + * In non-OS environment, It can be just implemented by disabling whole interrupt. \n + * In OS environment, You can replace it to critical section api supported by OS. + * + * @sa WIZCHIP_READ(), WIZCHIP_WRITE(), WIZCHIP_READ_BUF(), WIZCHIP_WRITE_BUF() + * @sa WIZCHIP_CRITICAL_ENTER() + */ +#define WIZCHIP_CRITICAL_EXIT() WIZCHIP.CRIS._exit() + + +//////////////////////// +// Basic I/O Function // +//////////////////////// + +/** + * @ingroup Basic_IO_function + * @brief It reads 1 byte value from a register. + * @param AddrSel Register address + * @return The value of register + */ +uint8_t WIZCHIP_READ (uint32_t AddrSel); + +/** + * @ingroup Basic_IO_function + * @brief It writes 1 byte value to a register. + * @param AddrSel Register address + * @param wb Write data + * @return void + */ +void WIZCHIP_WRITE(uint32_t AddrSel, uint8_t wb ); + +/** + * @ingroup Basic_IO_function + * @brief It reads sequence data from registers. + * @param AddrSel Register address + * @param pBuf Pointer buffer to read data + * @param len Data length + */ +void WIZCHIP_READ_BUF (uint32_t AddrSel, uint8_t* pBuf, uint16_t len); + +/** + * @ingroup Basic_IO_function + * @brief It writes sequence data to registers. + * @param AddrSel Register address + * @param pBuf Pointer buffer to write data + * @param len Data length + */ +void WIZCHIP_WRITE_BUF(uint32_t AddrSel, uint8_t* pBuf, uint16_t len); + +///////////////////////////////// +// Common Register I/O function // +///////////////////////////////// +/** + * @ingroup Common_register_access_function + * @brief Set Mode Register + * @param (uint8_t)mr The value to be set. + * @sa getMR() + */ +#define setMR(mr) \ + WIZCHIP_WRITE(MR,mr) + + +/** + * @ingroup Common_register_access_function + * @brief Get Mode Register + * @return uint8_t. The value of Mode register. + * @sa setMR() + */ +#define getMR() \ + WIZCHIP_READ(MR) + +/** + * @ingroup Common_register_access_function + * @brief Set gateway IP address + * @param (uint8_t*)gar Pointer variable to set gateway IP address. It should be allocated 4 bytes. + * @sa getGAR() + */ +#define setGAR(gar) \ + WIZCHIP_WRITE_BUF(GAR,gar,4) + +/** + * @ingroup Common_register_access_function + * @brief Get gateway IP address + * @param (uint8_t*)gar Pointer variable to get gateway IP address. It should be allocated 4 bytes. + * @sa setGAR() + */ +#define getGAR(gar) \ + WIZCHIP_READ_BUF(GAR,gar,4) + +/** + * @ingroup Common_register_access_function + * @brief Set subnet mask address + * @param (uint8_t*)subr Pointer variable to set subnet mask address. It should be allocated 4 bytes. + * @sa getSUBR() + */ +#define setSUBR(subr) \ + WIZCHIP_WRITE_BUF(SUBR, subr,4) + + +/** + * @ingroup Common_register_access_function + * @brief Get subnet mask address + * @param (uint8_t*)subr Pointer variable to get subnet mask address. It should be allocated 4 bytes. + * @sa setSUBR() + */ +#define getSUBR(subr) \ + WIZCHIP_READ_BUF(SUBR, subr, 4) + +/** + * @ingroup Common_register_access_function + * @brief Set local MAC address + * @param (uint8_t*)shar Pointer variable to set local MAC address. It should be allocated 6 bytes. + * @sa getSHAR() + */ +#define setSHAR(shar) \ + WIZCHIP_WRITE_BUF(SHAR, shar, 6) + +/** + * @ingroup Common_register_access_function + * @brief Get local MAC address + * @param (uint8_t*)shar Pointer variable to get local MAC address. It should be allocated 6 bytes. + * @sa setSHAR() + */ +#define getSHAR(shar) \ + WIZCHIP_READ_BUF(SHAR, shar, 6) + +/** + * @ingroup Common_register_access_function + * @brief Set local IP address + * @param (uint8_t*)sipr Pointer variable to set local IP address. It should be allocated 4 bytes. + * @sa getSIPR() + */ +#define setSIPR(sipr) \ + WIZCHIP_WRITE_BUF(SIPR, sipr, 4) + +/** + * @ingroup Common_register_access_function + * @brief Get local IP address + * @param (uint8_t*)sipr Pointer variable to get local IP address. It should be allocated 4 bytes. + * @sa setSIPR() + */ +#define getSIPR(sipr) \ + WIZCHIP_READ_BUF(SIPR, sipr, 4) + +/** + * @ingroup Common_register_access_function + * @brief Set INTLEVEL register + * @param (uint16_t)intlevel Value to set @ref INTLEVEL register. + * @sa getINTLEVEL() + */ +#define setINTLEVEL(intlevel) {\ + WIZCHIP_WRITE(INTLEVEL, (uint8_t)(intlevel >> 8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(INTLEVEL,1), (uint8_t) intlevel); \ + } + + +/** + * @ingroup Common_register_access_function + * @brief Get INTLEVEL register + * @return uint16_t. Value of @ref INTLEVEL register. + * @sa setINTLEVEL() + */ +//M20150401 : Type explict declaration +/* +#define getINTLEVEL() \ + ((WIZCHIP_READ(INTLEVEL) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(INTLEVEL,1))) +*/ +#define getINTLEVEL() \ + (((uint16_t)WIZCHIP_READ(INTLEVEL) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(INTLEVEL,1))) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref IR register + * @param (uint8_t)ir Value to set @ref IR register. + * @sa getIR() + */ +#define setIR(ir) \ + WIZCHIP_WRITE(IR, (ir & 0xF0)) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref IR register + * @return uint8_t. Value of @ref IR register. + * @sa setIR() + */ +#define getIR() \ + (WIZCHIP_READ(IR) & 0xF0) +/** + * @ingroup Common_register_access_function + * @brief Set @ref _IMR_ register + * @param (uint8_t)imr Value to set @ref _IMR_ register. + * @sa getIMR() + */ +#define setIMR(imr) \ + WIZCHIP_WRITE(_IMR_, imr) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref _IMR_ register + * @return uint8_t. Value of @ref _IMR_ register. + * @sa setIMR() + */ +#define getIMR() \ + WIZCHIP_READ(_IMR_) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref SIR register + * @param (uint8_t)sir Value to set @ref SIR register. + * @sa getSIR() + */ +#define setSIR(sir) \ + WIZCHIP_WRITE(SIR, sir) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref SIR register + * @return uint8_t. Value of @ref SIR register. + * @sa setSIR() + */ +#define getSIR() \ + WIZCHIP_READ(SIR) +/** + * @ingroup Common_register_access_function + * @brief Set @ref SIMR register + * @param (uint8_t)simr Value to set @ref SIMR register. + * @sa getSIMR() + */ +#define setSIMR(simr) \ + WIZCHIP_WRITE(SIMR, simr) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref SIMR register + * @return uint8_t. Value of @ref SIMR register. + * @sa setSIMR() + */ +#define getSIMR() \ + WIZCHIP_READ(SIMR) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref _RTR_ register + * @param (uint16_t)rtr Value to set @ref _RTR_ register. + * @sa getRTR() + */ +#define setRTR(rtr) {\ + WIZCHIP_WRITE(_RTR_, (uint8_t)(rtr >> 8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(_RTR_,1), (uint8_t) rtr); \ + } + +/** + * @ingroup Common_register_access_function + * @brief Get @ref _RTR_ register + * @return uint16_t. Value of @ref _RTR_ register. + * @sa setRTR() + */ +//M20150401 : Type explict declaration +/* +#define getRTR() \ + ((WIZCHIP_READ(_RTR_) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(_RTR_,1))) +*/ +#define getRTR() \ + (((uint16_t)WIZCHIP_READ(_RTR_) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(_RTR_,1))) + + +/** + * @ingroup Common_register_access_function + * @brief Set @ref _RCR_ register + * @param (uint8_t)rcr Value to set @ref _RCR_ register. + * @sa getRCR() + */ +#define setRCR(rcr) \ + WIZCHIP_WRITE(_RCR_, rcr) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref _RCR_ register + * @return uint8_t. Value of @ref _RCR_ register. + * @sa setRCR() + */ +#define getRCR() \ + WIZCHIP_READ(_RCR_) + +//================================================== test done =========================================================== + +/** + * @ingroup Common_register_access_function + * @brief Set @ref PTIMER register + * @param (uint8_t)ptimer Value to set @ref PTIMER register. + * @sa getPTIMER() + */ +#define setPTIMER(ptimer) \ + WIZCHIP_WRITE(PTIMER, ptimer) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref PTIMER register + * @return uint8_t. Value of @ref PTIMER register. + * @sa setPTIMER() + */ +#define getPTIMER() \ + WIZCHIP_READ(PTIMER) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref PMAGIC register + * @param (uint8_t)pmagic Value to set @ref PMAGIC register. + * @sa getPMAGIC() + */ +#define setPMAGIC(pmagic) \ + WIZCHIP_WRITE(PMAGIC, pmagic) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref PMAGIC register + * @return uint8_t. Value of @ref PMAGIC register. + * @sa setPMAGIC() + */ +#define getPMAGIC() \ + WIZCHIP_READ(PMAGIC) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref PHAR address + * @param (uint8_t*)phar Pointer variable to set PPP destination MAC register address. It should be allocated 6 bytes. + * @sa getPHAR() + */ +#define setPHAR(phar) \ + WIZCHIP_WRITE_BUF(PHAR, phar, 6) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref PHAR address + * @param (uint8_t*)phar Pointer variable to PPP destination MAC register address. It should be allocated 6 bytes. + * @sa setPHAR() + */ +#define getPHAR(phar) \ + WIZCHIP_READ_BUF(PHAR, phar, 6) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref PSID register + * @param (uint16_t)psid Value to set @ref PSID register. + * @sa getPSID() + */ +#define setPSID(psid) {\ + WIZCHIP_WRITE(PSID, (uint8_t)(psid >> 8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(PSID,1), (uint8_t) psid); \ + } + +/** + * @ingroup Common_register_access_function + * @brief Get @ref PSID register + * @return uint16_t. Value of @ref PSID register. + * @sa setPSID() + */ +//uint16_t getPSID(void); +//M20150401 : Type explict declaration +/* +#define getPSID() \ + ((WIZCHIP_READ(PSID) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(PSID,1))) +*/ +#define getPSID() \ + (((uint16_t)WIZCHIP_READ(PSID) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(PSID,1))) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref PMRU register + * @param (uint16_t)pmru Value to set @ref PMRU register. + * @sa getPMRU() + */ +#define setPMRU(pmru) { \ + WIZCHIP_WRITE(PMRU, (uint8_t)(pmru>>8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(PMRU,1), (uint8_t) pmru); \ + } + +/** + * @ingroup Common_register_access_function + * @brief Get @ref PMRU register + * @return uint16_t. Value of @ref PMRU register. + * @sa setPMRU() + */ +//M20150401 : Type explict declaration +/* +#define getPMRU() \ + ((WIZCHIP_READ(PMRU) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(PMRU,1))) +*/ +#define getPMRU() \ + (((uint16_t)WIZCHIP_READ(PMRU) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(PMRU,1))) + +/** + * @ingroup Common_register_access_function + * @brief Get unreachable IP address + * @param (uint8_t*)uipr Pointer variable to get unreachable IP address. It should be allocated 4 bytes. + */ +//M20150401 : Size Error of UIPR (6 -> 4) +/* +#define getUIPR(uipr) \ + WIZCHIP_READ_BUF(UIPR,uipr,6) +*/ +#define getUIPR(uipr) \ + WIZCHIP_READ_BUF(UIPR,uipr,4) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref UPORTR register + * @return uint16_t. Value of @ref UPORTR register. + */ +//M20150401 : Type explict declaration +/* +#define getUPORTR() \ + ((WIZCHIP_READ(UPORTR) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(UPORTR,1))) +*/ +#define getUPORTR() \ + (((uint16_t)WIZCHIP_READ(UPORTR) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(UPORTR,1))) + +/** + * @ingroup Common_register_access_function + * @brief Set @ref PHYCFGR register + * @param (uint8_t)phycfgr Value to set @ref PHYCFGR register. + * @sa getPHYCFGR() + */ +#define setPHYCFGR(phycfgr) \ + WIZCHIP_WRITE(PHYCFGR, phycfgr) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref PHYCFGR register + * @return uint8_t. Value of @ref PHYCFGR register. + * @sa setPHYCFGR() + */ +#define getPHYCFGR() \ + WIZCHIP_READ(PHYCFGR) + +/** + * @ingroup Common_register_access_function + * @brief Get @ref VERSIONR register + * @return uint8_t. Value of @ref VERSIONR register. + */ +#define getVERSIONR() \ + WIZCHIP_READ(VERSIONR) + +///////////////////////////////////// + +/////////////////////////////////// +// Socket N register I/O function // +/////////////////////////////////// +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_MR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)mr Value to set @ref Sn_MR + * @sa getSn_MR() + */ +#define setSn_MR(sn, mr) \ + WIZCHIP_WRITE(Sn_MR(sn),mr) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_MR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_MR. + * @sa setSn_MR() + */ +#define getSn_MR(sn) \ + WIZCHIP_READ(Sn_MR(sn)) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_CR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)cr Value to set @ref Sn_CR + * @sa getSn_CR() + */ +#define setSn_CR(sn, cr) \ + WIZCHIP_WRITE(Sn_CR(sn), cr) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_CR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_CR. + * @sa setSn_CR() + */ +#define getSn_CR(sn) \ + WIZCHIP_READ(Sn_CR(sn)) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_IR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)ir Value to set @ref Sn_IR + * @sa getSn_IR() + */ +#define setSn_IR(sn, ir) \ + WIZCHIP_WRITE(Sn_IR(sn), (ir & 0x1F)) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_IR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_IR. + * @sa setSn_IR() + */ +#define getSn_IR(sn) \ + (WIZCHIP_READ(Sn_IR(sn)) & 0x1F) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_IMR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)imr Value to set @ref Sn_IMR + * @sa getSn_IMR() + */ +#define setSn_IMR(sn, imr) \ + WIZCHIP_WRITE(Sn_IMR(sn), (imr & 0x1F)) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_IMR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_IMR. + * @sa setSn_IMR() + */ +#define getSn_IMR(sn) \ + (WIZCHIP_READ(Sn_IMR(sn)) & 0x1F) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_SR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_SR. + */ +#define getSn_SR(sn) \ + WIZCHIP_READ(Sn_SR(sn)) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_PORT register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint16_t)port Value to set @ref Sn_PORT. + * @sa getSn_PORT() + */ +#define setSn_PORT(sn, port) { \ + WIZCHIP_WRITE(Sn_PORT(sn), (uint8_t)(port >> 8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(Sn_PORT(sn),1), (uint8_t) port); \ + } + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_PORT register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_PORT. + * @sa setSn_PORT() + */ +//M20150401 : Type explict declaration +/* +#define getSn_PORT(sn) \ + ((WIZCHIP_READ(Sn_PORT(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_PORT(sn),1))) +*/ +#define getSn_PORT(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_PORT(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_PORT(sn),1))) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_DHAR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t*)dhar Pointer variable to set socket n destination hardware address. It should be allocated 6 bytes. + * @sa getSn_DHAR() + */ +#define setSn_DHAR(sn, dhar) \ + WIZCHIP_WRITE_BUF(Sn_DHAR(sn), dhar, 6) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_MR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t*)dhar Pointer variable to get socket n destination hardware address. It should be allocated 6 bytes. + * @sa setSn_DHAR() + */ +#define getSn_DHAR(sn, dhar) \ + WIZCHIP_READ_BUF(Sn_DHAR(sn), dhar, 6) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_DIPR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t*)dipr Pointer variable to set socket n destination IP address. It should be allocated 4 bytes. + * @sa getSn_DIPR() + */ +#define setSn_DIPR(sn, dipr) \ + WIZCHIP_WRITE_BUF(Sn_DIPR(sn), dipr, 4) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_DIPR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t*)dipr Pointer variable to get socket n destination IP address. It should be allocated 4 bytes. + * @sa setSn_DIPR() + */ +#define getSn_DIPR(sn, dipr) \ + WIZCHIP_READ_BUF(Sn_DIPR(sn), dipr, 4) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_DPORT register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint16_t)dport Value to set @ref Sn_DPORT + * @sa getSn_DPORT() + */ +#define setSn_DPORT(sn, dport) { \ + WIZCHIP_WRITE(Sn_DPORT(sn), (uint8_t) (dport>>8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(Sn_DPORT(sn),1), (uint8_t) dport); \ + } + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_DPORT register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_DPORT. + * @sa setSn_DPORT() + */ +//M20150401 : Type explict declaration +/* +#define getSn_DPORT(sn) \ + ((WIZCHIP_READ(Sn_DPORT(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_DPORT(sn),1))) +*/ +#define getSn_DPORT(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_DPORT(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_DPORT(sn),1))) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_MSSR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint16_t)mss Value to set @ref Sn_MSSR + * @sa setSn_MSSR() + */ +#define setSn_MSSR(sn, mss) { \ + WIZCHIP_WRITE(Sn_MSSR(sn), (uint8_t)(mss>>8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(Sn_MSSR(sn),1), (uint8_t) mss); \ + } + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_MSSR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_MSSR. + * @sa setSn_MSSR() + */ +//M20150401 : Type explict declaration +/* +#define getSn_MSSR(sn) \ + ((WIZCHIP_READ(Sn_MSSR(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_MSSR(sn),1))) +*/ +#define getSn_MSSR(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_MSSR(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_MSSR(sn),1))) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_TOS register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)tos Value to set @ref Sn_TOS + * @sa getSn_TOS() + */ +#define setSn_TOS(sn, tos) \ + WIZCHIP_WRITE(Sn_TOS(sn), tos) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_TOS register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of Sn_TOS. + * @sa setSn_TOS() + */ +#define getSn_TOS(sn) \ + WIZCHIP_READ(Sn_TOS(sn)) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_TTL register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)ttl Value to set @ref Sn_TTL + * @sa getSn_TTL() + */ +#define setSn_TTL(sn, ttl) \ + WIZCHIP_WRITE(Sn_TTL(sn), ttl) + + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_TTL register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_TTL. + * @sa setSn_TTL() + */ +#define getSn_TTL(sn) \ + WIZCHIP_READ(Sn_TTL(sn)) + + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_RXBUF_SIZE register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)rxbufsize Value to set @ref Sn_RXBUF_SIZE + * @sa getSn_RXBUF_SIZE() + */ +#define setSn_RXBUF_SIZE(sn, rxbufsize) \ + WIZCHIP_WRITE(Sn_RXBUF_SIZE(sn),rxbufsize) + + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_RXBUF_SIZE register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_RXBUF_SIZE. + * @sa setSn_RXBUF_SIZE() + */ +#define getSn_RXBUF_SIZE(sn) \ + WIZCHIP_READ(Sn_RXBUF_SIZE(sn)) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_TXBUF_SIZE register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)txbufsize Value to set @ref Sn_TXBUF_SIZE + * @sa getSn_TXBUF_SIZE() + */ +#define setSn_TXBUF_SIZE(sn, txbufsize) \ + WIZCHIP_WRITE(Sn_TXBUF_SIZE(sn), txbufsize) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_TXBUF_SIZE register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_TXBUF_SIZE. + * @sa setSn_TXBUF_SIZE() + */ +#define getSn_TXBUF_SIZE(sn) \ + WIZCHIP_READ(Sn_TXBUF_SIZE(sn)) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_TX_FSR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_TX_FSR. + */ +uint16_t getSn_TX_FSR(uint8_t sn); + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_TX_RD register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_TX_RD. + */ +//M20150401 : Type explict declaration +/* +#define getSn_TX_RD(sn) \ + ((WIZCHIP_READ(Sn_TX_RD(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_TX_RD(sn),1))) +*/ +#define getSn_TX_RD(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_TX_RD(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_TX_RD(sn),1))) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_TX_WR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint16_t)txwr Value to set @ref Sn_TX_WR + * @sa GetSn_TX_WR() + */ +#define setSn_TX_WR(sn, txwr) { \ + WIZCHIP_WRITE(Sn_TX_WR(sn), (uint8_t)(txwr>>8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(Sn_TX_WR(sn),1), (uint8_t) txwr); \ + } + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_TX_WR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_TX_WR. + * @sa setSn_TX_WR() + */ +//M20150401 : Type explict declaration +/* +#define getSn_TX_WR(sn) \ + ((WIZCHIP_READ(Sn_TX_WR(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_TX_WR(sn),1))) +*/ +#define getSn_TX_WR(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_TX_WR(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_TX_WR(sn),1))) + + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_RX_RSR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_RX_RSR. + */ +uint16_t getSn_RX_RSR(uint8_t sn); + + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_RX_RD register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint16_t)rxrd Value to set @ref Sn_RX_RD + * @sa getSn_RX_RD() + */ +#define setSn_RX_RD(sn, rxrd) { \ + WIZCHIP_WRITE(Sn_RX_RD(sn), (uint8_t)(rxrd>>8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(Sn_RX_RD(sn),1), (uint8_t) rxrd); \ + } + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_RX_RD register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_RX_RD. + * @sa setSn_RX_RD() + */ +//M20150401 : Type explict declaration +/* +#define getSn_RX_RD(sn) \ + ((WIZCHIP_READ(Sn_RX_RD(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_RX_RD(sn),1))) +*/ +#define getSn_RX_RD(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_RX_RD(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_RX_RD(sn),1))) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_RX_WR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_RX_WR. + */ +//M20150401 : Type explict declaration +/* +#define getSn_RX_WR(sn) \ + ((WIZCHIP_READ(Sn_RX_WR(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_RX_WR(sn),1))) +*/ +#define getSn_RX_WR(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_RX_WR(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_RX_WR(sn),1))) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_FRAG register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint16_t)frag Value to set @ref Sn_FRAG + * @sa getSn_FRAD() + */ +#define setSn_FRAG(sn, frag) { \ + WIZCHIP_WRITE(Sn_FRAG(sn), (uint8_t)(frag >>8)); \ + WIZCHIP_WRITE(WIZCHIP_OFFSET_INC(Sn_FRAG(sn),1), (uint8_t) frag); \ + } + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_FRAG register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of @ref Sn_FRAG. + * @sa setSn_FRAG() + */ +//M20150401 : Type explict declaration +/* +#define getSn_FRAG(sn) \ + ((WIZCHIP_READ(Sn_FRAG(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_FRAG(sn),1))) +*/ +#define getSn_FRAG(sn) \ + (((uint16_t)WIZCHIP_READ(Sn_FRAG(sn)) << 8) + WIZCHIP_READ(WIZCHIP_OFFSET_INC(Sn_FRAG(sn),1))) + +/** + * @ingroup Socket_register_access_function + * @brief Set @ref Sn_KPALVTR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param (uint8_t)kpalvt Value to set @ref Sn_KPALVTR + * @sa getSn_KPALVTR() + */ +#define setSn_KPALVTR(sn, kpalvt) \ + WIZCHIP_WRITE(Sn_KPALVTR(sn), kpalvt) + +/** + * @ingroup Socket_register_access_function + * @brief Get @ref Sn_KPALVTR register + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint8_t. Value of @ref Sn_KPALVTR. + * @sa setSn_KPALVTR() + */ +#define getSn_KPALVTR(sn) \ + WIZCHIP_READ(Sn_KPALVTR(sn)) + +////////////////////////////////////// + +///////////////////////////////////// +// Sn_TXBUF & Sn_RXBUF IO function // +///////////////////////////////////// +/** + * @brief Socket_register_access_function + * @brief Gets the max buffer size of socket sn passed as parameter. + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of Socket n RX max buffer size. + */ +//M20150401 : Type explict declaration +/* +#define getSn_RxMAX(sn) \ + (getSn_RXBUF_SIZE(sn) << 10) +*/ +#define getSn_RxMAX(sn) \ + (((uint16_t)getSn_RXBUF_SIZE(sn)) << 10) + +/** + * @brief Socket_register_access_function + * @brief Gets the max buffer size of socket sn passed as parameters. + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @return uint16_t. Value of Socket n TX max buffer size. + */ +//M20150401 : Type explict declaration +/* +#define getSn_TxMAX(sn) \ + (getSn_TXBUF_SIZE(sn) << 10) +*/ +#define getSn_TxMAX(sn) \ + (((uint16_t)getSn_TXBUF_SIZE(sn)) << 10) + +/** + * @ingroup Basic_IO_function + * @brief It copies data to internal TX memory + * + * @details This function reads the Tx write pointer register and after that, + * it copies the wizdata(pointer buffer) of the length of len(variable) bytes to internal TX memory + * and updates the Tx write pointer register. + * This function is being called by send() and sendto() function also. + * + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param wizdata Pointer buffer to write data + * @param len Data length + * @sa wiz_recv_data() + */ +void wiz_send_data(uint8_t sn, uint8_t *wizdata, uint16_t len); + +/** + * @ingroup Basic_IO_function + * @brief It copies data to your buffer from internal RX memory + * + * @details This function read the Rx read pointer register and after that, + * it copies the received data from internal RX memory + * to wizdata(pointer variable) of the length of len(variable) bytes. + * This function is being called by recv() also. + * + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param wizdata Pointer buffer to read data + * @param len Data length + * @sa wiz_send_data() + */ +void wiz_recv_data(uint8_t sn, uint8_t *wizdata, uint16_t len); + +/** + * @ingroup Basic_IO_function + * @brief It discard the received data in RX memory. + * @details It discards the data of the length of len(variable) bytes in internal RX memory. + * @param (uint8_t)sn Socket number. It should be 0 ~ 7. + * @param len Data length + */ +void wiz_recv_ignore(uint8_t sn, uint16_t len); + +/// @cond DOXY_APPLY_CODE +#endif +/// @endcond + +#ifdef __cplusplus +} +#endif + +#endif // _W5500_H_ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_conf.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_conf.c new file mode 100644 index 000000000..f6497ba0b --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_conf.c @@ -0,0 +1,908 @@ +//****************************************************************************/ +//! +//! \file wizchip_conf.c +//! \brief WIZCHIP Config Header File. +//! \version 1.0.1 +//! \date 2013/10/21 +//! \par Revision history +//! <2015/02/05> Notice +//! The version history is not updated after this point. +//! Download the latest version directly from GitHub. Please visit the our GitHub repository for ioLibrary. +//! >> https://github.com/Wiznet/ioLibrary_Driver +//! <2014/05/01> V1.0.1 Refer to M20140501 +//! 1. Explicit type casting in wizchip_bus_readdata() & wizchip_bus_writedata() +// Issued by Mathias ClauBen. +//! uint32_t type converts into ptrdiff_t first. And then recoverting it into uint8_t* +//! For remove the warning when pointer type size is not 32bit. +//! If ptrdiff_t doesn't support in your complier, You should must replace ptrdiff_t into your suitable pointer type. +//! <2013/10/21> 1st Release +//! \author MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//*****************************************************************************/ +//A20140501 : for use the type - ptrdiff_t +#include +// + +#include "wizchip_conf.h" + +///////////// +//M20150401 : Remove ; in the default callback function such as wizchip_cris_enter(), wizchip_cs_select() and etc. +///////////// + +/** + * @brief Default function to enable interrupt. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//void wizchip_cris_enter(void) {}; +void wizchip_cris_enter(void) {} + +/** + * @brief Default function to disable interrupt. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//void wizchip_cris_exit(void) {}; +void wizchip_cris_exit(void) {} + +/** + * @brief Default function to select chip. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//void wizchip_cs_select(void) {}; +void wizchip_cs_select(void) {} + +/** + * @brief Default function to deselect chip. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//void wizchip_cs_deselect(void) {}; +void wizchip_cs_deselect(void) {} + +/** + * @brief Default function to read in direct or indirect interface. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ + //M20150601 : Rename the function for integrating with W5300 +//uint8_t wizchip_bus_readbyte(uint32_t AddrSel) { return * ((volatile uint8_t *)((ptrdiff_t) AddrSel)); } +iodata_t wizchip_bus_readdata(uint32_t AddrSel) { return * ((volatile iodata_t *)((ptrdiff_t) AddrSel)); } + +/** + * @brief Default function to write in direct or indirect interface. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//M20150601 : Rename the function for integrating with W5300 +//void wizchip_bus_writebyte(uint32_t AddrSel, uint8_t wb) { *((volatile uint8_t*)((ptrdiff_t)AddrSel)) = wb; } +void wizchip_bus_writedata(uint32_t AddrSel, iodata_t wb) { *((volatile iodata_t*)((ptrdiff_t)AddrSel)) = wb; } + +/** + * @brief Default function to read in SPI interface. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//uint8_t wizchip_spi_readbyte(void) {return 0;}; +uint8_t wizchip_spi_readbyte(void) {return 0;} + +/** + * @brief Default function to write in SPI interface. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//void wizchip_spi_writebyte(uint8_t wb) {}; +void wizchip_spi_writebyte(uint8_t wb) {} + +/** + * @brief Default function to burst read in SPI interface. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//void wizchip_spi_readburst(uint8_t* pBuf, uint16_t len) {}; +void wizchip_spi_readburst(uint8_t* pBuf, uint16_t len) {} + +/** + * @brief Default function to burst write in SPI interface. + * @note This function help not to access wrong address. If you do not describe this function or register any functions, + * null function is called. + */ +//void wizchip_spi_writeburst(uint8_t* pBuf, uint16_t len) {}; +void wizchip_spi_writeburst(uint8_t* pBuf, uint16_t len) {} + +/** + * @\ref _WIZCHIP instance + */ +// +//M20150401 : For a compiler didnot support a member of structure +// Replace the assignment of struct members with the assingment of array +// +/* +_WIZCHIP WIZCHIP = + { + .id = _WIZCHIP_ID_, + .if_mode = _WIZCHIP_IO_MODE_, + .CRIS._enter = wizchip_cris_enter, + .CRIS._exit = wizchip_cris_exit, + .CS._select = wizchip_cs_select, + .CS._deselect = wizchip_cs_deselect, + .IF.BUS._read_byte = wizchip_bus_readbyte, + .IF.BUS._write_byte = wizchip_bus_writebyte +// .IF.SPI._read_byte = wizchip_spi_readbyte, +// .IF.SPI._write_byte = wizchip_spi_writebyte + }; +*/ +_WIZCHIP WIZCHIP = +{ + _WIZCHIP_IO_MODE_, + _WIZCHIP_ID_ , + { + wizchip_cris_enter, + wizchip_cris_exit + }, + { + wizchip_cs_select, + wizchip_cs_deselect + }, + { + { + //M20150601 : Rename the function + //wizchip_bus_readbyte, + //wizchip_bus_writebyte + wizchip_bus_readdata, + wizchip_bus_writedata + }, + + } +}; + + +static uint8_t _DNS_[4]; // DNS server ip address +static dhcp_mode _DHCP_; // DHCP mode + +void reg_wizchip_cris_cbfunc(void(*cris_en)(void), void(*cris_ex)(void)) +{ + if(!cris_en || !cris_ex) + { + WIZCHIP.CRIS._enter = wizchip_cris_enter; + WIZCHIP.CRIS._exit = wizchip_cris_exit; + } + else + { + WIZCHIP.CRIS._enter = cris_en; + WIZCHIP.CRIS._exit = cris_ex; + } +} + +void reg_wizchip_cs_cbfunc(void(*cs_sel)(void), void(*cs_desel)(void)) +{ + if(!cs_sel || !cs_desel) + { + WIZCHIP.CS._select = wizchip_cs_select; + WIZCHIP.CS._deselect = wizchip_cs_deselect; + } + else + { + WIZCHIP.CS._select = cs_sel; + WIZCHIP.CS._deselect = cs_desel; + } +} + +//M20150515 : For integrating with W5300 +//void reg_wizchip_bus_cbfunc(uint8_t(*bus_rb)(uint32_t addr), void (*bus_wb)(uint32_t addr, uint8_t wb)) +void reg_wizchip_bus_cbfunc(iodata_t(*bus_rb)(uint32_t addr), void (*bus_wb)(uint32_t addr, iodata_t wb)) +{ + while(!(WIZCHIP.if_mode & _WIZCHIP_IO_MODE_BUS_)); + //M20150601 : Rename call back function for integrating with W5300 + /* + if(!bus_rb || !bus_wb) + { + WIZCHIP.IF.BUS._read_byte = wizchip_bus_readbyte; + WIZCHIP.IF.BUS._write_byte = wizchip_bus_writebyte; + } + else + { + WIZCHIP.IF.BUS._read_byte = bus_rb; + WIZCHIP.IF.BUS._write_byte = bus_wb; + } + */ + if(!bus_rb || !bus_wb) + { + WIZCHIP.IF.BUS._read_data = wizchip_bus_readdata; + WIZCHIP.IF.BUS._write_data = wizchip_bus_writedata; + } + else + { + WIZCHIP.IF.BUS._read_data = bus_rb; + WIZCHIP.IF.BUS._write_data = bus_wb; + } +} + +void reg_wizchip_spi_cbfunc(uint8_t (*spi_rb)(void), void (*spi_wb)(uint8_t wb)) +{ + while(!(WIZCHIP.if_mode & _WIZCHIP_IO_MODE_SPI_)); + + if(!spi_rb || !spi_wb) + { + WIZCHIP.IF.SPI._read_byte = wizchip_spi_readbyte; + WIZCHIP.IF.SPI._write_byte = wizchip_spi_writebyte; + } + else + { + WIZCHIP.IF.SPI._read_byte = spi_rb; + WIZCHIP.IF.SPI._write_byte = spi_wb; + } +} + +// 20140626 Eric Added for SPI burst operations +void reg_wizchip_spiburst_cbfunc(void (*spi_rb)(uint8_t* pBuf, uint16_t len), void (*spi_wb)(uint8_t* pBuf, uint16_t len)) +{ + while(!(WIZCHIP.if_mode & _WIZCHIP_IO_MODE_SPI_)); + + if(!spi_rb || !spi_wb) + { + WIZCHIP.IF.SPI._read_burst = wizchip_spi_readburst; + WIZCHIP.IF.SPI._write_burst = wizchip_spi_writeburst; + } + else + { + WIZCHIP.IF.SPI._read_burst = spi_rb; + WIZCHIP.IF.SPI._write_burst = spi_wb; + } +} + +int8_t ctlwizchip(ctlwizchip_type cwtype, void* arg) +{ +#if _WIZCHIP_ == W5100S || _WIZCHIP_ == W5200 || _WIZCHIP_ == W5500 + uint8_t tmp = 0; +#endif + uint8_t* ptmp[2] = {0,0}; + switch(cwtype) + { + case CW_RESET_WIZCHIP: + wizchip_sw_reset(); + break; + case CW_INIT_WIZCHIP: + if(arg != 0) + { + ptmp[0] = (uint8_t*)arg; + ptmp[1] = ptmp[0] + _WIZCHIP_SOCK_NUM_; + } + return wizchip_init(ptmp[0], ptmp[1]); + case CW_CLR_INTERRUPT: + wizchip_clrinterrupt(*((intr_kind*)arg)); + break; + case CW_GET_INTERRUPT: + *((intr_kind*)arg) = wizchip_getinterrupt(); + break; + case CW_SET_INTRMASK: + wizchip_setinterruptmask(*((intr_kind*)arg)); + break; + case CW_GET_INTRMASK: + *((intr_kind*)arg) = wizchip_getinterruptmask(); + break; + //M20150601 : This can be supported by W5200, W5500 + //#if _WIZCHIP_ > W5100 + #if (_WIZCHIP_ == W5200 || _WIZCHIP_ == W5500) + case CW_SET_INTRTIME: + setINTLEVEL(*(uint16_t*)arg); + break; + case CW_GET_INTRTIME: + *(uint16_t*)arg = getINTLEVEL(); + break; + #endif + case CW_GET_ID: + ((uint8_t*)arg)[0] = WIZCHIP.id[0]; + ((uint8_t*)arg)[1] = WIZCHIP.id[1]; + ((uint8_t*)arg)[2] = WIZCHIP.id[2]; + ((uint8_t*)arg)[3] = WIZCHIP.id[3]; + ((uint8_t*)arg)[4] = WIZCHIP.id[4]; + ((uint8_t*)arg)[5] = 0; + break; + #if _WIZCHIP_ == W5100S || _WIZCHIP_ == W5500 + case CW_RESET_PHY: + wizphy_reset(); + break; + case CW_SET_PHYCONF: + wizphy_setphyconf((wiz_PhyConf*)arg); + break; + case CW_GET_PHYCONF: + wizphy_getphyconf((wiz_PhyConf*)arg); + break; + case CW_GET_PHYSTATUS: + break; + case CW_SET_PHYPOWMODE: + return wizphy_setphypmode(*(uint8_t*)arg); + #endif + #if _WIZCHIP_ == W5100S || _WIZCHIP_ == W5200 || _WIZCHIP_ == W5500 + case CW_GET_PHYPOWMODE: + tmp = wizphy_getphypmode(); + if((int8_t)tmp == -1) return -1; + *(uint8_t*)arg = tmp; + break; + case CW_GET_PHYLINK: + tmp = wizphy_getphylink(); + if((int8_t)tmp == -1) return -1; + *(uint8_t*)arg = tmp; + break; + #endif + default: + return -1; + } + return 0; +} + + +int8_t ctlnetwork(ctlnetwork_type cntype, void* arg) +{ + + switch(cntype) + { + case CN_SET_NETINFO: + wizchip_setnetinfo((wiz_NetInfo*)arg); + break; + case CN_GET_NETINFO: + wizchip_getnetinfo((wiz_NetInfo*)arg); + break; + case CN_SET_NETMODE: + return wizchip_setnetmode(*(netmode_type*)arg); + case CN_GET_NETMODE: + *(netmode_type*)arg = wizchip_getnetmode(); + break; + case CN_SET_TIMEOUT: + wizchip_settimeout((wiz_NetTimeout*)arg); + break; + case CN_GET_TIMEOUT: + wizchip_gettimeout((wiz_NetTimeout*)arg); + break; + default: + return -1; + } + return 0; +} + +void wizchip_sw_reset(void) +{ + uint8_t gw[4], sn[4], sip[4]; + uint8_t mac[6]; +//A20150601 +#if _WIZCHIP_IO_MODE_ == _WIZCHIP_IO_MODE_BUS_INDIR_ + uint16_t mr = (uint16_t)getMR(); + setMR(mr | MR_IND); +#endif +// + getSHAR(mac); + getGAR(gw); getSUBR(sn); getSIPR(sip); + setMR(MR_RST); + getMR(); // for delay +//A2015051 : For indirect bus mode +#if _WIZCHIP_IO_MODE_ == _WIZCHIP_IO_MODE_BUS_INDIR_ + setMR(mr | MR_IND); +#endif +// + setSHAR(mac); + setGAR(gw); + setSUBR(sn); + setSIPR(sip); +} + +int8_t wizchip_init(uint8_t* txsize, uint8_t* rxsize) +{ + int8_t i; +#if _WIZCHIP_ < W5200 + int8_t j; +#endif + int8_t tmp = 0; + wizchip_sw_reset(); + if(txsize) + { + tmp = 0; + //M20150601 : For integrating with W5300 + #if _WIZCHIP_ == W5300 + for(i = 0 ; i < _WIZCHIP_SOCK_NUM_; i++) + { + if(txsize[i] >= 64) return -1; //No use 64KB even if W5300 support max 64KB memory allocation + tmp += txsize[i]; + if(tmp > 128) return -1; + } + if(tmp % 8) return -1; + #else + for(i = 0 ; i < _WIZCHIP_SOCK_NUM_; i++) + { + tmp += txsize[i]; + + #if _WIZCHIP_ < W5200 //2016.10.28 peter add condition for w5100 and w5100s + if(tmp > 8) return -1; + #else + if(tmp > 16) return -1; + #endif + } + for(i = 0 ; i < _WIZCHIP_SOCK_NUM_; i++) + { + #if _WIZCHIP_ < W5200 //2016.10.28 peter add condition for w5100 + j = 0; + while((txsize[i] >> j != 1)&&(txsize[i] !=0)){j++;} + setSn_TXBUF_SIZE(i, j); + #else + setSn_TXBUF_SIZE(i, txsize[i]); + #endif + } + + #endif + } + + if(rxsize) + { + tmp = 0; + #if _WIZCHIP_ == W5300 + for(i = 0 ; i < _WIZCHIP_SOCK_NUM_; i++) + { + if(rxsize[i] >= 64) return -1; //No use 64KB even if W5300 support max 64KB memory allocation + tmp += rxsize[i]; + if(tmp > 128) return -1; + } + if(tmp % 8) return -1; + #else + for(i = 0 ; i < _WIZCHIP_SOCK_NUM_; i++) + { + tmp += rxsize[i]; + #if _WIZCHIP_ < W5200 //2016.10.28 peter add condition for w5100 and w5100s + if(tmp > 8) return -1; + #else + if(tmp > 16) return -1; + #endif + } + + for(i = 0 ; i < _WIZCHIP_SOCK_NUM_; i++) + { + #if _WIZCHIP_ < W5200 // add condition for w5100 + j = 0; + while((rxsize[i] >> j != 1)&&(txsize[i] !=0)){j++;} + setSn_RXBUF_SIZE(i, j); + #else + setSn_RXBUF_SIZE(i, rxsize[i]); + #endif + } + #endif + } + return 0; +} + +void wizchip_clrinterrupt(intr_kind intr) +{ + uint8_t ir = (uint8_t)intr; + uint8_t sir = (uint8_t)((uint16_t)intr >> 8); +#if _WIZCHIP_ < W5500 + ir |= (1<<4); // IK_WOL +#endif +#if _WIZCHIP_ == W5200 + ir |= (1 << 6); +#endif + +#if _WIZCHIP_ < W5200 + sir &= 0x0F; +#endif + +#if _WIZCHIP_ <= W5100S + ir |= sir; + setIR(ir); +//A20150601 : For integrating with W5300 +#elif _WIZCHIP_ == W5300 + setIR( ((((uint16_t)ir) << 8) | (((uint16_t)sir) & 0x00FF)) ); +#else + setIR(ir); +//M20200227 : For clear + //setSIR(sir); + for(ir=0; ir<8; ir++){ + if(sir & (0x01 <> 8); + sir = (uint8_t)ret; +#else + ir = getIR(); + sir = getSIR(); +#endif + +//M20150601 : For Integrating with W5300 +//#if _WIZCHIP_ < W5500 +#if _WIZCHIP_ < W5200 + ir &= ~(1<<4); // IK_WOL +#endif +#if _WIZCHIP_ == W5200 + ir &= ~(1 << 6); +#endif + ret = sir; + ret = (ret << 8) + ir; + return (intr_kind)ret; +} + +void wizchip_setinterruptmask(intr_kind intr) +{ + uint8_t imr = (uint8_t)intr; + uint8_t simr = (uint8_t)((uint16_t)intr >> 8); +#if _WIZCHIP_ < W5500 + imr &= ~(1<<4); // IK_WOL +#endif +#if _WIZCHIP_ == W5200 + imr &= ~(1 << 6); +#endif + +#if _WIZCHIP_ < W5200 + simr &= 0x0F; + imr |= simr; + setIMR(imr); +//A20150601 : For integrating with W5300 +#elif _WIZCHIP_ == W5300 + setIMR( ((((uint16_t)imr) << 8) | (((uint16_t)simr) & 0x00FF)) ); +#else + setIMR(imr); + setSIMR(simr); +#endif +} + +intr_kind wizchip_getinterruptmask(void) +{ + uint8_t imr = 0; + uint8_t simr = 0; + uint16_t ret = 0; +#if _WIZCHIP_ < W5200 + imr = getIMR(); + simr = imr & 0x0F; +//A20150601 : For integrating with W5300 +#elif _WIZCHIP_ == W5300 + ret = getIMR(); + imr = (uint8_t)(ret >> 8); + simr = (uint8_t)ret; +#else + imr = getIMR(); + simr = getSIMR(); +#endif + +#if _WIZCHIP_ < W5500 + imr &= ~(1<<4); // IK_WOL +#endif +#if _WIZCHIP_ == W5200 + imr &= ~(1 << 6); // IK_DEST_UNREACH +#endif + ret = simr; + ret = (ret << 8) + imr; + return (intr_kind)ret; +} + +int8_t wizphy_getphylink(void) +{ + int8_t tmp = PHY_LINK_OFF; +#if _WIZCHIP_ == W5100S + if(getPHYSR() & PHYSR_LNK) + tmp = PHY_LINK_ON; +#elif _WIZCHIP_ == W5200 + if(getPHYSTATUS() & PHYSTATUS_LINK) + tmp = PHY_LINK_ON; +#elif _WIZCHIP_ == W5500 + if(getPHYCFGR() & PHYCFGR_LNK_ON) + tmp = PHY_LINK_ON; + +#else + tmp = -1; +#endif + return tmp; +} + +#if _WIZCHIP_ > W5100 + +int8_t wizphy_getphypmode(void) +{ + int8_t tmp = 0; + #if _WIZCHIP_ == W5200 + if(getPHYSTATUS() & PHYSTATUS_POWERDOWN) + tmp = PHY_POWER_DOWN; + else + tmp = PHY_POWER_NORM; + #elif _WIZCHIP_ == 5500 + if((getPHYCFGR() & PHYCFGR_OPMDC_ALLA) == PHYCFGR_OPMDC_PDOWN) + tmp = PHY_POWER_DOWN; + else + tmp = PHY_POWER_NORM; + #else + tmp = -1; + #endif + return tmp; +} +#endif + +#if _WIZCHIP_ == W5100S +void wizphy_reset(void) +{ + uint16_t tmp = wiz_mdio_read(PHYMDIO_BMCR); + tmp |= BMCR_RESET; + wiz_mdio_write(PHYMDIO_BMCR, tmp); + while(wiz_mdio_read(PHYMDIO_BMCR)&BMCR_RESET){} +} + +void wizphy_setphyconf(wiz_PhyConf* phyconf) +{ + uint16_t tmp = wiz_mdio_read(PHYMDIO_BMCR); + if(phyconf->mode == PHY_MODE_AUTONEGO) + tmp |= BMCR_AUTONEGO; + else + { + tmp &= ~BMCR_AUTONEGO; + if(phyconf->duplex == PHY_DUPLEX_FULL) + { + tmp |= BMCR_DUP; + } + else + { + tmp &= ~BMCR_DUP; + } + if(phyconf->speed == PHY_SPEED_100) + { + tmp |= BMCR_SPEED; + } + else + { + tmp &= ~BMCR_SPEED; + } + } + wiz_mdio_write(PHYMDIO_BMCR, tmp); +} + +void wizphy_getphyconf(wiz_PhyConf* phyconf) +{ + uint16_t tmp = 0; + tmp = wiz_mdio_read(PHYMDIO_BMCR); + phyconf->by = PHY_CONFBY_SW; + if(tmp & BMCR_AUTONEGO) + { + phyconf->mode = PHY_MODE_AUTONEGO; + } + else + { + phyconf->mode = PHY_MODE_MANUAL; + if(tmp&BMCR_DUP) phyconf->duplex = PHY_DUPLEX_FULL; + else phyconf->duplex = PHY_DUPLEX_HALF; + if(tmp&BMCR_SPEED) phyconf->speed = PHY_SPEED_100; + else phyconf->speed = PHY_SPEED_10; + } +} + +int8_t wizphy_setphypmode(uint8_t pmode) +{ + uint16_t tmp = 0; + tmp = wiz_mdio_read(PHYMDIO_BMCR); + if( pmode == PHY_POWER_DOWN) + { + tmp |= BMCR_PWDN; + } + else + { + tmp &= ~BMCR_PWDN; + } + wiz_mdio_write(PHYMDIO_BMCR, tmp); + tmp = wiz_mdio_read(PHYMDIO_BMCR); + if( pmode == PHY_POWER_DOWN) + { + if(tmp & BMCR_PWDN) return 0; + } + else + { + if((tmp & BMCR_PWDN) != BMCR_PWDN) return 0; + } + return -1; +} + +#endif +#if _WIZCHIP_ == W5500 +void wizphy_reset(void) +{ + uint8_t tmp = getPHYCFGR(); + tmp &= PHYCFGR_RST; + setPHYCFGR(tmp); + tmp = getPHYCFGR(); + tmp |= ~PHYCFGR_RST; + setPHYCFGR(tmp); +} + +void wizphy_setphyconf(wiz_PhyConf* phyconf) +{ + uint8_t tmp = 0; + if(phyconf->by == PHY_CONFBY_SW) + tmp |= PHYCFGR_OPMD; + else + tmp &= ~PHYCFGR_OPMD; + if(phyconf->mode == PHY_MODE_AUTONEGO) + tmp |= PHYCFGR_OPMDC_ALLA; + else + { + if(phyconf->duplex == PHY_DUPLEX_FULL) + { + if(phyconf->speed == PHY_SPEED_100) + tmp |= PHYCFGR_OPMDC_100F; + else + tmp |= PHYCFGR_OPMDC_10F; + } + else + { + if(phyconf->speed == PHY_SPEED_100) + tmp |= PHYCFGR_OPMDC_100H; + else + tmp |= PHYCFGR_OPMDC_10H; + } + } + setPHYCFGR(tmp); + wizphy_reset(); +} + +void wizphy_getphyconf(wiz_PhyConf* phyconf) +{ + uint8_t tmp = 0; + tmp = getPHYCFGR(); + phyconf->by = (tmp & PHYCFGR_OPMD) ? PHY_CONFBY_SW : PHY_CONFBY_HW; + switch(tmp & PHYCFGR_OPMDC_ALLA) + { + case PHYCFGR_OPMDC_ALLA: + case PHYCFGR_OPMDC_100FA: + phyconf->mode = PHY_MODE_AUTONEGO; + break; + default: + phyconf->mode = PHY_MODE_MANUAL; + break; + } + switch(tmp & PHYCFGR_OPMDC_ALLA) + { + case PHYCFGR_OPMDC_100FA: + case PHYCFGR_OPMDC_100F: + case PHYCFGR_OPMDC_100H: + phyconf->speed = PHY_SPEED_100; + break; + default: + phyconf->speed = PHY_SPEED_10; + break; + } + switch(tmp & PHYCFGR_OPMDC_ALLA) + { + case PHYCFGR_OPMDC_100FA: + case PHYCFGR_OPMDC_100F: + case PHYCFGR_OPMDC_10F: + phyconf->duplex = PHY_DUPLEX_FULL; + break; + default: + phyconf->duplex = PHY_DUPLEX_HALF; + break; + } +} + +void wizphy_getphystat(wiz_PhyConf* phyconf) +{ + uint8_t tmp = getPHYCFGR(); + phyconf->duplex = (tmp & PHYCFGR_DPX_FULL) ? PHY_DUPLEX_FULL : PHY_DUPLEX_HALF; + phyconf->speed = (tmp & PHYCFGR_SPD_100) ? PHY_SPEED_100 : PHY_SPEED_10; +} + +int8_t wizphy_setphypmode(uint8_t pmode) +{ + uint8_t tmp = 0; + tmp = getPHYCFGR(); + if((tmp & PHYCFGR_OPMD)== 0) return -1; + tmp &= ~PHYCFGR_OPMDC_ALLA; + if( pmode == PHY_POWER_DOWN) + tmp |= PHYCFGR_OPMDC_PDOWN; + else + tmp |= PHYCFGR_OPMDC_ALLA; + setPHYCFGR(tmp); + wizphy_reset(); + tmp = getPHYCFGR(); + if( pmode == PHY_POWER_DOWN) + { + if(tmp & PHYCFGR_OPMDC_PDOWN) return 0; + } + else + { + if(tmp & PHYCFGR_OPMDC_ALLA) return 0; + } + return -1; +} +#endif + + +void wizchip_setnetinfo(wiz_NetInfo* pnetinfo) +{ + setSHAR(pnetinfo->mac); + setGAR(pnetinfo->gw); + setSUBR(pnetinfo->sn); + setSIPR(pnetinfo->ip); + _DNS_[0] = pnetinfo->dns[0]; + _DNS_[1] = pnetinfo->dns[1]; + _DNS_[2] = pnetinfo->dns[2]; + _DNS_[3] = pnetinfo->dns[3]; + _DHCP_ = pnetinfo->dhcp; +} + +void wizchip_getnetinfo(wiz_NetInfo* pnetinfo) +{ + getSHAR(pnetinfo->mac); + getGAR(pnetinfo->gw); + getSUBR(pnetinfo->sn); + getSIPR(pnetinfo->ip); + pnetinfo->dns[0]= _DNS_[0]; + pnetinfo->dns[1]= _DNS_[1]; + pnetinfo->dns[2]= _DNS_[2]; + pnetinfo->dns[3]= _DNS_[3]; + pnetinfo->dhcp = _DHCP_; +} + +int8_t wizchip_setnetmode(netmode_type netmode) +{ + uint8_t tmp = 0; +#if _WIZCHIP_ != W5500 + if(netmode & ~(NM_WAKEONLAN | NM_PPPOE | NM_PINGBLOCK)) return -1; +#else + if(netmode & ~(NM_WAKEONLAN | NM_PPPOE | NM_PINGBLOCK | NM_FORCEARP)) return -1; +#endif + tmp = getMR(); + tmp |= (uint8_t)netmode; + setMR(tmp); + return 0; +} + +netmode_type wizchip_getnetmode(void) +{ + return (netmode_type) getMR(); +} + +void wizchip_settimeout(wiz_NetTimeout* nettime) +{ + setRCR(nettime->retry_cnt); + setRTR(nettime->time_100us); +} + +void wizchip_gettimeout(wiz_NetTimeout* nettime) +{ + nettime->retry_cnt = getRCR(); + nettime->time_100us = getRTR(); +} diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_conf.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_conf.h new file mode 100644 index 000000000..698f82ba4 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_conf.h @@ -0,0 +1,661 @@ +//***************************************************************************** +// +//! \file wizchip_conf.h +//! \brief WIZCHIP Config Header File. +//! \version 1.0.0 +//! \date 2013/10/21 +//! \par Revision history +//! <2015/02/05> Notice +//! The version history is not updated after this point. +//! Download the latest version directly from GitHub. Please visit the our GitHub repository for ioLibrary. +//! >> https://github.com/Wiznet/ioLibrary_Driver +//! <2013/10/21> 1st Release +//! \author MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** + +/** + * @defgroup extra_functions 2. WIZnet Extra Functions + * + * @brief These functions is optional function. It could be replaced at WIZCHIP I/O function because they were made by WIZCHIP I/O functions. + * @details There are functions of configuring WIZCHIP, network, interrupt, phy, network information and timer. \n + * + */ + +#ifndef _WIZCHIP_CONF_H_ +#define _WIZCHIP_CONF_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +/** + * @brief Select WIZCHIP. + * @todo You should select one, \b W5100, \b W5100S, \b W5200, \b W5300, \b W5500 or etc. \n\n + * ex> #define \_WIZCHIP_ W5500 + */ + +#define W5100 5100 +#define W5100S 5100+5 +#define W5200 5200 +#define W5300 5300 +#define W5500 5500 + +#ifndef _WIZCHIP_ +#define _WIZCHIP_ W5500 // W5100, W5100S, W5200, W5300, W5500 +#endif + +#define _WIZCHIP_IO_MODE_NONE_ 0x0000 +#define _WIZCHIP_IO_MODE_BUS_ 0x0100 /**< Bus interface mode */ +#define _WIZCHIP_IO_MODE_SPI_ 0x0200 /**< SPI interface mode */ +//#define _WIZCHIP_IO_MODE_IIC_ 0x0400 +//#define _WIZCHIP_IO_MODE_SDIO_ 0x0800 +// Add to +// + +#define _WIZCHIP_IO_MODE_BUS_DIR_ (_WIZCHIP_IO_MODE_BUS_ + 1) /**< BUS interface mode for direct */ +#define _WIZCHIP_IO_MODE_BUS_INDIR_ (_WIZCHIP_IO_MODE_BUS_ + 2) /**< BUS interface mode for indirect */ + +#define _WIZCHIP_IO_MODE_SPI_VDM_ (_WIZCHIP_IO_MODE_SPI_ + 1) /**< SPI interface mode for variable length data*/ +#define _WIZCHIP_IO_MODE_SPI_FDM_ (_WIZCHIP_IO_MODE_SPI_ + 2) /**< SPI interface mode for fixed length data mode*/ +#define _WIZCHIP_IO_MODE_SPI_5500_ (_WIZCHIP_IO_MODE_SPI_ + 3) /**< SPI interface mode for fixed length data mode*/ + +#if (_WIZCHIP_ == W5100) + #define _WIZCHIP_ID_ "W5100\0" +/** + * @brief Define interface mode. + * @todo you should select interface mode as chip. Select one of @ref \_WIZCHIP_IO_MODE_SPI_ , @ref \_WIZCHIP_IO_MODE_BUS_DIR_ or @ref \_WIZCHIP_IO_MODE_BUS_INDIR_ + */ +// #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_BUS_DIR_ +// #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_BUS_INDIR_ + #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_SPI_ + +//A20150601 : Define the unit of IO DATA. + typedef uint8_t iodata_t; +//A20150401 : Indclude W5100.h file + #include "W5100/w5100.h" + +#elif (_WIZCHIP_ == W5100S) +#define _WIZCHIP_ID_ "W5100S\0" +/** +* @brief Define interface mode. +* @todo you should select interface mode as chip. Select one of @ref \_WIZCHIP_IO_MODE_SPI_ , @ref \_WIZCHIP_IO_MODE_BUS_DIR_ or @ref \_WIZCHIP_IO_MODE_BUS_INDIR_ +*/ +// #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_BUS_INDIR_ + //#define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_SPI_5500_ + #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_SPI_ + +//A20150601 : Define the unit of IO DATA. + typedef uint8_t iodata_t; +//A20150401 : Indclude W5100.h file + #include "W5100S/w5100s.h" +#elif (_WIZCHIP_ == W5200) + #define _WIZCHIP_ID_ "W5200\0" +/** + * @brief Define interface mode. + * @todo you should select interface mode as chip. Select one of @ref \_WIZCHIP_IO_MODE_SPI_ or @ref \ _WIZCHIP_IO_MODE_BUS_INDIR_ + */ +#ifndef _WIZCHIP_IO_MODE_ +// #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_BUS_INDIR_ + #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_SPI_ +#endif +//A20150601 : Define the unit of IO DATA. + typedef uint8_t iodata_t; + #include "W5200/w5200.h" +#elif (_WIZCHIP_ == W5500) + #define _WIZCHIP_ID_ "W5500\0" + +/** + * @brief Define interface mode. \n + * @todo Should select interface mode as chip. + * - @ref \_WIZCHIP_IO_MODE_SPI_ \n + * -@ref \_WIZCHIP_IO_MODE_SPI_VDM_ : Valid only in @ref \_WIZCHIP_ == W5500 \n + * -@ref \_WIZCHIP_IO_MODE_SPI_FDM_ : Valid only in @ref \_WIZCHIP_ == W5500 \n + * - @ref \_WIZCHIP_IO_MODE_BUS_ \n + * - @ref \_WIZCHIP_IO_MODE_BUS_DIR_ \n + * - @ref \_WIZCHIP_IO_MODE_BUS_INDIR_ \n + * - Others will be defined in future. \n\n + * ex> #define \_WIZCHIP_IO_MODE_ \_WIZCHIP_IO_MODE_SPI_VDM_ + * + */ +#ifndef _WIZCHIP_IO_MODE_ + //#define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_SPI_FDM_ + #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_SPI_VDM_ +#endif +//A20150601 : Define the unit of IO DATA. + typedef uint8_t iodata_t; + #include "W5500/w5500.h" +#elif ( _WIZCHIP_ == W5300) + #define _WIZCHIP_ID_ "W5300\0" +/** + * @brief Define interface mode. + * @todo you should select interface mode as chip. Select one of @ref \_WIZCHIP_IO_MODE_SPI_ , @ref \_WIZCHIP_IO_MODE_BUS_DIR_ or @ref \_WIZCHIP_IO_MODE_BUS_INDIR_ + */ +#ifndef _WIZCHIP_IO_MODE_ +// #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_BUS_DIR_ + #define _WIZCHIP_IO_MODE_ _WIZCHIP_IO_MODE_BUS_INDIR_ +#endif + +//A20150601 : Define the unit and bus width of IO DATA. + /** + * @brief Select the data width 8 or 16 bits. + * @todo you should select the bus width. Select one of 8 or 16. + */ + #ifndef _WIZCHIP_IO_BUS_WIDTH_ + #define _WIZCHIP_IO_BUS_WIDTH_ 8 // 16 + #endif + #if _WIZCHIP_IO_BUS_WIDTH_ == 8 + typedef uint8_t iodata_t; + #elif _WIZCHIP_IO_BUS_WIDTH_ == 16 + typedef uint16_t iodata_t; + #else + #error "Unknown _WIZCHIP_IO_BUS_WIDTH_. It should be 8 or 16." + #endif +// + #include "W5300/w5300.h" +#else + #error "Unknown defined _WIZCHIP_. You should define one of 5100, 5200, and 5500 !!!" +#endif + +#ifndef _WIZCHIP_IO_MODE_ + #error "Undefined _WIZCHIP_IO_MODE_. You should define it !!!" +#endif + +/** + * @brief Define I/O base address when BUS IF mode. + * @todo Should re-define it to fit your system when BUS IF Mode (@ref \_WIZCHIP_IO_MODE_BUS_, + * @ref \_WIZCHIP_IO_MODE_BUS_DIR_, @ref \_WIZCHIP_IO_MODE_BUS_INDIR_). \n\n + * ex> #define \_WIZCHIP_IO_BASE_ 0x00008000 + */ +#if _WIZCHIP_IO_MODE_ & _WIZCHIP_IO_MODE_BUS_ + #define _WIZCHIP_IO_BASE_ 0x60000000 // for 5100S IND +#elif _WIZCHIP_IO_MODE_ & _WIZCHIP_IO_MODE_SPI_ + #define _WIZCHIP_IO_BASE_ 0x00000000 // for 5100S SPI +#endif + +#ifndef _WIZCHIP_IO_BASE_ +#define _WIZCHIP_IO_BASE_ 0x00000000 // 0x8000 +#endif + +//M20150401 : Typing Error +//#if _WIZCHIP_IO_MODE_ & _WIZCHIP_IO_MODE_BUS +#if _WIZCHIP_IO_MODE_ & _WIZCHIP_IO_MODE_BUS_ + #ifndef _WIZCHIP_IO_BASE_ + #error "You should be define _WIZCHIP_IO_BASE to fit your system memory map." + #endif +#endif + +#if _WIZCHIP_ >= W5200 + #define _WIZCHIP_SOCK_NUM_ 8 ///< The count of independant socket of @b WIZCHIP +#else + #define _WIZCHIP_SOCK_NUM_ 4 ///< The count of independant socket of @b WIZCHIP +#endif + + +/******************************************************** +* WIZCHIP BASIC IF functions for SPI, SDIO, I2C , ETC. +*********************************************************/ +/** + * @ingroup DATA_TYPE + * @brief The set of callback functions for W5500:@ref WIZCHIP_IO_Functions W5200:@ref WIZCHIP_IO_Functions_W5200 + */ +typedef struct __WIZCHIP +{ + uint16_t if_mode; ///< host interface mode + uint8_t id[7]; ///< @b WIZCHIP ID such as @b 5100, @b 5200, @b 5500, and so on. + /** + * The set of critical section callback func. + */ + struct _CRIS + { + void (*_enter) (void); ///< crtical section enter + void (*_exit) (void); ///< critial section exit + }CRIS; + /** + * The set of @ref \_WIZCHIP_ select control callback func. + */ + struct _CS + { + void (*_select) (void); ///< @ref \_WIZCHIP_ selected + void (*_deselect)(void); ///< @ref \_WIZCHIP_ deselected + }CS; + /** + * The set of interface IO callback func. + */ + union _IF + { + /** + * For BUS interface IO + */ + //M20156501 : Modify the function name for integrating with W5300 + //struct + //{ + // uint8_t (*_read_byte) (uint32_t AddrSel); + // void (*_write_byte) (uint32_t AddrSel, uint8_t wb); + //}BUS; + struct + { + iodata_t (*_read_data) (uint32_t AddrSel); + void (*_write_data) (uint32_t AddrSel, iodata_t wb); + }BUS; + + /** + * For SPI interface IO + */ + struct + { + uint8_t (*_read_byte) (void); + void (*_write_byte) (uint8_t wb); + void (*_read_burst) (uint8_t* pBuf, uint16_t len); + void (*_write_burst) (uint8_t* pBuf, uint16_t len); + }SPI; + // To be added + // + }IF; +}_WIZCHIP; + +extern _WIZCHIP WIZCHIP; + +/** + * @ingroup DATA_TYPE + * WIZCHIP control type enumration used in @ref ctlwizchip(). + */ +typedef enum +{ + CW_RESET_WIZCHIP, ///< Resets WIZCHIP by softly + CW_INIT_WIZCHIP, ///< Initializes to WIZCHIP with SOCKET buffer size 2 or 1 dimension array typed uint8_t. + CW_GET_INTERRUPT, ///< Get Interrupt status of WIZCHIP + CW_CLR_INTERRUPT, ///< Clears interrupt + CW_SET_INTRMASK, ///< Masks interrupt + CW_GET_INTRMASK, ///< Get interrupt mask + CW_SET_INTRTIME, ///< Set interval time between the current and next interrupt. + CW_GET_INTRTIME, ///< Set interval time between the current and next interrupt. + CW_GET_ID, ///< Gets WIZCHIP name. + +//D20150601 : For no modification your application code +//#if _WIZCHIP_ == W5500 + CW_RESET_PHY, ///< Resets internal PHY. Valid Only W5500 + CW_SET_PHYCONF, ///< When PHY configured by internal register, PHY operation mode (Manual/Auto, 10/100, Half/Full). Valid Only W5000 + CW_GET_PHYCONF, ///< Get PHY operation mode in internal register. Valid Only W5500 + CW_GET_PHYSTATUS, ///< Get real PHY status on operating. Valid Only W5500 + CW_SET_PHYPOWMODE, ///< Set PHY power mode as normal and down when PHYSTATUS.OPMD == 1. Valid Only W5500 +//#endif +//D20150601 : For no modification your application code +//#if _WIZCHIP_ == W5200 || _WIZCHIP_ == W5500 + CW_GET_PHYPOWMODE, ///< Get PHY Power mode as down or normal, Valid Only W5100, W5200 + CW_GET_PHYLINK ///< Get PHY Link status, Valid Only W5100, W5200 +//#endif +}ctlwizchip_type; + +/** + * @ingroup DATA_TYPE + * Network control type enumration used in @ref ctlnetwork(). + */ +typedef enum +{ + CN_SET_NETINFO, ///< Set Network with @ref wiz_NetInfo + CN_GET_NETINFO, ///< Get Network with @ref wiz_NetInfo + CN_SET_NETMODE, ///< Set network mode as WOL, PPPoE, Ping Block, and Force ARP mode + CN_GET_NETMODE, ///< Get network mode as WOL, PPPoE, Ping Block, and Force ARP mode + CN_SET_TIMEOUT, ///< Set network timeout as retry count and time. + CN_GET_TIMEOUT, ///< Get network timeout as retry count and time. +}ctlnetwork_type; + +/** + * @ingroup DATA_TYPE + * Interrupt kind when CW_SET_INTRRUPT, CW_GET_INTERRUPT, CW_SET_INTRMASK + * and CW_GET_INTRMASK is used in @ref ctlnetwork(). + * It can be used with OR operation. + */ +typedef enum +{ +#if _WIZCHIP_ == W5500 + IK_WOL = (1 << 4), ///< Wake On Lan by receiving the magic packet. Valid in W500. +#elif _WIZCHIP_ == W5300 + IK_FMTU = (1 << 4), ///< Received a ICMP message (Fragment MTU) +#endif + + IK_PPPOE_TERMINATED = (1 << 5), ///< PPPoE Disconnected + +#if _WIZCHIP_ != W5200 + IK_DEST_UNREACH = (1 << 6), ///< Destination IP & Port Unreachable, No use in W5200 +#endif + + IK_IP_CONFLICT = (1 << 7), ///< IP conflict occurred + + IK_SOCK_0 = (1 << 8), ///< Socket 0 interrupt + IK_SOCK_1 = (1 << 9), ///< Socket 1 interrupt + IK_SOCK_2 = (1 << 10), ///< Socket 2 interrupt + IK_SOCK_3 = (1 << 11), ///< Socket 3 interrupt +#if _WIZCHIP_ > W5100S + IK_SOCK_4 = (1 << 12), ///< Socket 4 interrupt, No use in 5100 + IK_SOCK_5 = (1 << 13), ///< Socket 5 interrupt, No use in 5100 + IK_SOCK_6 = (1 << 14), ///< Socket 6 interrupt, No use in 5100 + IK_SOCK_7 = (1 << 15), ///< Socket 7 interrupt, No use in 5100 +#endif + +#if _WIZCHIP_ > W5100S + IK_SOCK_ALL = (0xFF << 8) ///< All Socket interrupt +#else + IK_SOCK_ALL = (0x0F << 8) ///< All Socket interrupt +#endif +}intr_kind; + +#define PHY_CONFBY_HW 0 ///< Configured PHY operation mode by HW pin +#define PHY_CONFBY_SW 1 ///< Configured PHY operation mode by SW register +#define PHY_MODE_MANUAL 0 ///< Configured PHY operation mode with user setting. +#define PHY_MODE_AUTONEGO 1 ///< Configured PHY operation mode with auto-negotiation +#define PHY_SPEED_10 0 ///< Link Speed 10 +#define PHY_SPEED_100 1 ///< Link Speed 100 +#define PHY_DUPLEX_HALF 0 ///< Link Half-Duplex +#define PHY_DUPLEX_FULL 1 ///< Link Full-Duplex +#define PHY_LINK_OFF 0 ///< Link Off +#define PHY_LINK_ON 1 ///< Link On +#define PHY_POWER_NORM 0 ///< PHY power normal mode +#define PHY_POWER_DOWN 1 ///< PHY power down mode + + +#if _WIZCHIP_ == W5100S || _WIZCHIP_ == W5500 +/** + * @ingroup DATA_TYPE + * It configures PHY configuration when CW_SET PHYCONF or CW_GET_PHYCONF in W5500, + * and it indicates the real PHY status configured by HW or SW in all WIZCHIP. \n + * Valid only in W5500. + */ +typedef struct wiz_PhyConf_t +{ + uint8_t by; ///< set by @ref PHY_CONFBY_HW or @ref PHY_CONFBY_SW + uint8_t mode; ///< set by @ref PHY_MODE_MANUAL or @ref PHY_MODE_AUTONEGO + uint8_t speed; ///< set by @ref PHY_SPEED_10 or @ref PHY_SPEED_100 + uint8_t duplex; ///< set by @ref PHY_DUPLEX_HALF @ref PHY_DUPLEX_FULL + //uint8_t power; ///< set by @ref PHY_POWER_NORM or @ref PHY_POWER_DOWN + //uint8_t link; ///< Valid only in CW_GET_PHYSTATUS. set by @ref PHY_LINK_ON or PHY_DUPLEX_OFF + }wiz_PhyConf; +#endif + +/** + * @ingroup DATA_TYPE + * It used in setting dhcp_mode of @ref wiz_NetInfo. + */ +typedef enum +{ + NETINFO_STATIC = 1, ///< Static IP configuration by manually. + NETINFO_DHCP ///< Dynamic IP configruation from a DHCP sever +}dhcp_mode; + +/** + * @ingroup DATA_TYPE + * Network Information for WIZCHIP + */ +typedef struct wiz_NetInfo_t +{ + uint8_t mac[6]; ///< Source Mac Address + uint8_t _pad[2]; ///< avoid 'non-aligned exception' in some cpu. @20201109 + uint8_t ip[4]; ///< Source IP Address + uint8_t sn[4]; ///< Subnet Mask + uint8_t gw[4]; ///< Gateway IP Address + uint8_t dns[4]; ///< DNS server IP Address + dhcp_mode dhcp; ///< 1 - Static, 2 - DHCP +}wiz_NetInfo; + +/** + * @ingroup DATA_TYPE + * Network mode + */ +typedef enum +{ +#if _WIZCHIP_ == W5500 + NM_FORCEARP = (1<<1), ///< Force to APP send whenever udp data is sent. Valid only in W5500 +#endif + NM_WAKEONLAN = (1<<5), ///< Wake On Lan + NM_PINGBLOCK = (1<<4), ///< Block ping-request + NM_PPPOE = (1<<3), ///< PPPoE mode +}netmode_type; + +/** + * @ingroup DATA_TYPE + * Used in CN_SET_TIMEOUT or CN_GET_TIMEOUT of @ref ctlwizchip() for timeout configruation. + */ +typedef struct wiz_NetTimeout_t +{ + uint8_t retry_cnt; ///< retry count + uint16_t time_100us; ///< time unit 100us +}wiz_NetTimeout; + +/** + *@brief Registers call back function for critical section of I/O functions such as + *\ref WIZCHIP_READ, @ref WIZCHIP_WRITE, @ref WIZCHIP_READ_BUF and @ref WIZCHIP_WRITE_BUF. + *@param cris_en : callback function for critical section enter. + *@param cris_ex : callback function for critical section exit. + *@todo Describe @ref WIZCHIP_CRITICAL_ENTER and @ref WIZCHIP_CRITICAL_EXIT marco or register your functions. + *@note If you do not describe or register, default functions(@ref wizchip_cris_enter & @ref wizchip_cris_exit) is called. + */ +void reg_wizchip_cris_cbfunc(void(*cris_en)(void), void(*cris_ex)(void)); + + +/** + *@brief Registers call back function for WIZCHIP select & deselect. + *@param cs_sel : callback function for WIZCHIP select + *@param cs_desel : callback fucntion for WIZCHIP deselect + *@todo Describe @ref wizchip_cs_select and @ref wizchip_cs_deselect function or register your functions. + *@note If you do not describe or register, null function is called. + */ +void reg_wizchip_cs_cbfunc(void(*cs_sel)(void), void(*cs_desel)(void)); + +/** + *@brief Registers call back function for bus interface. + *@param bus_rb : callback function to read byte data using system bus + *@param bus_wb : callback function to write byte data using system bus + *@todo Describe @ref wizchip_bus_readbyte and @ref wizchip_bus_writebyte function + *or register your functions. + *@note If you do not describe or register, null function is called. + */ +//M20150601 : For integrating with W5300 +//void reg_wizchip_bus_cbfunc(uint8_t (*bus_rb)(uint32_t addr), void (*bus_wb)(uint32_t addr, uint8_t wb)); +void reg_wizchip_bus_cbfunc(iodata_t (*bus_rb)(uint32_t addr), void (*bus_wb)(uint32_t addr, iodata_t wb)); + +/** + *@brief Registers call back function for SPI interface. + *@param spi_rb : callback function to read byte using SPI + *@param spi_wb : callback function to write byte using SPI + *@todo Describe \ref wizchip_spi_readbyte and \ref wizchip_spi_writebyte function + *or register your functions. + *@note If you do not describe or register, null function is called. + */ +void reg_wizchip_spi_cbfunc(uint8_t (*spi_rb)(void), void (*spi_wb)(uint8_t wb)); + +/** + *@brief Registers call back function for SPI interface. + *@param spi_rb : callback function to burst read using SPI + *@param spi_wb : callback function to burst write using SPI + *@todo Describe \ref wizchip_spi_readbyte and \ref wizchip_spi_writebyte function + *or register your functions. + *@note If you do not describe or register, null function is called. + */ +void reg_wizchip_spiburst_cbfunc(void (*spi_rb)(uint8_t* pBuf, uint16_t len), void (*spi_wb)(uint8_t* pBuf, uint16_t len)); + +/** + * @ingroup extra_functions + * @brief Controls to the WIZCHIP. + * @details Resets WIZCHIP & internal PHY, Configures PHY mode, Monitor PHY(Link,Speed,Half/Full/Auto), + * controls interrupt & mask and so on. + * @param cwtype : Decides to the control type + * @param arg : arg type is dependent on cwtype. + * @return 0 : Success \n + * -1 : Fail because of invalid \ref ctlwizchip_type or unsupported \ref ctlwizchip_type in WIZCHIP + */ +int8_t ctlwizchip(ctlwizchip_type cwtype, void* arg); + +/** + * @ingroup extra_functions + * @brief Controls to network. + * @details Controls to network environment, mode, timeout and so on. + * @param cntype : Input. Decides to the control type + * @param arg : Inout. arg type is dependent on cntype. + * @return -1 : Fail because of invalid \ref ctlnetwork_type or unsupported \ref ctlnetwork_type in WIZCHIP \n + * 0 : Success + */ +int8_t ctlnetwork(ctlnetwork_type cntype, void* arg); + + +/* + * The following functions are implemented for internal use. + * but You can call these functions for code size reduction instead of ctlwizchip() and ctlnetwork(). + */ + +/** + * @ingroup extra_functions + * @brief Reset WIZCHIP by softly. + */ +void wizchip_sw_reset(void); + +/** + * @ingroup extra_functions + * @brief Initializes WIZCHIP with socket buffer size + * @param txsize Socket tx buffer sizes. If null, initialized the default size 2KB. + * @param rxsize Socket rx buffer sizes. If null, initialized the default size 2KB. + * @return 0 : succcess \n + * -1 : fail. Invalid buffer size + */ +int8_t wizchip_init(uint8_t* txsize, uint8_t* rxsize); + +/** + * @ingroup extra_functions + * @brief Clear Interrupt of WIZCHIP. + * @param intr : @ref intr_kind value operated OR. It can type-cast to uint16_t. + */ +void wizchip_clrinterrupt(intr_kind intr); + +/** + * @ingroup extra_functions + * @brief Get Interrupt of WIZCHIP. + * @return @ref intr_kind value operated OR. It can type-cast to uint16_t. + */ +intr_kind wizchip_getinterrupt(void); + +/** + * @ingroup extra_functions + * @brief Mask or Unmask Interrupt of WIZCHIP. + * @param intr : @ref intr_kind value operated OR. It can type-cast to uint16_t. + */ +void wizchip_setinterruptmask(intr_kind intr); + +/** + * @ingroup extra_functions + * @brief Get Interrupt mask of WIZCHIP. + * @return : The operated OR vaule of @ref intr_kind. It can type-cast to uint16_t. + */ +intr_kind wizchip_getinterruptmask(void); + +//todo +#if _WIZCHIP_ > W5100 + int8_t wizphy_getphylink(void); ///< get the link status of phy in WIZCHIP. No use in W5100 + int8_t wizphy_getphypmode(void); ///< get the power mode of PHY in WIZCHIP. No use in W5100 +#endif + +#if _WIZCHIP_ == W5100S || _WIZCHIP_ == W5500 + void wizphy_reset(void); ///< Reset phy. Vailid only in W5500 +/** + * @ingroup extra_functions + * @brief Set the phy information for WIZCHIP without power mode + * @param phyconf : @ref wiz_PhyConf + */ + void wizphy_setphyconf(wiz_PhyConf* phyconf); + /** + * @ingroup extra_functions + * @brief Get phy configuration information. + * @param phyconf : @ref wiz_PhyConf + */ + void wizphy_getphyconf(wiz_PhyConf* phyconf); + /** + * @ingroup extra_functions + * @brief Get phy status. + * @param phyconf : @ref wiz_PhyConf + */ + void wizphy_getphystat(wiz_PhyConf* phyconf); + /** + * @ingroup extra_functions + * @brief set the power mode of phy inside WIZCHIP. Refer to @ref PHYCFGR in W5500, @ref PHYSTATUS in W5200 + * @param pmode Settig value of power down mode. + */ + int8_t wizphy_setphypmode(uint8_t pmode); +#endif + +/** +* @ingroup extra_functions + * @brief Set the network information for WIZCHIP + * @param pnetinfo : @ref wizNetInfo + */ +void wizchip_setnetinfo(wiz_NetInfo* pnetinfo); + +/** + * @ingroup extra_functions + * @brief Get the network information for WIZCHIP + * @param pnetinfo : @ref wizNetInfo + */ +void wizchip_getnetinfo(wiz_NetInfo* pnetinfo); + +/** + * @ingroup extra_functions + * @brief Set the network mode such WOL, PPPoE, Ping Block, and etc. + * @param pnetinfo Value of network mode. Refer to @ref netmode_type. + */ +int8_t wizchip_setnetmode(netmode_type netmode); + +/** + * @ingroup extra_functions + * @brief Get the network mode such WOL, PPPoE, Ping Block, and etc. + * @return Value of network mode. Refer to @ref netmode_type. + */ +netmode_type wizchip_getnetmode(void); + +/** + * @ingroup extra_functions + * @brief Set retry time value(@ref _RTR_) and retry count(@ref _RCR_). + * @details @ref _RTR_ configures the retransmission timeout period and @ref _RCR_ configures the number of time of retransmission. + * @param nettime @ref _RTR_ value and @ref _RCR_ value. Refer to @ref wiz_NetTimeout. + */ +void wizchip_settimeout(wiz_NetTimeout* nettime); + +/** + * @ingroup extra_functions + * @brief Get retry time value(@ref _RTR_) and retry count(@ref _RCR_). + * @details @ref _RTR_ configures the retransmission timeout period and @ref _RCR_ configures the number of time of retransmission. + * @param nettime @ref _RTR_ value and @ref _RCR_ value. Refer to @ref wiz_NetTimeout. + */ +void wizchip_gettimeout(wiz_NetTimeout* nettime); +#ifdef __cplusplus + } +#endif + +#endif // _WIZCHIP_CONF_H_ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_socket.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_socket.c new file mode 100644 index 000000000..2568ccdc7 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_socket.c @@ -0,0 +1,931 @@ +//***************************************************************************** +// +//! \file wizchip_socket.c +//! \brief SOCKET APIs Implements file. +//! \details SOCKET APIs like as Berkeley Socket APIs. +//! \version 1.0.3 +//! \date 2013/10/21 +//! \par Revision history +//! <2015/02/05> Notice +//! The version history is not updated after this point. +//! Download the latest version directly from GitHub. Please visit the our GitHub repository for ioLibrary. +//! >> https://github.com/Wiznet/ioLibrary_Driver +//! <2014/05/01> V1.0.3. Refer to M20140501 +//! 1. Implicit type casting -> Explicit type casting. +//! 2. replace 0x01 with PACK_REMAINED in recvfrom() +//! 3. Validation a destination ip in connect() & sendto(): +//! It occurs a fatal error on converting unint32 address if uint8* addr parameter is not aligned by 4byte address. +//! Copy 4 byte addr value into temporary uint32 variable and then compares it. +//! <2013/12/20> V1.0.2 Refer to M20131220 +//! Remove Warning. +//! <2013/11/04> V1.0.1 2nd Release. Refer to "20131104". +//! In sendto(), Add to clear timeout interrupt status (Sn_IR_TIMEOUT) +//! <2013/10/21> 1st Release +//! \author MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** +#include "wizchip_socket.h" + +//M20150401 : Typing Error +//#define SOCK_ANY_PORT_NUM 0xC000; +#define SOCK_ANY_PORT_NUM 0xC000 + +static uint16_t sock_any_port = SOCK_ANY_PORT_NUM; +static uint16_t sock_io_mode = 0; +static uint16_t sock_is_sending = 0; + +static uint16_t sock_remained_size[_WIZCHIP_SOCK_NUM_] = {0,0,}; + +//M20150601 : For extern decleation +//static uint8_t sock_pack_info[_WIZCHIP_SOCK_NUM_] = {0,}; +uint8_t sock_pack_info[_WIZCHIP_SOCK_NUM_] = {0,}; +// + +#if _WIZCHIP_ == 5200 + static uint16_t sock_next_rd[_WIZCHIP_SOCK_NUM_] ={0,}; +#endif + +//A20150601 : For integrating with W5300 +#if _WIZCHIP_ == 5300 + uint8_t sock_remained_byte[_WIZCHIP_SOCK_NUM_] = {0,}; // set by wiz_recv_data() +#endif + + +#define CHECK_SOCKNUM() \ + do{ \ + if(sn > _WIZCHIP_SOCK_NUM_) return SOCKERR_SOCKNUM; \ + }while(0); \ + +#define CHECK_SOCKMODE(mode) \ + do{ \ + if((getSn_MR(sn) & 0x0F) != mode) return SOCKERR_SOCKMODE; \ + }while(0); \ + +#define CHECK_SOCKINIT() \ + do{ \ + if((getSn_SR(sn) != SOCK_INIT)) return SOCKERR_SOCKINIT; \ + }while(0); \ + +#define CHECK_SOCKDATA() \ + do{ \ + if(len == 0) return SOCKERR_DATALEN; \ + }while(0); \ + + + +int8_t wizchip_socket(uint8_t sn, uint8_t protocol, uint16_t port, uint8_t flag) +{ + CHECK_SOCKNUM(); + switch(protocol) + { + case Sn_MR_TCP : + { + //M20150601 : Fixed the warning - taddr will never be NULL + /* + uint8_t taddr[4]; + getSIPR(taddr); + */ + uint32_t taddr; + getSIPR((uint8_t*)&taddr); + if(taddr == 0) return SOCKERR_SOCKINIT; + break; + } + case Sn_MR_UDP : + case Sn_MR_MACRAW : + case Sn_MR_IPRAW : + break; + #if ( _WIZCHIP_ < 5200 ) + case Sn_MR_PPPoE : + break; + #endif + default : + return SOCKERR_SOCKMODE; + } + //M20150601 : For SF_TCP_ALIGN & W5300 + //if((flag & 0x06) != 0) return SOCKERR_SOCKFLAG; + if((flag & 0x04) != 0) return SOCKERR_SOCKFLAG; +#if _WIZCHIP_ == 5200 + if(flag & 0x10) return SOCKERR_SOCKFLAG; +#endif + + if(flag != 0) + { + switch(protocol) + { + case Sn_MR_TCP: + //M20150601 : For SF_TCP_ALIGN & W5300 + #if _WIZCHIP_ == 5300 + if((flag & (SF_TCP_NODELAY|SF_IO_NONBLOCK|SF_TCP_ALIGN))==0) return SOCKERR_SOCKFLAG; + #else + if((flag & (SF_TCP_NODELAY|SF_IO_NONBLOCK))==0) return SOCKERR_SOCKFLAG; + #endif + + break; + case Sn_MR_UDP: + if(flag & SF_IGMP_VER2) + { + if((flag & SF_MULTI_ENABLE)==0) return SOCKERR_SOCKFLAG; + } + #if _WIZCHIP_ == 5500 + if(flag & SF_UNI_BLOCK) + { + if((flag & SF_MULTI_ENABLE) == 0) return SOCKERR_SOCKFLAG; + } + #endif + break; + default: + break; + } + } + wizchip_close(sn); + //M20150601 + #if _WIZCHIP_ == 5300 + setSn_MR(sn, ((uint16_t)(protocol | (flag & 0xF0))) | (((uint16_t)(flag & 0x02)) << 7) ); + #else + setSn_MR(sn, (protocol | (flag & 0xF0))); + #endif + if(!port) + { + port = sock_any_port++; + if(sock_any_port == 0xFFF0) sock_any_port = SOCK_ANY_PORT_NUM; + } + setSn_PORT(sn,port); + setSn_CR(sn,Sn_CR_OPEN); + while(getSn_CR(sn)); + //A20150401 : For release the previous sock_io_mode + sock_io_mode &= ~(1 < sn + //if( ((getSn_MR(s)& 0x0F) == Sn_MR_TCP) && (getSn_TX_FSR(s) != getSn_TxMAX(s)) ) + if( ((getSn_MR(sn)& 0x0F) == Sn_MR_TCP) && (getSn_TX_FSR(sn) != getSn_TxMAX(sn)) ) + { + uint8_t destip[4] = {0, 0, 0, 1}; + // TODO + // You can wait for completing to sending data; + // wait about 1 second; + // if you have completed to send data, skip the code of erratum 1 + // ex> wait_1s(); + // if (getSn_TX_FSR(s) == getSn_TxMAX(s)) continue; + // + //M20160503 : The socket() of close() calls close() itself again. It occures a infinite loop - close()->socket()->close()->socket()-> ~ + //socket(s,Sn_MR_UDP,0x3000,0); + //sendto(s,destip,1,destip,0x3000); // send the dummy data to an unknown destination(0.0.0.1). + setSn_MR(sn,Sn_MR_UDP); + setSn_PORTR(sn, 0x3000); + setSn_CR(sn,Sn_CR_OPEN); + while(getSn_CR(sn) != 0); + while(getSn_SR(sn) != SOCK_UDP); + sendto(sn,destip,1,destip,0x3000); // send the dummy data to an unknown destination(0.0.0.1). + }; +#endif + setSn_CR(sn,Sn_CR_CLOSE); + /* wait to process the command... */ + while( getSn_CR(sn) ); + /* clear all interrupt of the socket. */ + setSn_IR(sn, 0xFF); + //A20150401 : Release the sock_io_mode of socket n. + sock_io_mode &= ~(1< freesize) len = freesize; // check size not to exceed MAX size. + while(1) + { + freesize = getSn_TX_FSR(sn); + tmp = getSn_SR(sn); + if ((tmp != SOCK_ESTABLISHED) && (tmp != SOCK_CLOSE_WAIT)) + { + wizchip_close(sn); + return SOCKERR_SOCKSTATUS; + } + if( (sock_io_mode & (1< freesize) ) return SOCK_BUSY; + if(len <= freesize) break; + } + wiz_send_data(sn, buf, len); + #if _WIZCHIP_ == 5200 + sock_next_rd[sn] = getSn_TX_RD(sn) + len; + #endif + + #if _WIZCHIP_ == 5300 + setSn_TX_WRSR(sn,len); + #endif + + setSn_CR(sn,Sn_CR_SEND); + /* wait to process the command... */ + while(getSn_CR(sn)); + sock_is_sending |= (1 << sn); + //M20150409 : Explicit Type Casting + //return len; + return (int32_t)len; +} + + +int32_t wizchip_recv(uint8_t sn, uint8_t * buf, uint16_t len) +{ + uint8_t tmp = 0; + uint16_t recvsize = 0; +//A20150601 : For integarating with W5300 +#if _WIZCHIP_ == 5300 + uint8_t head[2]; + uint16_t mr; +#endif +// + CHECK_SOCKNUM(); + CHECK_SOCKMODE(Sn_MR_TCP); + CHECK_SOCKDATA(); + + recvsize = getSn_RxMAX(sn); + if(recvsize < len) len = recvsize; + +//A20150601 : For Integrating with W5300 +#if _WIZCHIP_ == 5300 + //sock_pack_info[sn] = PACK_COMPLETED; // for clear + if(sock_remained_size[sn] == 0) + { +#endif +// + while(1) + { + recvsize = getSn_RX_RSR(sn); + tmp = getSn_SR(sn); + if (tmp != SOCK_ESTABLISHED) + { + if(tmp == SOCK_CLOSE_WAIT) + { + if(recvsize != 0) break; + else if(getSn_TX_FSR(sn) == getSn_TxMAX(sn)) + { + wizchip_close(sn); + return SOCKERR_SOCKSTATUS; + } + } + else + { + wizchip_close(sn); + return SOCKERR_SOCKSTATUS; + } + } + if((sock_io_mode & (1< sock_remained_size[sn]) len = sock_remained_size[sn]; + recvsize = len; + if(sock_pack_info[sn] & PACK_FIFOBYTE) + { + *buf = sock_remained_byte[sn]; + buf++; + sock_pack_info[sn] &= ~(PACK_FIFOBYTE); + recvsize -= 1; + sock_remained_size[sn] -= 1; + } + if(recvsize != 0) + { + wiz_recv_data(sn, buf, recvsize); + setSn_CR(sn,Sn_CR_RECV); + while(getSn_CR(sn)); + } + sock_remained_size[sn] -= recvsize; + if(sock_remained_size[sn] != 0) + { + sock_pack_info[sn] |= PACK_REMAINED; + if(recvsize & 0x1) sock_pack_info[sn] |= PACK_FIFOBYTE; + } + else sock_pack_info[sn] = PACK_COMPLETED; + if(getSn_MR(sn) & Sn_MR_ALIGN) sock_remained_size[sn] = 0; + //len = recvsize; +#else + if(recvsize < len) len = recvsize; + wiz_recv_data(sn, buf, len); + setSn_CR(sn,Sn_CR_RECV); + while(getSn_CR(sn)); +#endif + + //M20150409 : Explicit Type Casting + //return len; + return (int32_t)len; +} + +int32_t wizchip_sendto(uint8_t sn, uint8_t * buf, uint16_t len, uint8_t * addr, uint16_t port) +{ + uint8_t tmp = 0; + uint16_t freesize = 0; + uint32_t taddr; + + CHECK_SOCKNUM(); + switch(getSn_MR(sn) & 0x0F) + { + case Sn_MR_UDP: + case Sn_MR_MACRAW: +// break; +// #if ( _WIZCHIP_ < 5200 ) + case Sn_MR_IPRAW: + break; +// #endif + default: + return SOCKERR_SOCKMODE; + } + CHECK_SOCKDATA(); + //M20140501 : For avoiding fatal error on memory align mismatched + //if(*((uint32_t*)addr) == 0) return SOCKERR_IPINVALID; + //{ + //uint32_t taddr; + taddr = ((uint32_t)addr[0]) & 0x000000FF; + taddr = (taddr << 8) + ((uint32_t)addr[1] & 0x000000FF); + taddr = (taddr << 8) + ((uint32_t)addr[2] & 0x000000FF); + taddr = (taddr << 8) + ((uint32_t)addr[3] & 0x000000FF); + //} + // + //if(*((uint32_t*)addr) == 0) return SOCKERR_IPINVALID; + if((taddr == 0) && ((getSn_MR(sn)&Sn_MR_MACRAW) != Sn_MR_MACRAW)) return SOCKERR_IPINVALID; + if((port == 0) && ((getSn_MR(sn)&Sn_MR_MACRAW) != Sn_MR_MACRAW)) return SOCKERR_PORTZERO; + tmp = getSn_SR(sn); +//#if ( _WIZCHIP_ < 5200 ) + if((tmp != SOCK_MACRAW) && (tmp != SOCK_UDP) && (tmp != SOCK_IPRAW)) return SOCKERR_SOCKSTATUS; +//#else +// if(tmp != SOCK_MACRAW && tmp != SOCK_UDP) return SOCKERR_SOCKSTATUS; +//#endif + + setSn_DIPR(sn,addr); + setSn_DPORT(sn,port); + freesize = getSn_TxMAX(sn); + if (len > freesize) len = freesize; // check size not to exceed MAX size. + while(1) + { + freesize = getSn_TX_FSR(sn); + if(getSn_SR(sn) == SOCK_CLOSED) return SOCKERR_SOCKCLOSED; + if( (sock_io_mode & (1< freesize) ) return SOCK_BUSY; + if(len <= freesize) break; + }; + wiz_send_data(sn, buf, len); + + #if _WIZCHIP_ < 5500 //M20150401 : for WIZCHIP Errata #4, #5 (ARP errata) + getSIPR((uint8_t*)&taddr); + if(taddr == 0) + { + getSUBR((uint8_t*)&taddr); + setSUBR((uint8_t*)"\x00\x00\x00\x00"); + } + else taddr = 0; + #endif + +//A20150601 : For W5300 +#if _WIZCHIP_ == 5300 + setSn_TX_WRSR(sn, len); +#endif +// + setSn_CR(sn,Sn_CR_SEND); + /* wait to process the command... */ + while(getSn_CR(sn)); + while(1) + { + tmp = getSn_IR(sn); + if(tmp & Sn_IR_SENDOK) + { + setSn_IR(sn, Sn_IR_SENDOK); + break; + } + //M:20131104 + //else if(tmp & Sn_IR_TIMEOUT) return SOCKERR_TIMEOUT; + else if(tmp & Sn_IR_TIMEOUT) + { + setSn_IR(sn, Sn_IR_TIMEOUT); + //M20150409 : Fixed the lost of sign bits by type casting. + //len = (uint16_t)SOCKERR_TIMEOUT; + //break; + #if _WIZCHIP_ < 5500 //M20150401 : for WIZCHIP Errata #4, #5 (ARP errata) + if(taddr) setSUBR((uint8_t*)&taddr); + #endif + return SOCKERR_TIMEOUT; + } + //////////// + } + #if _WIZCHIP_ < 5500 //M20150401 : for WIZCHIP Errata #4, #5 (ARP errata) + if(taddr) setSUBR((uint8_t*)&taddr); + #endif + //M20150409 : Explicit Type Casting + //return len; + return (int32_t)len; +} + + + +int32_t wizchip_recvfrom(uint8_t sn, uint8_t * buf, uint16_t len, uint8_t * addr, uint16_t *port) +{ +//M20150601 : For W5300 +#if _WIZCHIP_ == 5300 + uint16_t mr; + uint16_t mr1; +#else + uint8_t mr; +#endif +// + uint8_t head[8]; + uint16_t pack_len=0; + + CHECK_SOCKNUM(); + //CHECK_SOCKMODE(Sn_MR_UDP); +//A20150601 +#if _WIZCHIP_ == 5300 + mr1 = getMR(); +#endif + + switch((mr=getSn_MR(sn)) & 0x0F) + { + case Sn_MR_UDP: + case Sn_MR_IPRAW: + case Sn_MR_MACRAW: + break; + #if ( _WIZCHIP_ < 5200 ) + case Sn_MR_PPPoE: + break; + #endif + default: + return SOCKERR_SOCKMODE; + } + CHECK_SOCKDATA(); + if(sock_remained_size[sn] == 0) + { + while(1) + { + pack_len = getSn_RX_RSR(sn); + if(getSn_SR(sn) == SOCK_CLOSED) return SOCKERR_SOCKCLOSED; + if( (sock_io_mode & (1< 1514) + { + wizchip_close(sn); + return SOCKFATAL_PACKLEN; + } + sock_pack_info[sn] = PACK_FIRST; + } + if(len < sock_remained_size[sn]) pack_len = len; + else pack_len = sock_remained_size[sn]; + wiz_recv_data(sn,buf,pack_len); + break; + //#if ( _WIZCHIP_ < 5200 ) + case Sn_MR_IPRAW: + if(sock_remained_size[sn] == 0) + { + wiz_recv_data(sn, head, 6); + setSn_CR(sn,Sn_CR_RECV); + while(getSn_CR(sn)); + addr[0] = head[0]; + addr[1] = head[1]; + addr[2] = head[2]; + addr[3] = head[3]; + sock_remained_size[sn] = head[4]; + //M20150401 : For Typing Error + //sock_remaiend_size[sn] = (sock_remained_size[sn] << 8) + head[5]; + sock_remained_size[sn] = (sock_remained_size[sn] << 8) + head[5]; + sock_pack_info[sn] = PACK_FIRST; + } + // + // Need to packet length check + // + if(len < sock_remained_size[sn]) pack_len = len; + else pack_len = sock_remained_size[sn]; + wiz_recv_data(sn, buf, pack_len); // data copy. + break; + //#endif + default: + wiz_recv_ignore(sn, pack_len); // data copy. + sock_remained_size[sn] = pack_len; + break; + } + setSn_CR(sn,Sn_CR_RECV); + /* wait to process the command... */ + while(getSn_CR(sn)) ; + sock_remained_size[sn] -= pack_len; + //M20150601 : + //if(sock_remained_size[sn] != 0) sock_pack_info[sn] |= 0x01; + if(sock_remained_size[sn] != 0) + { + sock_pack_info[sn] |= PACK_REMAINED; + #if _WIZCHIP_ == 5300 + if(pack_len & 0x01) sock_pack_info[sn] |= PACK_FIFOBYTE; + #endif + } + else sock_pack_info[sn] = PACK_COMPLETED; +#if _WIZCHIP_ == 5300 + pack_len = len; +#endif + // + //M20150409 : Explicit Type Casting + //return pack_len; + return (int32_t)pack_len; +} + + +int8_t ctlsocket(uint8_t sn, ctlsock_type cstype, void* arg) +{ + uint8_t tmp = 0; + CHECK_SOCKNUM(); + switch(cstype) + { + case CS_SET_IOMODE: + tmp = *((uint8_t*)arg); + if(tmp == SOCK_IO_NONBLOCK) sock_io_mode |= (1< explict type casting + //*((uint8_t*)arg) = (sock_io_mode >> sn) & 0x0001; + *((uint8_t*)arg) = (uint8_t)((sock_io_mode >> sn) & 0x0001); + // + break; + case CS_GET_MAXTXBUF: + *((uint16_t*)arg) = getSn_TxMAX(sn); + break; + case CS_GET_MAXRXBUF: + *((uint16_t*)arg) = getSn_RxMAX(sn); + break; + case CS_CLR_INTERRUPT: + if( (*(uint8_t*)arg) > SIK_ALL) return SOCKERR_ARG; + setSn_IR(sn,*(uint8_t*)arg); + break; + case CS_GET_INTERRUPT: + *((uint8_t*)arg) = getSn_IR(sn); + break; + #if _WIZCHIP_ != 5100 + case CS_SET_INTMASK: + if( (*(uint8_t*)arg) > SIK_ALL) return SOCKERR_ARG; + setSn_IMR(sn,*(uint8_t*)arg); + break; + case CS_GET_INTMASK: + *((uint8_t*)arg) = getSn_IMR(sn); + break; + #endif + default: + return SOCKERR_ARG; + } + return SOCK_OK; +} + +int8_t wizchip_setsockopt(uint8_t sn, sockopt_type sotype, void* arg) +{ + // M20131220 : Remove warning + //uint8_t tmp; + CHECK_SOCKNUM(); + switch(sotype) + { + case SO_TTL: + setSn_TTL(sn,*(uint8_t*)arg); + break; + case SO_TOS: + setSn_TOS(sn,*(uint8_t*)arg); + break; + case SO_MSS: + setSn_MSSR(sn,*(uint16_t*)arg); + break; + case SO_DESTIP: + setSn_DIPR(sn, (uint8_t*)arg); + break; + case SO_DESTPORT: + setSn_DPORT(sn, *(uint16_t*)arg); + break; +#if _WIZCHIP_ != 5100 + case SO_KEEPALIVESEND: + CHECK_SOCKMODE(Sn_MR_TCP); + #if _WIZCHIP_ > 5200 + if(getSn_KPALVTR(sn) != 0) return SOCKERR_SOCKOPT; + #endif + setSn_CR(sn,Sn_CR_SEND_KEEP); + while(getSn_CR(sn) != 0) + { + // M20131220 + //if ((tmp = getSn_IR(sn)) & Sn_IR_TIMEOUT) + if (getSn_IR(sn) & Sn_IR_TIMEOUT) + { + setSn_IR(sn, Sn_IR_TIMEOUT); + return SOCKERR_TIMEOUT; + } + } + break; + #if !( (_WIZCHIP_ == 5100) || (_WIZCHIP_ == 5200) ) + case SO_KEEPALIVEAUTO: + CHECK_SOCKMODE(Sn_MR_TCP); + setSn_KPALVTR(sn,*(uint8_t*)arg); + break; + #endif +#endif + default: + return SOCKERR_ARG; + } + return SOCK_OK; +} + +int8_t wizchip_getsockopt(uint8_t sn, sockopt_type sotype, void* arg) +{ + CHECK_SOCKNUM(); + switch(sotype) + { + case SO_FLAG: + *(uint8_t*)arg = getSn_MR(sn) & 0xF0; + break; + case SO_TTL: + *(uint8_t*) arg = getSn_TTL(sn); + break; + case SO_TOS: + *(uint8_t*) arg = getSn_TOS(sn); + break; + case SO_MSS: + *(uint16_t*) arg = getSn_MSSR(sn); + break; + case SO_DESTIP: + getSn_DIPR(sn, (uint8_t*)arg); + break; + case SO_DESTPORT: + *(uint16_t*) arg = getSn_DPORT(sn); + break; + #if _WIZCHIP_ > 5200 + case SO_KEEPALIVEAUTO: + CHECK_SOCKMODE(Sn_MR_TCP); + *(uint16_t*) arg = getSn_KPALVTR(sn); + break; + #endif + case SO_SENDBUF: + *(uint16_t*) arg = getSn_TX_FSR(sn); + break; + case SO_RECVBUF: + *(uint16_t*) arg = getSn_RX_RSR(sn); + break; + case SO_STATUS: + *(uint8_t*) arg = getSn_SR(sn); + break; + case SO_REMAINSIZE: + if(getSn_MR(sn) & Sn_MR_TCP) + *(uint16_t*)arg = getSn_RX_RSR(sn); + else + *(uint16_t*)arg = sock_remained_size[sn]; + break; + case SO_PACKINFO: + //CHECK_SOCKMODE(Sn_MR_TCP); +#if _WIZCHIP_ != 5300 + if((getSn_MR(sn) == Sn_MR_TCP)) + return SOCKERR_SOCKMODE; +#endif + *(uint8_t*)arg = sock_pack_info[sn]; + break; + default: + return SOCKERR_SOCKOPT; + } + return SOCK_OK; +} diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_socket.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_socket.h new file mode 100644 index 000000000..7d53aa58a --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Ethernet/wizchip_socket.h @@ -0,0 +1,489 @@ +//***************************************************************************** +// +//! \file wizchip_socket.h +//! \brief SOCKET APIs Header file. +//! \details SOCKET APIs like as berkeley socket api. +//! \version 1.0.2 +//! \date 2013/10/21 +//! \par Revision history +//! <2015/02/05> Notice +//! The version history is not updated after this point. +//! Download the latest version directly from GitHub. Please visit the our GitHub repository for ioLibrary. +//! >> https://github.com/Wiznet/ioLibrary_Driver +//! <2014/05/01> V1.0.2. Refer to M20140501 +//! 1. Modify the comment : SO_REMAINED -> PACK_REMAINED +//! 2. Add the comment as zero byte udp data reception in getsockopt(). +//! <2013/10/21> 1st Release +//! \author MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** +/** + * @defgroup WIZnet_socket_APIs 1. WIZnet socket APIs + * @brief WIZnet socket APIs are based on Berkeley socket APIs, thus it has much similar name and interface. + * But there is a little bit of difference. + * @details + * Comparison between WIZnet and Berkeley SOCKET APIs + * + * + * + * + * + * + * + * + * + * + * + * + *
API WIZnet Berkeley
socket() O O
bind() X O
listen() O O
connect() O O
accept() X O
recv() O O
send() O O
recvfrom() O O
sendto() O O
closesocket() O
close() & disconnect()
O
+ * There are @b bind() and @b accept() functions in @b Berkeley SOCKET API but, + * not in @b WIZnet SOCKET API. Because socket() of WIZnet is not only creating a SOCKET but also binding a local port number, + * and listen() of WIZnet is not only listening to connection request from client but also accepting the connection request. \n + * When you program "TCP SERVER" with Berkeley SOCKET API, you can use only one listen port. + * When the listen SOCKET accepts a connection request from a client, it keeps listening. + * After accepting the connection request, a new SOCKET is created and the new SOCKET is used in communication with the client. \n + * Following figure shows network flow diagram by Berkeley SOCKET API. + * @image html Berkeley_SOCKET.jpg "" + * But, When you program "TCP SERVER" with WIZnet SOCKET API, you can use as many as 8 listen SOCKET with same port number. \n + * Because there's no accept() in WIZnet SOCKET APIs, when the listen SOCKET accepts a connection request from a client, + * it is changed in order to communicate with the client. + * And the changed SOCKET is not listening any more and is dedicated for communicating with the client. \n + * If there're many listen SOCKET with same listen port number and a client requests a connection, + * the SOCKET which has the smallest SOCKET number accepts the request and is changed as communication SOCKET. \n + * Following figure shows network flow diagram by WIZnet SOCKET API. + * @image html WIZnet_SOCKET.jpg "" + */ +#ifndef _WIZCHIP_SOCKET_H_ +#define _WIZCHIP_SOCKET_H_ +#ifdef __cplusplus + extern "C" { +#endif + +#include "wizchip_conf.h" + +#define SOCKET uint8_t ///< SOCKET type define for legacy driver + +#define SOCK_OK 1 ///< Result is OK about socket process. +#define SOCK_BUSY 0 ///< Socket is busy on processing the operation. Valid only Non-block IO Mode. +#define SOCK_FATAL -1000 ///< Result is fatal error about socket process. + +#define SOCK_ERROR 0 +#define SOCKERR_SOCKNUM (SOCK_ERROR - 1) ///< Invalid socket number +#define SOCKERR_SOCKOPT (SOCK_ERROR - 2) ///< Invalid socket option +#define SOCKERR_SOCKINIT (SOCK_ERROR - 3) ///< Socket is not initialized or SIPR is Zero IP address when Sn_MR_TCP +#define SOCKERR_SOCKCLOSED (SOCK_ERROR - 4) ///< Socket unexpectedly closed. +#define SOCKERR_SOCKMODE (SOCK_ERROR - 5) ///< Invalid socket mode for socket operation. +#define SOCKERR_SOCKFLAG (SOCK_ERROR - 6) ///< Invalid socket flag +#define SOCKERR_SOCKSTATUS (SOCK_ERROR - 7) ///< Invalid socket status for socket operation. +#define SOCKERR_ARG (SOCK_ERROR - 10) ///< Invalid argument. +#define SOCKERR_PORTZERO (SOCK_ERROR - 11) ///< Port number is zero +#define SOCKERR_IPINVALID (SOCK_ERROR - 12) ///< Invalid IP address +#define SOCKERR_TIMEOUT (SOCK_ERROR - 13) ///< Timeout occurred +#define SOCKERR_DATALEN (SOCK_ERROR - 14) ///< Data length is zero or greater than buffer max size. +#define SOCKERR_BUFFER (SOCK_ERROR - 15) ///< Socket buffer is not enough for data communication. + +#define SOCKFATAL_PACKLEN (SOCK_FATAL - 1) ///< Invalid packet length. Fatal Error. + +/* + * SOCKET FLAG + */ +#define SF_ETHER_OWN (Sn_MR_MFEN) ///< In @ref Sn_MR_MACRAW, Receive only the packet as broadcast, multicast and own packet +#define SF_IGMP_VER2 (Sn_MR_MC) ///< In @ref Sn_MR_UDP with \ref SF_MULTI_ENABLE, Select IGMP version 2. +#define SF_TCP_NODELAY (Sn_MR_ND) ///< In @ref Sn_MR_TCP, Use to nodelayed ack. +#define SF_MULTI_ENABLE (Sn_MR_MULTI) ///< In @ref Sn_MR_UDP, Enable multicast mode. + +#if _WIZCHIP_ == 5500 + #define SF_BROAD_BLOCK (Sn_MR_BCASTB) ///< In @ref Sn_MR_UDP or @ref Sn_MR_MACRAW, Block broadcast packet. Valid only in W5500 + #define SF_MULTI_BLOCK (Sn_MR_MMB) ///< In @ref Sn_MR_MACRAW, Block multicast packet. Valid only in W5500 + #define SF_IPv6_BLOCK (Sn_MR_MIP6B) ///< In @ref Sn_MR_MACRAW, Block IPv6 packet. Valid only in W5500 + #define SF_UNI_BLOCK (Sn_MR_UCASTB) ///< In @ref Sn_MR_UDP with \ref SF_MULTI_ENABLE. Valid only in W5500 +#endif + +//A201505 : For W5300 +#if _WIZCHIP_ == 5300 + #define SF_TCP_ALIGN 0x02 ///< Valid only \ref Sn_MR_TCP and W5300, refer to \ref Sn_MR_ALIGN +#endif + +#define SF_IO_NONBLOCK 0x01 ///< Socket nonblock io mode. It used parameter in \ref socket(). + +/* + * UDP & MACRAW Packet Infomation + */ +#define PACK_FIRST 0x80 ///< In Non-TCP packet, It indicates to start receiving a packet. (When W5300, This flag can be applied) +#define PACK_REMAINED 0x01 ///< In Non-TCP packet, It indicates to remain a packet to be received. (When W5300, This flag can be applied) +#define PACK_COMPLETED 0x00 ///< In Non-TCP packet, It indicates to complete to receive a packet. (When W5300, This flag can be applied) +//A20150601 : For Integrating with W5300 +#define PACK_FIFOBYTE 0x02 ///< Valid only W5300, It indicate to have read already the Sn_RX_FIFOR. +// + +/** + * @ingroup WIZnet_socket_APIs + * @brief Open a socket. + * @details Initializes the socket with 'sn' passed as parameter and open. + * + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @param protocol Protocol type to operate such as TCP, UDP and MACRAW. + * @param port Port number to be bined. + * @param flag Socket flags as \ref SF_ETHER_OWN, \ref SF_IGMP_VER2, \ref SF_TCP_NODELAY, \ref SF_MULTI_ENABLE, \ref SF_IO_NONBLOCK and so on.\n + * Valid flags only in W5500 : @ref SF_BROAD_BLOCK, @ref SF_MULTI_BLOCK, @ref SF_IPv6_BLOCK, and @ref SF_UNI_BLOCK. + * @sa Sn_MR + * + * @return @b Success : The socket number @b 'sn' passed as parameter\n + * @b Fail :\n @ref SOCKERR_SOCKNUM - Invalid socket number\n + * @ref SOCKERR_SOCKMODE - Not support socket mode as TCP, UDP, and so on. \n + * @ref SOCKERR_SOCKFLAG - Invaild socket flag. + */ +int8_t wizchip_socket(uint8_t sn, uint8_t protocol, uint16_t port, uint8_t flag); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Close a socket. + * @details It closes the socket with @b'sn' passed as parameter. + * + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * + * @return @b Success : @ref SOCK_OK \n + * @b Fail : @ref SOCKERR_SOCKNUM - Invalid socket number + */ +int8_t wizchip_close(uint8_t sn); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Listen to a connection request from a client. + * @details It is listening to a connection request from a client. + * If connection request is accepted successfully, the connection is established. Socket sn is used in passive(server) mode. + * + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @return @b Success : @ref SOCK_OK \n + * @b Fail :\n @ref SOCKERR_SOCKINIT - Socket is not initialized \n + * @ref SOCKERR_SOCKCLOSED - Socket closed unexpectedly. + */ +int8_t wizchip_listen(uint8_t sn); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Try to connect a server. + * @details It requests connection to the server with destination IP address and port number passed as parameter.\n + * @note It is valid only in TCP client mode. + * In block io mode, it does not return until connection is completed. + * In Non-block io mode, it return @ref SOCK_BUSY immediately. + * + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @param addr Pointer variable of destination IP address. It should be allocated 4 bytes. + * @param port Destination port number. + * + * @return @b Success : @ref SOCK_OK \n + * @b Fail :\n @ref SOCKERR_SOCKNUM - Invalid socket number\n + * @ref SOCKERR_SOCKMODE - Invalid socket mode\n + * @ref SOCKERR_SOCKINIT - Socket is not initialized\n + * @ref SOCKERR_IPINVALID - Wrong server IP address\n + * @ref SOCKERR_PORTZERO - Server port zero\n + * @ref SOCKERR_TIMEOUT - Timeout occurred during request connection\n + * @ref SOCK_BUSY - In non-block io mode, it returned immediately\n + */ +int8_t wizchip_connect(uint8_t sn, uint8_t * addr, uint16_t port); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Try to disconnect a connection socket. + * @details It sends request message to disconnect the TCP socket 'sn' passed as parameter to the server or client. + * @note It is valid only in TCP server or client mode. \n + * In block io mode, it does not return until disconnection is completed. \n + * In Non-block io mode, it return @ref SOCK_BUSY immediately. \n + + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @return @b Success : @ref SOCK_OK \n + * @b Fail :\n @ref SOCKERR_SOCKNUM - Invalid socket number \n + * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n + * @ref SOCKERR_TIMEOUT - Timeout occurred \n + * @ref SOCK_BUSY - Socket is busy. + */ +int8_t wizchip_disconnect(uint8_t sn); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Send data to the connected peer in TCP socket. + * @details It is used to send outgoing data to the connected socket. + * @note It is valid only in TCP server or client mode. It can't send data greater than socket buffer size. \n + * In block io mode, It doesn't return until data send is completed - socket buffer size is greater than data. \n + * In non-block io mode, It return @ref SOCK_BUSY immediately when socket buffer is not enough. \n + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @param buf Pointer buffer containing data to be sent. + * @param len The byte length of data in buf. + * @return @b Success : The sent data size \n + * @b Fail : \n @ref SOCKERR_SOCKSTATUS - Invalid socket status for socket operation \n + * @ref SOCKERR_TIMEOUT - Timeout occurred \n + * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n + * @ref SOCKERR_SOCKNUM - Invalid socket number \n + * @ref SOCKERR_DATALEN - zero data length \n + * @ref SOCK_BUSY - Socket is busy. + */ +int32_t wizchip_send(uint8_t sn, uint8_t * buf, uint16_t len); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Receive data from the connected peer. + * @details It is used to read incoming data from the connected socket.\n + * It waits for data as much as the application wants to receive. + * @note It is valid only in TCP server or client mode. It can't receive data greater than socket buffer size. \n + * In block io mode, it doesn't return until data reception is completed - data is filled as len in socket buffer. \n + * In non-block io mode, it return @ref SOCK_BUSY immediately when len is greater than data size in socket buffer. \n + * + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @param buf Pointer buffer to read incoming data. + * @param len The max data length of data in buf. + * @return @b Success : The real received data size \n + * @b Fail :\n + * @ref SOCKERR_SOCKSTATUS - Invalid socket status for socket operation \n + * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n + * @ref SOCKERR_SOCKNUM - Invalid socket number \n + * @ref SOCKERR_DATALEN - zero data length \n + * @ref SOCK_BUSY - Socket is busy. + */ +int32_t wizchip_recv(uint8_t sn, uint8_t * buf, uint16_t len); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Sends datagram to the peer with destination IP address and port number passed as parameter. + * @details It sends datagram of UDP or MACRAW to the peer with destination IP address and port number passed as parameter.\n + * Even if the connectionless socket has been previously connected to a specific address, + * the address and port number parameters override the destination address for that particular datagram only. + * @note In block io mode, It doesn't return until data send is completed - socket buffer size is greater than len. + * In non-block io mode, It return @ref SOCK_BUSY immediately when socket buffer is not enough. + * + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @param buf Pointer buffer to send outgoing data. + * @param len The byte length of data in buf. + * @param addr Pointer variable of destination IP address. It should be allocated 4 bytes. + * @param port Destination port number. + * + * @return @b Success : The sent data size \n + * @b Fail :\n @ref SOCKERR_SOCKNUM - Invalid socket number \n + * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n + * @ref SOCKERR_SOCKSTATUS - Invalid socket status for socket operation \n + * @ref SOCKERR_DATALEN - zero data length \n + * @ref SOCKERR_IPINVALID - Wrong server IP address\n + * @ref SOCKERR_PORTZERO - Server port zero\n + * @ref SOCKERR_SOCKCLOSED - Socket unexpectedly closed \n + * @ref SOCKERR_TIMEOUT - Timeout occurred \n + * @ref SOCK_BUSY - Socket is busy. + */ +int32_t wizchip_sendto(uint8_t sn, uint8_t * buf, uint16_t len, uint8_t * addr, uint16_t port); + +/** + * @ingroup WIZnet_socket_APIs + * @brief Receive datagram of UDP or MACRAW + * @details This function is an application I/F function which is used to receive the data in other then TCP mode. \n + * This function is used to receive UDP and MAC_RAW mode, and handle the header as well. + * This function can divide to received the packet data. + * On the MACRAW SOCKET, the addr and port parameters are ignored. + * @note In block io mode, it doesn't return until data reception is completed - data is filled as len in socket buffer + * In non-block io mode, it return @ref SOCK_BUSY immediately when len is greater than data size in socket buffer. + * + * @param sn Socket number. It should be 0 ~ @ref \_WIZCHIP_SOCK_NUM_. + * @param buf Pointer buffer to read incoming data. + * @param len The max data length of data in buf. + * When the received packet size <= len, receives data as packet sized. + * When others, receives data as len. + * @param addr Pointer variable of destination IP address. It should be allocated 4 bytes. + * It is valid only when the first call recvfrom for receiving the packet. + * When it is valid, @ref packinfo[7] should be set as '1' after call @ref getsockopt(sn, SO_PACKINFO, &packinfo). + * @param port Pointer variable of destination port number. + * It is valid only when the first call recvform for receiving the packet. +* When it is valid, @ref packinfo[7] should be set as '1' after call @ref getsockopt(sn, SO_PACKINFO, &packinfo). + * + * @return @b Success : This function return real received data size for success.\n + * @b Fail : @ref SOCKERR_DATALEN - zero data length \n + * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n + * @ref SOCKERR_SOCKNUM - Invalid socket number \n + * @ref SOCKBUSY - Socket is busy. + */ +int32_t wizchip_recvfrom(uint8_t sn, uint8_t * buf, uint16_t len, uint8_t * addr, uint16_t *port); + + +///////////////////////////// +// SOCKET CONTROL & OPTION // +///////////////////////////// +#define SOCK_IO_BLOCK 0 ///< Socket Block IO Mode in @ref setsockopt(). +#define SOCK_IO_NONBLOCK 1 ///< Socket Non-block IO Mode in @ref setsockopt(). + +/** + * @defgroup DATA_TYPE DATA TYPE + */ + +/** + * @ingroup DATA_TYPE + * @brief The kind of Socket Interrupt. + * @sa Sn_IR, Sn_IMR, setSn_IR(), getSn_IR(), setSn_IMR(), getSn_IMR() + */ +typedef enum +{ + SIK_CONNECTED = (1 << 0), ///< connected + SIK_DISCONNECTED = (1 << 1), ///< disconnected + SIK_RECEIVED = (1 << 2), ///< data received + SIK_TIMEOUT = (1 << 3), ///< timeout occurred + SIK_SENT = (1 << 4), ///< send ok + //M20150410 : Remove the comma of last member + //SIK_ALL = 0x1F, ///< all interrupt + SIK_ALL = 0x1F ///< all interrupt +}sockint_kind; + +/** + * @ingroup DATA_TYPE + * @brief The type of @ref ctlsocket(). + */ +typedef enum +{ + CS_SET_IOMODE, ///< set socket IO mode with @ref SOCK_IO_BLOCK or @ref SOCK_IO_NONBLOCK + CS_GET_IOMODE, ///< get socket IO mode + CS_GET_MAXTXBUF, ///< get the size of socket buffer allocated in TX memory + CS_GET_MAXRXBUF, ///< get the size of socket buffer allocated in RX memory + CS_CLR_INTERRUPT, ///< clear the interrupt of socket with @ref sockint_kind + CS_GET_INTERRUPT, ///< get the socket interrupt. refer to @ref sockint_kind +#if _WIZCHIP_ > 5100 + CS_SET_INTMASK, ///< set the interrupt mask of socket with @ref sockint_kind, Not supported in W5100 + CS_GET_INTMASK ///< get the masked interrupt of socket. refer to @ref sockint_kind, Not supported in W5100 +#endif +}ctlsock_type; + + +/** + * @ingroup DATA_TYPE + * @brief The type of socket option in @ref setsockopt() or @ref getsockopt() + */ +typedef enum +{ + SO_FLAG, ///< Valid only in getsockopt(), For set flag of socket refer to flag in @ref socket(). + SO_TTL, ///< Set TTL. @ref Sn_TTL ( @ref setSn_TTL(), @ref getSn_TTL() ) + SO_TOS, ///< Set TOS. @ref Sn_TOS ( @ref setSn_TOS(), @ref getSn_TOS() ) + SO_MSS, ///< Set MSS. @ref Sn_MSSR ( @ref setSn_MSSR(), @ref getSn_MSSR() ) + SO_DESTIP, ///< Set the destination IP address. @ref Sn_DIPR ( @ref setSn_DIPR(), @ref getSn_DIPR() ) + SO_DESTPORT, ///< Set the destination Port number. @ref Sn_DPORT ( @ref setSn_DPORT(), @ref getSn_DPORT() ) +#if _WIZCHIP_ != 5100 + SO_KEEPALIVESEND, ///< Valid only in setsockopt. Manually send keep-alive packet in TCP mode, Not supported in W5100 + #if !( (_WIZCHIP_ == 5100) || (_WIZCHIP_ == 5200) ) + SO_KEEPALIVEAUTO, ///< Set/Get keep-alive auto transmission timer in TCP mode, Not supported in W5100, W5200 + #endif +#endif + SO_SENDBUF, ///< Valid only in getsockopt. Get the free data size of Socekt TX buffer. @ref Sn_TX_FSR, @ref getSn_TX_FSR() + SO_RECVBUF, ///< Valid only in getsockopt. Get the received data size in socket RX buffer. @ref Sn_RX_RSR, @ref getSn_RX_RSR() + SO_STATUS, ///< Valid only in getsockopt. Get the socket status. @ref Sn_SR, @ref getSn_SR() + SO_REMAINSIZE, ///< Valid only in getsockopt. Get the remained packet size in other then TCP mode. + SO_PACKINFO ///< Valid only in getsockopt. Get the packet information as @ref PACK_FIRST, @ref PACK_REMAINED, and @ref PACK_COMPLETED in other then TCP mode. +}sockopt_type; + +/** + * @ingroup WIZnet_socket_APIs + * @brief Control socket. + * @details Control IO mode, Interrupt & Mask of socket and get the socket buffer information. + * Refer to @ref ctlsock_type. + * @param sn socket number + * @param cstype type of control socket. refer to @ref ctlsock_type. + * @param arg Data type and value is determined according to @ref ctlsock_type. \n + * + * + * + * + * + *
@b cstype @b data type@b value
@ref CS_SET_IOMODE \n @ref CS_GET_IOMODE uint8_t @ref SOCK_IO_BLOCK @ref SOCK_IO_NONBLOCK
@ref CS_GET_MAXTXBUF \n @ref CS_GET_MAXRXBUF uint16_t 0 ~ 16K
@ref CS_CLR_INTERRUPT \n @ref CS_GET_INTERRUPT \n @ref CS_SET_INTMASK \n @ref CS_GET_INTMASK @ref sockint_kind @ref SIK_CONNECTED, etc.
+ * @return @b Success @ref SOCK_OK \n + * @b fail @ref SOCKERR_ARG - Invalid argument\n + */ +int8_t wizchip_ctlsocket(uint8_t sn, ctlsock_type cstype, void* arg); + +/** + * @ingroup WIZnet_socket_APIs + * @brief set socket options + * @details Set socket option like as TTL, MSS, TOS, and so on. Refer to @ref sockopt_type. + * + * @param sn socket number + * @param sotype socket option type. refer to @ref sockopt_type + * @param arg Data type and value is determined according to sotype. \n + * + * + * + * + * + * + * + * + * + *
@b sotype @b data type@b value
@ref SO_TTL uint8_t 0 ~ 255
@ref SO_TOS uint8_t 0 ~ 255
@ref SO_MSS uint16_t 0 ~ 65535
@ref SO_DESTIP uint8_t[4]
@ref SO_DESTPORT uint16_t 0 ~ 65535
@ref SO_KEEPALIVESEND null null
@ref SO_KEEPALIVEAUTO uint8_t 0 ~ 255
+ * @return + * - @b Success : @ref SOCK_OK \n + * - @b Fail + * - @ref SOCKERR_SOCKNUM - Invalid Socket number \n + * - @ref SOCKERR_SOCKMODE - Invalid socket mode \n + * - @ref SOCKERR_SOCKOPT - Invalid socket option or its value \n + * - @ref SOCKERR_TIMEOUT - Timeout occurred when sending keep-alive packet \n + */ +int8_t wizchip_setsockopt(uint8_t sn, sockopt_type sotype, void* arg); + +/** + * @ingroup WIZnet_socket_APIs + * @brief get socket options + * @details Get socket option like as FLAG, TTL, MSS, and so on. Refer to @ref sockopt_type + * @param sn socket number + * @param sotype socket option type. refer to @ref sockopt_type + * @param arg Data type and value is determined according to sotype. \n + * + * + * + * + * + * + * + * + * + * + * + * + * + *
@b sotype @b data type@b value
@ref SO_FLAG uint8_t @ref SF_ETHER_OWN, etc...
@ref SO_TOS uint8_t 0 ~ 255
@ref SO_MSS uint16_t 0 ~ 65535
@ref SO_DESTIP uint8_t[4]
@ref SO_DESTPORT uint16_t
@ref SO_KEEPALIVEAUTO uint8_t 0 ~ 255
@ref SO_SENDBUF uint16_t 0 ~ 65535
@ref SO_RECVBUF uint16_t 0 ~ 65535
@ref SO_STATUS uint8_t @ref SOCK_ESTABLISHED, etc..
@ref SO_REMAINSIZE uint16_t 0~ 65535
@ref SO_PACKINFO uint8_t @ref PACK_FIRST, etc...
+ * @return + * - @b Success : @ref SOCK_OK \n + * - @b Fail + * - @ref SOCKERR_SOCKNUM - Invalid Socket number \n + * - @ref SOCKERR_SOCKOPT - Invalid socket option or its value \n + * - @ref SOCKERR_SOCKMODE - Invalid socket mode \n + * @note + * The option as PACK_REMAINED and SO_PACKINFO is valid only in NON-TCP mode and after call @ref recvfrom(). \n + * When SO_PACKINFO value is PACK_FIRST and the return value of recvfrom() is zero, + * This means the zero byte UDP data(UDP Header only) received. + */ +int8_t wizchip_getsockopt(uint8_t sn, sockopt_type sotype, void* arg); + +#ifdef __cplusplus + } +#endif + +#endif // _WIZCHIP_SOCKET_H_ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DHCP/wizchip_dhcp.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DHCP/wizchip_dhcp.c new file mode 100644 index 000000000..60310f83f --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DHCP/wizchip_dhcp.c @@ -0,0 +1,1030 @@ +//***************************************************************************** +// +//! \file wizchip_dhcp.c +//! \brief DHCP APIs implement file. +//! \details Processing DHCP protocol as DISCOVER, OFFER, REQUEST, ACK, NACK and DECLINE. +//! \version 1.1.1 +//! \date 2019/10/08 +//! \par Revision history +//! <2019/10/08> compare DHCP server ip address +//! <2013/11/18> 1st Release +//! <2012/12/20> V1.1.0 +//! 1. Optimize code +//! 2. Add reg_dhcp_cbfunc() +//! 3. Add DHCP_stop() +//! 4. Integrate check_DHCP_state() & DHCP_run() to DHCP_run() +//! 5. Don't care system endian +//! 6. Add comments +//! <2012/12/26> V1.1.1 +//! 1. Modify variable declaration: dhcp_tick_1s is declared volatile for code optimization +//! \author Eric Jung & MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** + +#include +#include "DHCP/wizchip_dhcp.h" + +/* If you want to display debug & processing message, Define _DHCP_DEBUG_ in dhcp.h */ + +#ifdef _DHCP_DEBUG_ + #include +#endif + +/* DHCP state machine. */ +#define STATE_DHCP_INIT 0 ///< Initialize +#define STATE_DHCP_DISCOVER 1 ///< send DISCOVER and wait OFFER +#define STATE_DHCP_REQUEST 2 ///< send REQEUST and wait ACK or NACK +#define STATE_DHCP_LEASED 3 ///< ReceiveD ACK and IP leased +#define STATE_DHCP_REREQUEST 4 ///< send REQUEST for maintaining leased IP +#define STATE_DHCP_RELEASE 5 ///< No use +#define STATE_DHCP_STOP 6 ///< Stop processing DHCP + +#define DHCP_FLAGSBROADCAST 0x8000 ///< The broadcast value of flags in @ref RIP_MSG +#define DHCP_FLAGSUNICAST 0x0000 ///< The unicast value of flags in @ref RIP_MSG + +/* DHCP message OP code */ +#define DHCP_BOOTREQUEST 1 ///< Request Message used in op of @ref RIP_MSG +#define DHCP_BOOTREPLY 2 ///< Reply Message used i op of @ref RIP_MSG + +/* DHCP message type */ +#define DHCP_DISCOVER 1 ///< DISCOVER message in OPT of @ref RIP_MSG +#define DHCP_OFFER 2 ///< OFFER message in OPT of @ref RIP_MSG +#define DHCP_REQUEST 3 ///< REQUEST message in OPT of @ref RIP_MSG +#define DHCP_DECLINE 4 ///< DECLINE message in OPT of @ref RIP_MSG +#define DHCP_ACK 5 ///< ACK message in OPT of @ref RIP_MSG +#define DHCP_NAK 6 ///< NACK message in OPT of @ref RIP_MSG +#define DHCP_RELEASE 7 ///< RELEASE message in OPT of @ref RIP_MSG. No use +#define DHCP_INFORM 8 ///< INFORM message in OPT of @ref RIP_MSG. No use + +#define DHCP_HTYPE10MB 1 ///< Used in type of @ref RIP_MSG +#define DHCP_HTYPE100MB 2 ///< Used in type of @ref RIP_MSG + +#define DHCP_HLENETHERNET 6 ///< Used in hlen of @ref RIP_MSG +#define DHCP_HOPS 0 ///< Used in hops of @ref RIP_MSG +#define DHCP_SECS 0 ///< Used in secs of @ref RIP_MSG + +#define INFINITE_LEASETIME 0xffffffff ///< Infinite lease time + +#define OPT_SIZE 312 /// Max OPT size of @ref RIP_MSG +#define RIP_MSG_SIZE (236+OPT_SIZE) /// Max size of @ref RIP_MSG + +/* + * @brief DHCP option and value (cf. RFC1533) + */ +enum +{ + padOption = 0, + subnetMask = 1, + timerOffset = 2, + routersOnSubnet = 3, + timeServer = 4, + nameServer = 5, + dns = 6, + logServer = 7, + cookieServer = 8, + lprServer = 9, + impressServer = 10, + resourceLocationServer = 11, + hostName = 12, + bootFileSize = 13, + meritDumpFile = 14, + domainName = 15, + swapServer = 16, + rootPath = 17, + extentionsPath = 18, + IPforwarding = 19, + nonLocalSourceRouting = 20, + policyFilter = 21, + maxDgramReasmSize = 22, + defaultIPTTL = 23, + pathMTUagingTimeout = 24, + pathMTUplateauTable = 25, + ifMTU = 26, + allSubnetsLocal = 27, + broadcastAddr = 28, + performMaskDiscovery = 29, + maskSupplier = 30, + performRouterDiscovery = 31, + routerSolicitationAddr = 32, + staticRoute = 33, + trailerEncapsulation = 34, + arpCacheTimeout = 35, + ethernetEncapsulation = 36, + tcpDefaultTTL = 37, + tcpKeepaliveInterval = 38, + tcpKeepaliveGarbage = 39, + nisDomainName = 40, + nisServers = 41, + ntpServers = 42, + vendorSpecificInfo = 43, + netBIOSnameServer = 44, + netBIOSdgramDistServer = 45, + netBIOSnodeType = 46, + netBIOSscope = 47, + xFontServer = 48, + xDisplayManager = 49, + dhcpRequestedIPaddr = 50, + dhcpIPaddrLeaseTime = 51, + dhcpOptionOverload = 52, + dhcpMessageType = 53, + dhcpServerIdentifier = 54, + dhcpParamRequest = 55, + dhcpMsg = 56, + dhcpMaxMsgSize = 57, + dhcpT1value = 58, + dhcpT2value = 59, + dhcpClassIdentifier = 60, + dhcpClientIdentifier = 61, + endOption = 255 +}; + +/* + * @brief DHCP message format + */ +typedef struct { + uint8_t op; ///< @ref DHCP_BOOTREQUEST or @ref DHCP_BOOTREPLY + uint8_t htype; ///< @ref DHCP_HTYPE10MB or @ref DHCP_HTYPE100MB + uint8_t hlen; ///< @ref DHCP_HLENETHERNET + uint8_t hops; ///< @ref DHCP_HOPS + uint32_t xid; ///< @ref DHCP_XID This increase one every DHCP transaction. + uint16_t secs; ///< @ref DHCP_SECS + uint16_t flags; ///< @ref DHCP_FLAGSBROADCAST or @ref DHCP_FLAGSUNICAST + uint8_t ciaddr[4]; ///< @ref Request IP to DHCP sever + uint8_t yiaddr[4]; ///< @ref Offered IP from DHCP server + uint8_t siaddr[4]; ///< No use + uint8_t giaddr[4]; ///< No use + uint8_t chaddr[16]; ///< DHCP client 6bytes MAC address. Others is filled to zero + uint8_t sname[64]; ///< No use + uint8_t file[128]; ///< No use + uint8_t OPT[OPT_SIZE]; ///< Option +} RIP_MSG; + + + +uint8_t DHCP_SOCKET; // Socket number for DHCP + +uint8_t DHCP_SIP[4]; // DHCP Server IP address +uint8_t DHCP_REAL_SIP[4]; // For extract my DHCP server in a few DHCP server + +// Network information from DHCP Server +uint8_t OLD_allocated_ip[4] = {0, }; // Previous IP address +uint8_t DHCP_allocated_ip[4] = {0, }; // IP address from DHCP +uint8_t DHCP_allocated_gw[4] = {0, }; // Gateway address from DHCP +uint8_t DHCP_allocated_sn[4] = {0, }; // Subnet mask from DHCP +uint8_t DHCP_allocated_dns[4] = {0, }; // DNS address from DHCP + + +int8_t dhcp_state = STATE_DHCP_INIT; // DHCP state +int8_t dhcp_retry_count = 0; + +uint32_t dhcp_lease_time = INFINITE_LEASETIME; +volatile uint32_t dhcp_tick_1s = 0; // unit 1 second +uint32_t dhcp_tick_next = DHCP_WAIT_TIME ; + +uint32_t DHCP_XID; // Any number + +RIP_MSG* pDHCPMSG; // Buffer pointer for DHCP processing + +uint8_t HOST_NAME[] = DCHP_HOST_NAME; + +uint8_t DHCP_CHADDR[6]; // DHCP Client MAC address. + +/* The default callback function */ +void default_ip_assign(void); +void default_ip_update(void); +void default_ip_conflict(void); + +/* Callback handler */ +void (*dhcp_ip_assign)(void) = default_ip_assign; /* handler to be called when the IP address from DHCP server is first assigned */ +void (*dhcp_ip_update)(void) = default_ip_update; /* handler to be called when the IP address from DHCP server is updated */ +void (*dhcp_ip_conflict)(void) = default_ip_conflict; /* handler to be called when the IP address from DHCP server is conflict */ + +void reg_dhcp_cbfunc(void(*ip_assign)(void), void(*ip_update)(void), void(*ip_conflict)(void)); + +char NibbleToHex(uint8_t nibble); + +/* send DISCOVER message to DHCP server */ +void send_DHCP_DISCOVER(void); + +/* send REQEUST message to DHCP server */ +void send_DHCP_REQUEST(void); + +/* send DECLINE message to DHCP server */ +void send_DHCP_DECLINE(void); + +/* IP conflict check by sending ARP-request to leased IP and wait ARP-response. */ +int8_t check_DHCP_leasedIP(void); + +/* check the timeout in DHCP process */ +uint8_t check_DHCP_timeout(void); + +/* Initialize to timeout process. */ +void reset_DHCP_timeout(void); + +/* Parse message as OFFER and ACK and NACK from DHCP server.*/ +int8_t parseDHCPCMSG(void); + +/* The default handler of ip assign first */ +void default_ip_assign(void) +{ + setSIPR(DHCP_allocated_ip); + setSUBR(DHCP_allocated_sn); + setGAR (DHCP_allocated_gw); +} + +/* The default handler of ip changed */ +void default_ip_update(void) +{ + /* WIZchip Software Reset */ + setMR(MR_RST); + getMR(); // for delay + default_ip_assign(); + setSHAR(DHCP_CHADDR); +} + +/* The default handler of ip changed */ +void default_ip_conflict(void) +{ + // WIZchip Software Reset + setMR(MR_RST); + getMR(); // for delay + setSHAR(DHCP_CHADDR); +} + +/* register the call back func. */ +void reg_dhcp_cbfunc(void(*ip_assign)(void), void(*ip_update)(void), void(*ip_conflict)(void)) +{ + dhcp_ip_assign = default_ip_assign; + dhcp_ip_update = default_ip_update; + dhcp_ip_conflict = default_ip_conflict; + if(ip_assign) dhcp_ip_assign = ip_assign; + if(ip_update) dhcp_ip_update = ip_update; + if(ip_conflict) dhcp_ip_conflict = ip_conflict; +} + +/* make the common DHCP message */ +void makeDHCPMSG(void) +{ + uint8_t bk_mac[6]; + uint8_t* ptmp; + uint8_t i; + getSHAR(bk_mac); + pDHCPMSG->op = DHCP_BOOTREQUEST; + pDHCPMSG->htype = DHCP_HTYPE10MB; + pDHCPMSG->hlen = DHCP_HLENETHERNET; + pDHCPMSG->hops = DHCP_HOPS; + ptmp = (uint8_t*)(&pDHCPMSG->xid); + *(ptmp+0) = (uint8_t)((DHCP_XID & 0xFF000000) >> 24); + *(ptmp+1) = (uint8_t)((DHCP_XID & 0x00FF0000) >> 16); + *(ptmp+2) = (uint8_t)((DHCP_XID & 0x0000FF00) >> 8); + *(ptmp+3) = (uint8_t)((DHCP_XID & 0x000000FF) >> 0); + pDHCPMSG->secs = DHCP_SECS; + ptmp = (uint8_t*)(&pDHCPMSG->flags); + *(ptmp+0) = (uint8_t)((DHCP_FLAGSBROADCAST & 0xFF00) >> 8); + *(ptmp+1) = (uint8_t)((DHCP_FLAGSBROADCAST & 0x00FF) >> 0); + + pDHCPMSG->ciaddr[0] = 0; + pDHCPMSG->ciaddr[1] = 0; + pDHCPMSG->ciaddr[2] = 0; + pDHCPMSG->ciaddr[3] = 0; + + pDHCPMSG->yiaddr[0] = 0; + pDHCPMSG->yiaddr[1] = 0; + pDHCPMSG->yiaddr[2] = 0; + pDHCPMSG->yiaddr[3] = 0; + + pDHCPMSG->siaddr[0] = 0; + pDHCPMSG->siaddr[1] = 0; + pDHCPMSG->siaddr[2] = 0; + pDHCPMSG->siaddr[3] = 0; + + pDHCPMSG->giaddr[0] = 0; + pDHCPMSG->giaddr[1] = 0; + pDHCPMSG->giaddr[2] = 0; + pDHCPMSG->giaddr[3] = 0; + + pDHCPMSG->chaddr[0] = DHCP_CHADDR[0]; + pDHCPMSG->chaddr[1] = DHCP_CHADDR[1]; + pDHCPMSG->chaddr[2] = DHCP_CHADDR[2]; + pDHCPMSG->chaddr[3] = DHCP_CHADDR[3]; + pDHCPMSG->chaddr[4] = DHCP_CHADDR[4]; + pDHCPMSG->chaddr[5] = DHCP_CHADDR[5]; + + for (i = 6; i < 16; i++) pDHCPMSG->chaddr[i] = 0; + for (i = 0; i < 64; i++) pDHCPMSG->sname[i] = 0; + for (i = 0; i < 128; i++) pDHCPMSG->file[i] = 0; + + // MAGIC_COOKIE + pDHCPMSG->OPT[0] = (uint8_t)((MAGIC_COOKIE & 0xFF000000) >> 24); + pDHCPMSG->OPT[1] = (uint8_t)((MAGIC_COOKIE & 0x00FF0000) >> 16); + pDHCPMSG->OPT[2] = (uint8_t)((MAGIC_COOKIE & 0x0000FF00) >> 8); + pDHCPMSG->OPT[3] = (uint8_t) (MAGIC_COOKIE & 0x000000FF) >> 0; +} + +/* SEND DHCP DISCOVER */ +void send_DHCP_DISCOVER(void) +{ + uint16_t i; + uint8_t ip[4]; + uint16_t k = 0; + + makeDHCPMSG(); + DHCP_SIP[0]=0; + DHCP_SIP[1]=0; + DHCP_SIP[2]=0; + DHCP_SIP[3]=0; + DHCP_REAL_SIP[0]=0; + DHCP_REAL_SIP[1]=0; + DHCP_REAL_SIP[2]=0; + DHCP_REAL_SIP[3]=0; + + k = 4; // because MAGIC_COOKIE already made by makeDHCPMSG() + + // Option Request Param + pDHCPMSG->OPT[k++] = dhcpMessageType; + pDHCPMSG->OPT[k++] = 0x01; + pDHCPMSG->OPT[k++] = DHCP_DISCOVER; + + // Client identifier + pDHCPMSG->OPT[k++] = dhcpClientIdentifier; + pDHCPMSG->OPT[k++] = 0x07; + pDHCPMSG->OPT[k++] = 0x01; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[0]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[1]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[2]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[3]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[4]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[5]; + + // host name + pDHCPMSG->OPT[k++] = hostName; + pDHCPMSG->OPT[k++] = 0; // fill zero length of hostname + for(i = 0 ; HOST_NAME[i] != 0; i++) + pDHCPMSG->OPT[k++] = HOST_NAME[i]; + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[3] >> 4); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[3]); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[4] >> 4); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[4]); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[5] >> 4); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[5]); + pDHCPMSG->OPT[k - (i+6+1)] = i+6; // length of hostname + + pDHCPMSG->OPT[k++] = dhcpParamRequest; + pDHCPMSG->OPT[k++] = 0x06; // length of request + pDHCPMSG->OPT[k++] = subnetMask; + pDHCPMSG->OPT[k++] = routersOnSubnet; + pDHCPMSG->OPT[k++] = dns; + pDHCPMSG->OPT[k++] = domainName; + pDHCPMSG->OPT[k++] = dhcpT1value; + pDHCPMSG->OPT[k++] = dhcpT2value; + pDHCPMSG->OPT[k++] = endOption; + + for (i = k; i < OPT_SIZE; i++) pDHCPMSG->OPT[i] = 0; + + // send broadcasting packet + ip[0] = 255; + ip[1] = 255; + ip[2] = 255; + ip[3] = 255; + +#ifdef _DHCP_DEBUG_ + printf("> Send DHCP_DISCOVER\r\n"); +#endif + + wizchip_sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); +} + +/* SEND DHCP REQUEST */ +void send_DHCP_REQUEST(void) +{ + int i; + uint8_t ip[4]; + uint16_t k = 0; + + makeDHCPMSG(); + + if(dhcp_state == STATE_DHCP_LEASED || dhcp_state == STATE_DHCP_REREQUEST) + { + *((uint8_t*)(&pDHCPMSG->flags)) = ((DHCP_FLAGSUNICAST & 0xFF00)>> 8); + *((uint8_t*)(&pDHCPMSG->flags)+1) = (DHCP_FLAGSUNICAST & 0x00FF); + pDHCPMSG->ciaddr[0] = DHCP_allocated_ip[0]; + pDHCPMSG->ciaddr[1] = DHCP_allocated_ip[1]; + pDHCPMSG->ciaddr[2] = DHCP_allocated_ip[2]; + pDHCPMSG->ciaddr[3] = DHCP_allocated_ip[3]; + ip[0] = DHCP_SIP[0]; + ip[1] = DHCP_SIP[1]; + ip[2] = DHCP_SIP[2]; + ip[3] = DHCP_SIP[3]; + } + else + { + ip[0] = 255; + ip[1] = 255; + ip[2] = 255; + ip[3] = 255; + } + + k = 4; // because MAGIC_COOKIE already made by makeDHCPMSG() + + // Option Request Param. + pDHCPMSG->OPT[k++] = dhcpMessageType; + pDHCPMSG->OPT[k++] = 0x01; + pDHCPMSG->OPT[k++] = DHCP_REQUEST; + + pDHCPMSG->OPT[k++] = dhcpClientIdentifier; + pDHCPMSG->OPT[k++] = 0x07; + pDHCPMSG->OPT[k++] = 0x01; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[0]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[1]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[2]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[3]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[4]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[5]; + + if(ip[3] == 255) // if(dchp_state == STATE_DHCP_LEASED || dchp_state == DHCP_REREQUEST_STATE) + { + pDHCPMSG->OPT[k++] = dhcpRequestedIPaddr; + pDHCPMSG->OPT[k++] = 0x04; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[0]; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[1]; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[2]; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[3]; + + pDHCPMSG->OPT[k++] = dhcpServerIdentifier; + pDHCPMSG->OPT[k++] = 0x04; + pDHCPMSG->OPT[k++] = DHCP_SIP[0]; + pDHCPMSG->OPT[k++] = DHCP_SIP[1]; + pDHCPMSG->OPT[k++] = DHCP_SIP[2]; + pDHCPMSG->OPT[k++] = DHCP_SIP[3]; + } + + // host name + pDHCPMSG->OPT[k++] = hostName; + pDHCPMSG->OPT[k++] = 0; // length of hostname + for(i = 0 ; HOST_NAME[i] != 0; i++) + pDHCPMSG->OPT[k++] = HOST_NAME[i]; + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[3] >> 4); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[3]); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[4] >> 4); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[4]); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[5] >> 4); + pDHCPMSG->OPT[k++] = NibbleToHex(DHCP_CHADDR[5]); + pDHCPMSG->OPT[k - (i+6+1)] = i+6; // length of hostname + + pDHCPMSG->OPT[k++] = dhcpParamRequest; + pDHCPMSG->OPT[k++] = 0x08; + pDHCPMSG->OPT[k++] = subnetMask; + pDHCPMSG->OPT[k++] = routersOnSubnet; + pDHCPMSG->OPT[k++] = dns; + pDHCPMSG->OPT[k++] = domainName; + pDHCPMSG->OPT[k++] = dhcpT1value; + pDHCPMSG->OPT[k++] = dhcpT2value; + pDHCPMSG->OPT[k++] = performRouterDiscovery; + pDHCPMSG->OPT[k++] = staticRoute; + pDHCPMSG->OPT[k++] = endOption; + + for (i = k; i < OPT_SIZE; i++) pDHCPMSG->OPT[i] = 0; + +#ifdef _DHCP_DEBUG_ + printf("> Send DHCP_REQUEST\r\n"); +#endif + + wizchip_sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); + +} + +/* SEND DHCP DHCPDECLINE */ +void send_DHCP_DECLINE(void) +{ + int i; + uint8_t ip[4]; + uint16_t k = 0; + + makeDHCPMSG(); + + k = 4; // because MAGIC_COOKIE already made by makeDHCPMSG() + + *((uint8_t*)(&pDHCPMSG->flags)) = ((DHCP_FLAGSUNICAST & 0xFF00)>> 8); + *((uint8_t*)(&pDHCPMSG->flags)+1) = (DHCP_FLAGSUNICAST & 0x00FF); + + // Option Request Param. + pDHCPMSG->OPT[k++] = dhcpMessageType; + pDHCPMSG->OPT[k++] = 0x01; + pDHCPMSG->OPT[k++] = DHCP_DECLINE; + + pDHCPMSG->OPT[k++] = dhcpClientIdentifier; + pDHCPMSG->OPT[k++] = 0x07; + pDHCPMSG->OPT[k++] = 0x01; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[0]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[1]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[2]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[3]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[4]; + pDHCPMSG->OPT[k++] = DHCP_CHADDR[5]; + + pDHCPMSG->OPT[k++] = dhcpRequestedIPaddr; + pDHCPMSG->OPT[k++] = 0x04; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[0]; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[1]; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[2]; + pDHCPMSG->OPT[k++] = DHCP_allocated_ip[3]; + + pDHCPMSG->OPT[k++] = dhcpServerIdentifier; + pDHCPMSG->OPT[k++] = 0x04; + pDHCPMSG->OPT[k++] = DHCP_SIP[0]; + pDHCPMSG->OPT[k++] = DHCP_SIP[1]; + pDHCPMSG->OPT[k++] = DHCP_SIP[2]; + pDHCPMSG->OPT[k++] = DHCP_SIP[3]; + + pDHCPMSG->OPT[k++] = endOption; + + for (i = k; i < OPT_SIZE; i++) pDHCPMSG->OPT[i] = 0; + + //send broadcasting packet + ip[0] = 0xFF; + ip[1] = 0xFF; + ip[2] = 0xFF; + ip[3] = 0xFF; + +#ifdef _DHCP_DEBUG_ + printf("\r\n> Send DHCP_DECLINE\r\n"); +#endif + + wizchip_sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); +} + +/* PARSE REPLY pDHCPMSG */ +int8_t parseDHCPMSG(void) +{ + uint8_t svr_addr[6]; + uint16_t svr_port; + uint16_t len; + + uint8_t * p; + uint8_t * e; + uint8_t type = 0; + uint8_t opt_len; + + if((len = getSn_RX_RSR(DHCP_SOCKET)) > 0) + { + len = wizchip_recvfrom(DHCP_SOCKET, (uint8_t *)pDHCPMSG, len, svr_addr, &svr_port); + #ifdef _DHCP_DEBUG_ + printf("DHCP message : %d.%d.%d.%d(%d) %d received. \r\n",svr_addr[0],svr_addr[1],svr_addr[2], svr_addr[3],svr_port, len); + #endif + } + else return 0; + if (svr_port == DHCP_SERVER_PORT) { + // compare mac address + if ( (pDHCPMSG->chaddr[0] != DHCP_CHADDR[0]) || (pDHCPMSG->chaddr[1] != DHCP_CHADDR[1]) || + (pDHCPMSG->chaddr[2] != DHCP_CHADDR[2]) || (pDHCPMSG->chaddr[3] != DHCP_CHADDR[3]) || + (pDHCPMSG->chaddr[4] != DHCP_CHADDR[4]) || (pDHCPMSG->chaddr[5] != DHCP_CHADDR[5]) ) + { +#ifdef _DHCP_DEBUG_ + printf("No My DHCP Message. This message is ignored.\r\n"); +#endif + return 0; + } + //compare DHCP server ip address + if((DHCP_SIP[0]!=0) || (DHCP_SIP[1]!=0) || (DHCP_SIP[2]!=0) || (DHCP_SIP[3]!=0)){ + if( ((svr_addr[0]!=DHCP_SIP[0])|| (svr_addr[1]!=DHCP_SIP[1])|| (svr_addr[2]!=DHCP_SIP[2])|| (svr_addr[3]!=DHCP_SIP[3])) && + ((svr_addr[0]!=DHCP_REAL_SIP[0])|| (svr_addr[1]!=DHCP_REAL_SIP[1])|| (svr_addr[2]!=DHCP_REAL_SIP[2])|| (svr_addr[3]!=DHCP_REAL_SIP[3])) ) + { +#ifdef _DHCP_DEBUG_ + printf("Another DHCP sever send a response message. This is ignored.\r\n"); +#endif + return 0; + } + } + p = (uint8_t *)(&pDHCPMSG->op); + p = p + 240; // 240 = sizeof(RIP_MSG) + MAGIC_COOKIE size in RIP_MSG.opt - sizeof(RIP_MSG.opt) + e = p + (len - 240); + + while ( p < e ) { + + switch ( *p ) { + + case endOption : + p = e; // for break while(p < e) + break; + case padOption : + p++; + break; + case dhcpMessageType : + p++; + p++; + type = *p++; + break; + case subnetMask : + p++; + p++; + DHCP_allocated_sn[0] = *p++; + DHCP_allocated_sn[1] = *p++; + DHCP_allocated_sn[2] = *p++; + DHCP_allocated_sn[3] = *p++; + break; + case routersOnSubnet : + p++; + opt_len = *p++; + DHCP_allocated_gw[0] = *p++; + DHCP_allocated_gw[1] = *p++; + DHCP_allocated_gw[2] = *p++; + DHCP_allocated_gw[3] = *p++; + p = p + (opt_len - 4); + break; + case dns : + p++; + opt_len = *p++; + DHCP_allocated_dns[0] = *p++; + DHCP_allocated_dns[1] = *p++; + DHCP_allocated_dns[2] = *p++; + DHCP_allocated_dns[3] = *p++; + p = p + (opt_len - 4); + break; + case dhcpIPaddrLeaseTime : + p++; + opt_len = *p++; + dhcp_lease_time = *p++; + dhcp_lease_time = (dhcp_lease_time << 8) + *p++; + dhcp_lease_time = (dhcp_lease_time << 8) + *p++; + dhcp_lease_time = (dhcp_lease_time << 8) + *p++; + #ifdef _DHCP_DEBUG_ + dhcp_lease_time = 10; + #endif + break; + case dhcpServerIdentifier : + p++; + opt_len = *p++; + DHCP_SIP[0] = *p++; + DHCP_SIP[1] = *p++; + DHCP_SIP[2] = *p++; + DHCP_SIP[3] = *p++; + DHCP_REAL_SIP[0]=svr_addr[0]; + DHCP_REAL_SIP[1]=svr_addr[1]; + DHCP_REAL_SIP[2]=svr_addr[2]; + DHCP_REAL_SIP[3]=svr_addr[3]; + break; + default : + p++; + opt_len = *p++; + p += opt_len; + break; + } // switch + } // while + } // if + return type; +} + +uint8_t DHCP_run(void) +{ + uint8_t type; + uint8_t ret; + + if(dhcp_state == STATE_DHCP_STOP) return DHCP_STOPPED; + + if(getSn_SR(DHCP_SOCKET) != SOCK_UDP) + wizchip_socket(DHCP_SOCKET, Sn_MR_UDP, DHCP_CLIENT_PORT, 0x00); + + ret = DHCP_RUNNING; + type = parseDHCPMSG(); + + switch ( dhcp_state ) { + case STATE_DHCP_INIT : + DHCP_allocated_ip[0] = 0; + DHCP_allocated_ip[1] = 0; + DHCP_allocated_ip[2] = 0; + DHCP_allocated_ip[3] = 0; + send_DHCP_DISCOVER(); + dhcp_state = STATE_DHCP_DISCOVER; + break; + case STATE_DHCP_DISCOVER : + if (type == DHCP_OFFER){ +#ifdef _DHCP_DEBUG_ + printf("> Receive DHCP_OFFER\r\n"); +#endif + DHCP_allocated_ip[0] = pDHCPMSG->yiaddr[0]; + DHCP_allocated_ip[1] = pDHCPMSG->yiaddr[1]; + DHCP_allocated_ip[2] = pDHCPMSG->yiaddr[2]; + DHCP_allocated_ip[3] = pDHCPMSG->yiaddr[3]; + + send_DHCP_REQUEST(); + dhcp_state = STATE_DHCP_REQUEST; + } else ret = check_DHCP_timeout(); + break; + + case STATE_DHCP_REQUEST : + if (type == DHCP_ACK) { + +#ifdef _DHCP_DEBUG_ + printf("> Receive DHCP_ACK\r\n"); +#endif + if (check_DHCP_leasedIP()) { + // Network info assignment from DHCP + dhcp_ip_assign(); + reset_DHCP_timeout(); + + dhcp_state = STATE_DHCP_LEASED; + } else { + // IP address conflict occurred + reset_DHCP_timeout(); + dhcp_ip_conflict(); + dhcp_state = STATE_DHCP_INIT; + } + } else if (type == DHCP_NAK) { + +#ifdef _DHCP_DEBUG_ + printf("> Receive DHCP_NACK\r\n"); +#endif + + reset_DHCP_timeout(); + + dhcp_state = STATE_DHCP_DISCOVER; + } else ret = check_DHCP_timeout(); + break; + + case STATE_DHCP_LEASED : + if ((dhcp_lease_time != INFINITE_LEASETIME) && ((dhcp_lease_time/2) < dhcp_tick_1s)) { + +#ifdef _DHCP_DEBUG_ + printf("> Maintains the IP address \r\n"); +#endif + + type = 0; + OLD_allocated_ip[0] = DHCP_allocated_ip[0]; + OLD_allocated_ip[1] = DHCP_allocated_ip[1]; + OLD_allocated_ip[2] = DHCP_allocated_ip[2]; + OLD_allocated_ip[3] = DHCP_allocated_ip[3]; + + DHCP_XID++; + + send_DHCP_REQUEST(); + + reset_DHCP_timeout(); + + dhcp_state = STATE_DHCP_REREQUEST; + } + else + { + ret = DHCP_IP_LEASED; + } + break; + + case STATE_DHCP_REREQUEST : + if (type == DHCP_ACK) { + dhcp_retry_count = 0; + if (OLD_allocated_ip[0] != DHCP_allocated_ip[0] || + OLD_allocated_ip[1] != DHCP_allocated_ip[1] || + OLD_allocated_ip[2] != DHCP_allocated_ip[2] || + OLD_allocated_ip[3] != DHCP_allocated_ip[3]) + { + ret = DHCP_IP_CHANGED; + dhcp_ip_update(); + #ifdef _DHCP_DEBUG_ + printf(">IP changed.\r\n"); + #endif + + } + #ifdef _DHCP_DEBUG_ + else printf(">IP is continued.\r\n"); + #endif + reset_DHCP_timeout(); + dhcp_state = STATE_DHCP_LEASED; + } else if (type == DHCP_NAK) { + +#ifdef _DHCP_DEBUG_ + printf("> Receive DHCP_NACK, Failed to maintain ip\r\n"); +#endif + + reset_DHCP_timeout(); + + dhcp_state = STATE_DHCP_DISCOVER; + } else ret = check_DHCP_timeout(); + break; + default : + break; + } + + return ret; +} + +void DHCP_stop(void) +{ + wizchip_close(DHCP_SOCKET); + dhcp_state = STATE_DHCP_STOP; +} + +uint8_t check_DHCP_timeout(void) +{ + uint8_t ret = DHCP_RUNNING; + + if (dhcp_retry_count < MAX_DHCP_RETRY) { + if (dhcp_tick_next < dhcp_tick_1s) { + + switch ( dhcp_state ) { + case STATE_DHCP_DISCOVER : +// printf("<> state : STATE_DHCP_DISCOVER\r\n"); + send_DHCP_DISCOVER(); + break; + + case STATE_DHCP_REQUEST : +// printf("<> state : STATE_DHCP_REQUEST\r\n"); + + send_DHCP_REQUEST(); + break; + + case STATE_DHCP_REREQUEST : +// printf("<> state : STATE_DHCP_REREQUEST\r\n"); + + send_DHCP_REQUEST(); + break; + + default : + break; + } + + dhcp_tick_1s = 0; + dhcp_tick_next = dhcp_tick_1s + DHCP_WAIT_TIME; + dhcp_retry_count++; + } + } else { // timeout occurred + + switch(dhcp_state) { + case STATE_DHCP_DISCOVER: + dhcp_state = STATE_DHCP_INIT; + ret = DHCP_FAILED; + break; + case STATE_DHCP_REQUEST: + case STATE_DHCP_REREQUEST: + send_DHCP_DISCOVER(); + dhcp_state = STATE_DHCP_DISCOVER; + break; + default : + break; + } + reset_DHCP_timeout(); + } + return ret; +} + +int8_t check_DHCP_leasedIP(void) +{ + uint8_t tmp; + int32_t ret; + + //WIZchip RCR value changed for ARP Timeout count control + tmp = getRCR(); + setRCR(0x03); + + // IP conflict detection : ARP request - ARP reply + // Broadcasting ARP Request for check the IP conflict using UDP sendto() function + ret = wizchip_sendto(DHCP_SOCKET, (uint8_t *)"CHECK_IP_CONFLICT", 17, DHCP_allocated_ip, 5000); + + // RCR value restore + setRCR(tmp); + + if(ret == SOCKERR_TIMEOUT) { + // UDP send Timeout occurred : allocated IP address is unique, DHCP Success + +#ifdef _DHCP_DEBUG_ + printf("\r\n> Check leased IP - OK\r\n"); +#endif + + return 1; + } else { + // Received ARP reply or etc : IP address conflict occur, DHCP Failed + send_DHCP_DECLINE(); + + ret = dhcp_tick_1s; + while((dhcp_tick_1s - ret) < 2) ; // wait for 1s over; wait to complete to send DECLINE message; + + return 0; + } +} + +void DHCP_init(uint8_t s, uint8_t * buf) +{ + uint8_t zeroip[4] = {0,0,0,0}; + getSHAR(DHCP_CHADDR); + if((DHCP_CHADDR[0] | DHCP_CHADDR[1] | DHCP_CHADDR[2] | DHCP_CHADDR[3] | DHCP_CHADDR[4] | DHCP_CHADDR[5]) == 0x00) + { + // assigning temporary mac address, you should be set SHAR before call this function. + DHCP_CHADDR[0] = 0x00; + DHCP_CHADDR[1] = 0x08; + DHCP_CHADDR[2] = 0xdc; + DHCP_CHADDR[3] = 0x00; + DHCP_CHADDR[4] = 0x00; + DHCP_CHADDR[5] = 0x00; + setSHAR(DHCP_CHADDR); + } + + DHCP_SOCKET = s; // SOCK_DHCP + pDHCPMSG = (RIP_MSG*)buf; + DHCP_XID = 0x12345678; + { + DHCP_XID += DHCP_CHADDR[3]; + DHCP_XID += DHCP_CHADDR[4]; + DHCP_XID += DHCP_CHADDR[5]; + DHCP_XID += (DHCP_CHADDR[3] ^ DHCP_CHADDR[4] ^ DHCP_CHADDR[5]); + } + // WIZchip Netinfo Clear + setSIPR(zeroip); + setGAR(zeroip); + + reset_DHCP_timeout(); + dhcp_state = STATE_DHCP_INIT; +} + + +/* Reset the DHCP timeout count and retry count. */ +void reset_DHCP_timeout(void) +{ + dhcp_tick_1s = 0; + dhcp_tick_next = DHCP_WAIT_TIME; + dhcp_retry_count = 0; +} + +void DHCP_time_handler(void) +{ + dhcp_tick_1s++; +} + +void getIPfromDHCP(uint8_t* ip) +{ + ip[0] = DHCP_allocated_ip[0]; + ip[1] = DHCP_allocated_ip[1]; + ip[2] = DHCP_allocated_ip[2]; + ip[3] = DHCP_allocated_ip[3]; +} + +void getGWfromDHCP(uint8_t* ip) +{ + ip[0] =DHCP_allocated_gw[0]; + ip[1] =DHCP_allocated_gw[1]; + ip[2] =DHCP_allocated_gw[2]; + ip[3] =DHCP_allocated_gw[3]; +} + +void getSNfromDHCP(uint8_t* ip) +{ + ip[0] = DHCP_allocated_sn[0]; + ip[1] = DHCP_allocated_sn[1]; + ip[2] = DHCP_allocated_sn[2]; + ip[3] = DHCP_allocated_sn[3]; +} + +void getDNSfromDHCP(uint8_t* ip) +{ + ip[0] = DHCP_allocated_dns[0]; + ip[1] = DHCP_allocated_dns[1]; + ip[2] = DHCP_allocated_dns[2]; + ip[3] = DHCP_allocated_dns[3]; +} + +uint32_t getDHCPLeasetime(void) +{ + return dhcp_lease_time; +} + +uint32_t getDHCPTick1s(void) +{ + return dhcp_tick_1s; +} + +char NibbleToHex(uint8_t nibble) +{ + nibble &= 0x0F; + if (nibble <= 9) + return nibble + '0'; + else + return nibble + ('A'-0x0A); +} + + diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DHCP/wizchip_dhcp.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DHCP/wizchip_dhcp.h new file mode 100644 index 000000000..ae5dc6e0e --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DHCP/wizchip_dhcp.h @@ -0,0 +1,162 @@ +//***************************************************************************** +// +//! \file wizchip_dhcp.h +//! \brief DHCP APIs Header file. +//! \details Processig DHCP protocol as DISCOVER, OFFER, REQUEST, ACK, NACK and DECLINE. +//! \version 1.1.1 +//! \date 2019/10/08 +//! \par Revision history +//! <2019/10/08> compare DHCP server ip address +//! <2013/11/18> 1st Release +//! <2012/12/20> V1.1.0 +//! 1. Move unreferenced DEFINE to dhcp.c +//! <2012/12/26> V1.1.1 +//! \author Eric Jung & MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** +#ifndef _WIZCHIP_DHCP_H_ +#define _WIZCHIP_DHCP_H_ +#ifdef __cplusplus +extern "C" { +#endif + +/* + * @brief + * @details If you want to display debug & processing message, Define _DHCP_DEBUG_ + * @note If defined, it depends on + */ +//#define _DHCP_DEBUG_ + + +/* Retry to processing DHCP */ +#define MAX_DHCP_RETRY 2 ///< Maximum retry count +#define DHCP_WAIT_TIME 10 ///< Wait Time 10s + + +/* UDP port numbers for DHCP */ +#define DHCP_SERVER_PORT 67 ///< DHCP server port number +#define DHCP_CLIENT_PORT 68 ///< DHCP client port number + + +#define MAGIC_COOKIE 0x63825363 ///< You should not modify it number. + +#define DCHP_HOST_NAME "WIZnet\0" + +/* + * @brief return value of @ref DHCP_run() + */ +enum +{ + DHCP_FAILED = 0, ///< Processing Fail + DHCP_RUNNING, ///< Processing DHCP protocol + DHCP_IP_ASSIGN, ///< First Occupy IP from DHPC server (if cbfunc == null, act as default default_ip_assign) + DHCP_IP_CHANGED, ///< Change IP address by new ip from DHCP (if cbfunc == null, act as default default_ip_update) + DHCP_IP_LEASED, ///< Stand by + DHCP_STOPPED ///< Stop processing DHCP protocol +}; + +/* + * @brief DHCP client initialization (outside of the main loop) + * @param s - socket number + * @param buf - buffer for processing DHCP message + */ +void DHCP_init(uint8_t s, uint8_t * buf); + +/* + * @brief DHCP 1s Tick Timer handler + * @note SHOULD BE register to your system 1s Tick timer handler + */ +void DHCP_time_handler(void); + +/* + * @brief Register call back function + * @param ip_assign - callback func when IP is assigned from DHCP server first + * @param ip_update - callback func when IP is changed + * @param ip_conflict - callback func when the assigned IP is conflict with others. + */ +void reg_dhcp_cbfunc(void(*ip_assign)(void), void(*ip_update)(void), void(*ip_conflict)(void)); + +/* + * @brief DHCP client in the main loop + * @return The value is as the follow \n + * @ref DHCP_FAILED \n + * @ref DHCP_RUNNING \n + * @ref DHCP_IP_ASSIGN \n + * @ref DHCP_IP_CHANGED \n + * @ref DHCP_IP_LEASED \n + * @ref DHCP_STOPPED \n + * + * @note This function is always called by you main task. + */ +uint8_t DHCP_run(void); + +/* + * @brief Stop DHCP processing + * @note If you want to restart. call DHCP_init() and DHCP_run() + */ +void DHCP_stop(void); + +/* Get Network information assigned from DHCP server */ +/* + * @brief Get IP address + * @param ip - IP address to be returned + */ +void getIPfromDHCP(uint8_t* ip); +/* + * @brief Get Gateway address + * @param ip - Gateway address to be returned + */ +void getGWfromDHCP(uint8_t* ip); +/* + * @brief Get Subnet mask value + * @param ip - Subnet mask to be returned + */ +void getSNfromDHCP(uint8_t* ip); +/* + * @brief Get DNS address + * @param ip - DNS address to be returned + */ +void getDNSfromDHCP(uint8_t* ip); + +/* + * @brief Get the leased time by DHCP sever + * @return unit 1s + */ +uint32_t getDHCPLeasetime(void); + +uint32_t getDHCPTick1s(void); + +#ifdef __cplusplus +} +#endif + +#endif /* _WIZCHIP_DHCP_H_ */ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DNS/wizchip_dns.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DNS/wizchip_dns.c new file mode 100644 index 000000000..bf40fedd8 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DNS/wizchip_dns.c @@ -0,0 +1,564 @@ +//***************************************************************************** +// +//! \file wizchip_dns.c +//! \brief DNS APIs Implement file. +//! \details Send DNS query & Receive DNS reponse. \n +//! It depends on stdlib.h & string.h in ansi-c library +//! \version 1.1.0 +//! \date 2013/11/18 +//! \par Revision history +//! <2013/10/21> 1st Release +//! <2013/12/20> V1.1.0 +//! 1. Remove secondary DNS server in DNS_run +//! If 1st DNS_run failed, call DNS_run with 2nd DNS again +//! 2. DNS_timerHandler -> DNS_time_handler +//! 3. Remove the unused define +//! 4. Integrated dns.h dns.c & dns_parse.h dns_parse.c into dns.h & dns.c +//! <2013/12/20> V1.1.0 +//! +//! \author Eric Jung & MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** + +#include +#include +#include + +#include "DNS/wizchip_dns.h" + +#ifdef _DNS_DEBUG_ + #include +#endif + +#define INITRTT 2000L /* Initial smoothed response time */ +#define MAXCNAME (MAX_DOMAIN_NAME + (MAX_DOMAIN_NAME>>1)) /* Maximum amount of cname recursion */ + +#define TYPE_A 1 /* Host address */ +#define TYPE_NS 2 /* Name server */ +#define TYPE_MD 3 /* Mail destination (obsolete) */ +#define TYPE_MF 4 /* Mail forwarder (obsolete) */ +#define TYPE_CNAME 5 /* Canonical name */ +#define TYPE_SOA 6 /* Start of Authority */ +#define TYPE_MB 7 /* Mailbox name (experimental) */ +#define TYPE_MG 8 /* Mail group member (experimental) */ +#define TYPE_MR 9 /* Mail rename name (experimental) */ +#define TYPE_NULL 10 /* Null (experimental) */ +#define TYPE_WKS 11 /* Well-known sockets */ +#define TYPE_PTR 12 /* Pointer record */ +#define TYPE_HINFO 13 /* Host information */ +#define TYPE_MINFO 14 /* Mailbox information (experimental)*/ +#define TYPE_MX 15 /* Mail exchanger */ +#define TYPE_TXT 16 /* Text strings */ +#define TYPE_ANY 255 /* Matches any type */ + +#define CLASS_IN 1 /* The ARPA Internet */ + +/* Round trip timing parameters */ +#define AGAIN 8 /* Average RTT gain = 1/8 */ +#define LAGAIN 3 /* Log2(AGAIN) */ +#define DGAIN 4 /* Mean deviation gain = 1/4 */ +#define LDGAIN 2 /* log2(DGAIN) */ + +/* Header for all domain messages */ +struct dhdr +{ + uint16_t id; /* Identification */ + uint8_t qr; /* Query/Response */ +#define QUERY 0 +#define RESPONSE 1 + uint8_t opcode; +#define IQUERY 1 + uint8_t aa; /* Authoratative answer */ + uint8_t tc; /* Truncation */ + uint8_t rd; /* Recursion desired */ + uint8_t ra; /* Recursion available */ + uint8_t rcode; /* Response code */ +#define NO_ERROR 0 +#define FORMAT_ERROR 1 +#define SERVER_FAIL 2 +#define NAME_ERROR 3 +#define NOT_IMPL 4 +#define REFUSED 5 + uint16_t qdcount; /* Question count */ + uint16_t ancount; /* Answer count */ + uint16_t nscount; /* Authority (name server) count */ + uint16_t arcount; /* Additional record count */ +}; + + +uint8_t* pDNSMSG; // DNS message buffer +uint8_t DNS_SOCKET; // SOCKET number for DNS +uint16_t DNS_MSGID; // DNS message ID + +uint32_t dns_1s_tick; // for timout of DNS processing +static uint8_t retry_count; + +/* converts uint16_t from network buffer to a host byte order integer. */ +uint16_t get16(uint8_t * s) +{ + uint16_t i; + i = *s++ << 8; + i = i + *s; + return i; +} + +/* copies uint16_t to the network buffer with network byte order. */ +uint8_t * put16(uint8_t * s, uint16_t i) +{ + *s++ = i >> 8; + *s++ = i; + return s; +} + + +/* + * CONVERT A DOMAIN NAME TO THE HUMAN-READABLE FORM + * + * Description : This function converts a compressed domain name to the human-readable form + * Arguments : msg - is a pointer to the reply message + * compressed - is a pointer to the domain name in reply message. + * buf - is a pointer to the buffer for the human-readable form name. + * len - is the MAX. size of buffer. + * Returns : the length of compressed message + */ +int parse_name(uint8_t * msg, uint8_t * compressed, char * buf, int16_t len) +{ + uint16_t slen; /* Length of current segment */ + uint8_t * cp; + int clen = 0; /* Total length of compressed name */ + int indirect = 0; /* Set if indirection encountered */ + int nseg = 0; /* Total number of segments in name */ + + cp = compressed; + + for (;;) + { + slen = *cp++; /* Length of this segment */ + + if (!indirect) clen++; + + if ((slen & 0xc0) == 0xc0) + { + if (!indirect) + clen++; + indirect = 1; + /* Follow indirection */ + cp = &msg[((slen & 0x3f)<<8) + *cp]; + slen = *cp++; + } + + if (slen == 0) /* zero length == all done */ + break; + + len -= slen + 1; + + if (len < 0) return -1; + + if (!indirect) clen += slen; + + while (slen-- != 0) *buf++ = (char)*cp++; + *buf++ = '.'; + nseg++; + } + + if (nseg == 0) + { + /* Root name; represent as single dot */ + *buf++ = '.'; + len--; + } + + *buf++ = '\0'; + len--; + + return clen; /* Length of compressed message */ +} + +/* + * PARSE QUESTION SECTION + * + * Description : This function parses the qeustion record of the reply message. + * Arguments : msg - is a pointer to the reply message + * cp - is a pointer to the qeustion record. + * Returns : a pointer the to next record. + */ +uint8_t * dns_question(uint8_t * msg, uint8_t * cp) +{ + int len; + char name[MAXCNAME]; + + len = parse_name(msg, cp, name, MAXCNAME); + + + if (len == -1) return 0; + + cp += len; + cp += 2; /* type */ + cp += 2; /* class */ + + return cp; +} + + +/* + * PARSE ANSER SECTION + * + * Description : This function parses the answer record of the reply message. + * Arguments : msg - is a pointer to the reply message + * cp - is a pointer to the answer record. + * Returns : a pointer the to next record. + */ +uint8_t * dns_answer(uint8_t * msg, uint8_t * cp, uint8_t * ip_from_dns) +{ + int len, type; + char name[MAXCNAME]; + + len = parse_name(msg, cp, name, MAXCNAME); + + if (len == -1) return 0; + + cp += len; + type = get16(cp); + cp += 2; /* type */ + cp += 2; /* class */ + cp += 4; /* ttl */ + cp += 2; /* len */ + + + switch (type) + { + case TYPE_A: + /* Just read the address directly into the structure */ + ip_from_dns[0] = *cp++; + ip_from_dns[1] = *cp++; + ip_from_dns[2] = *cp++; + ip_from_dns[3] = *cp++; + break; + case TYPE_CNAME: + case TYPE_MB: + case TYPE_MG: + case TYPE_MR: + case TYPE_NS: + case TYPE_PTR: + /* These types all consist of a single domain name */ + /* convert it to ascii format */ + len = parse_name(msg, cp, name, MAXCNAME); + if (len == -1) return 0; + + cp += len; + break; + case TYPE_HINFO: + len = *cp++; + cp += len; + + len = *cp++; + cp += len; + break; + case TYPE_MX: + cp += 2; + /* Get domain name of exchanger */ + len = parse_name(msg, cp, name, MAXCNAME); + if (len == -1) return 0; + + cp += len; + break; + case TYPE_SOA: + /* Get domain name of name server */ + len = parse_name(msg, cp, name, MAXCNAME); + if (len == -1) return 0; + + cp += len; + + /* Get domain name of responsible person */ + len = parse_name(msg, cp, name, MAXCNAME); + if (len == -1) return 0; + + cp += len; + + cp += 4; + cp += 4; + cp += 4; + cp += 4; + cp += 4; + break; + case TYPE_TXT: + /* Just stash */ + break; + default: + /* Ignore */ + break; + } + + return cp; +} + +/* + * PARSE THE DNS REPLY + * + * Description : This function parses the reply message from DNS server. + * Arguments : dhdr - is a pointer to the header for DNS message + * buf - is a pointer to the reply message. + * len - is the size of reply message. + * Returns : -1 - Domain name lenght is too big + * 0 - Fail (Timout or parse error) + * 1 - Success, + */ +int8_t parseDNSMSG(struct dhdr * pdhdr, uint8_t * pbuf, uint8_t * ip_from_dns) +{ + uint16_t tmp; + uint16_t i; + uint8_t * msg; + uint8_t * cp; + + msg = pbuf; + memset(pdhdr, 0, sizeof(*pdhdr)); + + pdhdr->id = get16(&msg[0]); + tmp = get16(&msg[2]); + if (tmp & 0x8000) pdhdr->qr = 1; + + pdhdr->opcode = (tmp >> 11) & 0xf; + + if (tmp & 0x0400) pdhdr->aa = 1; + if (tmp & 0x0200) pdhdr->tc = 1; + if (tmp & 0x0100) pdhdr->rd = 1; + if (tmp & 0x0080) pdhdr->ra = 1; + + pdhdr->rcode = tmp & 0xf; + pdhdr->qdcount = get16(&msg[4]); + pdhdr->ancount = get16(&msg[6]); + pdhdr->nscount = get16(&msg[8]); + pdhdr->arcount = get16(&msg[10]); + + + /* Now parse the variable length sections */ + cp = &msg[12]; + + /* Question section */ + for (i = 0; i < pdhdr->qdcount; i++) + { + cp = dns_question(msg, cp); + #ifdef _DNS_DEUBG_ + printf("MAX_DOMAIN_NAME is too small, it should be redfine in dns.h"); + #endif + if(!cp) return -1; + } + + /* Answer section */ + for (i = 0; i < pdhdr->ancount; i++) + { + cp = dns_answer(msg, cp, ip_from_dns); + #ifdef _DNS_DEUBG_ + printf("MAX_DOMAIN_NAME is too small, it should be redfine in dns.h"); + #endif + if(!cp) return -1; + } + + /* Name server (authority) section */ + for (i = 0; i < pdhdr->nscount; i++) + { + ; + } + + /* Additional section */ + for (i = 0; i < pdhdr->arcount; i++) + { + ; + } + + if(pdhdr->rcode == 0) return 1; // No error + else return 0; +} + + +/* + * MAKE DNS QUERY MESSAGE + * + * Description : This function makes DNS query message. + * Arguments : op - Recursion desired + * name - is a pointer to the domain name. + * buf - is a pointer to the buffer for DNS message. + * len - is the MAX. size of buffer. + * Returns : the pointer to the DNS message. + */ +int16_t dns_makequery(uint16_t op, char * name, uint8_t * buf, uint16_t len) +{ + uint8_t *cp; + char *cp1; + char sname[MAXCNAME]; + char *dname; + uint16_t p; + uint16_t dlen; + + cp = buf; + + DNS_MSGID++; + cp = put16(cp, DNS_MSGID); + p = (op << 11) | 0x0100; /* Recursion desired */ + cp = put16(cp, p); + cp = put16(cp, 1); + cp = put16(cp, 0); + cp = put16(cp, 0); + cp = put16(cp, 0); + + strcpy(sname, name); + dname = sname; + dlen = strlen(dname); + for (;;) + { + /* Look for next dot */ + cp1 = strchr(dname, '.'); + + if (cp1 != NULL) len = cp1 - dname; /* More to come */ + else len = dlen; /* Last component */ + + *cp++ = len; /* Write length of component */ + if (len == 0) break; + + /* Copy component up to (but not including) dot */ + strncpy((char *)cp, dname, len); + cp += len; + if (cp1 == NULL) + { + *cp++ = 0; /* Last one; write null and finish */ + break; + } + dname += len+1; + dlen -= len+1; + } + + cp = put16(cp, 0x0001); /* type */ + cp = put16(cp, 0x0001); /* class */ + + return ((int16_t)((uint32_t)(cp) - (uint32_t)(buf))); +} + +/* + * CHECK DNS TIMEOUT + * + * Description : This function check the DNS timeout + * Arguments : None. + * Returns : -1 - timeout occurred, 0 - timer over, but no timeout, 1 - no timer over, no timeout occur + * Note : timeout : retry count and timer both over. + */ + +int8_t check_DNS_timeout(void) +{ + + if(dns_1s_tick >= DNS_WAIT_TIME) + { + dns_1s_tick = 0; + if(retry_count >= MAX_DNS_RETRY) { + retry_count = 0; + return -1; // timeout occurred + } + retry_count++; + return 0; // timer over, but no timeout + } + + return 1; // no timer over, no timeout occur +} + + + +/* DNS CLIENT INIT */ +void DNS_init(uint8_t s, uint8_t * buf) +{ + DNS_SOCKET = s; // SOCK_DNS + pDNSMSG = buf; // User's shared buffer + DNS_MSGID = DNS_MSG_ID; +} + +/* DNS CLIENT RUN */ +int8_t DNS_run(uint8_t * dns_ip, uint8_t * name, uint8_t * ip_from_dns) +{ + int8_t ret; + struct dhdr dhp; + uint8_t ip[4]; + uint16_t len, port; + int8_t ret_check_timeout; + + retry_count = 0; + dns_1s_tick = 0; + + // Socket open + wizchip_socket(DNS_SOCKET, Sn_MR_UDP, 0, 0); + +#ifdef _DNS_DEBUG_ + printf("> DNS Query to DNS Server : %d.%d.%d.%d\r\n", dns_ip[0], dns_ip[1], dns_ip[2], dns_ip[3]); +#endif + + len = dns_makequery(0, (char *)name, pDNSMSG, MAX_DNS_BUF_SIZE); + wizchip_sendto(DNS_SOCKET, pDNSMSG, len, dns_ip, IPPORT_DOMAIN); + + while (1) + { + if ((len = getSn_RX_RSR(DNS_SOCKET)) > 0) + { + if (len > MAX_DNS_BUF_SIZE) len = MAX_DNS_BUF_SIZE; + len = wizchip_recvfrom(DNS_SOCKET, pDNSMSG, len, ip, &port); + #ifdef _DNS_DEBUG_ + printf("> Receive DNS message from %d.%d.%d.%d(%d). len = %d\r\n", ip[0], ip[1], ip[2], ip[3],port,len); + #endif + ret = parseDNSMSG(&dhp, pDNSMSG, ip_from_dns); + break; + } + // Check Timeout + ret_check_timeout = check_DNS_timeout(); + if (ret_check_timeout < 0) { + +#ifdef _DNS_DEBUG_ + printf("> DNS Server is not responding : %d.%d.%d.%d\r\n", dns_ip[0], dns_ip[1], dns_ip[2], dns_ip[3]); +#endif + wizchip_close(DNS_SOCKET); + return 0; // timeout occurred + } + else if (ret_check_timeout == 0) { + +#ifdef _DNS_DEBUG_ + printf("> DNS Timeout\r\n"); +#endif + wizchip_sendto(DNS_SOCKET, pDNSMSG, len, dns_ip, IPPORT_DOMAIN); + } + } + wizchip_close(DNS_SOCKET); + // Return value + // 0 > : failed / 1 - success + return ret; +} + + +/* DNS TIMER HANDLER */ +void DNS_time_handler(void) +{ + dns_1s_tick++; +} diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DNS/wizchip_dns.h b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DNS/wizchip_dns.h new file mode 100644 index 000000000..31ef51734 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/ioLibrary/Internet/DNS/wizchip_dns.h @@ -0,0 +1,109 @@ +//***************************************************************************** +// +//! \file wizchip_dns.h +//! \brief DNS APIs Header file. +//! \details Send DNS query & Receive DNS reponse. +//! \version 1.1.0 +//! \date 2013/11/18 +//! \par Revision history +//! <2013/10/21> 1st Release +//! <2013/12/20> V1.1.0 +//! 1. Remove secondary DNS server in DNS_run +//! If 1st DNS_run failed, call DNS_run with 2nd DNS again +//! 2. DNS_timerHandler -> DNS_time_handler +//! 3. Move the no reference define to dns.c +//! 4. Integrated dns.h dns.c & dns_parse.h dns_parse.c into dns.h & dns.c +//! <2013/12/20> V1.1.0 +//! +//! \author Eric Jung & MidnightCow +//! \copyright +//! +//! Copyright (c) 2013, WIZnet Co., LTD. +//! All rights reserved. +//! +//! Redistribution and use in source and binary forms, with or without +//! modification, are permitted provided that the following conditions +//! are met: +//! +//! * Redistributions of source code must retain the above copyright +//! notice, this list of conditions and the following disclaimer. +//! * Redistributions in binary form must reproduce the above copyright +//! notice, this list of conditions and the following disclaimer in the +//! documentation and/or other materials provided with the distribution. +//! * Neither the name of the nor the names of its +//! contributors may be used to endorse or promote products derived +//! from this software without specific prior written permission. +//! +//! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +//! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +//! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +//! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +//! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +//! CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +//! SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +//! INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +//! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +//! ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF +//! THE POSSIBILITY OF SUCH DAMAGE. +// +//***************************************************************************** + +#ifndef _WIZCHIP_DNS_H_ +#define _WIZCHIP_DNS_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +/* + * @brief Define it for Debug & Monitor DNS processing. + * @note If defined, it dependens on + */ +//#define _DNS_DEBUG_ + +#define MAX_DNS_BUF_SIZE 256 ///< maximum size of DNS buffer. */ +/* + * @brief Maxium length of your queried Domain name + * @todo SHOULD BE defined it equal as or greater than your Domain name lenght + null character(1) + * @note SHOULD BE careful to stack overflow because it is allocated 1.5 times as MAX_DOMAIN_NAME in stack. + */ +#define MAX_DOMAIN_NAME 16 // for example "www.google.com" + +#define MAX_DNS_RETRY 2 ///< Requery Count +#define DNS_WAIT_TIME 3 ///< Wait response time. unit 1s. + +#define IPPORT_DOMAIN 53 ///< DNS server port number + +#define DNS_MSG_ID 0x1122 ///< ID for DNS message. You can be modifyed it any number +/* + * @brief DNS process initialize + * @param s : Socket number for DNS + * @param buf : Buffer for DNS message + */ +void DNS_init(uint8_t s, uint8_t * buf); + +/* + * @brief DNS process + * @details Send DNS query and receive DNS response + * @param dns_ip : DNS server ip + * @param name : Domain name to be queryed + * @param ip_from_dns : IP address from DNS server + * @return -1 : failed. @ref MAX_DOMIN_NAME is too small \n + * 0 : failed (Timeout or Parse error)\n + * 1 : success + * @note This funtion blocks until success or fail. max time = @ref MAX_DNS_RETRY * @ref DNS_WAIT_TIME + */ +int8_t DNS_run(uint8_t * dns_ip, uint8_t * name, uint8_t * ip_from_dns); + +/* + * @brief DNS 1s Tick Timer handler + * @note SHOULD BE register to your system 1s Tick timer handler + */ +void DNS_time_handler(void); + +#ifdef __cplusplus +} +#endif + +#endif /* _WIZCHIP_DNS_H_ */ diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz.c new file mode 100644 index 000000000..6e8105cad --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz.c @@ -0,0 +1,987 @@ +/* + * Copyright (c) 2006-2022, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2018-09-26 chenyong first version + */ + +#include +#include +#include + +#include +#include +//h姝ゅ涓烘坊鍔犲唴瀹 +#ifdef __cplusplus +extern "C"{ +#endif +#include "drv_spi.h" +#ifdef __cplusplus +} +#endif +//娣诲姞鍐呭缁撴潫 + +#include +#ifdef WIZ_USING_DHCP +#include +#endif + +#include +#include + +#if !defined(WIZ_SPI_DEVICE) || !defined(WIZ_RST_PIN) || !defined(WIZ_IRQ_PIN) +#error "please config SPI device name, reset pin and irq pin in menuconfig." +#endif + +#define DBG_ENABLE +#define DBG_SECTION_NAME "wiz" +#ifdef WIZ_DEBUG +#define DBG_LEVEL DBG_LOG +#else +#define DBG_LEVEL DBG_INFO +#endif /* WIZ_DEBUG */ +#define DBG_COLOR +#include + +#define IMR_SENDOK 0x10 +#define IMR_TIMEOUT 0x08 +#define IMR_RECV 0x04 +#define IMR_DISCON 0x02 +#define IMR_CON 0x01 +#define WIZ_DEFAULT_MAC "00-E0-81-DC-53-1A" + +#define WIZ_ID_LEN 6 +static char wiz_netdev_name[WIZ_ID_LEN]; + +#define WIZ_DHCP_SOCKET 7 + +extern struct rt_spi_device *wiz_device; +extern int wiz_device_init(const char *spi_dev_name); +extern int wiz_inet_init(void); +static int wiz_netdev_info_update(struct netdev *netdev, rt_bool_t reset); + +rt_bool_t wiz_init_ok = RT_FALSE; +static wiz_NetInfo wiz_net_info; +static rt_timer_t dns_tick_timer; + +#ifdef WIZ_USING_DHCP +static rt_timer_t dhcp_timer; +#endif +static struct rt_work *dhcp_work = RT_NULL; +extern int wiz_recv_notice_cb(int socket); +extern int wiz_closed_notice_cb(int socket); + +static rt_mailbox_t wiz_rx_mb = RT_NULL; + +static void wiz_isr(void) +{ + /* enter interrupt */ + rt_interrupt_enter(); + + rt_mb_send(wiz_rx_mb, (rt_ubase_t) wiz_device); + + /* leave interrupt */ + rt_interrupt_leave(); +} + +static void wiz_data_thread_entry(void *parameter) +{ +#define IR_SOCK(ch) (0x01 << ch) /**< check socket interrupt */ + + struct rt_spi_device* dev; + + while (1) + { + if (rt_mb_recv(wiz_rx_mb, (rt_ubase_t*) &dev, RT_WAITING_FOREVER) == RT_EOK) + { + uint8_t ir, sir, sn_ir; + int8_t socket = -1; + + /* get IR data than clean IR */ + ir = getIR(); + setIR(ir); + + if ((ir & IR_CONFLICT) == IR_CONFLICT) + { + setIR(IR_CONFLICT); + } + + if ((ir & IR_UNREACH) == IR_UNREACH) + { + setIR(IR_UNREACH); + } + + /* get and process socket interrupt register */ + sir = getSIR(); + + for (socket = 0; socket < 8; socket++) + { + sn_ir = 0; + + if (sir & IR_SOCK(socket)) + { + /* save interrupt value*/ + sn_ir = getSn_IR(socket); + + if (sn_ir & Sn_IR_CON) + { + setSn_IR(socket, Sn_IR_CON); + } + if (sn_ir & Sn_IR_DISCON) + { + wiz_closed_notice_cb(socket); + setSn_IR(socket, Sn_IR_DISCON); + } + if (sn_ir & Sn_IR_RECV) + { + wiz_recv_notice_cb(socket); + setSn_IR(socket, Sn_IR_RECV); + } + if (sn_ir & Sn_IR_TIMEOUT) + { + /* deal with timeout event in the wiznet ioLibrary */ + //setSn_IR(socket, Sn_IR_TIMEOUT); + } + } + } + } + } +} + +static void spi_write_byte(uint8_t data) +{ + struct rt_spi_message spi_msg; + + rt_memset(&spi_msg, 0x00, sizeof(spi_msg)); + + spi_msg.send_buf = &data; + spi_msg.length = 1; + + rt_spi_transfer_message(wiz_device, &spi_msg); +} + +static uint8_t spi_read_byte(void) +{ + struct rt_spi_message spi_msg; + uint8_t data; + + rt_memset(&spi_msg, 0x00, sizeof(spi_msg)); + + spi_msg.recv_buf = &data; + spi_msg.length = 1; + + rt_spi_transfer_message(wiz_device, &spi_msg); + + return data; +} + +static void spi_write_burst(uint8_t *pbuf, uint16_t len) +{ + struct rt_spi_message spi_msg; + + rt_memset(&spi_msg, 0x00, sizeof(spi_msg)); + + spi_msg.send_buf = pbuf; + spi_msg.length = len; + + rt_spi_transfer_message(wiz_device, &spi_msg); +} + +static void spi_read_burst(uint8_t *pbuf, uint16_t len) +{ + struct rt_spi_message spi_msg; + + rt_memset(&spi_msg, 0x00, sizeof(spi_msg)); + + spi_msg.recv_buf = pbuf; + spi_msg.length = len; + + rt_spi_transfer_message(wiz_device, &spi_msg); +} + +static void spi_cris_enter(void) +{ + rt_spi_take_bus(wiz_device); +} + +static void spi_cris_exit(void) +{ + rt_spi_release_bus(wiz_device); +} + +static void spi_cs_select(void) +{ + rt_spi_take(wiz_device); +} + +static void spi_cs_deselect(void) +{ + rt_spi_release(wiz_device); +} + +/* register TCP communication related callback function */ +static int wiz_callback_register(void) +{ + /* register critical section callback function */ + reg_wizchip_cris_cbfunc(spi_cris_enter, spi_cris_exit); + +#if (_WIZCHIP_IO_MODE_ == _WIZCHIP_IO_MODE_SPI_VDM_) || (_WIZCHIP_IO_MODE_ == _WIZCHIP_IO_MODE_SPI_FDM_) + /* register SPI device CS select callback function */ + reg_wizchip_cs_cbfunc(spi_cs_select, spi_cs_deselect); +#else +#if (_WIZCHIP_IO_MODE_ & _WIZCHIP_IO_MODE_SIP_) != _WIZCHIP_IO_MODE_SIP_ +#error "Unknown _WIZCHIP_IO_MODE_" +#else + reg_wizchip_cs_cbfunc(wizchip_select, wizchip_deselect); +#endif +#endif + /* register SPI device read/write data callback function */ + reg_wizchip_spi_cbfunc(spi_read_byte, spi_write_byte); + reg_wizchip_spiburst_cbfunc(spi_read_burst, spi_write_burst); + + return RT_EOK; +} + +/* initialize WIZnet chip configures */ +static int wiz_chip_cfg_init(void) +{ +#define CW_INIT_MODE 2 +#define CW_INIT_SOCKETS 8 +#define CW_INIT_TIMEOUT (2 * RT_TICK_PER_SECOND) + + uint8_t memsize[CW_INIT_MODE][CW_INIT_SOCKETS] = { 0 }; + + /* reset WIZnet chip internal PHY, configures PHY mode. */ + if (ctlwizchip(CW_INIT_WIZCHIP, (void*) memsize) == -1) + { + LOG_E("WIZCHIP initialize failed."); + return -RT_ERROR; + } + + struct wiz_NetTimeout_t net_timeout; + net_timeout.retry_cnt=5; + net_timeout.time_100us=20000; + ctlnetwork(CN_SET_TIMEOUT, (void*) &net_timeout); + + return RT_EOK; +} + +/* WIZnet chip hardware reset */ +static void wiz_reset(void) +{ + rt_pin_write(WIZ_RST_PIN, PIN_LOW); + rt_thread_mdelay(2); + + rt_pin_write(WIZ_RST_PIN, PIN_HIGH); + rt_thread_mdelay(2); +} + +#ifdef WIZ_USING_DHCP +static void wiz_ip_assign(void) +{ + /* get the assigned IP address and reconfigure the IP address of the chip */ + getIPfromDHCP(wiz_net_info.ip); + getGWfromDHCP(wiz_net_info.gw); + getSNfromDHCP(wiz_net_info.sn); + getDNSfromDHCP(wiz_net_info.dns); + wiz_net_info.dhcp = NETINFO_DHCP; + + ctlnetwork(CN_SET_NETINFO, (void*) &wiz_net_info); +} + +static void wiz_ip_conflict(void) +{ + /* deal with conflict IP for WIZnet DHCP */ + LOG_D("conflict IP from DHCP."); + RT_ASSERT(0); +} + +static void wiz_dhcp_timer_entry(void *parameter) +{ + DHCP_time_handler(); +} +#endif /* WIZ_USING_DHCP */ + +static int wiz_netstr_to_array(const char *net_str, uint8_t *net_array) +{ + int ret; + unsigned int idx; + + RT_ASSERT(net_str); + RT_ASSERT(net_array); + + if (strstr(net_str, ".")) + { + int ip_addr[4]; + + /* resolve IP address, gateway address or subnet mask */ + ret = sscanf(net_str, "%d.%d.%d.%d", ip_addr + 0, ip_addr + 1, ip_addr + 2, ip_addr + 3); + if (ret != 4) + { + LOG_E("input address(%s) resolve error.", net_str); + return -RT_ERROR; + } + + for (idx = 0; idx < sizeof(ip_addr)/sizeof(ip_addr[0]); idx++) + { + net_array[idx] = ip_addr[idx]; + } + } + else + { + int mac_addr[6]; + + /* resolve MAC address */ + if (strstr(net_str, ":")) + { + ret = sscanf(net_str, "%02x:%02x:%02x:%02x:%02x:%02x", mac_addr + 0, mac_addr + 1, mac_addr + 2, + mac_addr + 3, mac_addr + 4, mac_addr + 5); + } + else if (strstr(net_str, "-")) + { + ret = sscanf(net_str, "%02x-%02x-%02x-%02x-%02x-%02x", mac_addr + 0, mac_addr + 1, mac_addr + 2, + mac_addr + 3, mac_addr + 4, mac_addr + 5); + } + else + { + LOG_E("input MAC address(%s) format error.", net_str); + return -RT_ERROR; + } + + if (ret != 6) + { + LOG_E("input MAC address(%s) resolve error.", net_str); + return -RT_ERROR; + } + + for (idx = 0; idx < sizeof(mac_addr)/sizeof(mac_addr[0]); idx++) + { + net_array[idx] = mac_addr[idx]; + } + } + + return RT_EOK; +} + +/* set WIZnet device MAC address */ +RT_WEAK void wiz_user_config_mac(char *mac_buf, rt_uint8_t buf_len) +{ + RT_ASSERT(mac_buf != RT_NULL); + RT_ASSERT(buf_len > 0); + + rt_memset(mac_buf, 0x0, buf_len); + rt_strncpy(mac_buf, WIZ_DEFAULT_MAC, buf_len); +} + +static void wiz_set_mac(void) +{ + char mac_str[32]; + + wiz_user_config_mac(mac_str, sizeof(mac_str)); + if (wiz_netstr_to_array(mac_str, wiz_net_info.mac) != RT_EOK) + { + wiz_netstr_to_array(WIZ_DEFAULT_MAC, wiz_net_info.mac); + } +} + +#ifdef WIZ_USING_DHCP +static int wiz_network_dhcp(struct netdev *netdev); +#endif + +/* initialize WIZnet network configures */ +static int wiz_network_init(rt_bool_t b_config) +{ + struct netdev * netdev; + netdev = netdev_get_by_name(wiz_netdev_name); + if (netdev == RT_NULL) + { + LOG_E("don`t find device(%s)", wiz_netdev_name); + return -RT_ERROR; + } + +#ifndef WIZ_USING_DHCP + if(wiz_netstr_to_array(WIZ_IPADDR, wiz_net_info.ip) != RT_EOK || + wiz_netstr_to_array(WIZ_MSKADDR, wiz_net_info.sn) != RT_EOK || + wiz_netstr_to_array(WIZ_GWADDR, wiz_net_info.dns) != RT_EOK || + wiz_netstr_to_array(WIZ_GWADDR, wiz_net_info.gw) != RT_EOK) + { + netdev_low_level_set_status(netdev, RT_FALSE); + netdev_low_level_set_link_status(netdev, RT_FALSE); + return -RT_ERROR; + } + wiz_net_info.dhcp = NETINFO_STATIC; +#endif + + int result = RT_EOK; + rt_bool_t b_status = b_config; + + /* set mac information */ + wiz_set_mac(); + /* set static WIZnet network information */ + ctlnetwork(CN_SET_NETINFO, (void*) &wiz_net_info); + +#ifdef WIZ_USING_DHCP + /* alloc IP address through DHCP */ + { + result = wiz_network_dhcp(netdev); + if (result != RT_EOK) + { + b_status = RT_FALSE; + LOG_E("WIZnet network initialize failed, DHCP timeout."); + } + else + { + b_status = RT_TRUE; + LOG_D("WIZnet network initialize success."); + } + } +#endif + + netdev_low_level_set_status(netdev, b_status); + wiz_netdev_info_update(netdev, RT_FALSE); + netdev_low_level_set_link_status(netdev, b_status); + + return result; +} + +/* wizenet socket initialize */ +static int wiz_socket_init(void) +{ + int idx = 0; + + /* socket(0-7) initialize */ + setSIMR(0xff); + + /* set socket receive/send buffer size */ + for (idx = 0; idx < WIZ_SOCKETS_NUM; idx++) + { + setSn_RXBUF_SIZE(idx, 0x02); + setSn_TXBUF_SIZE(idx, 0x02); + } + + /* set socket ISR state support */ + for (idx = 0; idx < WIZ_SOCKETS_NUM; idx++) + { + setSn_IMR(idx, (IMR_TIMEOUT | IMR_RECV | IMR_DISCON)); + } + + return RT_EOK; +} + +static void wiz_dns_time_handler(void *arg) +{ + extern void DNS_time_handler(void); + DNS_time_handler(); +} + +static int wiz_netdev_info_update(struct netdev *netdev, rt_bool_t reset) +{ + wiz_NetInfo net_info; + rt_memset(&net_info, 0, sizeof(net_info)); + + if(reset == RT_FALSE) + { + ctlnetwork(CN_GET_NETINFO, (void *)&net_info); + } + else + { + /* clean dns server information */ + netdev->dns_servers->addr = 0; + ctlnetwork(CN_SET_NETINFO, (void *)&net_info); + } + netdev_low_level_set_ipaddr(netdev, (const ip_addr_t *)&net_info.ip); + netdev_low_level_set_gw(netdev, (const ip_addr_t *)&net_info.gw); + netdev_low_level_set_netmask(netdev, (const ip_addr_t *)&net_info.sn); + netdev_low_level_set_dns_server(netdev, 0, (const ip_addr_t *)&net_info.dns); + memcpy(netdev->hwaddr, (const void *)&net_info.mac, netdev->hwaddr_len); + /* 1 - Static, 2 - DHCP */ + netdev_low_level_set_dhcp_status(netdev, net_info.dhcp - 1); + + return RT_EOK; +} + +static int wiz_netdev_set_up(struct netdev *netdev) +{ + netdev_low_level_set_status(netdev, RT_TRUE); + return RT_EOK; +} + +static int wiz_netdev_set_down(struct netdev *netdev) +{ + netdev_low_level_set_status(netdev, RT_FALSE); + return RT_EOK; +} + +static int wiz_netdev_set_addr_info(struct netdev *netdev, ip_addr_t *ip_addr, ip_addr_t *netmask, ip_addr_t *gw) +{ + rt_err_t result = RT_EOK; + + RT_ASSERT(netdev); + RT_ASSERT(ip_addr || netmask || gw); + + ctlnetwork(CN_GET_NETINFO, (void *)&wiz_net_info); + + if (ip_addr) + rt_memcpy(wiz_net_info.ip, &ip_addr->addr, sizeof(wiz_net_info.ip)); + + if (netmask) + rt_memcpy(wiz_net_info.sn, &netmask->addr, sizeof(wiz_net_info.sn)); + + if (gw) + rt_memcpy(wiz_net_info.gw, &gw->addr, sizeof(wiz_net_info.gw)); + + if (ctlnetwork(CN_SET_NETINFO, (void *)&wiz_net_info) == RT_EOK) + { + if (ip_addr) + netdev_low_level_set_ipaddr(netdev, ip_addr); + + if (netmask) + netdev_low_level_set_netmask(netdev, netmask); + + if (gw) + netdev_low_level_set_gw(netdev, gw); + + result = RT_EOK; + } + else + { + LOG_E("%s set addr info failed!", wiz_netdev_name); + result = -RT_ERROR; + } + + return result; +} + +static int wiz_netdev_set_dns_server(struct netdev *netdev, uint8_t dns_num, ip_addr_t *dns_server) +{ + rt_err_t result = RT_EOK; + + RT_ASSERT(netdev); + RT_ASSERT(dns_server); + + ctlnetwork(CN_GET_NETINFO, (void *)&wiz_net_info); + + rt_memcpy(wiz_net_info.dns, &dns_server->addr, sizeof(wiz_net_info.dns)); + + if (ctlnetwork(CN_SET_NETINFO, (void *)&wiz_net_info) == RT_EOK) + { + netdev_low_level_set_dns_server(netdev, dns_num, (const ip_addr_t *)dns_server); + result = RT_EOK; + } + else + { + LOG_E("%s set dns server failed!", wiz_netdev_name); + result = -RT_ERROR; + } + + return result; +} + +static int wiz_netdev_set_dhcp(struct netdev *netdev, rt_bool_t is_enabled) +{ + rt_err_t result = RT_EOK; + + RT_ASSERT(netdev); + + ctlnetwork(CN_GET_NETINFO, (void *)&wiz_net_info); + + /* 1 - Static, 2 - DHCP */ + wiz_net_info.dhcp = (dhcp_mode)(is_enabled + 1); + + if (ctlnetwork(CN_SET_NETINFO, (void *)&wiz_net_info) == RT_EOK) + { + netdev_low_level_set_dhcp_status(netdev, is_enabled); + result = RT_EOK; + + if(is_enabled == RT_FALSE) + { + if(dhcp_work != RT_NULL) + { + rt_work_cancel(dhcp_work); + } + LOG_D("wiznet(w5500) dhcp status is disable."); + } + else + { +#ifndef WIZ_USING_DHCP + LOG_W("wiznet(w5500) dhcp function haven't compiled."); + result = -RT_ERROR; +#else + if(dhcp_work != RT_NULL) + { + rt_work_submit(dhcp_work, RT_WAITING_NO); + LOG_D("wiznet(w5500) dhcp status is enable."); + } +#endif + } + } + else + { + LOG_E("%s set dhcp info failed!", wiz_netdev_name); + result = -RT_ERROR; + } + + return result; +} + +#ifdef RT_USING_FINSH +static int wiz_netdev_ping(struct netdev *netdev, const char *host, size_t data_len, uint32_t timeout, struct netdev_ping_resp *ping_resp) +{ + RT_ASSERT(netdev); + RT_ASSERT(host); + RT_ASSERT(ping_resp); + + extern int wiz_ping(struct netdev *netdev, const char *host, size_t data_len, uint32_t times, struct netdev_ping_resp *ping_resp); + + return wiz_ping(netdev, host, data_len, timeout, ping_resp); +} +#endif + +void wiz_netdev_netstat(struct netdev *netdev) +{ + // TODO + return; +} + +const struct netdev_ops wiz_netdev_ops = +{ + wiz_netdev_set_up, + wiz_netdev_set_down, + + wiz_netdev_set_addr_info, + wiz_netdev_set_dns_server, + wiz_netdev_set_dhcp, +#ifdef RT_USING_FINSH + wiz_netdev_ping, + wiz_netdev_netstat, +#endif +}; + +static struct netdev *wiz_netdev_add(const char *netdev_name) +{ +#define ETHERNET_MTU 1472 +#define HWADDR_LEN 6 + struct netdev *netdev = RT_NULL; + + netdev = (struct netdev *)rt_calloc(1, sizeof(struct netdev)); + if (netdev == RT_NULL) + { + return RT_NULL; + } + + netdev->flags = 0; + netdev->mtu = ETHERNET_MTU; + netdev->ops = &wiz_netdev_ops; + netdev->hwaddr_len = HWADDR_LEN; + +#ifdef PKG_USING_WIZNET + extern int sal_wiz_netdev_set_pf_info(struct netdev *netdev); + /* set the network interface socket/netdb operations */ + sal_wiz_netdev_set_pf_info(netdev); +#endif + + netdev_register(netdev, netdev_name, RT_NULL); + + return netdev; +} + +#ifdef WIZ_USING_DHCP +static void wiz_dhcp_work(struct rt_work *dhcp_work, void *dhcp_work_data) +{ +#define WIZ_DHCP_WORK_RETRY 3 /* DHCP will have 3 times handshake */ +#define WIZ_DHCP_WORK_RETRY_TIME (2 * RT_TICK_PER_SECOND) + static int wiz_dhcp_retry_times = WIZ_DHCP_WORK_RETRY * 20; + + RT_ASSERT(dhcp_work_data != RT_NULL); + + struct netdev *netdev = (struct netdev *)dhcp_work_data; + + uint8_t dhcp_times = 0; + uint32_t dhcp_work_times; + static uint8_t data_buffer[1024]; + static uint32_t dhcp_status = DHCP_FAILED; + + if(dhcp_status == DHCP_FAILED) + { + DHCP_init(WIZ_DHCP_SOCKET, data_buffer); + rt_timer_start(dhcp_timer); + } + + + while (1) + { + /* DHCP start, return DHCP_IP_LEASED is success. */ + dhcp_status = DHCP_run(); + + switch (dhcp_status) + { + case DHCP_IP_ASSIGN: + case DHCP_IP_CHANGED: + { + /* to update netdev information */ + wiz_netdev_info_update(netdev, RT_FALSE); + break; + } + case DHCP_IP_LEASED: + { + int hour, min; + /* to update netdev information */ + wiz_netdev_info_update(netdev, RT_FALSE); + + /* reset the previous work configure */ + rt_work_cancel(dhcp_work); + dhcp_work_times = (getDHCPTick1s() > getDHCPLeasetime() / 2) ? + 0 : getDHCPLeasetime() / 2 - getDHCPTick1s(); + /* according to the DHCP leaset time, config next DHCP produce */ + rt_work_submit(dhcp_work, (dhcp_work_times+1) * RT_TICK_PER_SECOND); + hour = getDHCPLeasetime() / 3600; + min = (getDHCPLeasetime() % 3600) / 60; + LOG_D("DHCP countdown to lease renewal [%dH: %dMin], retry time[%04d]", hour, min, dhcp_times); + wiz_dhcp_retry_times = WIZ_DHCP_WORK_RETRY * 20; + return; + } + case DHCP_STOPPED: + dhcp_times = wiz_dhcp_retry_times; + break; + case DHCP_FAILED: + { + dhcp_times = wiz_dhcp_retry_times; + LOG_E("dhcp handshake failed!"); + break; + } + default: + { + dhcp_times++; + + /* DHCP_RUNNING status, include don't receive data */ + rt_thread_mdelay(10); + break; + } + } + + if (dhcp_times >= wiz_dhcp_retry_times) + { + LOG_D("DHCP work in %d seconds, [%03d|%03d]", WIZ_DHCP_WORK_RETRY_TIME / RT_TICK_PER_SECOND, dhcp_times, wiz_dhcp_retry_times); + + /* if dhcp service is too busy to manger IP, increase retry times */ + wiz_dhcp_retry_times = wiz_dhcp_retry_times + WIZ_DHCP_WORK_RETRY; + + DHCP_stop(); + dhcp_status = DHCP_FAILED; + rt_timer_stop(dhcp_timer); + + rt_work_cancel(dhcp_work); + + /* according to WIZ_DHCP_WORK_RETRY_TIME, reconfigure in 2 seconds */ + rt_work_submit(dhcp_work, WIZ_DHCP_WORK_RETRY_TIME); + break; + } + } +} + +static int wiz_network_dhcp(struct netdev *netdev) +{ + if (netdev == RT_NULL) + return -RT_EINVAL; + + /* set default MAC address for DHCP */ + setSHAR(wiz_net_info.mac); + /* DHCP configure initialize, clear information other than MAC address */ + setSn_RXBUF_SIZE(WIZ_DHCP_SOCKET, 0x02); + setSn_TXBUF_SIZE(WIZ_DHCP_SOCKET, 0x02); + /* register to assign IP address and conflict callback */ + reg_dhcp_cbfunc(wiz_ip_assign, wiz_ip_assign, wiz_ip_conflict); + + dhcp_timer = rt_timer_create("wiz_dhcp", wiz_dhcp_timer_entry, RT_NULL, 1 * RT_TICK_PER_SECOND, RT_TIMER_FLAG_PERIODIC); + if (dhcp_timer == RT_NULL) + return -RT_ERROR; + + dhcp_work = (struct rt_work *)rt_calloc(1, sizeof(struct rt_work)); + if (dhcp_work == RT_NULL) + return -RT_ENOMEM; + + rt_work_init(dhcp_work, wiz_dhcp_work, (void *)netdev); + rt_work_submit(dhcp_work, WIZ_DHCP_WORK_RETRY_TIME); + + return RT_EOK; +} +#endif /* WIZ_USING_DHCP */ + +static void wiz_link_status_thread_entry(void *parameter) +{ +#define WIZ_PHYCFGR_LINK_STATUS 0x01 + + uint8_t phycfgr = 0; + struct netdev *netdev = RT_NULL; + + netdev = netdev_get_by_name(wiz_netdev_name); + if (netdev == RT_NULL) + { + LOG_E("don`t find device(%s)", wiz_netdev_name); + return; + } + + while (1) + { + /* Get PHYCFGR data */ + phycfgr = getPHYCFGR(); + + /* If the register contents are different from the struct contents, the struct needs to be updated */ + if ((phycfgr & WIZ_PHYCFGR_LINK_STATUS) != ((netdev->flags & NETDEV_FLAG_LINK_UP) ? RT_TRUE : RT_FALSE)) + { + if (phycfgr & WIZ_PHYCFGR_LINK_STATUS) + { + wiz_socket_init(); +#ifdef WIZ_USING_DHCP + if(dhcp_work) + { + DHCP_stop(); + rt_work_submit(dhcp_work, RT_WAITING_NO); + } +#else + wiz_network_init(RT_TRUE); +#endif + netdev_low_level_set_link_status(netdev, phycfgr & WIZ_PHYCFGR_LINK_STATUS); + wiz_netdev_info_update(netdev, RT_FALSE); + LOG_I("%s netdev link status becomes link up", wiz_netdev_name); + } + else + { + netdev_low_level_set_link_status(netdev, phycfgr & WIZ_PHYCFGR_LINK_STATUS); + if(dhcp_work) + { + rt_work_cancel(dhcp_work); + } + wiz_netdev_info_update(netdev, RT_TRUE); + LOG_I("%s netdev link status becomes link down", wiz_netdev_name); + } + } + rt_thread_mdelay(1000); + } +} + +static int wiz_interrupt_init(rt_base_t isr_pin) +{ + rt_thread_t tid; + + /* initialize RX mailbox */ + wiz_rx_mb = rt_mb_create("wiz_mb", WIZ_RX_MBOX_NUM, RT_IPC_FLAG_FIFO); + if (wiz_rx_mb == RT_NULL) + { + LOG_E("WIZnet create receive data mailbox error."); + return -RT_ENOMEM; + } + + /* create WIZnet SPI RX thread */ + tid = rt_thread_create("wiz", wiz_data_thread_entry, RT_NULL, 1024, RT_THREAD_PRIORITY_MAX / 6, 20); + if (tid != RT_NULL) + { + rt_thread_startup(tid); + } + + /* initialize interrupt pin */ + rt_pin_mode(isr_pin, PIN_MODE_INPUT_PULLUP); + rt_pin_attach_irq(isr_pin, PIN_IRQ_MODE_FALLING, (void (*)(void*)) wiz_isr, RT_NULL); + rt_pin_irq_enable(isr_pin, PIN_IRQ_ENABLE); + + return 0; +} + +static int wiz_is_exist(void) +{ + wiz_NetInfo ni; + int ret; + + wiz_set_mac(); + ctlnetwork(CN_SET_NETINFO, (void *)&wiz_net_info); + ctlnetwork(CN_GET_NETINFO, (void *)&ni); + + ret = rt_memcmp(wiz_net_info.mac, ni.mac, sizeof(ni.mac)); + + return (ret == 0); +} + +/* #include "stm32f4xx_hal.h" */ +/* WIZnet initialize device and network */ +int wiz_init(void) +{ + int result = RT_EOK; + rt_thread_t tid; + + if (wiz_init_ok == RT_TRUE) + { + LOG_I("RT-Thread WIZnet package is already initialized."); + return RT_EOK; + } + + /* initialize reset pin */ + rt_pin_mode(WIZ_RST_PIN, PIN_MODE_OUTPUT); + + /* I think you can attach w5500 into spi bus at here. You can use this function to realize.*/ + /* extern rt_err_t rt_hw_spi_device_attach(const char *bus_name, const char *device_name, GPIO_TypeDef *cs_gpiox, uint16_t cs_gpio_pin); */ + //rt_hw_spi_device_attach("spi1", "spi10", GPIOD, GPIO_PIN_2);//姝ゅ涓烘坊鍔犵殑鍔熻兘鍑芥暟 + //rt_spi_bus_attach_device(&wiz_device, "spi10", "spi1",(void *)NULL); + /* WIZnet SPI device and pin initialize */ + result = wiz_device_init(WIZ_SPI_DEVICE); + if (result != RT_EOK) + { + goto __exit; + } + + /* WIZnet SPI device reset */ + wiz_reset(); + /* set WIZnet device read/write data callback */ + wiz_callback_register(); + + if (!wiz_is_exist()) + { + result = -1; + LOG_E("Wiznet chip not detected"); + goto __exit; + } + + /* Add wiz to the netdev list */ + ctlwizchip(CW_GET_ID, (void *)wiz_netdev_name); + wiz_netdev_add(wiz_netdev_name); + + /* WIZnet chip configure initialize */ + wiz_chip_cfg_init(); + + /* WIZnet socket initialize */ + wiz_socket_init(); + /* WIZnet network initialize */ + result = wiz_network_init(RT_FALSE); + if (result != RT_EOK) + { + goto __exit; + } + + dns_tick_timer = rt_timer_create("dns_tick", wiz_dns_time_handler, RT_NULL, 1 * RT_TICK_PER_SECOND, RT_TIMER_FLAG_SOFT_TIMER | RT_TIMER_FLAG_PERIODIC); + rt_timer_start(dns_tick_timer); + + /* create WIZnet link status Polling thread */ + tid = rt_thread_create("wiz_stat", wiz_link_status_thread_entry, RT_NULL, 2048, RT_THREAD_PRIORITY_MAX - 4, 20); + if (tid != RT_NULL) + { + rt_thread_startup(tid); + } + + wiz_interrupt_init(WIZ_IRQ_PIN); + +__exit: + if (result == RT_EOK) + { + wiz_init_ok = RT_TRUE; + LOG_I("RT-Thread WIZnet package (V%s) initialize success.", WIZ_SW_VERSION); + } + else + { + LOG_E("RT-Thread WIZnet package (V%s) initialize failed(%d).", WIZ_SW_VERSION, result); + } + + return result; +} +INIT_ENV_EXPORT(wiz_init); diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_af_inet.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_af_inet.c new file mode 100644 index 000000000..323c8d00f --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_af_inet.c @@ -0,0 +1,110 @@ +/* + * Copyright (c) 2006-2022, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2018-09-26 chenyong first version + */ + +#include +#include + +#include +#include +#include + +#include +#include + +#ifdef SAL_USING_POSIX +#include +#endif + +#ifdef SAL_USING_POSIX +static int wiz_poll(struct dfs_fd *file, struct rt_pollreq *req) +{ + int mask = 0; + struct wiz_socket *sock; + struct sal_socket *sal_sock; + + sal_sock = sal_get_socket((int) file->data); + if(!sal_sock) + { + return -1; + } + + sock = wiz_get_socket((int)sal_sock->user_data); + if (sock != NULL) + { + rt_base_t level; + + rt_poll_add(&sock->wait_head, req); + + level = rt_hw_interrupt_disable(); + if (sock->rcvevent) + { + mask |= POLLIN; + } + if (sock->sendevent) + { + mask |= POLLOUT; + } + if (sock->errevent) + { + mask |= POLLERR; + } + rt_hw_interrupt_enable(level); + } + + return mask; +} +#endif + +static const struct sal_socket_ops wiz_socket_ops = +{ + wiz_socket, + wiz_closesocket, + wiz_bind, + wiz_listen, + wiz_connect, + wiz_accept, + wiz_sendto, + wiz_recvfrom, + wiz_getsockopt, + wiz_setsockopt, + wiz_shutdown, + NULL, + NULL, + NULL, +#ifdef SAL_USING_POSIX + wiz_poll, +#endif /* SAL_USING_POSIX */ +}; + +static const struct sal_netdb_ops wiz_netdb_ops = +{ + wiz_gethostbyname, + NULL, + wiz_getaddrinfo, + wiz_freeaddrinfo, +}; + + +static const struct sal_proto_family wiz_inet_family = +{ + AF_WIZ, + AF_INET, + &wiz_socket_ops, + &wiz_netdb_ops, +}; + +/* Set wiz network interface device protocol family information */ +int sal_wiz_netdev_set_pf_info(struct netdev *netdev) +{ + RT_ASSERT(netdev); + + netdev->sal_user_data = (void *) &wiz_inet_family; + return 0; +} diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_device.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_device.c new file mode 100644 index 000000000..d9b6b151d --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_device.c @@ -0,0 +1,83 @@ +/* + * Copyright (c) 2006-2022, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2018-09-26 chenyong first version + */ + +#include + +#include +#include +#include + +#define DBG_ENABLE +#define DBG_SECTION_NAME "wiz.dev" +#ifdef WIZ_DEBUG +#define DBG_LEVEL DBG_LOG +#else +#define DBG_LEVEL DBG_INFO +#endif /* WIZ_DEBUG */ +#define DBG_COLOR +#include + +struct rt_spi_device *wiz_device = RT_NULL; + +#ifndef WIZ_SPI_FREQ_MAX +#define WIZ_SPI_FREQ_MAX 10000000 +#endif + +static int wiz_spi_init(const char *spi_dev_name) +{ + RT_ASSERT(spi_dev_name); + + if (wiz_device != RT_NULL) + { + return 0; + } + + wiz_device = (struct rt_spi_device *) rt_device_find(spi_dev_name); + if (wiz_device == RT_NULL) + { + LOG_E("You should attach [%s] into SPI bus firstly.", spi_dev_name); + return -RT_ENOSYS; + } + + /* check SPI device type */ + RT_ASSERT(wiz_device->parent.type == RT_Device_Class_SPIDevice); + + /* configure SPI device*/ + { + struct rt_spi_configuration cfg; + cfg.data_width = 8; + cfg.mode = RT_SPI_MASTER | RT_SPI_MODE_0 | RT_SPI_MSB; /* SPI Compatible Modes 0 */ + cfg.max_hz = WIZ_SPI_FREQ_MAX; /* SPI Interface with Clock Speeds Up to 40 MHz */ + rt_spi_configure(wiz_device, &cfg); + } + + if (rt_device_open((rt_device_t) wiz_device, RT_DEVICE_OFLAG_RDWR) != RT_EOK) + { + LOG_E("open WIZnet SPI device %s error.", spi_dev_name); + return -RT_ERROR; + } + + return RT_EOK; +} + +int wiz_device_init(const char *spi_dev_name) +{ + int result = RT_EOK; + + /* WIZnet SPI device initialize */ + result = wiz_spi_init(spi_dev_name); + if (result != RT_EOK) + { + LOG_E("WIZnet SPI device initialize failed."); + return result; + } + + return RT_EOK; +} diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_ping.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_ping.c new file mode 100644 index 000000000..40f2cb23f --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_ping.c @@ -0,0 +1,259 @@ +/* + * Copyright (c) 2006-2022, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2018-09-26 chenyong first version + */ + +#include +#include + +#include + +#include +#include + +#include +#include + +#define Sn_PROTO(ch) (0x001408 + (ch<<5)) + +#define WIZ_PING_DATA_LEN 32 +#define WIZ_PING_HEAD_LEN 8 + +#define WIZ_PING_PORT 3000 +#define WIZ_PING_REQUEST 8 +#define WIZ_PING_REPLY 0 +#define WIZ_PING_CODE 0 +#define WIZ_PING_DELAY (1 * RT_TICK_PER_SECOND) +#define WIZ_PING_TIMEOUT (2 * RT_TICK_PER_SECOND) + +struct wiz_ping_msg +{ + uint8_t type; // 0 - Ping Reply, 8 - Ping Request + uint8_t code; // Always 0 + uint16_t check_sum; // Check sum + uint16_t id; // Identification + uint16_t seq_num; // Sequence Number + int8_t data[WIZ_PING_DATA_LEN]; // Ping Data : 1452 = IP RAW MTU - sizeof(type+code+check_sum+id+seq_num) +}; + +/* calculate string check value */ +static uint16_t wiz_checksum( uint8_t *src, uint32_t len ) +{ + uint16_t sum, tsum, i, j; + uint32_t lsum; + + j = len >> 1; + lsum = 0; + + for (i = 0; i < j; i++) + { + tsum = src[i * 2]; + tsum = tsum << 8; + tsum += src[i * 2 + 1]; + lsum += tsum; + } + + if (len % 2) + { + tsum = src[i * 2]; + lsum += (tsum << 8); + } + + sum = lsum; + sum = ~(sum + (lsum >> 16)); + return (uint16_t) sum; +} + +static int wiz_ping_request(int socket) +{ + int idx, send_len; + uint16_t tmp_checksum; + struct wiz_ping_msg ping_req; + + /* set request ping message object */ + ping_req.type = WIZ_PING_REQUEST; + ping_req.code = WIZ_PING_CODE; + ping_req.id = htons(rand() % 0xffff); + ping_req.seq_num = htons(rand() % 0xffff); + for (idx = 0; idx < WIZ_PING_DATA_LEN; idx++) + { + ping_req.data[idx] = (idx) % 8; + } + ping_req.check_sum = 0; + /* calculate request ping message check value */ + tmp_checksum = wiz_checksum((uint8_t *) &ping_req, sizeof(ping_req)); + ping_req.check_sum = htons(tmp_checksum); + + /* send request ping message */ + send_len = wiz_send(socket, &ping_req, sizeof(ping_req), 0); + if (send_len != sizeof(ping_req)) + { + return -1; + } + + return send_len - WIZ_PING_HEAD_LEN; +} + +static int wiz_ping_reply(int socket, struct sockaddr *from) +{ + uint16_t tmp_checksum; + uint8_t recv_buf[WIZ_PING_HEAD_LEN + WIZ_PING_DATA_LEN + 1]; + struct wiz_ping_msg ping_rep; + rt_tick_t start_tick; + int recv_len; + int idx; + + start_tick = rt_tick_get(); + while(1) + { + if (rt_tick_get() - start_tick > WIZ_PING_TIMEOUT) + { + return -1; + } + + if (getSn_RX_RSR(socket) <= 0) + { + rt_thread_mdelay(1); + continue; + } + else + { + struct sockaddr *sin = (struct sockaddr *)from; + socklen_t addr_len = sizeof(struct sockaddr_in); + recv_len = wiz_recvfrom(socket, recv_buf, WIZ_PING_HEAD_LEN + WIZ_PING_DATA_LEN, 0, sin, &addr_len); + if (recv_len < 0) + { + return -1; + } + break; + } + } + + if (recv_buf[0] == WIZ_PING_REPLY) + { + ping_rep.type = recv_buf[0]; + ping_rep.code = recv_buf[1]; + ping_rep.check_sum = (recv_buf[3] << 8) + recv_buf[2]; + ping_rep.id = (recv_buf[5] << 8) + recv_buf[4]; + ping_rep.seq_num = (recv_buf[7] << 8) + recv_buf[6]; + for (idx = 0; idx < recv_len - 8; idx++) + { + ping_rep.data[idx] = recv_buf[8 + idx]; + } + + tmp_checksum = ~wiz_checksum(recv_buf, recv_len); + if (tmp_checksum != 0xffff) + { + return -2; + } + } + else if (recv_buf[0] == WIZ_PING_REQUEST) + { + ping_rep.code = recv_buf[1]; + ping_rep.type = recv_buf[2]; + ping_rep.check_sum = (recv_buf[3] << 8) + recv_buf[2]; + ping_rep.id = (recv_buf[5] << 8) + recv_buf[4]; + ping_rep.seq_num = (recv_buf[7] << 8) + recv_buf[6]; + for (idx = 0; idx < recv_len - 8; idx++) + { + ping_rep.data[idx] = recv_buf[8 + idx]; + } + + tmp_checksum = ping_rep.check_sum; + ping_rep.check_sum = 0; + if (tmp_checksum != ping_rep.check_sum) + { + return -2; + } + } + else + { + rt_kprintf("wiz_ping: unknown ping receive message.\n"); + return -1; + } + + return recv_len - WIZ_PING_HEAD_LEN; +} + +int wiz_ping(struct netdev *netdev, const char *host, size_t data_len, uint32_t times, struct netdev_ping_resp *ping_resp) +{ + int result = RT_EOK, socket; + struct sockaddr_in server_addr; + struct timeval timeout; + struct in_addr ina; + struct hostent *hostent; + rt_tick_t recv_start_tick; + struct sal_proto_family *pf = (struct sal_proto_family *) netdev->sal_user_data; + + /* get network interface socket operations */ + if (pf == RT_NULL || pf->skt_ops == RT_NULL) + { + rt_kprintf("wiz_ping: pf or pf->skt_ops is RT_NULL.\n"); + return -RT_FALSE; + } + + hostent = (struct hostent *) pf->netdb_ops->gethostbyname(host); + if (hostent == RT_NULL) + { + rt_kprintf("wiz_ping: hostent is RT_NULL.\n"); + return -RT_FALSE; + } + + socket = -1; + + socket = wiz_socket(AF_WIZ, SOCK_RAW, 0); + if (socket < 0) + { + rt_kprintf("wiz_ping: create ping socket(%d) failed.\n",socket); + return -1; + } + /* set socket ICMP protocol */ + IINCHIP_WRITE(Sn_PROTO(socket), IPPROTO_ICMP); + + /* Check socket register */ + while(getSn_SR(socket) != SOCK_IPRAW); + + timeout.tv_sec = times / RT_TICK_PER_SECOND; + timeout.tv_usec = (times % RT_TICK_PER_SECOND) * 1000 / RT_TICK_PER_SECOND; + + /* set receive and send timeout option */ + wiz_setsockopt(socket, SOL_SOCKET, SO_RCVTIMEO, (void *) &timeout, + sizeof(timeout)); + wiz_setsockopt(socket, SOL_SOCKET, SO_SNDTIMEO, (void *) &timeout, + sizeof(timeout)); + + server_addr.sin_family = AF_WIZ; + server_addr.sin_port = htons(WIZ_PING_PORT); + server_addr.sin_addr = *((struct in_addr *)hostent->h_addr); + rt_memset(&(server_addr.sin_zero), 0, sizeof(server_addr.sin_zero)); + rt_memcpy(&ina, &server_addr.sin_addr, sizeof(ina)); + + if (wiz_connect(socket, (struct sockaddr *) &server_addr, sizeof(struct sockaddr)) < 0) + { + wiz_closesocket(socket); + return -1; + } + + if ((result = wiz_ping_request(socket)) > 0) + { + recv_start_tick = rt_tick_get(); + result = wiz_ping_reply(socket, (struct sockaddr *) &server_addr); + } + + if(result > 0) + { + ping_resp->ip_addr.addr = ((struct in_addr *)hostent->h_addr)->s_addr; + ping_resp->ticks = rt_tick_get() - recv_start_tick; + ping_resp->data_len = data_len; + ping_resp->ttl = getSn_TTL(socket); + } + + wiz_closesocket(socket); + + return result; +} diff --git a/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_socket.c b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_socket.c new file mode 100644 index 000000000..cbf1ce930 --- /dev/null +++ b/Ubiquitous/RT-Thread_Fusion_XiUOS/app_match_rt-thread/wiznet/src/wiz_socket.c @@ -0,0 +1,1739 @@ +/* + * Copyright (c) 2006-2022, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2018-09-26 chenyong first version + */ + +#include +#include +#include +#include +#include + +#include +#ifdef SAL_USING_POSIX +#include +#endif + +#include + +#include +#include +#include + +#define DBG_ENABLE +#define DBG_SECTION_NAME "wiz.socket" +#ifdef WIZ_DEBUG +#define DBG_LEVEL DBG_LOG +#else +#define DBG_LEVEL DBG_INFO +#endif /* WIZ_DEBUG */ +#define DBG_COLOR +#include + +#ifndef WIZ_SOCKETS_NUM +#define WIZ_SOCKETS_NUM 8 +#endif + +#ifndef WIZ_DEF_LOCAL_PORT +#define WIZ_DEF_LOCAL_PORT 6000 +#endif + +#ifndef RT_USING_TIMER_SOFT +#error "please enable soft timer(RT_USING_TIMER_SOFT) support in kernel configure." +#endif + +extern rt_bool_t wiz_init_ok; +#define WIZ_INIT_STATUS_CHECK \ + if (wiz_init_ok == RT_FALSE || \ + (getPHYCFGR() & PHYCFGR_LNK_ON) != PHYCFGR_LNK_ON) \ + { \ + return -1; \ + } \ + +#define HTONS_PORT(x) ((((x) & 0x00ffUL) << 8) | (((x) & 0xff00UL) >> 8)) +#define NIPQUAD(addr, index) ((unsigned char *)&addr)[index] + +#define WIZ_MAX(x , y) (((x) > (y)) ? (x) : (y)) +#define WIZ_MIN(x , y) (((x) < (y)) ? (x) : (y)) + +typedef enum +{ + WIZ_EVENT_SEND, + WIZ_EVENT_RECV, + WIZ_EVENT_ERROR, +} wiz_event_t; + +/* the global array of available sockets */ +static struct wiz_socket sockets[WIZ_SOCKETS_NUM] = {0}; +static uint16_t wiz_port = WIZ_DEF_LOCAL_PORT; + +struct wiz_socket *wiz_get_socket(int socket) +{ + if (socket < 0 || socket >= WIZ_SOCKETS_NUM) + { + return RT_NULL; + } + + /* check socket structure valid or not */ + if (sockets[socket].magic != WIZ_SOCKET_MAGIC) + { + return RT_NULL; + } + + return &sockets[socket]; +} + +static void wiz_do_event_changes(struct wiz_socket *sock, wiz_event_t event, rt_bool_t is_plus) +{ + switch (event) + { + case WIZ_EVENT_SEND: + { + if (is_plus) + { + sock->sendevent = 1; + +#ifdef SAL_USING_POSIX + rt_wqueue_wakeup(&sock->wait_head, (void *)POLLOUT); +#endif + } + else if (sock->sendevent) + { + sock->sendevent = 0; + } + break; + } + case WIZ_EVENT_RECV: + { + if (is_plus) + { + sock->rcvevent++; + +#ifdef SAL_USING_POSIX + rt_wqueue_wakeup(&sock->wait_head, (void *)POLLIN); +#endif + } + else if (sock->rcvevent) + { + sock->rcvevent--; + } + break; + } + case WIZ_EVENT_ERROR: + { + if (is_plus) + { + sock->errevent++; + +#ifdef SAL_USING_POSIX + rt_wqueue_wakeup(&sock->wait_head, (void *)POLLERR); +#endif + } + else if (sock->errevent) + { + sock->errevent--; + } + break; + } + default: + LOG_E("Not supported event (%d)", event); + } +} + +static void wiz_do_event_clean(struct wiz_socket *sock, wiz_event_t event) +{ + switch (event) + { + case WIZ_EVENT_SEND: + { + sock->sendevent = 0; + break; + } + case WIZ_EVENT_RECV: + { + sock->rcvevent = 0; + break; + } + case WIZ_EVENT_ERROR: + { + sock->errevent = 0; + break; + } + default: + LOG_E("Not supported event (%d)", event); + } +} + +int wiz_recv_notice_cb(int socket) +{ + struct wiz_socket *sock = RT_NULL; + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + rt_sem_release(sock->recv_notice); + + wiz_do_event_changes(sock, WIZ_EVENT_RECV, RT_TRUE); + + return 0; +} + +int wiz_closed_notice_cb(int socket) +{ + struct wiz_socket *sock = RT_NULL; + uint8_t socket_state = 0; + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + socket_state = getSn_SR(socket); + if (socket_state != SOCK_CLOSE_WAIT) + { + return -1; + } + + if (wizchip_close(socket) != SOCK_OK) + { + LOG_E("WIZnet socket(%d) close failed.", socket); + return -1; + } + sock->state = SOCK_CLOSED; + + wiz_do_event_changes(sock, WIZ_EVENT_RECV, RT_TRUE); + wiz_do_event_changes(sock, WIZ_EVENT_ERROR, RT_TRUE); + + rt_sem_release(sock->recv_notice); + + return 0; +} + +static struct wiz_socket *alloc_socket(void) +{ + static rt_mutex_t wiz_slock = RT_NULL; + struct wiz_socket *sock = RT_NULL; + char name[RT_NAME_MAX] = {0}; + int idx = 0; + + if (wiz_slock == RT_NULL) + { + /* create WIZnet socket lock */ + wiz_slock = rt_mutex_create("w_lock", RT_IPC_FLAG_FIFO); + if (wiz_slock == RT_NULL) + { + LOG_E("No memory for WIZnet socket lock!"); + return RT_NULL; + } + } + + rt_mutex_take(wiz_slock, RT_WAITING_FOREVER); + + /* find an empty WIZnet socket entry */ + for (idx = 0; idx < WIZ_SOCKETS_NUM && sockets[idx].magic; idx++); + + /* can't find an empty protocol family entry */ + if (idx == WIZ_SOCKETS_NUM) + { + goto __err; + } + + sock = &(sockets[idx]); + sock->magic = WIZ_SOCKET_MAGIC; + sock->socket = idx; + sock->port = 0; + sock->state = SOCK_CLOSED; + sock->remote_addr = RT_NULL; + sock->recv_timeout = 0; + sock->send_timeout = 0; + sock->rcvevent = 0; + sock->sendevent = 0; + sock->errevent = 0; + /* for server socket */ + sock->svr_info = RT_NULL; + + rt_snprintf(name, RT_NAME_MAX, "%s%d", "wiz_sr", idx); + /* create WIZnet socket receive mailbox */ + if ((sock->recv_notice = rt_sem_create(name, 0, RT_IPC_FLAG_FIFO)) == RT_NULL) + { + goto __err; + } + + rt_snprintf(name, RT_NAME_MAX, "%s%d", "wiz_sr", idx); + /* create WIZnet socket receive ring buffer lock */ + if ((sock->recv_lock = rt_mutex_create(name, RT_IPC_FLAG_FIFO)) == RT_NULL) + { + goto __err; + } + + rt_mutex_release(wiz_slock); + return sock; + +__err: + rt_mutex_release(wiz_slock); + return RT_NULL; +} + +int wiz_socket(int domain, int type, int protocol) +{ + struct wiz_socket *sock = RT_NULL; + uint8_t socket_type = 0; + uint8_t socket_state = 0; + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + /* check socket family protocol */ + RT_ASSERT(domain == 46 || domain == 2); + + switch (type) + { + case SOCK_STREAM: + socket_type = Sn_MR_TCP; + break; + + case SOCK_DGRAM: + socket_type = Sn_MR_UDP; + break; + + case SOCK_RAW: + socket_type = Sn_MR_IPRAW; + break; + + default: + LOG_E("don't support socket type (%d)!", type); + return -1; + } + + /* allocate and initialize a new WIZnet socket */ + sock = alloc_socket(); + if (sock == RT_NULL) + { + LOG_E("allocate a new WIZnet socket failed!"); + return -1; + } + sock->type = socket_type; + +#ifdef SAL_USING_POSIX + rt_wqueue_init(&sock->wait_head); +#endif + + socket_state = getSn_SR(sock->socket); + if (socket_state == SOCK_CLOSED) + { + switch (sock->type) + { + case Sn_MR_TCP: + if (wizchip_socket(sock->socket, sock->type, wiz_port, Sn_MR_ND) != sock->socket) + { + LOG_E("WIZnet TCP socket(%d) create failed!", sock->socket); + rt_memset(sock, 0x00, sizeof(struct wiz_socket)); + return -1; + } + sock->port = wiz_port++; + break; + + case Sn_MR_UDP: + case Sn_MR_IPRAW: + if (wizchip_socket(sock->socket, sock->type, wiz_port, 0) != sock->socket) + { + LOG_E("WIZnet UDP socket(%d) create failed!", sock->socket); + rt_memset(sock, 0x00, sizeof(struct wiz_socket)); + return -1; + } + sock->port = wiz_port++; + break; + + default: + LOG_E("Socket (%d) type %d is not support.", sock->socket, sock->type); + return -1; + } + } + else + { + rt_memset(sock, 0x00, sizeof(struct wiz_socket)); + LOG_E("socket(%d) is not closed(0x%x).", sock->socket, socket_state); + return -1; + } + sock->state = SOCK_INIT; + + return sock->socket; +} + +/* free server information and close all client socket in server clnt_list */ +static int free_svr_info(struct wiz_socket *sock) +{ + struct wiz_svr_info *svr_info = sock->svr_info; + struct wiz_clnt_info *clnt_info = RT_NULL; + rt_slist_t *node = RT_NULL; + rt_base_t level; + + level = rt_hw_interrupt_disable(); + /* close all client socket and free client information object */ + rt_slist_for_each(node, &svr_info->clnt_list) + { + clnt_info = rt_slist_entry(node, struct wiz_clnt_info, list); + if (clnt_info) + { + rt_slist_remove(&svr_info->clnt_list, node); + wiz_closesocket(clnt_info->socket); + rt_free(clnt_info); + } + } + rt_hw_interrupt_enable(level); + + if (svr_info->conn_tmr) + { + rt_timer_stop(svr_info->conn_tmr); + rt_timer_delete(svr_info->conn_tmr); + } + + if (svr_info->conn_mbox) + { + rt_mb_delete(svr_info->conn_mbox); + } + + if (svr_info) + { + rt_free(svr_info); + sock->svr_info = RT_NULL; + } + + return 0; +} + +/* remove client information from server socket clnt_list */ +static int remove_clnt_list(struct wiz_socket *sock) +{ + struct wiz_socket *svr_sock = RT_NULL; + struct wiz_svr_info *svr_info = RT_NULL; + int index = 0; + + for (index = 0; index < WIZ_SOCKETS_NUM; index++) + { + svr_sock = wiz_get_socket(index); + if (svr_sock == RT_NULL) + { + continue; + } + svr_info = svr_sock->svr_info; + + /* find server socket by bind port */ + if (svr_sock->svr_info && svr_sock->port == sock->port) + { + struct wiz_clnt_info *clnt_info = RT_NULL; + rt_slist_t *node = RT_NULL; + rt_base_t level; + + level = rt_hw_interrupt_disable(); + /* find client socket information in server clnt_list */ + rt_slist_for_each(node, &svr_info->clnt_list) + { + clnt_info = rt_slist_entry(node, struct wiz_clnt_info, list); + if (clnt_info && clnt_info->socket == sock->socket) + { + rt_slist_remove(&svr_info->clnt_list, node); + rt_hw_interrupt_enable(level); + + /* add server socket listen number */ + svr_info->backlog++; + rt_free(clnt_info); + return 0; + } + } + rt_hw_interrupt_enable(level); + } + } + + return 0; +} + +static int free_socket(struct wiz_socket *sock) +{ + if (sock->recv_notice) + { + rt_sem_delete(sock->recv_notice); + } + + if (sock->recv_lock) + { + rt_mutex_delete(sock->recv_lock); + } + + if (sock->remote_addr) + { + rt_free(sock->remote_addr); + } + + if (sock->svr_info) + { + /* is server socket, free server information and close all client socket on clnt_list */ + free_svr_info(sock); + } + else + { + /* is client socket, remove client socket list from server socket */ + remove_clnt_list(sock); + } + + rt_memset(sock, 0x00, sizeof(struct wiz_socket)); + + return 0; +} + +int wiz_closesocket(int socket) +{ + struct wiz_socket *sock = RT_NULL; + uint8_t socket_state = 0; + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + socket_state = getSn_SR(socket); + if (socket_state == SOCK_CLOSED) + { + free_socket(sock); + return -1; + } + + if (wizchip_close(socket) != SOCK_OK) + { + LOG_E("WIZnet socket(%d) close failed.", socket); + free_socket(sock); + return -1; + } + + return free_socket(sock); +} + +int wiz_shutdown(int socket, int how) +{ + struct wiz_socket *sock = RT_NULL; + uint8_t socket_state = 0; + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + socket_state = getSn_SR(socket); + if (socket_state == SOCK_CLOSED) + { + free_socket(sock); + return -1; + } + + if (wizchip_close(socket) != SOCK_OK) + { + LOG_E("WIZnet socket(%d) shutdown failed.", socket); + free_socket(sock); + return -1; + } + + return free_socket(sock); +} + +static struct wiz_clnt_info *wiz_conn_clnt_info_get(struct wiz_socket *svr_sock) +{ + rt_base_t level; + rt_slist_t *node = RT_NULL; + struct wiz_clnt_info *clnt_info = RT_NULL; + struct wiz_svr_info *svr_info = svr_sock->svr_info; + + level = rt_hw_interrupt_disable(); + + rt_slist_for_each(node, &svr_info->clnt_list) + { + clnt_info = rt_slist_entry(node, struct wiz_clnt_info, list); + if (clnt_info->state == SOCK_LISTEN || clnt_info->state == SOCK_INIT) + { + rt_hw_interrupt_enable(level); + return clnt_info; + } + } + + rt_hw_interrupt_enable(level); + return RT_NULL; +} + +static void wiz_timer_entry(void *parameter) +{ + struct wiz_socket *svr_sock = RT_NULL; + struct wiz_socket *clnt_sock = RT_NULL; + struct wiz_clnt_info *clnt_info = RT_NULL; + int clnt_socket = -1; + int bind_port = 0; + uint8_t status = 0; + + svr_sock = (struct wiz_socket *)parameter; + bind_port = svr_sock->port; + + /* check server socket listen status */ + if (svr_sock->state != SOCK_LISTEN) + { + return; + } + + /* allocate and initialize a new client socket */ + clnt_info = wiz_conn_clnt_info_get(svr_sock); + if (clnt_info == RT_NULL) + { + /* check server listen backlog number */ + if (svr_sock->svr_info->backlog < 0) + { + goto __error; + } + + clnt_sock = alloc_socket(); + if (clnt_sock == RT_NULL) + { + goto __error; + } + clnt_sock->type = Sn_MR_TCP; + +#ifdef SAL_USING_POSIX + rt_wqueue_init(&clnt_sock->wait_head); +#endif + if (wizchip_socket(clnt_sock->socket, clnt_sock->type, bind_port, 0) != clnt_sock->socket) + { + goto __error; + } + clnt_sock->state = SOCK_INIT; + clnt_sock->port = svr_sock->port; + clnt_socket = clnt_sock->socket; + + /* create client information and add client to server clnt_list */ + clnt_info = rt_calloc(1, sizeof(struct wiz_clnt_info)); + if (clnt_info == RT_NULL) + { + LOG_E("no memory for clinet information."); + goto __error; + } + clnt_info->socket = clnt_sock->socket; + clnt_info->state = clnt_sock->state; + rt_slist_init(&clnt_info->list); + rt_slist_append(&svr_sock->svr_info->clnt_list, &clnt_info->list); + } + else + { + /* get client socket structure by socket descriptor */ + clnt_sock = wiz_get_socket(clnt_info->socket); + if (clnt_sock == RT_NULL) + { + goto __error; + } + } + clnt_socket = clnt_info->socket; + + status = getSn_SR(clnt_socket); + clnt_info->state = status; + switch (status) + { + case SOCK_INIT: + /* listen for open local ports and wait for client connections */ + if (wizchip_listen(clnt_socket) < 0) + { + goto __error; + } + break; + case SOCK_ESTABLISHED: + /* set server socket to recevice connected status */ + svr_sock->state = SOCK_SYNRECV; + svr_sock->svr_info->backlog--; + /* send client socket connect message and events */ + rt_mb_send(svr_sock->svr_info->conn_mbox, (rt_uint32_t)clnt_sock); + wiz_do_event_changes(svr_sock, WIZ_EVENT_RECV, RT_TRUE); + break; + case SOCK_LISTEN: + /* socket input listen mode, wait client connect */ + break; + case SOCK_CLOSE_WAIT: + case SOCK_CLOSED: + default: + goto __error; + } + return; + +__error: + rt_mb_send(svr_sock->svr_info->conn_mbox, (rt_uint32_t)clnt_sock); + wiz_do_event_changes(svr_sock, WIZ_EVENT_ERROR, RT_TRUE); +} + +int wiz_listen(int socket, int backlog) +{ + struct wiz_socket *sock = RT_NULL; + + /* limit the "backlog" parameter to fit in an uint8_t */ + backlog = WIZ_MIN(WIZ_MAX(backlog, 0), WIZ_SOCKETS_NUM); + if (backlog == 0) + { + LOG_E("not emought socket for server listen."); + return -1; + } + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + /* set server socket status and listen sockets number */ + sock->state = SOCK_LISTEN; + + /* create connect timer for client connect event notice */ + if (sock->svr_info == RT_NULL) + { +#define WIZ_MB_NUM 8 +#define WIZ_TIMER_TICK rt_tick_from_millisecond(100) + + char name[RT_NAME_MAX] = {0}; + static int socket_counts = 0; + struct wiz_svr_info *svr_info = RT_NULL; + + sock->svr_info = rt_calloc(1, sizeof(struct wiz_svr_info)); + if (sock->svr_info == RT_NULL) + { + return -1; + } + svr_info = sock->svr_info; + + /* full server infomation */ + svr_info->backlog = backlog - 1; + rt_slist_init(&svr_info->clnt_list); + + /* create client socket connection event mailbox */ + rt_snprintf(name, RT_NAME_MAX, "wiz_mb%d", socket_counts); + svr_info->conn_mbox = rt_mb_create(name, WIZ_MB_NUM, RT_IPC_FLAG_FIFO); + if (svr_info->conn_mbox == RT_NULL) + { + return -1; + } + + /* create client socket connect timer */ + rt_snprintf(name, RT_NAME_MAX, "wiz_tm%d", socket_counts++); + svr_info->conn_tmr = rt_timer_create(name, wiz_timer_entry, (void *)sock, + WIZ_TIMER_TICK, RT_TIMER_FLAG_SOFT_TIMER | RT_TIMER_FLAG_PERIODIC); + if (svr_info->conn_tmr == RT_NULL) + { + return -1; + } + rt_timer_start(svr_info->conn_tmr); + } + + return 0; +} + +/* get IP address and port by socketaddr structure information */ +static int socketaddr_to_ipaddr_port(const struct sockaddr *sockaddr, ip_addr_t *addr, uint16_t *port) +{ + const struct sockaddr_in *sin = (const struct sockaddr_in *)sockaddr; + +#if NETDEV_IPV4 && NETDEV_IPV6 + (*addr).u_addr.ip4.addr = sin->sin_addr.s_addr; +#elif NETDEV_IPV4 + (*addr).addr = sin->sin_addr.s_addr; +#elif NETDEV_IPV6 + LOG_E("not support IPV6."); +#endif /* NETDEV_IPV4 && NETDEV_IPV6 */ + + *port = (uint16_t)HTONS_PORT(sin->sin_port); + + return 0; +} + +/* ipaddr structure change to IP address */ +static int ipaddr_to_ipstr(const struct sockaddr *sockaddr, uint8_t *ipstr) +{ + struct sockaddr_in *sin = (struct sockaddr_in *)sockaddr; + + /* change network ip_addr to ip string */ + ipstr[0] = NIPQUAD(sin->sin_addr.s_addr, 0); + ipstr[1] = NIPQUAD(sin->sin_addr.s_addr, 1); + ipstr[2] = NIPQUAD(sin->sin_addr.s_addr, 2); + ipstr[3] = NIPQUAD(sin->sin_addr.s_addr, 3); + + return 0; +} + +int wiz_bind(int socket, const struct sockaddr *name, socklen_t namelen) +{ + struct wiz_socket *sock = RT_NULL; + uint16_t port = 0; + ip_addr_t ipaddr; + + RT_ASSERT(name); + + /* Only support signed w5500 network interface device in wiznet, + and the bind function is implemented in the SAL component, + need to define "wiz_bind" function and register it. */ + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + /* prase ip address and port */ + socketaddr_to_ipaddr_port(name, &ipaddr, &port); + + /* check socket bind port */ + if (sock->port != port && sock->type == Sn_MR_UDP) + { + struct wiz_socket *new_sock = RT_NULL; + + /* close old socket */ + if (wiz_closesocket(socket) < 0) + { + return -1; + } + + /* create new socket by bind port */ + new_sock = alloc_socket(); + if (new_sock == RT_NULL) + { + return -1; + } + new_sock->type = Sn_MR_UDP; + +#ifdef SAL_USING_POSIX + rt_wqueue_init(&new_sock->wait_head); +#endif + if (wizchip_socket(new_sock->socket, new_sock->type, port, 0) != new_sock->socket) + { + return -1; + } + new_sock->state = SOCK_INIT; + new_sock->port = port; + } + else + { + sock->port = port; + } + + return 0; +} + +int wiz_connect(int socket, const struct sockaddr *name, socklen_t namelen) +{ + struct wiz_socket *sock = RT_NULL; + ip_addr_t remote_addr; + uint16_t remote_port = 0; + uint8_t socket_state = 0; + uint8_t ipstr[4] = {0}; + int result = 0; + + RT_ASSERT(name); + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + socket_state = getSn_SR(socket); + if (socket_state == SOCK_UDP || socket_state == SOCK_IPRAW) + { + if (sock->remote_addr == RT_NULL) + { + sock->remote_addr = rt_calloc(1, sizeof(struct sockaddr)); + if (sock->remote_addr == RT_NULL) + { + LOG_E("no memory for structure sockaddr."); + return -1; + } + } + sock->remote_addr->sa_len = name->sa_len; + sock->remote_addr->sa_family = name->sa_family; + rt_memcpy(sock->remote_addr->sa_data, name->sa_data, 14); + + return 0; + } + else if (socket_state != SOCK_INIT) + { + LOG_E("WIZnet connect failed, get socket(%d) register state(%d) error.", socket, socket_state); + result = -1; + goto __exit; + } + + /* get IP address and port by socketaddr structure */ + socketaddr_to_ipaddr_port(name, &remote_addr, &remote_port); + ipaddr_to_ipstr(name, ipstr); + + if (wizchip_connect(socket, ipstr, remote_port) != SOCK_OK) + { + LOG_E("WIZnet socket(%d) connect failed.", socket); + result = -1; + goto __exit; + } + sock->state = SOCK_ESTABLISHED; + +__exit: + if (result < 0) + { + wiz_do_event_changes(sock, WIZ_EVENT_ERROR, RT_TRUE); + } + else + { + wiz_do_event_changes(sock, WIZ_EVENT_SEND, RT_TRUE); + } + + return result; +} + +int wiz_accept(int socket, struct sockaddr *addr, socklen_t *addrlen) +{ + struct wiz_socket *svr_sock = RT_NULL; + struct wiz_svr_info *svr_info = RT_NULL; + struct wiz_socket *clnt_sock = RT_NULL; + int clnt_socket = -1; + + RT_ASSERT(addr); + RT_ASSERT(addrlen); + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + svr_sock = wiz_get_socket(socket); + if (svr_sock == RT_NULL) + { + return -1; + } + svr_info = svr_sock->svr_info; + /* set server socket to SOCK_LISTEN status for socket connect timer */ + svr_sock->state = SOCK_LISTEN; + + while (1) + { + /* receive client connect message */ + if (rt_mb_recv(svr_info->conn_mbox, (void *)&clnt_sock, RT_WAITING_FOREVER) != RT_EOK) + { + return -1; + } + + /* check connect message type */ + clnt_socket = clnt_sock->socket; + if (getSn_SR(clnt_socket) != SOCK_ESTABLISHED) + { + /* clean server socket error event */ + wiz_do_event_clean(svr_sock, WIZ_EVENT_ERROR); + /* error massage, close client socket */ + wiz_closesocket(clnt_socket); + return -1; + } + + /* get new client socket information */ + { + struct sockaddr_in *sin = (struct sockaddr_in *)addr; + uint8_t ipstr[4] = {0}; + uint16_t remote_port = 0; + char remote_ipaddr[16] = {0}; + + /* set client socket status */ + clnt_sock->state = SOCK_ESTABLISHED; + + /* get the remote IP address and port */ + getSn_DIPR(clnt_socket, ipstr); + remote_port = getSn_DPORT(clnt_socket); + rt_snprintf(remote_ipaddr, sizeof(remote_ipaddr), "%d.%d.%d.%d", ipstr[0], ipstr[1], ipstr[2], ipstr[3]); + LOG_D("remote ip: %s, remote port: %d\n", remote_ipaddr, remote_port); + + /* full address and port */ + sin->sin_port = htons(remote_port); + sin->sin_addr.s_addr = inet_addr((const char *)remote_ipaddr); + rt_memset(&(sin->sin_zero), 0, sizeof(sin->sin_zero)); + *addrlen = sizeof(struct sockaddr); + + /* clean server socket receive event and status */ + wiz_do_event_clean(svr_sock, WIZ_EVENT_RECV); + + return clnt_socket; + } + } +} + +int wiz_sendto(int socket, const void *data, size_t size, int flags, const struct sockaddr *to, socklen_t tolen) +{ + struct wiz_socket *sock = RT_NULL; + uint8_t socket_state = 0; + int32_t send_len = 0; + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + if (data == RT_NULL || size == 0) + { + LOG_E("WIZnet sendto input data or size error!"); + return -1; + } + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + socket_state = getSn_SR(socket); + switch (sock->type) + { + case Sn_MR_TCP: + { + if (socket_state == SOCK_CLOSED) + { + return 0; + } + else if (socket_state != SOCK_ESTABLISHED) + { + LOG_E("WIZnet send failed, get socket(%d) register state(%d) error.", socket, socket_state); + return -1; + } + + if ((send_len = wizchip_send(socket, (uint8_t *)data, size)) < 0) + { + LOG_E("WIZnet socket(%d) send data failed(%d).", socket, send_len); + return -1; + } + break; + } + + case Sn_MR_UDP: + case Sn_MR_IPRAW: + { + ip_addr_t remote_addr; + uint16_t remote_port = 0; + uint8_t ipstr[4] = {0}; + + if (socket_state != SOCK_UDP && socket_state != SOCK_IPRAW) + { + LOG_E("WIZnet sendto failed, get socket(%d) register state(%d) error.", socket, socket_state); + return -1; + } + + if (to) + { + socketaddr_to_ipaddr_port(to, &remote_addr, &remote_port); + ipaddr_to_ipstr(to, ipstr); + } + else if (sock->remote_addr) + { + socketaddr_to_ipaddr_port(sock->remote_addr, &remote_addr, &remote_port); + ipaddr_to_ipstr(sock->remote_addr, ipstr); + } + + if ((send_len = wizchip_sendto(socket, (uint8_t *)data, size, ipstr, remote_port)) < 0) + { + LOG_E("WIZnet socket(%d) send data failed(%d).", socket, send_len); + return -1; + } + break; + } + + default: + LOG_E("WIZnet socket (%d) type %d is not support.", socket, sock->type); + return -1; + } + + return send_len; +} + +int wiz_send(int socket, const void *data, size_t size, int flags) +{ + return wiz_sendto(socket, data, size, flags, RT_NULL, 0); +} + +int wiz_recvfrom(int socket, void *mem, size_t len, int flags, struct sockaddr *from, socklen_t *fromlen) +{ + struct wiz_socket *sock = RT_NULL; + uint8_t socket_state = 0; + int32_t recv_len = 0, timeout = 0; + int result = 0; + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + if (mem == RT_NULL || len == 0) + { + LOG_E("WIZnet recvfrom input data or length error!"); + return -1; + } + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + /* non-blocking sockets receive data */ + if (flags & MSG_DONTWAIT) + { + timeout = RT_WAITING_NO; + } + else if ((timeout = sock->recv_timeout) == 0) + { + /* set WIZNnet socket receive timeout */ + timeout = RT_WAITING_FOREVER; + } + + socket_state = getSn_SR(socket); + switch (sock->type) + { + case Sn_MR_TCP: + { + uint16_t recvsize = getSn_RX_RSR(socket); + /* receive last transmission of remaining data */ + if (recvsize > 0) + { + rt_mutex_take(sock->recv_lock, RT_WAITING_FOREVER); + recv_len = wizchip_recv(socket, mem, len); + if (recv_len > 0) + { + rt_mutex_release(sock->recv_lock); + goto __exit; + } + rt_mutex_release(sock->recv_lock); + } + + if (socket_state == SOCK_CLOSED) + { + return 0; + } + else if (socket_state != SOCK_ESTABLISHED) + { + LOG_E("WIZnet receive failed, get socket(%d) register state(%d) error.", socket, socket_state); + result = -1; + goto __exit; + } + + while (1) + { + /* wait the receive semaphore */ + if (rt_sem_take(sock->recv_notice, timeout) < 0) + { + result = -1; + /* blocking mode will prints an error and non-blocking mode exits directly */ + if ((flags & MSG_DONTWAIT) == 0) + { + LOG_E("WIZnet socket (%d) receive timeout (%d)!", socket, timeout); + errno = EAGAIN; + } + goto __exit; + } + else + { + if (sock->state == SOCK_ESTABLISHED) + { + /* get receive buffer to receiver ring buffer */ + rt_mutex_take(sock->recv_lock, RT_WAITING_FOREVER); + recv_len = wizchip_recv(socket, mem, len); + if (recv_len < 0) + { + LOG_E("WIZnet socket(%d) receive data failed(%d).", socket, recv_len); + rt_mutex_release(sock->recv_lock); + result = -1; + goto __exit; + } + rt_mutex_release(sock->recv_lock); + } + else if (sock->state == SOCK_CLOSED) + { + result = 0; + goto __exit; + } + break; + } + } + break; + } + + case Sn_MR_UDP: + case Sn_MR_IPRAW: + { + uint16_t remote_port = 0; + uint8_t ipstr[4] = {0}; + uint16_t rx_len = 0; + + if (socket_state != SOCK_UDP && socket_state != SOCK_IPRAW) + { + LOG_E("WIZnet recvfrom failed, get socket(%d) register state(%d) error.", socket, socket_state); + return -1; + } + +__continue: + if (rt_sem_take(sock->recv_notice, timeout) < 0) + { + result = -1; + /* blocking mode will prints an error and non-blocking mode exits directly */ + if ((flags & MSG_DONTWAIT) == 0) + { + LOG_E("WIZnet socket (%d) receive timeout (%d)!", socket, timeout); + } + goto __exit; + } + else + { + if ((rx_len = getSn_RX_RSR(socket)) > 0) + { + rx_len = rx_len > len ? len : rx_len; + + if (sock->state != SOCK_CLOSED) + { + recv_len = wizchip_recvfrom(socket, mem, rx_len, ipstr, &remote_port); + if (recv_len < 0) + { + LOG_E("WIZnet socket(%d) receive data failed(%d).", socket, recv_len); + result = -1; + goto __exit; + } + else + { + char remote_ipaddr[16] = {0}; + struct sockaddr_in *sin = (struct sockaddr_in *)from; + + rt_snprintf(remote_ipaddr, sizeof(remote_ipaddr), "%d.%d.%d.%d", + ipstr[0], ipstr[1], ipstr[2], ipstr[3]); + /* full address and port */ + sin->sin_port = htons(remote_port); + sin->sin_addr.s_addr = inet_addr((const char *)remote_ipaddr); + rt_memset(&(sin->sin_zero), 0, sizeof(sin->sin_zero)); + *fromlen = sizeof(struct sockaddr); + } + } + else if (sock->state == SOCK_CLOSED) + { + result = 0; + goto __exit; + } + } + else + { + /* clean receive data isr */ + goto __continue; + } + } + break; + } + + default: + LOG_E("WIZnet socket (%d) type %d is not support.", socket, sock->type); + return -1; + } + +__exit: + if (recv_len > 0) + { + errno = 0; + result = recv_len; + wiz_do_event_changes(sock, WIZ_EVENT_RECV, RT_FALSE); + + if (getSn_RX_RSR(socket) == 0) + { + wiz_do_event_clean(sock, WIZ_EVENT_RECV); + } + } + else + { + wiz_do_event_changes(sock, WIZ_EVENT_ERROR, RT_TRUE); + } + + return result; +} + +int wiz_recv(int socket, void *mem, size_t len, int flags) +{ + return wiz_recvfrom(socket, mem, len, flags, RT_NULL, RT_NULL); +} + +int wiz_getsockopt(int socket, int level, int optname, void *optval, socklen_t *optlen) +{ + struct wiz_socket *sock = RT_NULL; + int32_t timeout = 0; + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + if (optval == RT_NULL || optlen == RT_NULL) + { + LOG_E("WIZnet getsocketopt input option value or option length error."); + return -1; + } + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + switch (level) + { + case SOL_SOCKET: + { + switch (optname) + { + case SO_RCVTIMEO: + timeout = sock->recv_timeout; + ((struct timeval *)(optval))->tv_sec = (timeout) / 1000U; + ((struct timeval *)(optval))->tv_usec = (timeout % 1000U) * 1000U; + break; + + case SO_SNDTIMEO: + timeout = sock->send_timeout; + ((struct timeval *)optval)->tv_sec = timeout / 1000U; + ((struct timeval *)optval)->tv_usec = (timeout % 1000U) * 1000U; + break; + + default: + LOG_E("WIZnet socket (%d) not support option name : %d.", socket, optname); + return -1; + } + break; + } + + default: + { + int8_t ret = 0; + + ret = wizchip_getsockopt(socket, (sockopt_type)level, optval); + if (ret != SOCK_OK) + { + LOG_E("WIZnet getsocketopt input level(%d) error.", level); + return ret; + } + break; + } + } + + return 0; +} +int wiz_setsockopt(int socket, int level, int optname, const void *optval, socklen_t optlen) +{ + struct wiz_socket *sock = RT_NULL; + + /* check WIZnet initialize status */ + WIZ_INIT_STATUS_CHECK; + + if (optval == RT_NULL) + { + LOG_E("WIZnet setsockopt input option value or option length error."); + return -1; + } + + sock = wiz_get_socket(socket); + if (sock == RT_NULL) + { + return -1; + } + + switch (level) + { + case SOL_SOCKET: + { + switch (optname) + { + case SO_RCVTIMEO: + sock->recv_timeout = ((const struct timeval *)optval)->tv_sec * 1000 + ((const struct timeval *)optval)->tv_usec / 1000; + break; + + case SO_SNDTIMEO: + sock->send_timeout = ((const struct timeval *)optval)->tv_sec * 1000 + ((const struct timeval *)optval)->tv_usec / 1000; + break; + + default: + LOG_E("WIZnet socket (%d) not support option name : %d.", socket, optname); + return -1; + } + break; + } + + case IPPROTO_TCP: + { + switch (optname) + { + case TCP_NODELAY: + break; + } + break; + } + + default: + { + int8_t ret = 0; + + ret = wizchip_setsockopt(socket, (sockopt_type)optname, (void *)optval); + if (ret != SOCK_OK) + { + LOG_E("WIZnet getsocketopt input level(%d) error.", level); + return ret; + } + break; + } + } + + return 0; +} + +static uint32_t ipstr_atol(const char *nptr) +{ + uint32_t total = 0; + char sign = '+'; + /* jump space */ + while (isspace(*nptr)) + { + ++nptr; + } + + if (*nptr == '-' || *nptr == '+') + { + sign = *nptr++; + } + + while (isdigit(*nptr)) + { + total = 10 * total + ((*nptr++) - '0'); + } + return (sign == '-') ? -total : total; +} + +/* IP address to unsigned int type */ +static uint32_t ipstr_to_u32(char *ipstr) +{ + char ipBytes[4] = {0}; + uint32_t i; + + for (i = 0; i < 4; i++, ipstr++) + { + ipBytes[i] = (char)ipstr_atol(ipstr); + if ((ipstr = strchr(ipstr, '.')) == RT_NULL) + { + break; + } + } + return *(uint32_t *)ipBytes; +} + +struct hostent *wiz_gethostbyname(const char *name) +{ + ip_addr_t addr; + char ipstr[16] = {0}; + /* buffer variables for at_gethostbyname() */ + static struct hostent s_hostent; + static char *s_aliases; + static ip_addr_t s_hostent_addr; + static ip_addr_t *s_phostent_addr[2]; + static char s_hostname[DNS_MAX_NAME_LENGTH + 1]; + size_t idx = 0; + + /* check WIZnet initialize status */ + if (wiz_init_ok == RT_FALSE || + (getPHYCFGR() & PHYCFGR_LNK_ON) != PHYCFGR_LNK_ON) + { + return RT_NULL; + } + + if (name == RT_NULL) + { + LOG_E("WIZnet gethostbyname input name error!"); + return RT_NULL; + } + + /* check domain name or IP address */ + for (idx = 0; idx < rt_strlen(name) && !isalpha(name[idx]); idx++); + + if (idx < rt_strlen(name)) + { + int8_t ret = 0; + uint8_t remote_ip[4] = {0}; + uint8_t data_buffer[512]; + + /* allocate and initialize a new WIZnet socket */ + for (idx = 0; idx < WIZ_SOCKETS_NUM && sockets[idx].magic; idx++); + if (idx >= WIZ_SOCKETS_NUM) + { + LOG_E("WIZnet DNS failed, socket number is full."); + return RT_NULL; + } + + wiz_NetInfo net_info; + ctlnetwork(CN_GET_NETINFO, (void *)&net_info); + + /* DNS client initialize */ + DNS_init(idx, data_buffer); + /* DNS client processing */ + ret = DNS_run(net_info.dns, (uint8_t *)name, remote_ip); + if (ret == -1) + { + LOG_E("WIZnet MAX_DOMAIN_NAME is too small, should be redefined it."); + return RT_NULL; + } + else if (ret < 0) + { + return RT_NULL; + } + + /* domain resolve failed */ + if (remote_ip[0] == 0) + { + return RT_NULL; + } + + rt_snprintf(ipstr, 16, "%u.%u.%u.%u", remote_ip[0], remote_ip[1], remote_ip[2], remote_ip[3]); + } + else + { + /* input name is IP address */ + rt_strncpy(ipstr, name, rt_strlen(name)); + } + +#if NETDEV_IPV4 && NETDEV_IPV6 + addr.u_addr.ip4.addr = ipstr_to_u32(ipstr); +#elif NETDEV_IPV4 + addr.addr = ipstr_to_u32(ipstr); +#elif NETDEV_IPV6 + LOG_E("not support IPV6."); +#endif /* NETDEV_IPV4 && NETDEV_IPV6 */ + + /* fill hostent structure */ + s_hostent_addr = addr; + s_phostent_addr[0] = &s_hostent_addr; + s_phostent_addr[1] = RT_NULL; + rt_strncpy(s_hostname, name, DNS_MAX_NAME_LENGTH); + s_hostname[DNS_MAX_NAME_LENGTH] = 0; + s_hostent.h_name = s_hostname; + s_aliases = RT_NULL; + s_hostent.h_aliases = &s_aliases; + s_hostent.h_addrtype = AF_WIZ; + s_hostent.h_length = sizeof(ip_addr_t); + s_hostent.h_addr_list = (char **)&s_phostent_addr; + + return &s_hostent; +} + +int wiz_getaddrinfo(const char *nodename, const char *servname, const struct addrinfo *hints, struct addrinfo **res) +{ + int port_nr = 0; + ip_addr_t addr; + struct addrinfo *ai = RT_NULL; + struct sockaddr_storage *sa = RT_NULL; + size_t total_size = 0; + size_t namelen = 0; + int ai_family = 0; + + /* check WIZnet initialize status */ + if (wiz_init_ok == RT_FALSE || + (getPHYCFGR() & PHYCFGR_LNK_ON) != PHYCFGR_LNK_ON) + { + return EAI_FAIL; + } + + if (res == RT_NULL) + { + return EAI_FAIL; + } + *res = RT_NULL; + + if ((nodename == RT_NULL) && (servname == RT_NULL)) + { + return EAI_NONAME; + } + + if (hints != RT_NULL) + { + ai_family = hints->ai_family; + if (hints->ai_family != AF_WIZ && hints->ai_family != AF_INET && hints->ai_family != AF_UNSPEC) + { + return EAI_FAMILY; + } + } + + if (servname != RT_NULL) + { + /* service name specified: convert to port number */ + port_nr = atoi(servname); + if ((port_nr <= 0) || (port_nr > 0xffff)) + { + return EAI_SERVICE; + } + } + + if (nodename != RT_NULL) + { + /* service location specified, try to resolve */ + if ((hints != RT_NULL) && (hints->ai_flags & AI_NUMERICHOST)) + { + /* no DNS lookup, just parse for an address string */ + if (!inet_aton(nodename, (ip4_addr_t *)&addr)) + { + return EAI_NONAME; + } + + if (ai_family == AF_WIZ || ai_family == AF_INET) + { + return EAI_NONAME; + } + } + else + { + char ipstr[16] = {0}; + size_t idx = 0; + + /* check domain name or IP address */ + for (idx = 0; idx < rt_strlen(nodename) && !isalpha(nodename[idx]); idx++); + + if (idx < rt_strlen(nodename)) + { + int8_t ret; + uint8_t remote_ip[4] = {0}; + uint8_t data_buffer[512]; + + for (idx = 0; idx < WIZ_SOCKETS_NUM && sockets[idx].magic; idx++); + if (idx >= WIZ_SOCKETS_NUM) + { + LOG_E("wizenet getaddrinfo failed, socket number is full."); + return EAI_FAIL; + } + + wiz_NetInfo net_info; + ctlnetwork(CN_GET_NETINFO, (void *)&net_info); + + /* DNS client initialize */ + DNS_init(idx, data_buffer); + /* DNS client processing */ + ret = DNS_run(net_info.dns, (uint8_t *)nodename, remote_ip); + if (ret == -1) + { + LOG_E("WIZnet MAX_DOMAIN_NAME is too small, should be redefined it."); + return EAI_FAIL; + } + else if (ret < 0) + { + LOG_E("WIZnet getaddrinfo failed(%d).", ret); + return EAI_FAIL; + } + + /* domain resolve failed */ + if (remote_ip[0] == 0) + { + return EAI_FAIL; + } + + rt_snprintf(ipstr, 16, "%u.%u.%u.%u", remote_ip[0], remote_ip[1], remote_ip[2], remote_ip[3]); + } + else + { + /* input name is IP address */ + rt_strncpy(ipstr, nodename, rt_strlen(nodename)); + } + +#if NETDEV_IPV4 && NETDEV_IPV6 + addr.type = IPADDR_TYPE_V4; + if ((addr.u_addr.ip4.addr = ipstr_to_u32(ip_str)) == 0) + { + return EAI_FAIL; + } +#elif NETDEV_IPV4 + addr.addr = ipstr_to_u32(ipstr); +#elif NETDEV_IPV6 + LOG_E("not support IPV6."); +#endif /* NETDEV_IPV4 && NETDEV_IPV6 */ + } + } + else + { + /* to do service location specified, use loopback address */ + } + + total_size = sizeof(struct addrinfo) + sizeof(struct sockaddr_storage); + if (nodename != RT_NULL) + { + namelen = rt_strlen(nodename); + if (namelen > DNS_MAX_NAME_LENGTH) + { + /* invalid name length */ + return EAI_FAIL; + } + RT_ASSERT(total_size + namelen + 1 > total_size); + total_size += namelen + 1; + } + /* If this fails, please report to lwip-devel! :-) */ + RT_ASSERT(total_size <= sizeof(struct addrinfo) + sizeof(struct sockaddr_storage) + DNS_MAX_NAME_LENGTH + 1); + ai = (struct addrinfo *)rt_malloc(total_size); + if (ai == RT_NULL) + { + return EAI_MEMORY; + } + rt_memset(ai, 0, total_size); + /* cast through void* to get rid of alignment warnings */ + sa = (struct sockaddr_storage *)(void *)((uint8_t *)ai + sizeof(struct addrinfo)); + struct sockaddr_in *sa4 = (struct sockaddr_in *)sa; + /* set up sockaddr */ +#if NETDEV_IPV4 && NETDEV_IPV6 + sa4->sin_addr.s_addr = addr.u_addr.ip4.addr; +#elif NETDEV_IPV4 + sa4->sin_addr.s_addr = addr.addr; +#elif NETDEV_IPV6 + LOG_E("not support IPV6."); +#endif /* NETDEV_IPV4 && NETDEV_IPV6 */ + sa4->sin_family = AF_INET; + sa4->sin_len = sizeof(struct sockaddr_in); + sa4->sin_port = htons((uint16_t)port_nr); + ai->ai_family = AF_INET; + + /* set up addrinfo */ + if (hints != RT_NULL) + { + /* copy socktype & protocol from hints if specified */ + ai->ai_socktype = hints->ai_socktype; + ai->ai_protocol = hints->ai_protocol; + } + if (nodename != RT_NULL) + { + /* copy nodename to canonname if specified */ + ai->ai_canonname = ((char *)ai + sizeof(struct addrinfo) + sizeof(struct sockaddr_storage)); + rt_memcpy(ai->ai_canonname, nodename, namelen); + ai->ai_canonname[namelen] = 0; + } + ai->ai_addrlen = sizeof(struct sockaddr_storage); + ai->ai_addr = (struct sockaddr *)sa; + + *res = ai; + + return 0; +} + +void wiz_freeaddrinfo(struct addrinfo *ai) +{ + struct addrinfo *next = RT_NULL; + + /* check WIZnet initialize status */ + if (wiz_init_ok == RT_FALSE || + (getPHYCFGR() & PHYCFGR_LNK_ON) != PHYCFGR_LNK_ON) + { + return; + } + + while (ai != NULL) + { + next = ai->ai_next; + rt_free(ai); + ai = next; + } +}