forked from xuos/xiuos
This commit is contained in:
commit
a337904560
|
@ -13,3 +13,6 @@
|
|||
[submodule "Ubiquitous/Nuttx_Fusion_XiUOS/nuttx"]
|
||||
path = Ubiquitous/Nuttx_Fusion_XiUOS/nuttx
|
||||
url = https://code.gitlink.org.cn/wgzAIIT/incubator-nuttx.git
|
||||
[submodule "Ubiquitous/XiZi/fs/lwext4/lwext4_submodule"]
|
||||
path = Ubiquitous/XiZi/fs/lwext4/lwext4_submodule
|
||||
url = https://gitlink.org.cn/xuos/lwext4_filesystem_support_XiUOS.git
|
||||
|
|
|
@ -0,0 +1,7 @@
|
|||
############################################################################
|
||||
# APP_Framework/Framework/connection/4g/Make.defs
|
||||
############################################################################
|
||||
ifneq ($(CONFIG_CONNECTION_ADAPTER_4G),)
|
||||
CONFIGURED_APPS += $(APPDIR)/../../../APP_Framework/Framework/connection/4g
|
||||
endif
|
||||
include $(wildcard $(APPDIR)/../../../APP_Framework/Framework/connection/4g/*/Make.defs)
|
|
@ -1,7 +1,17 @@
|
|||
SRC_FILES := adapter_4g.c
|
||||
include $(KERNEL_ROOT)/.config
|
||||
ifeq ($(CONFIG_ADD_NUTTX_FETURES),y)
|
||||
include $(APPDIR)/Make.defs
|
||||
CSRCS += adapter_4g.c
|
||||
include $(APPDIR)/Application.mk
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_EC200T),y)
|
||||
SRC_DIR += ec200t
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
ifeq ($(CONFIG_ADD_XIZI_FETURES),y)
|
||||
SRC_FILES := adapter_4g.c
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_EC200T),y)
|
||||
SRC_DIR += ec200t
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
endif
|
|
@ -24,8 +24,6 @@
|
|||
extern AdapterProductInfoType Ec200tAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_4G_NAME "4G"
|
||||
|
||||
static int Adapter4GRegister(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
|
@ -92,8 +90,8 @@ int Adapter4GTest(void)
|
|||
|
||||
#ifdef ADAPTER_EC200T
|
||||
//Using Hang Xiao server to test 4G Socket connection
|
||||
uint8 server_addr[64] = "101.68.82.219";
|
||||
uint8 server_port[64] = "9898";
|
||||
uint8 server_addr[64] = "120.76.100.197";
|
||||
uint8 server_port[64] = "10002";
|
||||
|
||||
adapter->socket.socket_id = 0;
|
||||
|
||||
|
|
|
@ -32,6 +32,9 @@ if ADD_XIZI_FETURES
|
|||
endif
|
||||
|
||||
if ADD_NUTTX_FETURES
|
||||
config ADAPTER_EC200T_DRIVER
|
||||
string "EC200T device uart driver path"
|
||||
default "/dev/ttyS8"
|
||||
|
||||
endif
|
||||
|
||||
|
|
|
@ -0,0 +1,6 @@
|
|||
############################################################################
|
||||
# APP_Framework/Framework/connection/4g/ec200t/Make.defs
|
||||
############################################################################
|
||||
ifneq ($(CONFIG_ADAPTER_4G_EC200T),)
|
||||
CONFIGURED_APPS += $(APPDIR)/../../../APP_Framework/Framework/connection/4g/ec200t
|
||||
endif
|
|
@ -1,3 +1,14 @@
|
|||
SRC_FILES := ec200t.c
|
||||
include $(KERNEL_ROOT)/.config
|
||||
ifeq ($(CONFIG_ADD_NUTTX_FETURES),y)
|
||||
include $(APPDIR)/Make.defs
|
||||
CSRCS += ec200t.c
|
||||
include $(APPDIR)/Application.mk
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADD_XIZI_FETURES),y)
|
||||
SRC_FILES := ec200t.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
endif
|
||||
|
|
|
@ -36,6 +36,11 @@
|
|||
#define EC200T_CREG_REPLY ",1"
|
||||
#define EC200T_CONNECT_REPLY "CONNECT"
|
||||
|
||||
#define TRY_TIMES 10
|
||||
|
||||
#ifdef ADD_NUTTX_FETURES
|
||||
static void Ec200tPowerSet(void){ return; }
|
||||
#else
|
||||
static void Ec200tPowerSet(void)
|
||||
{
|
||||
int pin_fd;
|
||||
|
@ -69,6 +74,7 @@ static void Ec200tPowerSet(void)
|
|||
|
||||
PrivTaskDelay(10000);
|
||||
}
|
||||
#endif
|
||||
|
||||
static int Ec200tOpen(struct Adapter *adapter)
|
||||
{
|
||||
|
@ -82,7 +88,7 @@ static int Ec200tOpen(struct Adapter *adapter)
|
|||
/*step2: init AT agent*/
|
||||
if (!adapter->agent) {
|
||||
char *agent_name = "4G_uart_client";
|
||||
if (EOK != InitATAgent(agent_name, adapter->fd, 512)) {
|
||||
if (0 != InitATAgent(agent_name, adapter->fd, 512)) {
|
||||
printf("at agent init failed !\n");
|
||||
return -1;
|
||||
}
|
||||
|
@ -116,6 +122,7 @@ static int Ec200tClose(struct Adapter *adapter)
|
|||
/*step2: serial write "AT+QICLOSE", close socket connect before open socket*/
|
||||
memset(ec200t_cmd, 0, sizeof(ec200t_cmd));
|
||||
sprintf(ec200t_cmd, EC200T_CLOSE_SOCKET_CMD, adapter->socket.socket_id);
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec200t_cmd, EC200T_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
|
@ -137,6 +144,10 @@ out:
|
|||
return ret;
|
||||
}
|
||||
|
||||
|
||||
#ifdef ADD_NUTTX_FETURES
|
||||
static int Ec200tIoctl(struct Adapter *adapter, int cmd, void *args){ return 0;}
|
||||
#else
|
||||
static int Ec200tIoctl(struct Adapter *adapter, int cmd, void *args)
|
||||
{
|
||||
if (OPE_INT != cmd) {
|
||||
|
@ -169,10 +180,12 @@ static int Ec200tIoctl(struct Adapter *adapter, int cmd, void *args)
|
|||
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
static int Ec200tConnect(struct Adapter *adapter, enum NetRoleType net_role, const char *ip, const char *port, enum IpType ip_type)
|
||||
{
|
||||
int ret = 0;
|
||||
int try = 0;
|
||||
uint8_t ec200t_cmd[64];
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 0x4F, 0x4B);
|
||||
|
@ -181,19 +194,34 @@ static int Ec200tConnect(struct Adapter *adapter, enum NetRoleType net_role, con
|
|||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "+++");
|
||||
|
||||
/*step2: serial write "AT+CCID", get SIM ID*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_GET_CCID_CMD, EC200T_OK_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_GET_CCID_CMD, EC200T_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step3: serial write "AT+CPIN?", check SIM status*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_GET_CPIN_CMD, EC200T_READY_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_GET_CPIN_CMD, EC200T_READY_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step4: serial write "AT+CREG?", check whether registered to GSM net*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_GET_CREG_CMD, EC200T_CREG_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_GET_CREG_CMD, EC200T_CREG_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
@ -207,7 +235,12 @@ static int Ec200tConnect(struct Adapter *adapter, enum NetRoleType net_role, con
|
|||
strcpy(ec200t_cmd, "AT+QICSGP=1,2,\"CMNET\",\"\",\"\",1\r\n");
|
||||
}
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec200t_cmd, EC200T_OK_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec200t_cmd, EC200T_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
@ -215,19 +248,34 @@ static int Ec200tConnect(struct Adapter *adapter, enum NetRoleType net_role, con
|
|||
/*step6: serial write "AT+QICLOSE", close socket connect before open socket*/
|
||||
memset(ec200t_cmd, 0, sizeof(ec200t_cmd));
|
||||
sprintf(ec200t_cmd, EC200T_CLOSE_SOCKET_CMD, adapter->socket.socket_id);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec200t_cmd, EC200T_OK_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec200t_cmd, EC200T_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step7: serial write "AT+QIDEACT", close TCP net before open socket*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_DEACTIVE_PDP_CMD, EC200T_OK_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_DEACTIVE_PDP_CMD, EC200T_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step8: serial write "AT+QIACT", open TCP net*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_ACTIVE_PDP_CMD, EC200T_OK_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC200T_ACTIVE_PDP_CMD, EC200T_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
@ -243,7 +291,12 @@ static int Ec200tConnect(struct Adapter *adapter, enum NetRoleType net_role, con
|
|||
|
||||
AtSetReplyEndChar(adapter->agent, 0x43, 0x54);
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec200t_cmd, EC200T_CONNECT_REPLY);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec200t_cmd, EC200T_CONNECT_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
@ -260,7 +313,6 @@ out:
|
|||
|
||||
static int Ec200tSend(struct Adapter *adapter, const void *buf, size_t len)
|
||||
{
|
||||
x_err_t result = EOK;
|
||||
if (adapter->agent) {
|
||||
EntmSend(adapter->agent, (const char *)buf, len);
|
||||
} else {
|
||||
|
|
|
@ -45,6 +45,15 @@ extern "C" {
|
|||
#define ADAPTER_DEBUG
|
||||
#endif
|
||||
|
||||
#define ADAPTER_4G_NAME "4G"
|
||||
#define ADAPTER_BLUETOOTH_NAME "bluetooth"
|
||||
#define ADAPTER_ETHERNET_NAME "ethernet"
|
||||
#define ADAPTER_ETHERCAT_NAME "ethercat"
|
||||
#define ADAPTER_LORA_NAME "lora"
|
||||
#define ADAPTER_NBIOT_NAME "nbiot"
|
||||
#define ADAPTER_WIFI_NAME "wifi"
|
||||
#define ADAPTER_ZIGBEE_NAME "zigbee"
|
||||
|
||||
struct Adapter;
|
||||
struct AdapterProductInfo;
|
||||
typedef struct Adapter *AdapterType;
|
||||
|
@ -108,6 +117,12 @@ enum IpType
|
|||
IPV6,
|
||||
};
|
||||
|
||||
struct AdapterData
|
||||
{
|
||||
uint32 len;
|
||||
uint8 *buffer;
|
||||
};
|
||||
|
||||
struct AdapterProductInfo
|
||||
{
|
||||
uint32_t functions;
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
#define AT_CMD_MAX_LEN 128
|
||||
#define AT_AGENT_MAX 2
|
||||
static char send_buf[AT_CMD_MAX_LEN];
|
||||
static uint32 last_cmd_len = 0;
|
||||
static uint32_t last_cmd_len = 0;
|
||||
|
||||
static struct ATAgent at_agent_table[AT_AGENT_MAX] = {0};
|
||||
|
||||
|
@ -126,7 +126,7 @@ void ATSprintf(int fd, const char *format, va_list params)
|
|||
PrivWrite(fd, send_buf, last_cmd_len);
|
||||
}
|
||||
|
||||
int ATOrderSend(ATAgentType agent, uint32 timeout_s, ATReplyType reply, const char *cmd_expr, ...)
|
||||
int ATOrderSend(ATAgentType agent, uint32_t timeout_s, ATReplyType reply, const char *cmd_expr, ...)
|
||||
{
|
||||
if (agent == NULL) {
|
||||
printf("ATAgent is null");
|
||||
|
@ -147,8 +147,8 @@ int ATOrderSend(ATAgentType agent, uint32 timeout_s, ATReplyType reply, const ch
|
|||
agent->entm_recv_len = 0;
|
||||
|
||||
va_list params;
|
||||
uint32 cmd_size = 0;
|
||||
uint32 result = 0;
|
||||
uint32_t cmd_size = 0;
|
||||
uint32_t result = 0;
|
||||
const char *cmd = NULL;
|
||||
|
||||
agent->reply = reply;
|
||||
|
@ -194,13 +194,15 @@ int AtCmdConfigAndCheck(ATAgentType agent, char *cmd, char *check)
|
|||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
ret = ATOrderSend(agent, REPLY_TIME_OUT, reply, cmd);
|
||||
if(ret < 0){
|
||||
printf("%s %d ATOrderSend failed.\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
// PrivTaskDelay(3000);
|
||||
|
||||
//PrivTaskDelay(3000);
|
||||
|
||||
result = GetReplyText(reply);
|
||||
if (!result) {
|
||||
|
@ -295,7 +297,7 @@ int EntmRecv(ATAgentType agent, char *rev_buffer, int buffer_len, int timeout_s)
|
|||
agent->receive_mode = ENTM_MODE;
|
||||
agent->read_len = buffer_len;
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
// PrivTaskDelay(1000);
|
||||
//PrivTaskDelay(1000);
|
||||
if (PrivSemaphoreObtainWait(&agent->entm_rx_notice, &abstime)) {
|
||||
printf("wait sem[%d] timeout\n",agent->entm_rx_notice);
|
||||
return -ERROR;
|
||||
|
@ -317,7 +319,7 @@ int EntmRecv(ATAgentType agent, char *rev_buffer, int buffer_len, int timeout_s)
|
|||
|
||||
static int GetCompleteATReply(ATAgentType agent)
|
||||
{
|
||||
uint32 read_len = 0;
|
||||
uint32_t read_len = 0;
|
||||
char ch = 0, last_ch = 0;
|
||||
bool is_full = false;
|
||||
|
||||
|
@ -335,7 +337,9 @@ static int GetCompleteATReply(ATAgentType agent)
|
|||
{
|
||||
PrivRead(agent->fd, &ch, 1);
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
printf(" %c (0x%x)\n", ch, ch);
|
||||
if(ch != 0){
|
||||
printf(" %c (0x%x)\n", ch, ch);
|
||||
}
|
||||
#endif
|
||||
|
||||
PrivMutexObtain(&agent->lock);
|
||||
|
@ -365,9 +369,13 @@ static int GetCompleteATReply(ATAgentType agent)
|
|||
{
|
||||
if (read_len < agent->maintain_max)
|
||||
{
|
||||
agent->maintain_buffer[read_len] = ch;
|
||||
read_len++;
|
||||
agent->maintain_len = read_len;
|
||||
if(ch != 0) ///< if the char is null then do not save it to the buff
|
||||
{
|
||||
agent->maintain_buffer[read_len] = ch;
|
||||
read_len++;
|
||||
agent->maintain_len = read_len;
|
||||
}
|
||||
|
||||
} else {
|
||||
printf("maintain_len is_full ...\n");
|
||||
is_full = true;
|
||||
|
@ -424,10 +432,17 @@ int DeleteATAgent(ATAgentType agent)
|
|||
PrivClose(agent->fd);
|
||||
}
|
||||
|
||||
#ifdef ADD_NUTTX_FETURES
|
||||
if (agent->lock.sem.semcount > 0) {
|
||||
printf("delete agent lock = %d\n",agent->lock.sem.semcount);
|
||||
PrivMutexDelete(&agent->lock);
|
||||
}
|
||||
#else
|
||||
if (agent->lock) {
|
||||
printf("delete agent lock = %d\n",agent->lock);
|
||||
PrivMutexDelete(&agent->lock);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (agent->entm_rx_notice) {
|
||||
printf("delete agent entm_rx_notice = %d\n",agent->entm_rx_notice);
|
||||
|
@ -516,7 +531,7 @@ static int ATAgentInit(ATAgentType agent)
|
|||
|
||||
#else
|
||||
pthread_attr_t attr;
|
||||
attr.schedparam.sched_priority = 18;
|
||||
attr.schedparam.sched_priority = 25;
|
||||
attr.stacksize = 4096;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -53,7 +53,11 @@ struct ATAgent
|
|||
uint32 maintain_len;
|
||||
uint32 maintain_max;
|
||||
|
||||
#ifdef ADD_NUTTX_FETURES
|
||||
pthread_mutex_t lock;
|
||||
#else
|
||||
int lock;
|
||||
#endif
|
||||
|
||||
ATReplyType reply;
|
||||
char reply_lr_end;
|
||||
|
@ -87,7 +91,7 @@ int InitATAgent(const char *agent_name, int fd, uint32 maintain_max);
|
|||
int DeleteATAgent(ATAgentType agent);
|
||||
int ParseATReply(char* str, const char *format, ...);
|
||||
void DeleteATReply(ATReplyType reply);
|
||||
int ATOrderSend(ATAgentType agent, uint32 timeout_s, ATReplyType reply, const char *cmd_expr, ...);
|
||||
int ATOrderSend(ATAgentType agent, uint32_t timeout_s, ATReplyType reply, const char *cmd_expr, ...);
|
||||
int AtCmdConfigAndCheck(ATAgentType agent, char *cmd, char *check);
|
||||
|
||||
#endif
|
|
@ -24,8 +24,6 @@
|
|||
extern AdapterProductInfoType Hc08Attach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_BLUETOOTH_NAME "bluetooth"
|
||||
|
||||
static int AdapterBlueToothRegister(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
|
|
|
@ -24,8 +24,6 @@
|
|||
extern AdapterProductInfoType Hfa21EthernetAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_ETHERNET_NAME "ethernet"
|
||||
|
||||
static int AdapterEthernetRegister(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
extern AdapterProductInfoType Hfa21EthercatAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_ETHERCAT_NAME "ethercat"
|
||||
|
||||
/**
|
||||
* @description: clear the datagram in ethercat frame, do not free the frame itself, since it may be a memory space on stack
|
||||
* @param frame - ethercat frame pointer
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
// therefore, only the TCP/UDP datagrams are considered,
|
||||
// here EtherCAT is in fact an application layer protocol.
|
||||
|
||||
#define ADAPTER_ETHERNET_NAME "ethernet" //"wifi"
|
||||
// #define ADAPTER_ETHERNET_NAME "ethernet" //"wifi"
|
||||
EcatFrame ecat_data;
|
||||
static struct Adapter *ethernet;
|
||||
uint32_t self_address;
|
||||
|
|
|
@ -1,6 +1,10 @@
|
|||
config ADAPTER_SX1278
|
||||
bool "Using lora adapter device SX1278"
|
||||
default y
|
||||
default n
|
||||
|
||||
config ADAPTER_E220
|
||||
bool "Using lora adapter device E220-400T22S"
|
||||
default n
|
||||
|
||||
choice
|
||||
prompt "Lora device adapter select net role type "
|
||||
|
@ -15,16 +19,20 @@ endchoice
|
|||
|
||||
if AS_LORA_GATEWAY_ROLE
|
||||
config ADAPTER_LORA_NET_ROLE_ID
|
||||
hex "if Lora device config as a gateway, set gateway net id"
|
||||
default "0x10"
|
||||
hex "if Lora device config as a gateway, set gateway net id"
|
||||
default "0xFF"
|
||||
endif
|
||||
|
||||
if AS_LORA_CLIENT_ROLE
|
||||
config ADAPTER_LORA_NET_ROLE_ID
|
||||
hex "if Lora device config as a client, set client net id"
|
||||
default "0x01"
|
||||
hex "if Lora device config as a client, set client net id"
|
||||
default "0x01"
|
||||
endif
|
||||
|
||||
if ADAPTER_SX1278
|
||||
source "$APP_DIR/Framework/connection/lora/sx1278/Kconfig"
|
||||
endif
|
||||
|
||||
if ADAPTER_E220
|
||||
source "$APP_DIR/Framework/connection/lora/e220/Kconfig"
|
||||
endif
|
||||
|
|
|
@ -8,9 +8,14 @@ endif
|
|||
|
||||
ifeq ($(CONFIG_ADD_XIZI_FETURES),y)
|
||||
SRC_FILES := adapter_lora.c
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_SX1278),y)
|
||||
SRC_DIR += sx1278
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_E220),y)
|
||||
SRC_DIR += e220
|
||||
endif
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
endif
|
||||
|
|
|
@ -24,10 +24,13 @@
|
|||
extern AdapterProductInfoType Sx1278Attach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_LORA_NAME "lora"
|
||||
#define ADAPTER_LORA_CLIENT_NUM 6
|
||||
#define ADAPTER_LORA_DATA_LENGTH 128
|
||||
#define ADAPTER_LORA_RECV_DATA_LENGTH 256
|
||||
#ifdef ADAPTER_E220
|
||||
extern AdapterProductInfoType E220Attach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_LORA_CLIENT_NUM 255
|
||||
#define ADAPTER_LORA_DATA_LENGTH 256
|
||||
#define ADAPTER_LORA_RECV_DATA_LENGTH ADAPTER_LORA_DATA_LENGTH + 16
|
||||
|
||||
#define ADAPTER_LORA_DATA_HEAD 0x3C
|
||||
#define ADAPTER_LORA_NET_PANID 0x0102
|
||||
|
@ -164,13 +167,7 @@ static int LoraReceiveDataCheck(uint8 *data, uint16 length, struct LoraDataForma
|
|||
uint32 recv_data_length = 0;
|
||||
for ( i = 0; i < length; i ++) {
|
||||
if (ADAPTER_LORA_DATA_HEAD == data[i]) {
|
||||
#ifdef ADD_NUTTX_FETURES
|
||||
/*Big-Endian*/
|
||||
recv_data_length = (data[i + 4] & 0xFF) | ((data[i + 5] & 0xFF) << 8) | ((data[i + 6] & 0xFF) << 16) | ((data[i + 7] & 0xFF) << 24);
|
||||
#else
|
||||
/*Little-Endian*/
|
||||
recv_data_length = ((data[i + 4] & 0xFF) << 24) | ((data[i + 5] & 0xFF) << 16) | ((data[i + 6] & 0xFF) << 8) | (data[i + 7] & 0xFF);
|
||||
#endif
|
||||
if (sizeof(struct LoraDataFormat) == recv_data_length) {
|
||||
memcpy(recv_data, (uint8 *)(data + i), sizeof(struct LoraDataFormat));
|
||||
return 0;
|
||||
|
@ -422,7 +419,7 @@ static int LoraClientDataAnalyze(struct Adapter *adapter, void *send_buf, int le
|
|||
|
||||
LoraReceiveDataCheck(lora_recv_data, ADAPTER_LORA_RECV_DATA_LENGTH, client_recv_data);
|
||||
|
||||
printf("%s:client_recv_data\n",__func__);
|
||||
printf("%s:client_recv_data\n", __func__);
|
||||
printf("head 0x%x length %d panid 0x%x data_type 0x%x client_id 0x%x gateway_id 0x%x crc 0x%x\n",
|
||||
client_recv_data->flame_head, client_recv_data->length, client_recv_data->panid, client_recv_data->data_type,
|
||||
client_recv_data->client_id, client_recv_data->gateway_id, client_recv_data->crc16);
|
||||
|
@ -466,6 +463,7 @@ static int LoraClientDataAnalyze(struct Adapter *adapter, void *send_buf, int le
|
|||
static int LoraClientJoinNet(struct Adapter *adapter, unsigned short panid)
|
||||
{
|
||||
struct LoraDataFormat client_join_data;
|
||||
struct AdapterData priv_lora_net;
|
||||
|
||||
memset(&client_join_data, 0, sizeof(struct LoraDataFormat));
|
||||
|
||||
|
@ -476,12 +474,15 @@ static int LoraClientJoinNet(struct Adapter *adapter, unsigned short panid)
|
|||
client_join_data.client_id = adapter->net_role_id;
|
||||
client_join_data.crc16 = LoraCrc16((uint8 *)&client_join_data, sizeof(struct LoraDataFormat) - 2);
|
||||
|
||||
printf("%s:client_join_data\n",__func__);
|
||||
printf("%s:client_join_data\n", __func__);
|
||||
printf("head 0x%x length %d panid 0x%x data_type 0x%x client_id 0x%x gateway_id 0x%x crc 0x%x\n",
|
||||
client_join_data.flame_head, client_join_data.length, client_join_data.panid, client_join_data.data_type,
|
||||
client_join_data.client_id, client_join_data.gateway_id, client_join_data.crc16);
|
||||
|
||||
if (AdapterDeviceJoin(adapter, (uint8 *)&client_join_data) < 0) {
|
||||
priv_lora_net.len = sizeof(struct LoraDataFormat);
|
||||
priv_lora_net.buffer = (uint8 *)&client_join_data;
|
||||
|
||||
if (AdapterDeviceJoin(adapter, (uint8 *)&priv_lora_net) < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
@ -495,18 +496,22 @@ static int LoraClientJoinNet(struct Adapter *adapter, unsigned short panid)
|
|||
*/
|
||||
static int LoraClientQuitNet(struct Adapter *adapter, unsigned short panid)
|
||||
{
|
||||
struct LoraDataFormat client_join_data;
|
||||
struct LoraDataFormat client_quit_data;
|
||||
struct AdapterData priv_lora_net;
|
||||
|
||||
memset(&client_join_data, 0, sizeof(struct LoraDataFormat));
|
||||
memset(&client_quit_data, 0, sizeof(struct LoraDataFormat));
|
||||
|
||||
client_join_data.flame_head = ADAPTER_LORA_DATA_HEAD;
|
||||
client_join_data.length = sizeof(struct LoraDataFormat);
|
||||
client_join_data.panid = panid;
|
||||
client_join_data.data_type = ADAPTER_LORA_DATA_TYPE_QUIT;
|
||||
client_join_data.client_id = adapter->net_role_id;
|
||||
client_join_data.crc16 = LoraCrc16((uint8 *)&client_join_data, sizeof(struct LoraDataFormat) - 2);
|
||||
client_quit_data.flame_head = ADAPTER_LORA_DATA_HEAD;
|
||||
client_quit_data.length = sizeof(struct LoraDataFormat);
|
||||
client_quit_data.panid = panid;
|
||||
client_quit_data.data_type = ADAPTER_LORA_DATA_TYPE_QUIT;
|
||||
client_quit_data.client_id = adapter->net_role_id;
|
||||
client_quit_data.crc16 = LoraCrc16((uint8 *)&client_quit_data, sizeof(struct LoraDataFormat) - 2);
|
||||
|
||||
if (AdapterDeviceDisconnect(adapter, (uint8 *)&client_join_data) < 0) {
|
||||
priv_lora_net.len = sizeof(struct LoraDataFormat);
|
||||
priv_lora_net.buffer = (uint8 *)&client_quit_data;
|
||||
|
||||
if (AdapterDeviceDisconnect(adapter, (uint8 *)&priv_lora_net) < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
@ -620,7 +625,6 @@ static void *LoraGatewayTask(void *parameter)
|
|||
static void *LoraClientDataTask(void *parameter)
|
||||
{
|
||||
int i, ret = 0;
|
||||
int join_times = 10;
|
||||
struct Adapter *lora_adapter = (struct Adapter *)parameter;
|
||||
struct LoraClientParam *client = (struct LoraClientParam *)lora_adapter->adapter_param;
|
||||
|
||||
|
@ -786,6 +790,19 @@ int AdapterLoraInit(void)
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef ADAPTER_E220
|
||||
AdapterProductInfoType product_info = E220Attach(adapter);
|
||||
if (!product_info) {
|
||||
printf("AdapterLoraInit e220 attach error\n");
|
||||
PrivFree(adapter);
|
||||
return -1;
|
||||
}
|
||||
|
||||
adapter->product_info_flag = 1;
|
||||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,44 @@
|
|||
config ADAPTER_LORA_E220
|
||||
string "E220-400T22S adapter name"
|
||||
default "e220"
|
||||
|
||||
if ADD_XIZI_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/pin_dev"
|
||||
|
||||
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/uart1_dev1"
|
||||
depends on !ADAPTER_E220_DRIVER_EXTUART
|
||||
|
||||
if ADAPTER_E220_DRIVER_EXTUART
|
||||
config ADAPTER_E220_DRIVER
|
||||
string "E220 device extra uart driver path"
|
||||
default "/dev/extuart_dev3"
|
||||
|
||||
config ADAPTER_E220_DRIVER_EXT_PORT
|
||||
int "if E220 device using extuart, choose port"
|
||||
default "3"
|
||||
endif
|
||||
endif
|
||||
|
||||
if ADD_NUTTX_FETURES
|
||||
|
||||
endif
|
||||
|
||||
if ADD_RTTHREAD_FETURES
|
||||
|
||||
endif
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := e220.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,536 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS 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 e220.c
|
||||
* @brief Implement the connection E220-400T22S lora adapter function
|
||||
* @version 2.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2022.4.20
|
||||
*/
|
||||
|
||||
#include <adapter.h>
|
||||
|
||||
#define E220_GATEWAY_ADDRESS 0xFFFF
|
||||
#define E220_CHANNEL 0x04
|
||||
|
||||
#ifdef AS_LORA_GATEWAY_ROLE
|
||||
#define E220_ADDRESS E220_GATEWAY_ADDRESS
|
||||
#endif
|
||||
|
||||
#ifdef AS_LORA_CLIENT_ROLE
|
||||
#define E220_ADDRESS 0xFFFF
|
||||
#endif
|
||||
|
||||
#define E220_UART_BAUD_RATE 9600
|
||||
|
||||
enum E220LoraMode
|
||||
{
|
||||
DATA_TRANSFER_MODE = 0, //M1 : M0 = 0 : 0
|
||||
WOR_SEND_MODE, //M1 : M0 = 0 : 1
|
||||
WOR_RECEIVE_MODE, //M1 : M0 = 1 : 0
|
||||
CONFIGURE_MODE_MODE, //M1 : M0 = 1 : 1
|
||||
};
|
||||
|
||||
/**
|
||||
* @description: Config E220 work mode by set M1/M0 pin
|
||||
* @param mode Lora working mode
|
||||
* @return NULL
|
||||
*/
|
||||
static void E220LoraModeConfig(enum E220LoraMode mode)
|
||||
{
|
||||
//delay 1s , wait AUX ready
|
||||
PrivTaskDelay(1000);
|
||||
|
||||
int pin_fd;
|
||||
pin_fd = PrivOpen(ADAPTER_E220_PIN_DRIVER, O_RDWR);
|
||||
if (pin_fd < 0) {
|
||||
printf("open %s error\n", ADAPTER_E220_PIN_DRIVER);
|
||||
return;
|
||||
}
|
||||
|
||||
//Step1: config M0 and M1 GPIO
|
||||
struct PinParam pin_param;
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_OUTPUT;
|
||||
pin_param.pin = ADAPTER_E220_M0;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
pin_param.pin = ADAPTER_E220_M1;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
//Step2 : set M0 and M1 high or low
|
||||
struct PinStat pin_stat;
|
||||
|
||||
switch (mode)
|
||||
{
|
||||
case DATA_TRANSFER_MODE:
|
||||
pin_stat.pin = ADAPTER_E220_M1;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_stat.pin = ADAPTER_E220_M0;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
break;
|
||||
|
||||
case WOR_SEND_MODE:
|
||||
pin_stat.pin = ADAPTER_E220_M1;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_stat.pin = ADAPTER_E220_M0;
|
||||
pin_stat.val = GPIO_HIGH;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
break;
|
||||
|
||||
case WOR_RECEIVE_MODE:
|
||||
pin_stat.pin = ADAPTER_E220_M1;
|
||||
pin_stat.val = GPIO_HIGH;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_stat.pin = ADAPTER_E220_M0;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
break;
|
||||
|
||||
case CONFIGURE_MODE_MODE:
|
||||
pin_stat.pin = ADAPTER_E220_M1;
|
||||
pin_stat.val = GPIO_HIGH;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_stat.pin = ADAPTER_E220_M0;
|
||||
pin_stat.val = GPIO_HIGH;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
PrivClose(pin_fd);
|
||||
|
||||
//delay 20ms , wait mode switch done
|
||||
PrivTaskDelay(20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: Switch baud rate to register bit
|
||||
* @param baud_rate - baud_rate
|
||||
* @return baud_rate_bit
|
||||
*/
|
||||
static uint8 E220BaudRateSwitch(uint32 baud_rate)
|
||||
{
|
||||
uint8 baud_rate_bit;
|
||||
|
||||
switch (baud_rate)
|
||||
{
|
||||
case 1200:
|
||||
baud_rate_bit = 0x0;
|
||||
break;
|
||||
|
||||
case 2400:
|
||||
baud_rate_bit = 0x1;
|
||||
break;
|
||||
|
||||
case 4800:
|
||||
baud_rate_bit = 0x2;
|
||||
break;
|
||||
|
||||
case 9600:
|
||||
baud_rate_bit = 0x3;
|
||||
break;
|
||||
|
||||
case 19200:
|
||||
baud_rate_bit = 0x4;
|
||||
break;
|
||||
|
||||
case 38400:
|
||||
baud_rate_bit = 0x5;
|
||||
break;
|
||||
|
||||
case 57600:
|
||||
baud_rate_bit = 0x6;
|
||||
break;
|
||||
|
||||
case 115200:
|
||||
baud_rate_bit = 0x7;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return baud_rate_bit;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: Set E220 register, such as address、channel、baud rate...
|
||||
* @param adapter - lora adapter
|
||||
* @param address - address
|
||||
* @param channel - channel
|
||||
* @param baud_rate - baud_rate
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220SetRegisterParam(struct Adapter *adapter, uint16 address, uint8 channel, uint32 baud_rate)
|
||||
{
|
||||
int ret;
|
||||
uint8 buffer[50] = {0};
|
||||
uint8 baud_rate_bit = E220BaudRateSwitch(baud_rate);
|
||||
|
||||
E220LoraModeConfig(CONFIGURE_MODE_MODE);
|
||||
PrivTaskDelay(30);
|
||||
|
||||
buffer[0] = 0xC0; //write register order
|
||||
buffer[1] = 0x00; //register start-address
|
||||
buffer[2] = 0x08; //register length
|
||||
|
||||
buffer[3] = (address >> 8) & 0xFF; //high address
|
||||
buffer[4] = address & 0xFF; //low adderss
|
||||
|
||||
buffer[5] = ((baud_rate_bit << 5) & 0xE0) | 0x04;
|
||||
|
||||
buffer[6] = 0x00;
|
||||
buffer[7] = channel; //channel
|
||||
buffer[8] = 0x03;
|
||||
buffer[9] = 0; //high-cipher
|
||||
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);
|
||||
PrivTaskDelay(1000);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: Get E220 register, such as address、channel、baud rate...
|
||||
* @param buf - data buf
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220GetRegisterParam(uint8 *buf)
|
||||
{
|
||||
int ret;
|
||||
uint8 buffer[3] = {0};
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_LORA_NAME);
|
||||
if (NULL == adapter) {
|
||||
printf("E220GetRegisterParam find lora adapter error\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
E220LoraModeConfig(CONFIGURE_MODE_MODE);
|
||||
PrivTaskDelay(30);
|
||||
|
||||
buffer[0] = 0xC1; //read register order
|
||||
buffer[1] = 0x00; //register start-address
|
||||
buffer[2] = 0x08; //register length
|
||||
|
||||
ret = PrivWrite(adapter->fd, (void *)buffer, 3);
|
||||
if(ret < 0){
|
||||
printf("E220GetRegisterParam send failed %d!\n", ret);
|
||||
}
|
||||
|
||||
PrivRead(adapter->fd, buf, 11);
|
||||
|
||||
E220LoraModeConfig(DATA_TRANSFER_MODE);
|
||||
PrivTaskDelay(30);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: Open E220 uart function
|
||||
* @param adapter - Lora device pointer
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
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
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = &cfg;
|
||||
|
||||
PrivIoctl(adapter->fd, OPE_INT, &ioctl_cfg);
|
||||
|
||||
E220SetRegisterParam(adapter, E220_ADDRESS, E220_CHANNEL, E220_UART_BAUD_RATE);
|
||||
|
||||
ADAPTER_DEBUG("E220Open done\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: Close E220 uart function
|
||||
* @param adapter - Lora device pointer
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220Close(struct Adapter *adapter)
|
||||
{
|
||||
/*step1: close e220 uart port*/
|
||||
int ret;
|
||||
ret = PrivClose(adapter->fd);
|
||||
if(ret < 0) {
|
||||
printf("E220 close failed: %d!\n", ret);
|
||||
return -1;
|
||||
}
|
||||
|
||||
ADAPTER_DEBUG("E220 Close done\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: E220 ioctl function
|
||||
* @param adapter - Lora device pointer
|
||||
* @param cmd - ioctl cmd
|
||||
* @param args - iotl params
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220Ioctl(struct Adapter *adapter, int cmd, void *args)
|
||||
{
|
||||
/*to do*/
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: E220 join lora net group function
|
||||
* @param adapter - Lora device pointer
|
||||
* @param priv_net_group - priv_net_group params
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220Join(struct Adapter *adapter, unsigned char *priv_net_group)
|
||||
{
|
||||
int ret;
|
||||
struct AdapterData *priv_net_group_data = (struct AdapterData *)priv_net_group;
|
||||
|
||||
ret = PrivWrite(adapter->fd, (void *)priv_net_group_data->buffer, priv_net_group_data->len);
|
||||
if(ret < 0) {
|
||||
printf("E220 Join net group failed: %d!\n", ret);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: E220 send data function
|
||||
* @param adapter - Lora device pointer
|
||||
* @param buf - data buffers
|
||||
* @param len - data len
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220Send(struct Adapter *adapter, const void *buf, size_t len)
|
||||
{
|
||||
int ret;
|
||||
|
||||
ret = PrivWrite(adapter->fd, (void *)buf, len);
|
||||
if(ret < 0){
|
||||
printf("send failed %d!\n", ret);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: E220 receive data function
|
||||
* @param adapter - Lora device pointer
|
||||
* @param buf - data buffers
|
||||
* @param len - data len
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220Recv(struct Adapter *adapter, void *buf, size_t len)
|
||||
{
|
||||
int recv_len, recv_len_continue;
|
||||
|
||||
uint8 *recv_buf = PrivMalloc(len);
|
||||
|
||||
recv_len = PrivRead(adapter->fd, recv_buf, len);
|
||||
while (recv_len < len) {
|
||||
recv_len_continue = PrivRead(adapter->fd, recv_buf + recv_len, len - recv_len);
|
||||
|
||||
recv_len += recv_len_continue;
|
||||
}
|
||||
|
||||
memcpy(buf, recv_buf, recv_len);
|
||||
|
||||
PrivFree(recv_buf);
|
||||
|
||||
return recv_len;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: E220 quit lora net group function
|
||||
* @param adapter - Lora device pointer
|
||||
* @param priv_net_group - priv_net_group params
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int E220Quit(struct Adapter *adapter, unsigned char *priv_net_group)
|
||||
{
|
||||
int ret;
|
||||
|
||||
struct AdapterData *priv_net_group_data = (struct AdapterData *)priv_net_group;
|
||||
|
||||
ret = PrivWrite(adapter->fd, (void *)priv_net_group_data->buffer, priv_net_group_data->len);
|
||||
if(ret < 0){
|
||||
printf("E220 quit net group failed %d!\n", ret);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static const struct PrivProtocolDone e220_done =
|
||||
{
|
||||
.open = E220Open,
|
||||
.close = E220Close,
|
||||
.ioctl = E220Ioctl,
|
||||
.setup = NULL,
|
||||
.setdown = NULL,
|
||||
.setaddr = NULL,
|
||||
.setdns = NULL,
|
||||
.setdhcp = NULL,
|
||||
.ping = NULL,
|
||||
.netstat = NULL,
|
||||
.join = E220Join,
|
||||
.send = E220Send,
|
||||
.recv = E220Recv,
|
||||
.quit = E220Quit,
|
||||
};
|
||||
|
||||
AdapterProductInfoType E220Attach(struct Adapter *adapter)
|
||||
{
|
||||
struct AdapterProductInfo *product_info = malloc(sizeof(struct AdapterProductInfo));
|
||||
if (!product_info) {
|
||||
printf("E220Attach malloc product_info error\n");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
strncpy(product_info->model_name, ADAPTER_LORA_E220,sizeof(product_info->model_name));
|
||||
product_info->model_done = (void *)&e220_done;
|
||||
|
||||
return product_info;
|
||||
}
|
||||
|
||||
//###################TEST####################
|
||||
static void LoraOpen(void)
|
||||
{
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_LORA_NAME);
|
||||
if (NULL == adapter) {
|
||||
printf("LoraReceive find lora adapter error\n");
|
||||
return;
|
||||
}
|
||||
|
||||
E220Open(adapter);
|
||||
}
|
||||
|
||||
static void LoraRead(void *parameter)
|
||||
{
|
||||
int RevLen;
|
||||
uint8 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)
|
||||
{
|
||||
KPrintf("ready to read lora data\n");
|
||||
|
||||
RevLen = E220Recv(adapter, buffer, 256);
|
||||
if (RevLen) {
|
||||
KPrintf("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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void LoraTest(void)
|
||||
{
|
||||
int ret;
|
||||
|
||||
LoraOpen();
|
||||
|
||||
int task_lora_read = KTaskCreate("task_lora_read", LoraRead, NONE, 2048, 10);
|
||||
ret = StartupKTask(task_lora_read);
|
||||
if (ret != EOK) {
|
||||
KPrintf("StartupKTask task_lora_read failed .\n");
|
||||
return;
|
||||
}
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN),
|
||||
LoraTest, LoraTest, lora send and receive message);
|
||||
|
||||
static void LoraSend(int argc, char *argv[])
|
||||
{
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_LORA_NAME);
|
||||
if (NULL == adapter) {
|
||||
printf("LoraRead find lora adapter error\n");
|
||||
return;
|
||||
}
|
||||
|
||||
char Msg[256] = {0};
|
||||
|
||||
if (argc == 2) {
|
||||
strncpy(Msg, argv[1], 256);
|
||||
|
||||
E220Send(adapter, Msg, strlen(Msg));
|
||||
}
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN),
|
||||
LoraSend, LoraSend, lora send message);
|
|
@ -108,7 +108,9 @@ static int Sx1278Ioctl(struct Adapter *adapter, int cmd, void *args)
|
|||
static int Sx1278Join(struct Adapter *adapter, unsigned char *priv_net_group)
|
||||
{
|
||||
int ret;
|
||||
ret = Sx127x_Nuttx_Write(adapter->fd, (void *)priv_net_group, 144);
|
||||
struct AdapterData *priv_net_group_data = (struct AdapterData *)priv_net_group;
|
||||
|
||||
ret = Sx127x_Nuttx_Write(adapter->fd, (void *)priv_net_group_data->buffer, priv_net_group_data->len);
|
||||
if(ret < 0){
|
||||
printf("Sx1278 Join net group failed: %d!\n", ret);
|
||||
}
|
||||
|
@ -119,7 +121,9 @@ static int Sx1278Join(struct Adapter *adapter, unsigned char *priv_net_group)
|
|||
static int Sx1278Join(struct Adapter *adapter, unsigned char *priv_net_group)
|
||||
{
|
||||
int ret;
|
||||
ret = PrivWrite(adapter->fd, (void *)priv_net_group, 144);
|
||||
struct AdapterData *priv_net_group_data = (struct AdapterData *)priv_net_group;
|
||||
|
||||
ret = PrivWrite(adapter->fd, (void *)priv_net_group_data->buffer, priv_net_group_data->len);
|
||||
if(ret < 0){
|
||||
printf("Sx1278 Join net group failed: %d!\n", ret);
|
||||
}
|
||||
|
@ -196,7 +200,9 @@ static int Sx1278Recv(struct Adapter *adapter, void *buf, size_t len)
|
|||
static int Sx1278Quit(struct Adapter *adapter, unsigned char *priv_net_group)
|
||||
{
|
||||
int ret;
|
||||
ret = Sx127x_Nuttx_Write(adapter->fd, (void *)priv_net_group, 144);
|
||||
struct AdapterData *priv_net_group_data = (struct AdapterData *)priv_net_group;
|
||||
|
||||
ret = Sx127x_Nuttx_Write(adapter->fd, (void *)priv_net_group_data->buffer, priv_net_group_data->len);
|
||||
if(ret < 0){
|
||||
printf("Sx1278 quit net group failed %d!\n", ret);
|
||||
}
|
||||
|
@ -207,7 +213,9 @@ static int Sx1278Quit(struct Adapter *adapter, unsigned char *priv_net_group)
|
|||
static int Sx1278Quit(struct Adapter *adapter, unsigned char *priv_net_group)
|
||||
{
|
||||
int ret;
|
||||
ret = PrivWrite(adapter->fd, (void *)priv_net_group, 144);
|
||||
struct AdapterData *priv_net_group_data = (struct AdapterData *)priv_net_group;
|
||||
|
||||
ret = PrivWrite(adapter->fd, (void *)priv_net_group_data->buffer, priv_net_group_data->len);
|
||||
if(ret < 0){
|
||||
printf("Sx1278 quit net group failed %d!\n", ret);
|
||||
}
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
extern AdapterProductInfoType BC28Attach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_NBIOT_NAME "nbiot"
|
||||
|
||||
static int AdapterNbiotRegister(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
|
|
|
@ -7,3 +7,11 @@ config ADAPTER_HFA21_WIFI
|
|||
if ADAPTER_HFA21_WIFI
|
||||
source "$APP_DIR/Framework/connection/wifi/hfa21_wifi/Kconfig"
|
||||
endif
|
||||
|
||||
config ADAPTER_ESP07S_WIFI
|
||||
bool "Using wifi adapter device esp07s"
|
||||
default n
|
||||
|
||||
if ADAPTER_ESP07S_WIFI
|
||||
source "$APP_DIR/Framework/connection/wifi/esp07s_wifi/Kconfig"
|
||||
endif
|
||||
|
|
|
@ -4,4 +4,8 @@ ifeq ($(CONFIG_ADAPTER_HFA21_WIFI),y)
|
|||
SRC_DIR += hfa21_wifi
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_ESP07S_WIFI),y)
|
||||
SRC_DIR += esp07s_wifi
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
|
|
@ -19,13 +19,15 @@
|
|||
*/
|
||||
|
||||
#include <adapter.h>
|
||||
#include "adapter_wifi.h"
|
||||
#include <bus_pin.h>
|
||||
|
||||
#ifdef ADAPTER_HFA21_WIFI
|
||||
extern AdapterProductInfoType Hfa21WifiAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_WIFI_NAME "wifi"
|
||||
#ifdef ADAPTER_ESP07S_WIFI
|
||||
extern AdapterProductInfoType Esp07sWifiAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
static int AdapterWifiRegister(struct Adapter *adapter)
|
||||
{
|
||||
|
@ -77,13 +79,26 @@ int AdapterWifiInit(void)
|
|||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
|
||||
#endif
|
||||
#ifdef ADAPTER_ESP07S_WIFI
|
||||
AdapterProductInfoType product_info = Esp07sWifiAttach(adapter);
|
||||
if (!product_info) {
|
||||
printf("AdapterWifiInit ESP07S attach error\n");
|
||||
PrivFree(adapter);
|
||||
return -1;
|
||||
}
|
||||
|
||||
adapter->product_info_flag = 1;
|
||||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/******************wifi TEST*********************/
|
||||
int AdapterWifiTest(void)
|
||||
int AdapterwifiTest(void)
|
||||
{
|
||||
char cmd[64];
|
||||
int baud_rate = BAUD_RATE_57600;
|
||||
|
@ -140,14 +155,14 @@ int AdapterWifiTest(void)
|
|||
|
||||
|
||||
AdapterDeviceOpen(adapter);
|
||||
AdapterDeviceControl(adapter, OPE_INT, &baud_rate);
|
||||
// AdapterDeviceControl(adapter, OPE_INT, &baud_rate);
|
||||
|
||||
AdapterDeviceSetUp(adapter);
|
||||
AdapterDeviceSetAddr(adapter, "192.168.66.253", "255.255.255.0", "192.168.66.1");
|
||||
AdapterDeviceSetAddr(adapter, "192.168.64.253", "192.168.66.1", "255.255.252.0");
|
||||
AdapterDevicePing(adapter, "36.152.44.95");
|
||||
AdapterDeviceNetstat(adapter);
|
||||
|
||||
const char *ip = "192.168.66.211";
|
||||
const char *ip = "192.168.64.60";
|
||||
const char *port = "12345";
|
||||
enum NetRoleType net_role = CLIENT;
|
||||
enum IpType ip_type = IPV4;
|
||||
|
@ -166,4 +181,97 @@ int AdapterWifiTest(void)
|
|||
}
|
||||
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0)|SHELL_CMD_DISABLE_RETURN, AdapterWifiTest, AdapterWifiTest, show adapter wifi information);
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0)|SHELL_CMD_DISABLE_RETURN, AdapterwifiTest, AdapterwifiTest, show adapter wifi information);
|
||||
|
||||
int wifiopen(void)
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
|
||||
AdapterDeviceOpen(adapter);
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0)|SHELL_CMD_DISABLE_RETURN, wifiopen, wifiopen, open adapter wifi );
|
||||
int wificlose(void)
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
|
||||
AdapterDeviceClose(adapter);
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0)|SHELL_CMD_DISABLE_RETURN, wificlose, wificlose, close adapter wifi );
|
||||
|
||||
int wifisetup(int argc, char *argv[])
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
struct WifiParam param;
|
||||
memset(¶m,0,sizeof(struct WifiParam));
|
||||
strncpy(param.wifi_ssid, argv[1], strlen(argv[1]));
|
||||
strncpy(param.wifi_pwd, argv[2], strlen(argv[2]));
|
||||
|
||||
adapter->adapter_param = ¶m;
|
||||
|
||||
AdapterDeviceSetUp(adapter);
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_PARAM_NUM(3)|SHELL_CMD_DISABLE_RETURN, wifisetup, wifisetup, setup adapter wifi );
|
||||
int wifiaddrset(int argc, char *argv[])
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
char *ip = argv[1];
|
||||
char *gateway = argv[2];
|
||||
char *netmask = argv[3];
|
||||
|
||||
AdapterDeviceSetAddr(adapter, ip, gateway, netmask);
|
||||
AdapterDevicePing(adapter, "36.152.44.95");///< ping www.baidu.com
|
||||
AdapterDeviceNetstat(adapter);
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_PARAM_NUM(4)|SHELL_CMD_DISABLE_RETURN, wifiaddrset, wifiaddrset, addrset adapter wifi);
|
||||
|
||||
int wifiping(int argc, char *argv[])
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
printf("ping %s\n",argv[1]);
|
||||
AdapterDevicePing(adapter, argv[1]);
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_PARAM_NUM(3), wifiping, wifiping, wifiping adapter );
|
||||
|
||||
int wificonnect(int argc, char *argv[])
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
char *ip = argv[1];
|
||||
char *port = argv[2];
|
||||
enum NetRoleType net_role = CLIENT;
|
||||
enum IpType ip_type = IPV4;
|
||||
|
||||
if(0 == strncmp("tcp",argv[3],strlen("tcp"))) {
|
||||
adapter->socket.protocal = SOCKET_PROTOCOL_TCP;
|
||||
}
|
||||
|
||||
if(0 == strncmp("udp",argv[3],strlen("udp"))) {
|
||||
adapter->socket.protocal = SOCKET_PROTOCOL_UDP;
|
||||
}
|
||||
|
||||
AdapterDeviceConnect(adapter, net_role, ip, port, ip_type);
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_PARAM_NUM(4)|SHELL_CMD_DISABLE_RETURN, wificonnect, wificonnect, wificonnect adapter);
|
||||
int wifisend(int argc, char *argv[])
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
|
||||
const char *wifi_msg = argv[1];
|
||||
int len = strlen(wifi_msg);
|
||||
for(int i = 0;i < 10; ++i) {
|
||||
AdapterDeviceSend(adapter, wifi_msg, len);
|
||||
PrivTaskDelay(1000);
|
||||
}
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_PARAM_NUM(3)|SHELL_CMD_DISABLE_RETURN, wifisend, wifisend, wifisend adapter wifi information);
|
||||
int wifirecv(int argc, char *argv[])
|
||||
{
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_WIFI_NAME);
|
||||
|
||||
char wifi_recv_msg[128];
|
||||
while (1) {
|
||||
AdapterDeviceRecv(adapter, wifi_recv_msg, 128);
|
||||
PrivTaskDelay(1000);
|
||||
printf("wifi recv [%s]\n",wifi_recv_msg);
|
||||
}
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_PARAM_NUM(3)|SHELL_CMD_DISABLE_RETURN, wifirecv, wifirecv, wifirecv adapter wifi information);
|
||||
|
|
|
@ -0,0 +1,19 @@
|
|||
#ifndef ADAPTER_WIFI_H
|
||||
#define ADAPTER_WIFI_H
|
||||
|
||||
#define CONFIG_WIFI_RESET (0)
|
||||
#define CONFIG_WIFI_RESTORE (1)
|
||||
#define CONFIG_WIFI_BAUDRATE (2)
|
||||
|
||||
|
||||
#define SOCKET_PROTOCOL_TCP (6)
|
||||
#define SOCKET_PROTOCOL_UDP (17)
|
||||
|
||||
struct WifiParam
|
||||
{
|
||||
uint8_t wifi_ssid[128];
|
||||
uint8_t wifi_pwd[128];
|
||||
};
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,33 @@
|
|||
config ADAPTER_WIFI_ESP07S
|
||||
string "ESP07S WIFI adapter name"
|
||||
default "esp07s_wifi"
|
||||
|
||||
if ADD_XIZI_FETURES
|
||||
|
||||
config ADAPTER_ESP07S_DRIVER_EXTUART
|
||||
bool "Using extra uart to support wifi"
|
||||
default n
|
||||
|
||||
config ADAPTER_ESP07S_DRIVER
|
||||
string "ESP07S device uart driver path"
|
||||
default "/dev/uart2_dev2"
|
||||
depends on !ADAPTER_ESP07S_DRIVER_EXTUART
|
||||
|
||||
if ADAPTER_ESP07S_DRIVER_EXTUART
|
||||
config ADAPTER_ESP07S_DRIVER
|
||||
string "ESP07S device extra uart driver path"
|
||||
default "/dev/extuart_dev6"
|
||||
|
||||
config ADAPTER_ESP07S_DRIVER_EXT_PORT
|
||||
int "if ESP07S device using extuart, choose port"
|
||||
default "6"
|
||||
endif
|
||||
endif
|
||||
|
||||
if ADD_NUTTX_FETURES
|
||||
|
||||
endif
|
||||
|
||||
if ADD_RTTHREAD_FETURES
|
||||
|
||||
endif
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := esp07s_wifi.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,587 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS 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 esp07_wifi.c
|
||||
* @brief Implement the connection wifi adapter function, using ESP07S device
|
||||
* @version 1.1
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2022.04.08
|
||||
*/
|
||||
|
||||
#include <adapter.h>
|
||||
#include <at_agent.h>
|
||||
#include "../adapter_wifi.h"
|
||||
#include <stdlib.h>
|
||||
|
||||
#define LEN_PARA_BUF 128
|
||||
|
||||
static int Esp07sWifiSetDown(struct Adapter *adapter_at);
|
||||
|
||||
/**
|
||||
* @description: check AT startup status
|
||||
* @param at_agent - wifi device agent pointer
|
||||
* @return success: EOK
|
||||
*/
|
||||
static int Esp07sWifiTestAtCmd(ATAgentType at_agent)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
ret = AtCmdConfigAndCheck(at_agent, "ATE0\r\n", "OK"); ///< close echo function
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[ATE0] config failed!\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
}
|
||||
|
||||
PrivTaskDelay(2000);
|
||||
ret = AtCmdConfigAndCheck(at_agent, "AT\r\n", "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[AT] config failed!\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int Esp07sUartOpen(struct Adapter *adapter)
|
||||
{
|
||||
if (NULL == adapter) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Open device in read-write mode */
|
||||
adapter->fd = PrivOpen(ADAPTER_ESP07S_DRIVER, O_RDWR);
|
||||
if (adapter->fd < 0) {
|
||||
printf("Esp07sWifiOpen get serial %s fd error\n", ADAPTER_ESP07S_DRIVER);
|
||||
return -1;
|
||||
}
|
||||
/* set serial config, serial_baud_rate = 115200 */
|
||||
|
||||
struct SerialDataCfg cfg;
|
||||
memset(&cfg, 0 ,sizeof(struct SerialDataCfg));
|
||||
|
||||
cfg.serial_baud_rate = BAUD_RATE_115200;
|
||||
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;
|
||||
|
||||
#ifdef ADAPTER_ESP07S_DRIVER_EXT_PORT
|
||||
cfg.ext_uart_no = ADAPTER_ESP07S_DRIVER_EXT_PORT;
|
||||
cfg.port_configure = PORT_CFG_INIT;
|
||||
#endif
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = &cfg;
|
||||
|
||||
PrivIoctl(adapter->fd, OPE_INT, &ioctl_cfg);
|
||||
PrivTaskDelay(1000);
|
||||
|
||||
printf("esp07s uart config ready\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: Open wifi
|
||||
* @param adapter - wifi device pointer
|
||||
* @return success: EOK, failure: ENOMEMORY
|
||||
*/
|
||||
static int Esp07sWifiOpen(struct Adapter *adapter)
|
||||
{
|
||||
/*step1: open esp07s serial port*/
|
||||
Esp07sUartOpen(adapter);
|
||||
|
||||
/*step2: init AT agent*/
|
||||
if (!adapter->agent) {
|
||||
char *agent_name = "wifi_uart_client";
|
||||
if (EOK != InitATAgent(agent_name, adapter->fd, 512)) {
|
||||
printf("at agent init failed !\n");
|
||||
return -1;
|
||||
}
|
||||
ATAgentType at_agent = GetATAgent(agent_name);
|
||||
|
||||
adapter->agent = at_agent;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent,'O','K');
|
||||
|
||||
ADAPTER_DEBUG("Esp07sWifi open done\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: Close wifi
|
||||
* @param adapter - wifi device pointer
|
||||
* @return success: EOK
|
||||
*/
|
||||
static int Esp07sWifiClose(struct Adapter *adapter)
|
||||
{
|
||||
Esp07sWifiSetDown(adapter);
|
||||
PrivClose(adapter->fd);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: send data to adapter
|
||||
* @param adapter - wifi device pointer
|
||||
* @param data - data buffer
|
||||
* @param data - data length
|
||||
* @return success: EOK
|
||||
*/
|
||||
static int Esp07sWifiSend(struct Adapter *adapter, const void *data, size_t len)
|
||||
{
|
||||
x_err_t result = EOK;
|
||||
if (adapter->agent) {
|
||||
EntmSend(adapter->agent, (const char *)data, len);
|
||||
}else {
|
||||
printf("Esp07sWifiSend can not find agent!\n");
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: receive data from adapter
|
||||
* @param adapter - wifi device pointer
|
||||
* @param data - data buffer
|
||||
* @param data - data length
|
||||
* @return success: EOK
|
||||
*/
|
||||
static int Esp07sWifiReceive(struct Adapter *adapter, void *rev_buffer, size_t buffer_len)
|
||||
{
|
||||
x_err_t result = EOK;
|
||||
printf("esp07s receive waiting ... \n");
|
||||
|
||||
if (adapter->agent) {
|
||||
return EntmRecv(adapter->agent, (char *)rev_buffer, buffer_len, 40);
|
||||
} else {
|
||||
printf("Esp07sWifiReceive can not find agent!\n");
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: connnect wifi to internet
|
||||
* @param adapter - wifi device pointer
|
||||
* @return success: EOK
|
||||
*/
|
||||
static int Esp07sWifiSetUp(struct Adapter *adapter)
|
||||
{
|
||||
char cmd[LEN_PARA_BUF];
|
||||
int ret = 0;
|
||||
char *result = NULL;
|
||||
|
||||
struct WifiParam *param = (struct WifiParam *)adapter->adapter_param;
|
||||
struct ATAgent *agent = adapter->agent;
|
||||
|
||||
PrivTaskDelay(2000);
|
||||
|
||||
if(Esp07sWifiTestAtCmd(agent) < 0)
|
||||
{
|
||||
printf("wifi at cmd startup failed.\n");
|
||||
return -1;
|
||||
}
|
||||
PrivTaskDelay(2000);
|
||||
/* config as softAP+station mode */
|
||||
ret = AtCmdConfigAndCheck(agent, "AT+CWMODE=3\r\n", "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[AT+CWMODE=3] config failed!\n",__func__,__LINE__);
|
||||
return -1;
|
||||
}
|
||||
PrivTaskDelay(2000);
|
||||
/* connect the router */
|
||||
memset(cmd,0,sizeof(cmd));
|
||||
strncpy(cmd,"AT+CWJAP=",strlen("AT+CWJAP="));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,param->wifi_ssid,strlen(param->wifi_ssid));
|
||||
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,",",1);
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,param->wifi_pwd,strlen(param->wifi_pwd));
|
||||
|
||||
strncat(cmd,"\"",1);
|
||||
strcat(cmd,"\r\n");
|
||||
|
||||
ret = AtCmdConfigAndCheck(agent, cmd, "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] connect[%s] failed!\n",__func__,__LINE__,cmd,param->wifi_ssid);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* check the wifi ip address */
|
||||
ATReplyType reply = CreateATReply(256);
|
||||
if (NULL == reply) {
|
||||
printf("%s %d at_create_resp failed!\n",__func__,__LINE__);
|
||||
return -1;
|
||||
}
|
||||
ret = ATOrderSend(agent, REPLY_TIME_OUT, reply, "AT+CIFSR\r\n");
|
||||
if(ret < 0){
|
||||
printf("%s %d ATOrderSend AT+CIFSR failed.\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
result = GetReplyText(reply);
|
||||
if (!result) {
|
||||
printf("%s %n get reply failed.\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
printf("[%s]\n", result);
|
||||
|
||||
__exit:
|
||||
DeleteATReply(reply);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: disconnnect wifi from internet
|
||||
* @param adapter - wifi device pointer
|
||||
* @return success: EOK
|
||||
*/
|
||||
static int Esp07sWifiSetDown(struct Adapter *adapter)
|
||||
{
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "AT+RESTORE\r\n");
|
||||
PrivTaskDelay(2000);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: set wifi ip/gateway/netmask address(in sta mode)
|
||||
* @param adapter - wifi device pointer
|
||||
* @param ip - ip address
|
||||
* @param gateway - gateway address
|
||||
* @param netmask - netmask address
|
||||
* @return success: EOK, failure: ENOMEMORY
|
||||
*/
|
||||
static int Esp07sWifiSetAddr(struct Adapter *adapter, const char *ip, const char *gateway, const char *netmask)
|
||||
{
|
||||
int ret = 0;
|
||||
char cmd[LEN_PARA_BUF];
|
||||
|
||||
/* e.g. AT+CIPSTA_DEF="192.168.6.100","192.168.6.1","255.255.255.0" */
|
||||
memset(cmd,0,sizeof(cmd));
|
||||
strncpy(cmd,"AT+CIPAP_DEF=",strlen(" AT+CIPAP_DEF="));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,ip,strlen(ip));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,",",1);
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,gateway,strlen(gateway));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,",",1);
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,netmask,strlen(netmask));
|
||||
strncat(cmd,"\"",1);
|
||||
strcat(cmd,"\r\n");
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd, "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config ip failed!\n",__func__,__LINE__,cmd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: wifi ping function
|
||||
* @param adapter - wifi device pointer
|
||||
* @param destination - domain name or ip address
|
||||
* @return success: EOK, failure: ENOMEMORY
|
||||
*/
|
||||
static int Esp07sWifiPing(struct Adapter *adapter, const char *destination)
|
||||
{
|
||||
char cmd[LEN_PARA_BUF];
|
||||
int ret = 0;
|
||||
|
||||
memset(cmd,0,sizeof(cmd));
|
||||
strncpy(cmd,"AT+PING=",strlen("AT+PING="));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,destination,strlen(destination));
|
||||
strncat(cmd,"\"",1);
|
||||
strcat(cmd,"\r\n");
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd, "OK"); ///< config as softAP+station mode
|
||||
if(ret < 0) {
|
||||
printf("%s %d ping [%s] failed!\n",__func__,__LINE__,destination);
|
||||
return -1;
|
||||
}
|
||||
|
||||
printf("ping [%s] ok\n", destination);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: display wifi network configuration
|
||||
* @param adapter - wifi device pointer
|
||||
* @return success: EOK, failure: ENOMEMORY
|
||||
*/
|
||||
static int Esp07sWifiNetstat(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
char *result = NULL;
|
||||
|
||||
/* check the wifi ip address */
|
||||
ATReplyType reply = CreateATReply(256);
|
||||
if (NULL == reply) {
|
||||
printf("%s %d at_create_resp failed!\n",__func__,__LINE__);
|
||||
return -1;
|
||||
}
|
||||
ret = ATOrderSend(adapter->agent, REPLY_TIME_OUT, reply, "AT+CIFSR\r\n");
|
||||
if(ret < 0){
|
||||
printf("%s %d ATOrderSend AT+CIFSR failed.\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
result = GetReplyText(reply);
|
||||
if (!result) {
|
||||
printf("%s %n get reply failed.\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
printf("[%s]\n", result);
|
||||
|
||||
__exit:
|
||||
DeleteATReply(reply);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: wifi connect function
|
||||
* @param adapter - wifi device pointer
|
||||
* @param net_role - net role, CLIENT or SERVER
|
||||
* @param ip - ip address
|
||||
* @param port - port num
|
||||
* @param ip_type - ip type, IPV4 or IPV6
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int Esp07sWifiConnect(struct Adapter *adapter, enum NetRoleType net_role, const char *ip, const char *port, enum IpType ip_type)
|
||||
{
|
||||
int ret = EOK;
|
||||
char cmd[LEN_PARA_BUF];
|
||||
struct ATAgent *agent = adapter->agent;
|
||||
|
||||
memset(cmd,0,sizeof(cmd));
|
||||
if(adapter->socket.protocal == SOCKET_PROTOCOL_TCP && net_role == CLIENT) //esp07s as tcp client to connect server
|
||||
{
|
||||
//e.g. AT+CIPSTART="TCP","192.168.3.116",8080 protocol, server IP and port
|
||||
strncpy(cmd,"AT+CIPSTART=",strlen("AT+CIPSTART="));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,"TCP",strlen("TCP"));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd, ",", 1);
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd, ip, strlen(ip));
|
||||
strncat(cmd, "\"", 1);
|
||||
strncat(cmd, ",", 1);
|
||||
strncat(cmd, port, strlen(port));
|
||||
strcat(cmd,"\r\n");
|
||||
|
||||
ret = AtCmdConfigAndCheck(agent, cmd, "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d tcp connect [%s] failed!\n",__func__,__LINE__,ip);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
else if(adapter->socket.protocal == SOCKET_PROTOCOL_UDP)
|
||||
{
|
||||
//e.g. AT+CIPSTART="UDP","192.168.3.116",8080,2233,0 UDP protocol, server IP, port,local port,udp mode
|
||||
strncpy(cmd,"AT+CIPSTART=",strlen("AT+CIPSTART="));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd,"UDP",strlen("UDP"));
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd, ",", 1);
|
||||
strncat(cmd,"\"",1);
|
||||
strncat(cmd, ip, strlen(ip));
|
||||
strncat(cmd, "\"", 1);
|
||||
strncat(cmd, ",", 1);
|
||||
strncat(cmd, port, strlen(port));
|
||||
strncat(cmd, ",", 1);
|
||||
strncat(cmd, "2233", strlen("2233")); ///< local port
|
||||
strncat(cmd, ",", 1);
|
||||
strncat(cmd, "0", 1); ///< udp transparent transmission mode must be 0
|
||||
strcat(cmd,"\r\n");
|
||||
|
||||
ret = AtCmdConfigAndCheck(agent, cmd, "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d udp connect [%s] failed!\n",__func__,__LINE__,ip);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
ret = AtCmdConfigAndCheck(agent, "AT+CIPMODE=1\r\n", "OK"); ///< config as transparent transmission
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config as transparent transmission failed!\n",__func__,__LINE__,cmd);
|
||||
return -1;
|
||||
}
|
||||
ATOrderSend(agent, REPLY_TIME_OUT, NULL, "AT+CIPSEND\r\n");
|
||||
|
||||
printf("[%s] connection config as transparent transmission\n",adapter->socket.protocal == SOCKET_PROTOCOL_UDP ? "udp" : "tcp");
|
||||
adapter->net_role = net_role;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @description: wifi disconnect function
|
||||
* @param adapter - wifi device pointer
|
||||
* @return success: 0, failure: -1
|
||||
*/
|
||||
static int Esp07sWifiDisconnect(struct Adapter *adapter)
|
||||
{
|
||||
int ret = EOK;
|
||||
char cmd[LEN_PARA_BUF];
|
||||
struct ATAgent *agent = adapter->agent;
|
||||
memset(cmd,0,sizeof(cmd));
|
||||
|
||||
/* step1: stop transparent transmission mode */
|
||||
ATOrderSend(agent, REPLY_TIME_OUT, NULL, "+++\r\n");
|
||||
|
||||
/* step2: exit transparent transmission mode */
|
||||
ret = AtCmdConfigAndCheck(agent, "AT+CIPMODE=0\r\n", "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[AT+CIPMODE=0] exit failed!\n",__func__,__LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* step3: disconnect */
|
||||
ret = AtCmdConfigAndCheck(agent, "AT+CIPCLOSE\r\n", "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd [AT+CIPCLOSE] disconnect failed!\n",__func__,__LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int Esp07sWifiIoctl(struct Adapter *adapter, int cmd, void *args)
|
||||
{
|
||||
int32_t ret = 0;
|
||||
char baud_str[LEN_PARA_BUF];
|
||||
struct SerialDataCfg cfg;
|
||||
char at_cmd[LEN_PARA_BUF];
|
||||
uint32_t baud_rate = 0 ;
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case CONFIG_WIFI_RESET: /* reset wifi */
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "AT+RST\r\n");
|
||||
break;
|
||||
case CONFIG_WIFI_RESTORE: /* resore wifi */
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "AT+RESTORE\r\n");
|
||||
break;
|
||||
case CONFIG_WIFI_BAUDRATE:
|
||||
/* step1: config mcu uart*/
|
||||
baud_rate = *((uint32_t *)args);
|
||||
|
||||
memset(at_cmd, 0, sizeof(at_cmd));
|
||||
memset(baud_str, 0, sizeof(baud_str));
|
||||
memset(&cfg, 0 ,sizeof(struct SerialDataCfg));
|
||||
|
||||
cfg.serial_baud_rate = baud_rate;
|
||||
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;
|
||||
|
||||
#ifdef ADAPTER_ESP07S_DRIVER_EXT_PORT
|
||||
cfg.ext_uart_no = ADAPTER_ESP07S_DRIVER_EXT_PORT;
|
||||
cfg.port_configure = PORT_CFG_INIT;
|
||||
#endif
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = &cfg;
|
||||
|
||||
PrivIoctl(adapter->fd, OPE_INT, &ioctl_cfg);
|
||||
|
||||
/* step2: config wifi uart*/
|
||||
itoa(baud_rate, baud_str, 10);
|
||||
|
||||
strncpy(at_cmd, "AT+UART_DEF=", strlen("AT+UART_DEF="));
|
||||
strncat(at_cmd, baud_str, strlen(baud_str));
|
||||
strncat(at_cmd, ",", 1);
|
||||
strncat(at_cmd, "8", 1);
|
||||
strncat(at_cmd, ",", 1);
|
||||
strncat(at_cmd, "1", 1);
|
||||
strncat(at_cmd, ",", 1);
|
||||
strncat(at_cmd, "0", 1);
|
||||
strncat(at_cmd, ",", 1);
|
||||
strncat(at_cmd, "3", 1);
|
||||
strcat(at_cmd,"\r\n");
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, at_cmd, "OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd [%s] config uart failed!\n",__func__,__LINE__,at_cmd);
|
||||
ret = -1;
|
||||
}
|
||||
|
||||
break;
|
||||
default:
|
||||
ret = -1;
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static const struct IpProtocolDone esp07s_wifi_done =
|
||||
{
|
||||
.open = Esp07sWifiOpen,
|
||||
.close = Esp07sWifiClose,
|
||||
.ioctl = Esp07sWifiIoctl,
|
||||
.setup = Esp07sWifiSetUp,
|
||||
.setdown = Esp07sWifiSetDown,
|
||||
.setaddr = Esp07sWifiSetAddr,
|
||||
.setdns = NULL,
|
||||
.setdhcp = NULL,
|
||||
.ping = Esp07sWifiPing,
|
||||
.netstat = Esp07sWifiNetstat,
|
||||
.connect = Esp07sWifiConnect,
|
||||
.send = Esp07sWifiSend,
|
||||
.recv = Esp07sWifiReceive,
|
||||
.disconnect = Esp07sWifiDisconnect,
|
||||
};
|
||||
|
||||
/**
|
||||
* @description: Register wifi device esp07s
|
||||
* @return success: EOK, failure: ERROR
|
||||
*/
|
||||
AdapterProductInfoType Esp07sWifiAttach(struct Adapter *adapter)
|
||||
{
|
||||
struct AdapterProductInfo *product_info = PrivMalloc(sizeof(struct AdapterProductInfo));
|
||||
if (!product_info)
|
||||
{
|
||||
printf("Esp07sWifiAttach Attach malloc product_info error\n");
|
||||
PrivFree(product_info);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
strncpy(product_info->model_name, ADAPTER_WIFI_ESP07S, strlen(ADAPTER_WIFI_ESP07S));
|
||||
|
||||
product_info->model_done = (void *)&esp07s_wifi_done;
|
||||
|
||||
return product_info;
|
||||
}
|
|
@ -26,8 +26,6 @@
|
|||
extern AdapterProductInfoType E18Attach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#define ADAPTER_ZIGBEE_NAME "zigbee"
|
||||
|
||||
static int AdapterZigbeeRegister(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
|
|
|
@ -18,6 +18,13 @@ endchoice
|
|||
|
||||
|
||||
if ADD_XIZI_FETURES
|
||||
config ADAPTER_E18_MODEPIN
|
||||
int "E18 MODE pin number"
|
||||
default "61"
|
||||
|
||||
config ADAPTER_BC28_PIN_DRIVER
|
||||
string "BC28 device pin driver path"
|
||||
default "/dev/pin_dev"
|
||||
|
||||
config ADAPTER_E18_DRIVER_EXTUART
|
||||
bool "Using extra uart to support zigbee"
|
||||
|
|
|
@ -37,6 +37,33 @@ char *cmd_role_as_e = "AT+DEV=E"; /*set device type for end device*/
|
|||
char *cmd_role_as_r = "AT+DEV=R"; /*set device type for router*/
|
||||
char *cmd_set_ch = "AT+CH=11"; /*set channel as 11*/
|
||||
|
||||
#define E18_AS_HEX_MODE 0
|
||||
#define E18_AS_AT_MODE 1
|
||||
|
||||
static int E18HardwareModeGet()
|
||||
{
|
||||
int ret = 0;
|
||||
int pin_fd;
|
||||
|
||||
pin_fd = PrivOpen(ADAPTER_BC28_PIN_DRIVER, O_RDWR);
|
||||
|
||||
struct PinStat pin_stat;
|
||||
pin_stat.pin = ADAPTER_E18_MODEPIN;
|
||||
|
||||
ret = PrivRead(pin_fd, &pin_stat, 1);
|
||||
|
||||
PrivTaskDelay(200);
|
||||
|
||||
PrivClose(pin_fd);
|
||||
|
||||
if(pin_stat.val == GPIO_HIGH) {
|
||||
printf(" E18 as AT mode\n");
|
||||
return E18_AS_AT_MODE;
|
||||
} else {
|
||||
printf(" E18 as HEX mode\n");
|
||||
return E18_AS_HEX_MODE;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef ADD_NUTTX_FETURES
|
||||
static int E18UartOpen(struct Adapter *adapter)
|
||||
|
@ -96,16 +123,23 @@ static int E18UartOpen(struct Adapter *adapter)
|
|||
static int E18NetworkModeConfig(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
int mode = -1;
|
||||
|
||||
if (NULL == adapter) {
|
||||
return -1;
|
||||
}
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_hex2at, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_hex2at);
|
||||
ret = -1;
|
||||
goto out;
|
||||
mode = E18HardwareModeGet();
|
||||
if(E18_AS_HEX_MODE == mode)
|
||||
{
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_hex2at, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_hex2at);
|
||||
ret = -1;
|
||||
goto out;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
switch (adapter->info->work_mode)
|
||||
{
|
||||
case TT_MODE1:
|
||||
|
@ -141,27 +175,36 @@ static int E18NetworkModeConfig(struct Adapter *adapter)
|
|||
}
|
||||
|
||||
out:
|
||||
AtCmdConfigAndCheck(adapter->agent, cmd_exit, "+OK");
|
||||
if(E18_AS_HEX_MODE == mode){
|
||||
AtCmdConfigAndCheck(adapter->agent, cmd_exit, "+OK");
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int E18NetRoleConfig(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
int mode = -1;
|
||||
|
||||
|
||||
if (NULL == adapter) {
|
||||
printf("%s %d adapter is null!\n",__func__,__LINE__);
|
||||
ret = -1;
|
||||
goto out;
|
||||
}
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_hex2at, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_hex2at);
|
||||
ret = -1;
|
||||
goto out;
|
||||
mode = E18HardwareModeGet();
|
||||
if(E18_AS_HEX_MODE == mode)
|
||||
{
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_hex2at, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_hex2at);
|
||||
ret = -1;
|
||||
goto out;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
switch (adapter->net_role)
|
||||
{
|
||||
case COORDINATOR:
|
||||
|
@ -197,7 +240,10 @@ static int E18NetRoleConfig(struct Adapter *adapter)
|
|||
}
|
||||
|
||||
out:
|
||||
AtCmdConfigAndCheck(adapter->agent, cmd_exit, "+OK");
|
||||
if(E18_AS_HEX_MODE == mode) {
|
||||
AtCmdConfigAndCheck(adapter->agent, cmd_exit, "+OK");
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -205,6 +251,7 @@ static int E18Open(struct Adapter *adapter)
|
|||
{
|
||||
int ret = 0;
|
||||
int try_times = 5;
|
||||
int count = 0;
|
||||
|
||||
if (NULL == adapter) {
|
||||
return -1;
|
||||
|
@ -231,9 +278,12 @@ static int E18Open(struct Adapter *adapter)
|
|||
try_again:
|
||||
while(try_times--){
|
||||
ret = E18NetRoleConfig(adapter);
|
||||
count++;
|
||||
if(ret < 0){
|
||||
printf("E18NetRoleConfig failed [%d] times.\n",try_times);
|
||||
goto try_again;
|
||||
printf("E18NetRoleConfig failed [%d] times.\n",count);
|
||||
continue;
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -274,12 +324,17 @@ static int E18Ioctl(struct Adapter *adapter, int cmd, void *args)
|
|||
static int E18Join(struct Adapter *adapter, unsigned char *priv_net_group)
|
||||
{
|
||||
int ret = 0;
|
||||
int mode = -1;
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_hex2at, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_hex2at);
|
||||
ret = -1;
|
||||
goto out;
|
||||
mode = E18HardwareModeGet();
|
||||
if(E18_AS_HEX_MODE == mode)
|
||||
{
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_hex2at, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_hex2at);
|
||||
ret = -1;
|
||||
goto out;
|
||||
}
|
||||
}
|
||||
|
||||
switch (adapter->net_role)
|
||||
|
@ -327,9 +382,13 @@ static int E18Join(struct Adapter *adapter, unsigned char *priv_net_group)
|
|||
|
||||
// }
|
||||
if(!ret){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_exit, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_exit);
|
||||
if(E18_AS_HEX_MODE == mode) {
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, cmd_exit, "+OK");
|
||||
if(ret < 0) {
|
||||
printf("%s %d cmd[%s] config failed!\n",__func__,__LINE__,cmd_exit);
|
||||
ret = -1;
|
||||
}
|
||||
} else {
|
||||
ret = -1;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -55,7 +55,15 @@ int PrivSemaphoreDelete(sem_t *sem)
|
|||
|
||||
int PrivSemaphoreObtainWait(sem_t *sem, const struct timespec *abstime)
|
||||
{
|
||||
return sem_timedwait(sem, abstime);
|
||||
struct timespec timeout;
|
||||
clock_gettime(CLOCK_REALTIME, &timeout);
|
||||
timeout.tv_sec += abstime->tv_sec;
|
||||
return sem_timedwait(sem, &timeout);
|
||||
}
|
||||
|
||||
int PrivSemaphoreObtainWaitForever(sem_t *sem)
|
||||
{
|
||||
return sem_wait(sem);
|
||||
}
|
||||
|
||||
int PrivSemaphoreObtainNoWait(sem_t *sem)
|
||||
|
|
|
@ -180,6 +180,7 @@ int PrivMutexAbandon(pthread_mutex_t *p_mutex);
|
|||
int PrivSemaphoreCreate(sem_t *sem, int pshared, unsigned int value);
|
||||
int PrivSemaphoreDelete(sem_t *sem);
|
||||
int PrivSemaphoreObtainWait(sem_t *sem, const struct timespec *abstime);
|
||||
int PrivSemaphoreObtainWaitForever(sem_t *sem);
|
||||
int PrivSemaphoreObtainNoWait(sem_t *sem);
|
||||
int PrivSemaphoreAbandon(sem_t *sem);
|
||||
int32_t PrivSemaphoreSetValue(int32_t sem, uint16_t val);
|
||||
|
|
|
@ -0,0 +1,66 @@
|
|||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
CONFIG_ADD_NUTTX_FETURES=y
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD="xidatong"
|
||||
CONFIG_ARCH_BOARD_XIDATONG=y
|
||||
CONFIG_ARCH_CHIP="imxrt"
|
||||
CONFIG_ARCH_CHIP_IMXRT=y
|
||||
CONFIG_ARCH_CHIP_MIMXRT1052CVL5B=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=10240
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=104926
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_EXAMPLES_HELLO=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=2048
|
||||
CONFIG_IMXRT_LPUART1=y
|
||||
CONFIG_INTELHEX_BINARY=y
|
||||
CONFIG_LPUART1_SERIAL_CONSOLE=y
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_LINELEN=64
|
||||
CONFIG_NSH_READLINE=y
|
||||
CONFIG_RAM_SIZE=524288
|
||||
CONFIG_RAM_START=0x20200000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_START_DAY=14
|
||||
CONFIG_START_MONTH=3
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_DEV_GPIO=y
|
||||
CONFIG_IMXRT_LPUART8=y
|
||||
CONFIG_LPUART8_RXBUFSIZE=128
|
||||
CONFIG_LPUART8_TXBUFSIZE=128
|
||||
CONFIG_LPUART8_BAUD=115200
|
||||
CONFIG_LPUART8_BITS=8
|
||||
CONFIG_LPUART8_PARITY=0
|
||||
CONFIG_LPUART8_2STOP=0
|
||||
CONFIG_LPUART8_NOIFLOWCONTROL=y
|
||||
CONFIG_SUPPORT_CONNECTION_FRAMEWORK=y
|
||||
CONFIG_CONNECTION_FRAMEWORK_DEBUG=y
|
||||
CONFIG_CONNECTION_ADAPTER_4G=y
|
||||
CONFIG_ADAPTER_EC200T=y
|
||||
CONFIG_ADAPTER_4G_EC200T="ec200t"
|
||||
CONFIG_ADAPTER_EC200T_DRIVER="/dev/ttyS8"
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_CMD_HISTORY_LEN=100
|
||||
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
|
@ -45,4 +45,11 @@ CONFIG_START_MONTH=6
|
|||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYS_RESERVED=9
|
||||
CONFIG_DEV_GPIO=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_CMD_HISTORY_LEN=100
|
||||
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -44,4 +44,11 @@ CONFIG_START_DAY=14
|
|||
CONFIG_START_MONTH=3
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_DEV_GPIO=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_CMD_HISTORY_LEN=100
|
||||
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -22,7 +22,8 @@ CONFIG_ARMV7M_USEBASEPRI=y
|
|||
CONFIG_BOARD_LOOPSPERMSEC=104926
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_ETH0_PHY_KSZ8081=y
|
||||
CONFIG_ETH0_PHY_LAN8720=y
|
||||
CONFIG_IMXRT_ENET_PHYINIT=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=2048
|
||||
CONFIG_IMXRT_ENET=y
|
||||
|
@ -66,4 +67,11 @@ CONFIG_SYSTEM_NSH=y
|
|||
CONFIG_SYSTEM_PING6=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_DEV_GPIO=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_CMD_HISTORY_LEN=100
|
||||
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -42,4 +42,11 @@ CONFIG_START_DAY=14
|
|||
CONFIG_START_MONTH=3
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_DEV_GPIO=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_CMD_HISTORY_LEN=100
|
||||
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -64,4 +64,11 @@ CONFIG_SYSTEM_CLE_CMD_HISTORY=y
|
|||
CONFIG_SYSTEM_COLOR_CLE=y
|
||||
CONFIG_FS_AUTOMOUNTER=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_CMD_HISTORY_LEN=100
|
||||
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -62,4 +62,11 @@ CONFIG_USBHOST=y
|
|||
CONFIG_USBHOST_MSC=y
|
||||
CONFIG_USBHOST_MSC_NOTIFIER=y
|
||||
CONFIG_DEV_GPIO=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_CMD_HISTORY_LEN=100
|
||||
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -0,0 +1,4 @@
|
|||
#start up Adapter4GTest
|
||||
echo "start 4g Adapter!"
|
||||
|
||||
Adapter4GTest
|
|
@ -0,0 +1,3 @@
|
|||
#start up hello
|
||||
|
||||
hello
|
|
@ -0,0 +1,3 @@
|
|||
#default start up nsh shell
|
||||
|
||||
nsh
|
|
@ -0,0 +1,89 @@
|
|||
unsigned char romfs_img[] = {
|
||||
0x2d, 0x72, 0x6f, 0x6d, 0x31, 0x66, 0x73, 0x2d, 0x00, 0x00, 0x01, 0xb0,
|
||||
0xf9, 0xaf, 0xcc, 0x42, 0x78, 0x69, 0x64, 0x61, 0x74, 0x6f, 0x6e, 0x67,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x49,
|
||||
0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0xd1, 0xff, 0xff, 0x97,
|
||||
0x2e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x20,
|
||||
0x00, 0x00, 0x00, 0x00, 0xd1, 0xd1, 0xff, 0x80, 0x2e, 0x2e, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x09, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00,
|
||||
0x68, 0x2d, 0x96, 0x03, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc2,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0x28, 0x9a, 0x92, 0xbb,
|
||||
0x68, 0x65, 0x6c, 0x6c, 0x6f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x23, 0x73, 0x74, 0x61, 0x72, 0x74, 0x20, 0x75,
|
||||
0x70, 0x20, 0x68, 0x65, 0x6c, 0x6c, 0x6f, 0x0a, 0x0a, 0x68, 0x65, 0x6c,
|
||||
0x6c, 0x6f, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x01, 0x22, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40,
|
||||
0x8e, 0xe1, 0xc5, 0x87, 0x41, 0x64, 0x61, 0x70, 0x74, 0x65, 0x72, 0x34,
|
||||
0x47, 0x54, 0x65, 0x73, 0x74, 0x00, 0x00, 0x00, 0x23, 0x73, 0x74, 0x61,
|
||||
0x72, 0x74, 0x20, 0x75, 0x70, 0x20, 0x41, 0x64, 0x61, 0x70, 0x74, 0x65,
|
||||
0x72, 0x34, 0x47, 0x54, 0x65, 0x73, 0x74, 0x0a, 0x65, 0x63, 0x68, 0x6f,
|
||||
0x20, 0x22, 0x73, 0x74, 0x61, 0x72, 0x74, 0x20, 0x34, 0x67, 0x20, 0x41,
|
||||
0x64, 0x61, 0x70, 0x74, 0x65, 0x72, 0x21, 0x22, 0x0a, 0x0a, 0x41, 0x64,
|
||||
0x61, 0x70, 0x74, 0x65, 0x72, 0x34, 0x47, 0x54, 0x65, 0x73, 0x74, 0x0a,
|
||||
0x00, 0x00, 0x01, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00,
|
||||
0xd1, 0xff, 0xfe, 0x60, 0x2e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x92,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x21, 0x8d, 0x9c, 0xab, 0x4d,
|
||||
0x72, 0x63, 0x53, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x23, 0x64, 0x65, 0x66, 0x61, 0x75, 0x6c, 0x74,
|
||||
0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x20, 0x75, 0x70, 0x20, 0x6e, 0x73,
|
||||
0x68, 0x20, 0x73, 0x68, 0x65, 0x6c, 0x6c, 0x0a, 0x0a, 0x6e, 0x73, 0x68,
|
||||
0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20,
|
||||
0x00, 0x00, 0x00, 0x00, 0xd1, 0xd1, 0xff, 0xe0, 0x2e, 0x2e, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00
|
||||
};
|
||||
unsigned int romfs_img_len = 1024;
|
|
@ -655,6 +655,10 @@ config NSH_DISABLE_ADAPTER_LORATEST
|
|||
bool "Disable sx1278 AdapterLoraTest."
|
||||
default n
|
||||
|
||||
config NSH_DISABLE_ADAPTER_4GTEST
|
||||
bool "Disable ec200t Adapter4GTest."
|
||||
default n
|
||||
|
||||
config NSH_DISABLE_K210_FFT
|
||||
bool "Disable the K210 fft device."
|
||||
default n
|
||||
|
|
|
@ -1486,6 +1486,10 @@ int nsh_foreach_var(FAR struct nsh_vtbl_s *vtbl, nsh_foreach_var_t cb,
|
|||
int cmd_AdapterLoraTest(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_ADAPTER_4G_EC200T) && !defined(CONFIG_NSH_DISABLE_ADAPTER_4GTEST)
|
||||
int cmd_Adapter4GTest(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_K210_FFT_TEST) && !defined(CONFIG_NSH_DISABLE_K210_FFT)
|
||||
int cmd_fft(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
|
||||
#endif
|
||||
|
|
|
@ -283,6 +283,17 @@ int cmd_AdapterLoraTest(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_ADAPTER_4G_EC200T) && !defined(CONFIG_NSH_DISABLE_ADAPTER_4GTEST)
|
||||
extern int Adapter4GTest(void);
|
||||
int cmd_Adapter4GTest(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
|
||||
{
|
||||
nsh_output(vtbl, "Hello, world!\n");
|
||||
FrameworkInit();
|
||||
Adapter4GTest();
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_K210_FFT_TEST) && !defined(CONFIG_NSH_DISABLE_K210_FFT)
|
||||
extern void nuttx_k210_fft_test(void);
|
||||
int cmd_fft(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
|
||||
|
|
|
@ -658,6 +658,10 @@ static const struct cmdmap_s g_cmdmap[] =
|
|||
{ "AdapterLoraTest", cmd_AdapterLoraTest, 1, 1, "[Lora sx128 test.]" },
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_ADAPTER_4G_EC200T) && !defined(CONFIG_NSH_DISABLE_ADAPTER_4GTEST)
|
||||
{ "Adapter4GTest", cmd_Adapter4GTest, 1, 1, "[4G ec200t test.]" },
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_K210_FFT_TEST) && !defined(CONFIG_NSH_DISABLE_K210_FFT)
|
||||
{ "fft", cmd_fft, 1, 1, "[K210 fft function.]" },
|
||||
#endif
|
||||
|
|
2654
Ubiquitous/Nuttx_Fusion_XiUOS/app_match_nuttx/nuttx/arch/arm/src/imxrt/imxrt_enet.c
Executable file
2654
Ubiquitous/Nuttx_Fusion_XiUOS/app_match_nuttx/nuttx/arch/arm/src/imxrt/imxrt_enet.c
Executable file
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,380 @@
|
|||
#
|
||||
# Automatically generated file; DO NOT EDIT.
|
||||
# RT-Thread Configuration
|
||||
#
|
||||
CONFIG_ROOT_DIR="../../../.."
|
||||
CONFIG_BSP_DIR="."
|
||||
CONFIG_RT_Thread_DIR="../.."
|
||||
CONFIG_RTT_DIR="../../rt-thread"
|
||||
|
||||
#
|
||||
# RT-Thread Kernel
|
||||
#
|
||||
CONFIG_RT_NAME_MAX=8
|
||||
# CONFIG_RT_USING_BIG_ENDIAN is not set
|
||||
# CONFIG_RT_USING_ARCH_DATA_TYPE is not set
|
||||
# CONFIG_RT_USING_SMP is not set
|
||||
CONFIG_RT_ALIGN_SIZE=4
|
||||
# CONFIG_RT_THREAD_PRIORITY_8 is not set
|
||||
CONFIG_RT_THREAD_PRIORITY_32=y
|
||||
# CONFIG_RT_THREAD_PRIORITY_256 is not set
|
||||
CONFIG_RT_THREAD_PRIORITY_MAX=32
|
||||
CONFIG_RT_TICK_PER_SECOND=1000
|
||||
CONFIG_RT_USING_OVERFLOW_CHECK=y
|
||||
CONFIG_RT_USING_HOOK=y
|
||||
CONFIG_RT_USING_IDLE_HOOK=y
|
||||
CONFIG_RT_IDLE_HOOK_LIST_SIZE=4
|
||||
CONFIG_IDLE_THREAD_STACK_SIZE=256
|
||||
CONFIG_RT_USING_TIMER_SOFT=y
|
||||
CONFIG_RT_TIMER_THREAD_PRIO=4
|
||||
CONFIG_RT_TIMER_THREAD_STACK_SIZE=512
|
||||
|
||||
#
|
||||
# kservice optimization
|
||||
#
|
||||
# CONFIG_RT_KSERVICE_USING_STDLIB is not set
|
||||
# CONFIG_RT_KSERVICE_USING_TINY_SIZE is not set
|
||||
# CONFIG_RT_USING_ASM_MEMCPY is not set
|
||||
CONFIG_RT_DEBUG=y
|
||||
CONFIG_RT_DEBUG_COLOR=y
|
||||
# CONFIG_RT_DEBUG_INIT_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_THREAD_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_SCHEDULER_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_IPC_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_TIMER_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_IRQ_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_MEM_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_SLAB_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_MEMHEAP_CONFIG is not set
|
||||
# CONFIG_RT_DEBUG_MODULE_CONFIG is not set
|
||||
|
||||
#
|
||||
# Inter-Thread communication
|
||||
#
|
||||
CONFIG_RT_USING_SEMAPHORE=y
|
||||
CONFIG_RT_USING_MUTEX=y
|
||||
CONFIG_RT_USING_EVENT=y
|
||||
CONFIG_RT_USING_MAILBOX=y
|
||||
CONFIG_RT_USING_MESSAGEQUEUE=y
|
||||
# CONFIG_RT_USING_SIGNALS is not set
|
||||
|
||||
#
|
||||
# Memory Management
|
||||
#
|
||||
CONFIG_RT_USING_MEMPOOL=y
|
||||
CONFIG_RT_USING_MEMHEAP=y
|
||||
CONFIG_RT_USING_MEMHEAP_AUTO_BINDING=y
|
||||
# CONFIG_RT_USING_NOHEAP is not set
|
||||
# CONFIG_RT_USING_SMALL_MEM is not set
|
||||
# CONFIG_RT_USING_SLAB is not set
|
||||
CONFIG_RT_USING_MEMHEAP_AS_HEAP=y
|
||||
# CONFIG_RT_USING_USERHEAP is not set
|
||||
# CONFIG_RT_USING_MEMTRACE is not set
|
||||
CONFIG_RT_USING_HEAP=y
|
||||
|
||||
#
|
||||
# Kernel Device Object
|
||||
#
|
||||
CONFIG_RT_USING_DEVICE=y
|
||||
# CONFIG_RT_USING_DEVICE_OPS is not set
|
||||
# CONFIG_RT_USING_INTERRUPT_INFO is not set
|
||||
CONFIG_RT_USING_CONSOLE=y
|
||||
CONFIG_RT_CONSOLEBUF_SIZE=128
|
||||
CONFIG_RT_CONSOLE_DEVICE_NAME="uart1"
|
||||
# CONFIG_RT_PRINTF_LONGLONG is not set
|
||||
CONFIG_RT_VER_NUM=0x40004
|
||||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_RT_USING_CPU_FFS=y
|
||||
CONFIG_ARCH_ARM_CORTEX_M=y
|
||||
CONFIG_ARCH_ARM_CORTEX_M4=y
|
||||
# CONFIG_ARCH_CPU_STACK_GROWS_UPWARD is not set
|
||||
|
||||
#
|
||||
# RT-Thread Components
|
||||
#
|
||||
CONFIG_RT_USING_COMPONENTS_INIT=y
|
||||
CONFIG_RT_USING_USER_MAIN=y
|
||||
CONFIG_RT_MAIN_THREAD_STACK_SIZE=2048
|
||||
CONFIG_RT_MAIN_THREAD_PRIORITY=10
|
||||
|
||||
#
|
||||
# C++ features
|
||||
#
|
||||
# CONFIG_RT_USING_CPLUSPLUS is not set
|
||||
|
||||
#
|
||||
# Command shell
|
||||
#
|
||||
CONFIG_RT_USING_FINSH=y
|
||||
CONFIG_RT_USING_MSH=y
|
||||
CONFIG_FINSH_USING_MSH=y
|
||||
CONFIG_FINSH_THREAD_NAME="tshell"
|
||||
CONFIG_FINSH_THREAD_PRIORITY=20
|
||||
CONFIG_FINSH_THREAD_STACK_SIZE=4096
|
||||
CONFIG_FINSH_USING_HISTORY=y
|
||||
CONFIG_FINSH_HISTORY_LINES=5
|
||||
CONFIG_FINSH_USING_SYMTAB=y
|
||||
CONFIG_FINSH_CMD_SIZE=80
|
||||
CONFIG_MSH_USING_BUILT_IN_COMMANDS=y
|
||||
CONFIG_FINSH_USING_DESCRIPTION=y
|
||||
# CONFIG_FINSH_ECHO_DISABLE_DEFAULT is not set
|
||||
# CONFIG_FINSH_USING_AUTH is not set
|
||||
CONFIG_FINSH_ARG_MAX=10
|
||||
|
||||
#
|
||||
# Device virtual file system
|
||||
#
|
||||
CONFIG_RT_USING_DFS=y
|
||||
CONFIG_DFS_USING_WORKDIR=y
|
||||
CONFIG_DFS_FILESYSTEMS_MAX=4
|
||||
CONFIG_DFS_FILESYSTEM_TYPES_MAX=4
|
||||
CONFIG_DFS_FD_MAX=16
|
||||
# CONFIG_RT_USING_DFS_MNTTABLE is not set
|
||||
CONFIG_RT_USING_DFS_ELMFAT=y
|
||||
|
||||
#
|
||||
# elm-chan's FatFs, Generic FAT Filesystem Module
|
||||
#
|
||||
CONFIG_RT_DFS_ELM_CODE_PAGE=437
|
||||
CONFIG_RT_DFS_ELM_WORD_ACCESS=y
|
||||
# CONFIG_RT_DFS_ELM_USE_LFN_0 is not set
|
||||
# CONFIG_RT_DFS_ELM_USE_LFN_1 is not set
|
||||
# CONFIG_RT_DFS_ELM_USE_LFN_2 is not set
|
||||
CONFIG_RT_DFS_ELM_USE_LFN_3=y
|
||||
CONFIG_RT_DFS_ELM_USE_LFN=3
|
||||
CONFIG_RT_DFS_ELM_LFN_UNICODE_0=y
|
||||
# CONFIG_RT_DFS_ELM_LFN_UNICODE_1 is not set
|
||||
# CONFIG_RT_DFS_ELM_LFN_UNICODE_2 is not set
|
||||
# CONFIG_RT_DFS_ELM_LFN_UNICODE_3 is not set
|
||||
CONFIG_RT_DFS_ELM_LFN_UNICODE=0
|
||||
CONFIG_RT_DFS_ELM_MAX_LFN=255
|
||||
CONFIG_RT_DFS_ELM_DRIVES=2
|
||||
CONFIG_RT_DFS_ELM_MAX_SECTOR_SIZE=4096
|
||||
# CONFIG_RT_DFS_ELM_USE_ERASE is not set
|
||||
CONFIG_RT_DFS_ELM_REENTRANT=y
|
||||
CONFIG_RT_DFS_ELM_MUTEX_TIMEOUT=3000
|
||||
CONFIG_RT_USING_DFS_DEVFS=y
|
||||
CONFIG_RT_USING_DFS_ROMFS=y
|
||||
# CONFIG_RT_USING_DFS_RAMFS is not set
|
||||
|
||||
#
|
||||
# Device Drivers
|
||||
#
|
||||
CONFIG_RT_USING_DEVICE_IPC=y
|
||||
CONFIG_RT_PIPE_BUFSZ=512
|
||||
CONFIG_RT_USING_SYSTEM_WORKQUEUE=y
|
||||
CONFIG_RT_SYSTEM_WORKQUEUE_STACKSIZE=2048
|
||||
CONFIG_RT_SYSTEM_WORKQUEUE_PRIORITY=23
|
||||
CONFIG_RT_USING_SERIAL=y
|
||||
CONFIG_RT_USING_SERIAL_V1=y
|
||||
# CONFIG_RT_USING_SERIAL_V2 is not set
|
||||
# CONFIG_RT_SERIAL_USING_DMA is not set
|
||||
CONFIG_RT_SERIAL_RB_BUFSZ=64
|
||||
CONFIG_RT_USING_CAN=y
|
||||
# CONFIG_RT_CAN_USING_HDR is not set
|
||||
# CONFIG_RT_USING_HWTIMER is not set
|
||||
# CONFIG_RT_USING_CPUTIME is not set
|
||||
CONFIG_RT_USING_I2C=y
|
||||
# CONFIG_RT_I2C_DEBUG is not set
|
||||
CONFIG_RT_USING_I2C_BITOPS=y
|
||||
# CONFIG_RT_I2C_BITOPS_DEBUG is not set
|
||||
# CONFIG_RT_USING_PHY is not set
|
||||
CONFIG_RT_USING_PIN=y
|
||||
# CONFIG_RT_USING_ADC is not set
|
||||
# CONFIG_RT_USING_DAC is not set
|
||||
# CONFIG_RT_USING_PWM is not set
|
||||
# CONFIG_RT_USING_MTD_NOR is not set
|
||||
# CONFIG_RT_USING_MTD_NAND is not set
|
||||
# CONFIG_RT_USING_PM is not set
|
||||
CONFIG_RT_USING_RTC=y
|
||||
# CONFIG_RT_USING_ALARM is not set
|
||||
# CONFIG_RT_USING_SOFT_RTC is not set
|
||||
# CONFIG_RT_USING_SDIO is not set
|
||||
CONFIG_RT_USING_SPI=y
|
||||
# CONFIG_RT_USING_QSPI is not set
|
||||
CONFIG_RT_USING_SPI_MSD=y
|
||||
CONFIG_RT_USING_SFUD=y
|
||||
CONFIG_RT_SFUD_USING_SFDP=y
|
||||
CONFIG_RT_SFUD_USING_FLASH_INFO_TABLE=y
|
||||
# CONFIG_RT_SFUD_USING_QSPI is not set
|
||||
CONFIG_RT_SFUD_SPI_MAX_HZ=50000000
|
||||
# CONFIG_RT_DEBUG_SFUD is not set
|
||||
# CONFIG_RT_USING_ENC28J60 is not set
|
||||
# CONFIG_RT_USING_SPI_WIFI is not set
|
||||
# CONFIG_RT_USING_WDT is not set
|
||||
# CONFIG_RT_USING_AUDIO is not set
|
||||
# CONFIG_RT_USING_SENSOR is not set
|
||||
# CONFIG_RT_USING_TOUCH is not set
|
||||
# CONFIG_RT_USING_HWCRYPTO is not set
|
||||
# CONFIG_RT_USING_PULSE_ENCODER is not set
|
||||
# CONFIG_RT_USING_INPUT_CAPTURE is not set
|
||||
# CONFIG_RT_USING_WIFI is not set
|
||||
|
||||
#
|
||||
# Using USB
|
||||
#
|
||||
# CONFIG_RT_USING_USB_HOST is not set
|
||||
# CONFIG_RT_USING_USB_DEVICE is not set
|
||||
|
||||
#
|
||||
# POSIX layer and C standard library
|
||||
#
|
||||
CONFIG_RT_USING_LIBC=y
|
||||
CONFIG_RT_USING_PTHREADS=y
|
||||
CONFIG_PTHREAD_NUM_MAX=8
|
||||
CONFIG_RT_USING_POSIX=y
|
||||
# CONFIG_RT_USING_POSIX_MMAP is not set
|
||||
# CONFIG_RT_USING_POSIX_TERMIOS is not set
|
||||
# CONFIG_RT_USING_POSIX_GETLINE is not set
|
||||
# CONFIG_RT_USING_POSIX_AIO is not set
|
||||
CONFIG_RT_LIBC_USING_TIME=y
|
||||
# CONFIG_RT_USING_MODULE is not set
|
||||
CONFIG_RT_LIBC_DEFAULT_TIMEZONE=8
|
||||
|
||||
#
|
||||
# Network
|
||||
#
|
||||
|
||||
#
|
||||
# Socket abstraction layer
|
||||
#
|
||||
# CONFIG_RT_USING_SAL is not set
|
||||
|
||||
#
|
||||
# Network interface device
|
||||
#
|
||||
# CONFIG_RT_USING_NETDEV is not set
|
||||
|
||||
#
|
||||
# light weight TCP/IP stack
|
||||
#
|
||||
# CONFIG_RT_USING_LWIP is not set
|
||||
|
||||
#
|
||||
# AT commands
|
||||
#
|
||||
# CONFIG_RT_USING_AT is not set
|
||||
|
||||
#
|
||||
# VBUS(Virtual Software BUS)
|
||||
#
|
||||
# CONFIG_RT_USING_VBUS is not set
|
||||
|
||||
#
|
||||
# Utilities
|
||||
#
|
||||
# CONFIG_RT_USING_RYM is not set
|
||||
# CONFIG_RT_USING_ULOG is not set
|
||||
# CONFIG_RT_USING_UTEST is not set
|
||||
# CONFIG_RT_USING_VAR_EXPORT is not set
|
||||
# CONFIG_RT_USING_RT_LINK is not set
|
||||
# CONFIG_RT_USING_LWP is not set
|
||||
|
||||
#
|
||||
# RT-Thread Utestcases
|
||||
#
|
||||
# CONFIG_RT_USING_UTESTCASES is not set
|
||||
CONFIG_SOC_FAMILY_STM32=y
|
||||
CONFIG_SOC_SERIES_STM32F4=y
|
||||
|
||||
#
|
||||
# Hardware Drivers Config
|
||||
#
|
||||
CONFIG_SOC_STM32F407ZG=y
|
||||
CONFIG_BSP_USING_GPIO=y
|
||||
CONFIG_BSP_USING_UART=y
|
||||
CONFIG_BSP_USING_UART1=y
|
||||
# CONFIG_BSP_USING_UART2 is not set
|
||||
# CONFIG_BSP_USING_UART3 is not set
|
||||
# CONFIG_BSP_USING_UART4 is not set
|
||||
# CONFIG_BSP_USING_I2C1 is not set
|
||||
# CONFIG_BSP_USING_SPI is not set
|
||||
# CONFIG_BSP_USING_CH438 is not set
|
||||
CONFIG_BSP_USING_USB=y
|
||||
CONFIG_BSP_USING_STM32_USBH=y
|
||||
CONFIG_USB_BUS_NAME="usb"
|
||||
CONFIG_USB_DRIVER_NAME="usb_drv"
|
||||
CONFIG_USB_DEVICE_NAME="usb_dev"
|
||||
# CONFIG_BSP_USING_RNG is not set
|
||||
# CONFIG_BSP_USING_UDID is not set
|
||||
|
||||
#
|
||||
# MicroPython
|
||||
#
|
||||
# CONFIG_PKG_USING_MICROPYTHON is not set
|
||||
|
||||
#
|
||||
# More Drivers
|
||||
#
|
||||
# CONFIG_PKG_USING_RW007 is not set
|
||||
# CONFIG_DRV_USING_OV2640 is not set
|
||||
|
||||
#
|
||||
# APP_Framework
|
||||
#
|
||||
|
||||
#
|
||||
# Framework
|
||||
#
|
||||
CONFIG_TRANSFORM_LAYER_ATTRIUBUTE=y
|
||||
CONFIG_ADD_XIZI_FETURES=y
|
||||
# CONFIG_ADD_NUTTX_FETURES is not set
|
||||
# CONFIG_ADD_RTTHREAD_FETURES is not set
|
||||
# CONFIG_SUPPORT_SENSOR_FRAMEWORK is not set
|
||||
# CONFIG_SUPPORT_CONNECTION_FRAMEWORK is not set
|
||||
# CONFIG_SUPPORT_KNOWING_FRAMEWORK is not set
|
||||
# CONFIG_SUPPORT_CONTROL_FRAMEWORK is not set
|
||||
|
||||
#
|
||||
# Security
|
||||
#
|
||||
# CONFIG_CRYPTO is not set
|
||||
|
||||
#
|
||||
# Applications
|
||||
#
|
||||
|
||||
#
|
||||
# config stack size and priority of main task
|
||||
#
|
||||
CONFIG_MAIN_KTASK_STACK_SIZE=1024
|
||||
|
||||
#
|
||||
# ota app
|
||||
#
|
||||
# CONFIG_APPLICATION_OTA is not set
|
||||
|
||||
#
|
||||
# test app
|
||||
#
|
||||
# CONFIG_USER_TEST is not set
|
||||
|
||||
#
|
||||
# connection app
|
||||
#
|
||||
# CONFIG_APPLICATION_CONNECTION is not set
|
||||
|
||||
#
|
||||
# control app
|
||||
#
|
||||
|
||||
#
|
||||
# knowing app
|
||||
#
|
||||
# CONFIG_APPLICATION_KNOWING is not set
|
||||
|
||||
#
|
||||
# sensor app
|
||||
#
|
||||
# CONFIG_APPLICATION_SENSOR is not set
|
||||
# CONFIG_USING_EMBEDDED_DATABASE_APP is not set
|
||||
|
||||
#
|
||||
# lib
|
||||
#
|
||||
CONFIG_APP_SELECT_NEWLIB=y
|
||||
# CONFIG_APP_SELECT_OTHER_LIB is not set
|
||||
# CONFIG_LIB_USING_CJSON is not set
|
||||
# CONFIG_LIB_USING_QUEUE is not set
|
||||
# CONFIG_LIB_LV is not set
|
||||
# CONFIG_USING_EMBEDDED_DATABASE is not set
|
|
@ -0,0 +1,243 @@
|
|||
# this
|
||||
*.map
|
||||
*.dblite
|
||||
*.bin
|
||||
*.axf
|
||||
*.old
|
||||
*~
|
||||
*.o
|
||||
*.bak
|
||||
*.dep
|
||||
*.i
|
||||
*.d
|
||||
*.uimg
|
||||
GPATH
|
||||
GRTAGS
|
||||
GTAGS
|
||||
JLinkLog.txt
|
||||
JLinkSettings.ini
|
||||
DebugConfig/
|
||||
RTE/
|
||||
settings/
|
||||
*.uvguix*
|
||||
cconfig.h
|
||||
|
||||
# General
|
||||
.DS_Store
|
||||
.AppleDouble
|
||||
.LSOverride
|
||||
|
||||
# Icon must end with two \r
|
||||
Icon
|
||||
|
||||
|
||||
# Thumbnails
|
||||
._*
|
||||
|
||||
# Files that might appear in the root of a volume
|
||||
.DocumentRevisions-V100
|
||||
.fseventsd
|
||||
.Spotlight-V100
|
||||
.TemporaryItems
|
||||
.Trashes
|
||||
.VolumeIcon.icns
|
||||
.com.apple.timemachine.donotpresent
|
||||
|
||||
# Directories potentially created on remote AFP share
|
||||
.AppleDB
|
||||
.AppleDesktop
|
||||
Network Trash Folder
|
||||
Temporary Items
|
||||
.apdisk
|
||||
|
||||
# Byte-compiled / optimized / DLL files
|
||||
__pycache__/
|
||||
*.py[cod]
|
||||
*$py.class
|
||||
|
||||
# C extensions
|
||||
*.so
|
||||
|
||||
# Distribution / packaging
|
||||
.Python
|
||||
build/
|
||||
develop-eggs/
|
||||
dist/
|
||||
downloads/
|
||||
eggs/
|
||||
.eggs/
|
||||
lib/
|
||||
lib64/
|
||||
parts/
|
||||
sdist/
|
||||
var/
|
||||
wheels/
|
||||
share/python-wheels/
|
||||
*.egg-info/
|
||||
.installed.cfg
|
||||
*.egg
|
||||
MANIFEST
|
||||
|
||||
# PyInstaller
|
||||
# Usually these files are written by a python script from a template
|
||||
# before PyInstaller builds the exe, so as to inject date/other infos into it.
|
||||
*.manifest
|
||||
*.spec
|
||||
|
||||
# Installer logs
|
||||
pip-log.txt
|
||||
pip-delete-this-directory.txt
|
||||
|
||||
# Unit test / coverage reports
|
||||
htmlcov/
|
||||
.tox/
|
||||
.nox/
|
||||
.coverage
|
||||
.coverage.*
|
||||
.cache
|
||||
nosetests.xml
|
||||
coverage.xml
|
||||
*.cover
|
||||
*.py,cover
|
||||
.hypothesis/
|
||||
.pytest_cache/
|
||||
cover/
|
||||
|
||||
# Translations
|
||||
*.mo
|
||||
*.pot
|
||||
|
||||
# Django stuff:
|
||||
*.log
|
||||
local_settings.py
|
||||
db.sqlite3
|
||||
db.sqlite3-journal
|
||||
|
||||
# Flask stuff:
|
||||
instance/
|
||||
.webassets-cache
|
||||
|
||||
# Scrapy stuff:
|
||||
.scrapy
|
||||
|
||||
# Sphinx documentation
|
||||
docs/_build/
|
||||
|
||||
# PyBuilder
|
||||
.pybuilder/
|
||||
target/
|
||||
|
||||
# Jupyter Notebook
|
||||
.ipynb_checkpoints
|
||||
|
||||
# IPython
|
||||
profile_default/
|
||||
ipython_config.py
|
||||
|
||||
# pyenv
|
||||
# For a library or package, you might want to ignore these files since the code is
|
||||
# intended to run in multiple environments; otherwise, check them in:
|
||||
# .python-version
|
||||
|
||||
# pipenv
|
||||
# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control.
|
||||
# However, in case of collaboration, if having platform-specific dependencies or dependencies
|
||||
# having no cross-platform support, pipenv may install dependencies that don't work, or not
|
||||
# install all needed dependencies.
|
||||
#Pipfile.lock
|
||||
|
||||
# PEP 582; used by e.g. github.com/David-OConnor/pyflow
|
||||
__pypackages__/
|
||||
|
||||
# Celery stuff
|
||||
celerybeat-schedule
|
||||
celerybeat.pid
|
||||
|
||||
# SageMath parsed files
|
||||
*.sage.py
|
||||
|
||||
# Environments
|
||||
.env
|
||||
.venv
|
||||
env/
|
||||
venv/
|
||||
ENV/
|
||||
env.bak/
|
||||
venv.bak/
|
||||
|
||||
# Spyder project settings
|
||||
.spyderproject
|
||||
.spyproject
|
||||
|
||||
# Rope project settings
|
||||
.ropeproject
|
||||
|
||||
# mkdocs documentation
|
||||
/site
|
||||
|
||||
# mypy
|
||||
.mypy_cache/
|
||||
.dmypy.json
|
||||
dmypy.json
|
||||
|
||||
# Pyre type checker
|
||||
.pyre/
|
||||
|
||||
# pytype static type analyzer
|
||||
.pytype/
|
||||
|
||||
# Cython debug symbols
|
||||
cython_debug/
|
||||
|
||||
# Prerequisites
|
||||
*.d
|
||||
|
||||
# Object files
|
||||
*.o
|
||||
*.ko
|
||||
*.obj
|
||||
*.elf
|
||||
|
||||
# Linker output
|
||||
*.ilk
|
||||
*.map
|
||||
*.exp
|
||||
|
||||
# Precompiled Headers
|
||||
*.gch
|
||||
*.pch
|
||||
|
||||
# Libraries
|
||||
*.lib
|
||||
*.a
|
||||
*.la
|
||||
*.lo
|
||||
|
||||
# Shared objects (inc. Windows DLLs)
|
||||
*.dll
|
||||
*.so
|
||||
*.so.*
|
||||
*.dylib
|
||||
|
||||
# Executables
|
||||
*.exe
|
||||
*.out
|
||||
*.app
|
||||
*.i*86
|
||||
*.x86_64
|
||||
*.hex
|
||||
|
||||
# Debug files
|
||||
*.dSYM/
|
||||
*.su
|
||||
*.idb
|
||||
*.pdb
|
||||
|
||||
# Kernel Module Compile Results
|
||||
*.mod*
|
||||
*.cmd
|
||||
.tmp_versions/
|
||||
modules.order
|
||||
Module.symvers
|
||||
Mkfile.old
|
||||
dkms.con
|
|
@ -0,0 +1,29 @@
|
|||
mainmenu "RT-Thread Configuration"
|
||||
|
||||
config ROOT_DIR
|
||||
string
|
||||
default "../../../.."
|
||||
|
||||
config BSP_DIR
|
||||
string
|
||||
default "."
|
||||
|
||||
config RT_Thread_DIR
|
||||
string
|
||||
default "../.."
|
||||
|
||||
config RTT_DIR
|
||||
string
|
||||
default "../../rt-thread"
|
||||
|
||||
config APP_DIR
|
||||
string
|
||||
default "../../../../APP_Framework"
|
||||
|
||||
source "$RTT_DIR/Kconfig"
|
||||
source "$RTT_DIR/bsp/stm32/libraries/Kconfig"
|
||||
source "board/Kconfig"
|
||||
source "$RT_Thread_DIR/micropython/Kconfig"
|
||||
source "$RT_Thread_DIR/app_match_rt-thread/Kconfig"
|
||||
source "$ROOT_DIR/APP_Framework/Kconfig"
|
||||
|
|
@ -0,0 +1,91 @@
|
|||
# STM32F407最小系统板说明
|
||||
|
||||
采用ST公司的32位ARM-Cortex M4内核的STM32F407
|
||||
|
||||
## 以下为引脚硬件的连接表
|
||||
|
||||
## **W25q16(SPI1 )**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | W25q16 |
|
||||
| ---- | --------- | -------- | --------|
|
||||
| PA5 | SPI1_SCK | 41 | CLK |
|
||||
| PA6 | SPI1_MISO | 42 | DO |
|
||||
| PA7 | SPI1_MOSI | 43 | DI |
|
||||
| PB0 | SpiFlash_nCS | 46 | nCS |
|
||||
|
||||
## **CRF1278-L3(SPI2 )**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | CRF1278 |
|
||||
| ---- | --------- | -------- | --------|
|
||||
| PB13 | SPI2_SCK | 74 | SCK |
|
||||
| PC2 | SPI2_MISO | 28 | MISO |
|
||||
| PC3 | SPI2_MOSI | 29 | MOSI |
|
||||
| PC6 | LORA_nCS | 96 | NSS |
|
||||
|
||||
## **XPT2046(SPI3)**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | XPT2046 |
|
||||
| ---- | --------- | -------- | --------|
|
||||
| PB3 | SPI3_SCK | 133 | DCLK |
|
||||
| PB4 | SPI3_MISO | 134 | DOUT |
|
||||
| PB5 | SPI3_MOSI | 135 | DIN |
|
||||
| PG13 | T_nCS | 128 | CS |
|
||||
|
||||
## **sensor(I2C1)**
|
||||
|
||||
| PB6 | I2C_SCL |
|
||||
| ---- | ---------- |
|
||||
| PB7 | I2C_SDA |
|
||||
|
||||
|
||||
## **TTL_debug(uart1)**
|
||||
| 引脚 | 作用 | 引脚序号 | TTL_debug |
|
||||
| ---- | ----------|------------ |--------- |
|
||||
| PA9 | USART1_TX | 101 |USART1_RX |
|
||||
| PA10 | USART1_RX | 102 |USART1_TX |
|
||||
|
||||
## **NB/4G(uart2)**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | NB/4G |
|
||||
| ---- | ----------|------------ |--------- |
|
||||
| PA2 | USART2_TX | 36 |USART2_RX |
|
||||
| PA3 | USART2_RX | 37 |USART2_TX |
|
||||
|
||||
## **Ethernet/WIFI(uart3)**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | Ethernet/WIFI |
|
||||
| ---- | ----------|------------ |------------- |
|
||||
| PB10 | USART3_TX | 69 |UART0_RXD |
|
||||
| PB11 | USART3_RX | 70 |UART0_TXD |
|
||||
|
||||
|
||||
## **BT-HC08(uart4)**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | BT-HC08 |
|
||||
| -----------| ---------|------------ |--------- |
|
||||
| PA0_WAKEUP | UART4_TX | 34 | RXD |
|
||||
| PA1 | UART4_RX | 35 | TXD |
|
||||
|
||||
## **SD**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | TF-01A |
|
||||
| ---- | --------- | -------- | ---------|
|
||||
| PC10 | SDIO_D2 | 114 | DATA2 |
|
||||
| PC11 | SDIO_D3 | 115 | DATA3 |
|
||||
| PD2 | SDIO_CMD | 116 | CMD |
|
||||
| PC12 | SDIO_CK | 113 | CLK |
|
||||
| PC8 | SDIO_D0 | 98 | DATA0 |
|
||||
| PC9 | SDIO_D1 | 99 | DATA1 |
|
||||
|
||||
## **USB-HOST**
|
||||
|
||||
| 引脚 | 作用 | 引脚序号 | USB-S |
|
||||
| -----------| --------- |------------ |------------|
|
||||
| PA12 | USB_OTG_DP | 104 | USB_OTG_DP |
|
||||
| PA11 | USB_OTG_DM | 103 | USB_OTG_DM |
|
||||
|
||||
## **CAN**
|
||||
| 引脚 | 作用 | 引脚序号 | USB-S |
|
||||
| -----------| --------- |------------ |---------|
|
||||
| PB8 | CAN1_RX | 139 | CAN1_TX |
|
||||
| PB9 | CAN1_TX | 140 | CAN1_RX |
|
|
@ -0,0 +1,15 @@
|
|||
# for module compiling
|
||||
import os
|
||||
Import('RTT_ROOT')
|
||||
from building import *
|
||||
|
||||
cwd = GetCurrentDir()
|
||||
objs = []
|
||||
list = os.listdir(cwd)
|
||||
|
||||
for d in list:
|
||||
path = os.path.join(cwd, d)
|
||||
if os.path.isfile(os.path.join(path, 'SConscript')):
|
||||
objs = objs + SConscript(os.path.join(d, 'SConscript'))
|
||||
|
||||
Return('objs')
|
|
@ -0,0 +1,92 @@
|
|||
import os
|
||||
import sys
|
||||
import rtconfig
|
||||
import SCons
|
||||
|
||||
if os.getenv('RTT_ROOT'):
|
||||
RTT_ROOT = os.getenv('RTT_ROOT')
|
||||
else:
|
||||
RTT_ROOT = os.path.normpath(os.getcwd() + '/../../rt-thread')
|
||||
|
||||
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
|
||||
try:
|
||||
from building import *
|
||||
except:
|
||||
print('Cannot found RT-Thread root directory, please check RTT_ROOT')
|
||||
print(RTT_ROOT)
|
||||
exit(-1)
|
||||
|
||||
TARGET = 'rt-thread.' + rtconfig.TARGET_EXT
|
||||
|
||||
DefaultEnvironment(tools=[])
|
||||
env = Environment(tools = ['mingw'],
|
||||
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
|
||||
CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
|
||||
AR = rtconfig.AR, ARFLAGS = '-rc',
|
||||
CXX = rtconfig.CXX, CXXFLAGS = rtconfig.CXXFLAGS,
|
||||
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
|
||||
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
|
||||
|
||||
AddOption('--compiledb',
|
||||
dest = 'compiledb',
|
||||
action = 'store_true',
|
||||
default = False,
|
||||
help = 'generate compile_commands.json')
|
||||
|
||||
if GetOption('compiledb'):
|
||||
if int(SCons.__version__.split('.')[0]) >= 4:
|
||||
env['COMPILATIONDB_USE_ABSPATH'] = True
|
||||
env.Tool('compilation_db')
|
||||
env.CompilationDatabase('compile_commands.json')
|
||||
else:
|
||||
print('Warning: --compiledb only support on SCons 4.0+')
|
||||
|
||||
if rtconfig.PLATFORM == 'iar':
|
||||
env.Replace(CCCOM = ['$CC $CCFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
|
||||
env.Replace(ARFLAGS = [''])
|
||||
env.Replace(LINKCOM = env["LINKCOM"] + ' --map rt-thread.map')
|
||||
|
||||
Export('RTT_ROOT')
|
||||
Export('rtconfig')
|
||||
|
||||
SDK_ROOT = os.path.abspath('./')
|
||||
|
||||
#if os.path.exists(SDK_ROOT + '/libraries'):
|
||||
# libraries_path_prefix = SDK_ROOT + '/libraries'
|
||||
#else:
|
||||
# libraries_path_prefix = os.path.dirname(SDK_ROOT) + '/libraries'
|
||||
|
||||
libraries_path_prefix = RTT_ROOT + '/bsp/stm32/libraries'
|
||||
|
||||
SDK_LIB = libraries_path_prefix
|
||||
Export('SDK_LIB')
|
||||
|
||||
# prepare building environment
|
||||
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
|
||||
|
||||
stm32_library = 'STM32F4xx_HAL'
|
||||
rtconfig.BSP_LIBRARY_TYPE = stm32_library
|
||||
|
||||
# include libraries
|
||||
objs.extend(SConscript(os.path.join(libraries_path_prefix, stm32_library, 'SConscript')))
|
||||
|
||||
# include drivers
|
||||
objs.extend(SConscript(os.path.join(libraries_path_prefix, 'HAL_Drivers', 'SConscript')))
|
||||
|
||||
# include more drivers
|
||||
objs.extend(SConscript(os.getcwd() + '/../../app_match_rt-thread/SConscript'))
|
||||
|
||||
# include APP_Framework/Framework
|
||||
objs.extend(SConscript(os.getcwd() + '/../../../../APP_Framework/Framework/SConscript'))
|
||||
|
||||
# include APP_Framework/Applications
|
||||
objs.extend(SConscript(os.getcwd() + '/../../../../APP_Framework/Applications/SConscript'))
|
||||
|
||||
# include APP_Framework/lib
|
||||
objs.extend(SConscript(os.getcwd() + '/../../../../APP_Framework/lib/SConscript'))
|
||||
|
||||
# include Ubiquitous/RT-Thread/micropython
|
||||
objs.extend(SConscript(os.getcwd() + '/../../micropython/SConscript'))
|
||||
|
||||
# make a building
|
||||
DoBuilding(TARGET, objs)
|
|
@ -0,0 +1,12 @@
|
|||
import rtconfig
|
||||
from building import *
|
||||
|
||||
cwd = GetCurrentDir()
|
||||
CPPPATH = [cwd]
|
||||
src = Split("""
|
||||
main.c
|
||||
""")
|
||||
|
||||
group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
|
||||
|
||||
Return('group')
|
|
@ -0,0 +1,51 @@
|
|||
/*
|
||||
* @Author: chunyexixiaoyu
|
||||
* @Date: 2021-09-24 16:33:15
|
||||
* @LastEditTime: 2021-09-24 15:48:30
|
||||
* @LastEditors: Please set LastEditors
|
||||
* @Description: In User Settings Edit
|
||||
* @FilePath: \xiuos\Ubiquitous\RT_Thread\bsp\stm32f407-atk-coreboard\applications\main.c
|
||||
*/
|
||||
|
||||
/*
|
||||
* Copyright (c) 2006-2018, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
*/
|
||||
|
||||
#include <rtthread.h>
|
||||
#include <board.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#ifdef RT_USING_POSIX
|
||||
#include <pthread.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <dfs_poll.h>
|
||||
#include <dfs_posix.h>
|
||||
#include <dfs.h>
|
||||
#ifdef RT_USING_POSIX_TERMIOS
|
||||
#include <posix_termios.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define LED0_PIN GET_PIN(G, 15)
|
||||
extern int FrameworkInit();
|
||||
int main(void)
|
||||
{
|
||||
int count = 1;
|
||||
rt_pin_mode(LED0_PIN, PIN_MODE_OUTPUT);
|
||||
rt_thread_mdelay(100);
|
||||
FrameworkInit();
|
||||
printf("XIUOS stm32f4 build %s %s\n",__DATE__,__TIME__);
|
||||
while (count++)
|
||||
{
|
||||
rt_pin_write(LED0_PIN, PIN_HIGH);
|
||||
rt_thread_mdelay(500);
|
||||
rt_pin_write(LED0_PIN, PIN_LOW);
|
||||
rt_thread_mdelay(500);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,43 @@
|
|||
/*
|
||||
* @Author: yongliang
|
||||
* @Date: 2022-03-31 16:00:00
|
||||
* @Description: uart_test code
|
||||
* @FilePath: \xiuos\Ubiquitous\RT_Thread\aiit_board\stm32f407_mini_board\applications\uart_test.c
|
||||
*/
|
||||
|
||||
/*
|
||||
* Copyright (c) 2006-2018, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
*/
|
||||
|
||||
#include <rtthread.h>
|
||||
#include <board.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
int main (void)
|
||||
{
|
||||
/*1.设置系统中断优先组*/
|
||||
|
||||
/*2.串口初始化*/
|
||||
while(1)
|
||||
{
|
||||
if(USART_RX_STA&0X8000)
|
||||
{
|
||||
len =USART_RX_STA&0X3fff;
|
||||
printf("发送的消息为:\r\n");
|
||||
for(t=0;t<len;t++)
|
||||
{
|
||||
USART_SendData(USART1,USART_RX_BUF[T]);
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,441 @@
|
|||
#MicroXplorer Configuration settings - do not modify
|
||||
CAN1.CalculateTimeQuantum=380.95238095238096
|
||||
CAN1.IPParameters=CalculateTimeQuantum
|
||||
FSMC.IPParameters=WriteOperation1
|
||||
FSMC.WriteOperation1=FSMC_WRITE_OPERATION_ENABLE
|
||||
File.Version=6
|
||||
GPIO.groupedBy=Group By Peripherals
|
||||
KeepUserPlacement=false
|
||||
Mcu.Family=STM32F4
|
||||
Mcu.IP0=CAN1
|
||||
Mcu.IP1=FSMC
|
||||
Mcu.IP10=SPI3
|
||||
Mcu.IP11=SYS
|
||||
Mcu.IP12=TIM2
|
||||
Mcu.IP13=TIM11
|
||||
Mcu.IP14=TIM13
|
||||
Mcu.IP15=TIM14
|
||||
Mcu.IP16=UART4
|
||||
Mcu.IP17=USART1
|
||||
Mcu.IP18=USART2
|
||||
Mcu.IP19=USART3
|
||||
Mcu.IP2=I2C1
|
||||
Mcu.IP3=IWDG
|
||||
Mcu.IP4=NVIC
|
||||
Mcu.IP5=RCC
|
||||
Mcu.IP6=RTC
|
||||
Mcu.IP7=SDIO
|
||||
Mcu.IP8=SPI1
|
||||
Mcu.IP9=SPI2
|
||||
Mcu.IPNb=20
|
||||
Mcu.Name=STM32F407Z(E-G)Tx
|
||||
Mcu.Package=LQFP144
|
||||
Mcu.Pin0=PC14-OSC32_IN
|
||||
Mcu.Pin1=PC15-OSC32_OUT
|
||||
Mcu.Pin10=PC2
|
||||
Mcu.Pin11=PC3
|
||||
Mcu.Pin12=PA0-WKUP
|
||||
Mcu.Pin13=PA1
|
||||
Mcu.Pin14=PA2
|
||||
Mcu.Pin15=PA3
|
||||
Mcu.Pin16=PA5
|
||||
Mcu.Pin17=PA6
|
||||
Mcu.Pin18=PA7
|
||||
Mcu.Pin19=PF12
|
||||
Mcu.Pin2=PF0
|
||||
Mcu.Pin20=PF13
|
||||
Mcu.Pin21=PF14
|
||||
Mcu.Pin22=PF15
|
||||
Mcu.Pin23=PG0
|
||||
Mcu.Pin24=PG1
|
||||
Mcu.Pin25=PE7
|
||||
Mcu.Pin26=PE8
|
||||
Mcu.Pin27=PE9
|
||||
Mcu.Pin28=PE10
|
||||
Mcu.Pin29=PE11
|
||||
Mcu.Pin3=PF1
|
||||
Mcu.Pin30=PE12
|
||||
Mcu.Pin31=PE13
|
||||
Mcu.Pin32=PE14
|
||||
Mcu.Pin33=PE15
|
||||
Mcu.Pin34=PB10
|
||||
Mcu.Pin35=PB11
|
||||
Mcu.Pin36=PB13
|
||||
Mcu.Pin37=PD8
|
||||
Mcu.Pin38=PD9
|
||||
Mcu.Pin39=PD10
|
||||
Mcu.Pin4=PF2
|
||||
Mcu.Pin40=PD11
|
||||
Mcu.Pin41=PD12
|
||||
Mcu.Pin42=PD13
|
||||
Mcu.Pin43=PD14
|
||||
Mcu.Pin44=PD15
|
||||
Mcu.Pin45=PG2
|
||||
Mcu.Pin46=PG3
|
||||
Mcu.Pin47=PG4
|
||||
Mcu.Pin48=PG5
|
||||
Mcu.Pin49=PC8
|
||||
Mcu.Pin5=PF3
|
||||
Mcu.Pin50=PC9
|
||||
Mcu.Pin51=PA9
|
||||
Mcu.Pin52=PA10
|
||||
Mcu.Pin53=PA13
|
||||
Mcu.Pin54=PA14
|
||||
Mcu.Pin55=PC10
|
||||
Mcu.Pin56=PC11
|
||||
Mcu.Pin57=PC12
|
||||
Mcu.Pin58=PD0
|
||||
Mcu.Pin59=PD1
|
||||
Mcu.Pin6=PF4
|
||||
Mcu.Pin60=PD2
|
||||
Mcu.Pin61=PD4
|
||||
Mcu.Pin62=PD5
|
||||
Mcu.Pin63=PG10
|
||||
Mcu.Pin64=PG11
|
||||
Mcu.Pin65=PG12
|
||||
Mcu.Pin66=PG13
|
||||
Mcu.Pin67=PG14
|
||||
Mcu.Pin68=PB3
|
||||
Mcu.Pin69=PB4
|
||||
Mcu.Pin7=PF5
|
||||
Mcu.Pin70=PB5
|
||||
Mcu.Pin71=PB6
|
||||
Mcu.Pin72=PB7
|
||||
Mcu.Pin73=PB8
|
||||
Mcu.Pin74=PB9
|
||||
Mcu.Pin75=PE0
|
||||
Mcu.Pin76=PE1
|
||||
Mcu.Pin77=VP_IWDG_VS_IWDG
|
||||
Mcu.Pin78=VP_RTC_VS_RTC_Activate
|
||||
Mcu.Pin79=VP_SYS_VS_Systick
|
||||
Mcu.Pin8=PH0-OSC_IN
|
||||
Mcu.Pin80=VP_TIM2_VS_ClockSourceINT
|
||||
Mcu.Pin81=VP_TIM11_VS_ClockSourceINT
|
||||
Mcu.Pin82=VP_TIM13_VS_ClockSourceINT
|
||||
Mcu.Pin83=VP_TIM14_VS_ClockSourceINT
|
||||
Mcu.Pin9=PH1-OSC_OUT
|
||||
Mcu.PinsNb=84
|
||||
Mcu.ThirdPartyNb=0
|
||||
Mcu.UserConstants=
|
||||
Mcu.UserName=STM32F407ZGTx
|
||||
MxCube.Version=5.6.0
|
||||
MxDb.Version=DB.5.0.60
|
||||
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
NVIC.ForceEnableDMAVector=true
|
||||
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
|
||||
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true
|
||||
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
|
||||
PA0-WKUP.Locked=true
|
||||
PA0-WKUP.Mode=Asynchronous
|
||||
PA0-WKUP.Signal=UART4_TX
|
||||
PA1.Locked=true
|
||||
PA1.Mode=Asynchronous
|
||||
PA1.Signal=UART4_RX
|
||||
PA10.Mode=Asynchronous
|
||||
PA10.Signal=USART1_RX
|
||||
PA13.Mode=Serial_Wire
|
||||
PA13.Signal=SYS_JTMS-SWDIO
|
||||
PA14.Mode=Serial_Wire
|
||||
PA14.Signal=SYS_JTCK-SWCLK
|
||||
PA2.Locked=true
|
||||
PA2.Mode=Asynchronous
|
||||
PA2.Signal=USART2_TX
|
||||
PA3.Locked=true
|
||||
PA3.Mode=Asynchronous
|
||||
PA3.Signal=USART2_RX
|
||||
PA5.Locked=true
|
||||
PA5.Mode=Full_Duplex_Master
|
||||
PA5.Signal=SPI1_SCK
|
||||
PA6.Locked=true
|
||||
PA6.Mode=Full_Duplex_Master
|
||||
PA6.Signal=SPI1_MISO
|
||||
PA7.Locked=true
|
||||
PA7.Mode=Full_Duplex_Master
|
||||
PA7.Signal=SPI1_MOSI
|
||||
PA9.Mode=Asynchronous
|
||||
PA9.Signal=USART1_TX
|
||||
PB10.Mode=Asynchronous
|
||||
PB10.Signal=USART3_TX
|
||||
PB11.Mode=Asynchronous
|
||||
PB11.Signal=USART3_RX
|
||||
PB13.Mode=Full_Duplex_Master
|
||||
PB13.Signal=SPI2_SCK
|
||||
PB3.Locked=true
|
||||
PB3.Mode=Full_Duplex_Master
|
||||
PB3.Signal=SPI3_SCK
|
||||
PB4.Locked=true
|
||||
PB4.Mode=Full_Duplex_Master
|
||||
PB4.Signal=SPI3_MISO
|
||||
PB5.Locked=true
|
||||
PB5.Mode=Full_Duplex_Master
|
||||
PB5.Signal=SPI3_MOSI
|
||||
PB6.Locked=true
|
||||
PB6.Mode=I2C
|
||||
PB6.Signal=I2C1_SCL
|
||||
PB7.Locked=true
|
||||
PB7.Mode=I2C
|
||||
PB7.Signal=I2C1_SDA
|
||||
PB8.Mode=Master
|
||||
PB8.Signal=CAN1_RX
|
||||
PB9.Locked=true
|
||||
PB9.Mode=Master
|
||||
PB9.Signal=CAN1_TX
|
||||
PC10.Mode=SD_4_bits_Wide_bus
|
||||
PC10.Signal=SDIO_D2
|
||||
PC11.Mode=SD_4_bits_Wide_bus
|
||||
PC11.Signal=SDIO_D3
|
||||
PC12.Mode=SD_4_bits_Wide_bus
|
||||
PC12.Signal=SDIO_CK
|
||||
PC14-OSC32_IN.Mode=LSE-External-Oscillator
|
||||
PC14-OSC32_IN.Signal=RCC_OSC32_IN
|
||||
PC15-OSC32_OUT.Mode=LSE-External-Oscillator
|
||||
PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
|
||||
PC2.Mode=Full_Duplex_Master
|
||||
PC2.Signal=SPI2_MISO
|
||||
PC3.Mode=Full_Duplex_Master
|
||||
PC3.Signal=SPI2_MOSI
|
||||
PC8.Mode=SD_4_bits_Wide_bus
|
||||
PC8.Signal=SDIO_D0
|
||||
PC9.Mode=SD_4_bits_Wide_bus
|
||||
PC9.Signal=SDIO_D1
|
||||
PD0.Signal=FSMC_D2_DA2
|
||||
PD1.Signal=FSMC_D3_DA3
|
||||
PD10.Signal=FSMC_D15_DA15
|
||||
PD11.Signal=FSMC_A16_CLE
|
||||
PD12.Signal=FSMC_A17_ALE
|
||||
PD13.Signal=FSMC_A18
|
||||
PD14.Signal=FSMC_D0_DA0
|
||||
PD15.Signal=FSMC_D1_DA1
|
||||
PD2.Mode=SD_4_bits_Wide_bus
|
||||
PD2.Signal=SDIO_CMD
|
||||
PD4.Signal=FSMC_NOE
|
||||
PD5.Signal=FSMC_NWE
|
||||
PD8.Signal=FSMC_D13_DA13
|
||||
PD9.Signal=FSMC_D14_DA14
|
||||
PE0.Signal=FSMC_NBL0
|
||||
PE1.Signal=FSMC_NBL1
|
||||
PE10.Signal=FSMC_D7_DA7
|
||||
PE11.Signal=FSMC_D8_DA8
|
||||
PE12.Signal=FSMC_D9_DA9
|
||||
PE13.Signal=FSMC_D10_DA10
|
||||
PE14.Signal=FSMC_D11_DA11
|
||||
PE15.Signal=FSMC_D12_DA12
|
||||
PE7.Signal=FSMC_D4_DA4
|
||||
PE8.Signal=FSMC_D5_DA5
|
||||
PE9.Signal=FSMC_D6_DA6
|
||||
PF0.Signal=FSMC_A0
|
||||
PF1.Signal=FSMC_A1
|
||||
PF12.Signal=FSMC_A6
|
||||
PF13.Signal=FSMC_A7
|
||||
PF14.Signal=FSMC_A8
|
||||
PF15.Signal=FSMC_A9
|
||||
PF2.Signal=FSMC_A2
|
||||
PF3.Signal=FSMC_A3
|
||||
PF4.Signal=FSMC_A4
|
||||
PF5.Signal=FSMC_A5
|
||||
PG0.Signal=FSMC_A10
|
||||
PG1.Signal=FSMC_A11
|
||||
PG10.Mode=NorPsramChipSelect3_1
|
||||
PG10.Signal=FSMC_NE3
|
||||
PG11.Locked=true
|
||||
PG11.Signal=GPIO_Output
|
||||
PG12.Locked=true
|
||||
PG12.Signal=FSMC_NE4
|
||||
PG13.Locked=true
|
||||
PG13.Signal=ETH_TXD0
|
||||
PG14.Locked=true
|
||||
PG14.Signal=GPIO_Output
|
||||
PG2.Signal=FSMC_A12
|
||||
PG3.Signal=FSMC_A13
|
||||
PG4.Signal=FSMC_A14
|
||||
PG5.Signal=FSMC_A15
|
||||
PH0-OSC_IN.Mode=HSE-External-Oscillator
|
||||
PH0-OSC_IN.Signal=RCC_OSC_IN
|
||||
PH1-OSC_OUT.Mode=HSE-External-Oscillator
|
||||
PH1-OSC_OUT.Signal=RCC_OSC_OUT
|
||||
PinOutPanel.RotationAngle=0
|
||||
ProjectManager.AskForMigrate=true
|
||||
ProjectManager.BackupPrevious=false
|
||||
ProjectManager.CompilerOptimize=6
|
||||
ProjectManager.ComputerToolchain=false
|
||||
ProjectManager.CoupleFile=false
|
||||
ProjectManager.CustomerFirmwarePackage=
|
||||
ProjectManager.DefaultFWLocation=true
|
||||
ProjectManager.DeletePrevious=true
|
||||
ProjectManager.DeviceId=STM32F407ZGTx
|
||||
ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.25.0
|
||||
ProjectManager.FreePins=false
|
||||
ProjectManager.HalAssertFull=false
|
||||
ProjectManager.HeapSize=0x200
|
||||
ProjectManager.KeepUserCode=true
|
||||
ProjectManager.LastFirmware=true
|
||||
ProjectManager.LibraryCopy=0
|
||||
ProjectManager.MainLocation=Src
|
||||
ProjectManager.NoMain=false
|
||||
ProjectManager.PreviousToolchain=
|
||||
ProjectManager.ProjectBuild=false
|
||||
ProjectManager.ProjectFileName=CubeMX_Config.ioc
|
||||
ProjectManager.ProjectName=CubeMX_Config
|
||||
ProjectManager.RegisterCallBack=
|
||||
ProjectManager.StackSize=0x400
|
||||
ProjectManager.TargetToolchain=MDK-ARM V5
|
||||
ProjectManager.ToolChainLocation=
|
||||
ProjectManager.UnderRoot=false
|
||||
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_USART1_UART_Init-USART1-false-HAL-true,4-MX_USART3_UART_Init-USART3-false-HAL-true,5-MX_RTC_Init-RTC-false-HAL-true,6-MX_IWDG_Init-IWDG-false-HAL-true,7-MX_TIM14_Init-TIM14-false-HAL-true,8-MX_TIM13_Init-TIM13-false-HAL-true,9-MX_TIM11_Init-TIM11-false-HAL-true,10-MX_SDIO_SD_Init-SDIO-false-HAL-true,11-MX_TIM2_Init-TIM2-false-HAL-true,12-MX_SPI2_Init-SPI2-false-HAL-true,13-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,14-MX_FSMC_Init-FSMC-false-HAL-true,15-MX_UART4_Init-UART4-false-HAL-true,16-MX_USART2_UART_Init-USART2-false-HAL-true,17-MX_CAN1_Init-CAN1-false-HAL-true
|
||||
RCC.48MHZClocksFreq_Value=48000000
|
||||
RCC.AHBFreq_Value=168000000
|
||||
RCC.APB1CLKDivider=RCC_HCLK_DIV4
|
||||
RCC.APB1Freq_Value=42000000
|
||||
RCC.APB1TimFreq_Value=84000000
|
||||
RCC.APB2CLKDivider=RCC_HCLK_DIV2
|
||||
RCC.APB2Freq_Value=84000000
|
||||
RCC.APB2TimFreq_Value=168000000
|
||||
RCC.CortexFreq_Value=168000000
|
||||
RCC.EthernetFreq_Value=168000000
|
||||
RCC.FCLKCortexFreq_Value=168000000
|
||||
RCC.FamilyName=M
|
||||
RCC.HCLKFreq_Value=168000000
|
||||
RCC.HSE_VALUE=8000000
|
||||
RCC.HSI_VALUE=16000000
|
||||
RCC.I2SClocksFreq_Value=192000000
|
||||
RCC.IPParameters=48MHZClocksFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,EthernetFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2SClocksFreq_Value,LSI_VALUE,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLM,PLLN,PLLQ,PLLQCLKFreq_Value,PLLSourceVirtual,RCC_RTC_Clock_Source,RCC_RTC_Clock_SourceVirtual,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VcooutputI2S
|
||||
RCC.LSI_VALUE=32000
|
||||
RCC.MCO2PinFreq_Value=168000000
|
||||
RCC.PLLCLKFreq_Value=168000000
|
||||
RCC.PLLM=4
|
||||
RCC.PLLN=168
|
||||
RCC.PLLQ=7
|
||||
RCC.PLLQCLKFreq_Value=48000000
|
||||
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
|
||||
RCC.RCC_RTC_Clock_Source=RCC_RTCCLKSOURCE_LSE
|
||||
RCC.RCC_RTC_Clock_SourceVirtual=RCC_RTCCLKSOURCE_LSE
|
||||
RCC.RTCFreq_Value=32768
|
||||
RCC.RTCHSEDivFreq_Value=4000000
|
||||
RCC.SYSCLKFreq_VALUE=168000000
|
||||
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
|
||||
RCC.VCOI2SOutputFreq_Value=384000000
|
||||
RCC.VCOInputFreq_Value=2000000
|
||||
RCC.VCOOutputFreq_Value=336000000
|
||||
RCC.VcooutputI2S=192000000
|
||||
SH.FSMC_A0.0=FSMC_A0,19b-a1
|
||||
SH.FSMC_A0.ConfNb=1
|
||||
SH.FSMC_A1.0=FSMC_A1,19b-a1
|
||||
SH.FSMC_A1.ConfNb=1
|
||||
SH.FSMC_A10.0=FSMC_A10,19b-a1
|
||||
SH.FSMC_A10.ConfNb=1
|
||||
SH.FSMC_A11.0=FSMC_A11,19b-a1
|
||||
SH.FSMC_A11.ConfNb=1
|
||||
SH.FSMC_A12.0=FSMC_A12,19b-a1
|
||||
SH.FSMC_A12.ConfNb=1
|
||||
SH.FSMC_A13.0=FSMC_A13,19b-a1
|
||||
SH.FSMC_A13.ConfNb=1
|
||||
SH.FSMC_A14.0=FSMC_A14,19b-a1
|
||||
SH.FSMC_A14.ConfNb=1
|
||||
SH.FSMC_A15.0=FSMC_A15,19b-a1
|
||||
SH.FSMC_A15.ConfNb=1
|
||||
SH.FSMC_A16_CLE.0=FSMC_A16,19b-a1
|
||||
SH.FSMC_A16_CLE.ConfNb=1
|
||||
SH.FSMC_A17_ALE.0=FSMC_A17,19b-a1
|
||||
SH.FSMC_A17_ALE.ConfNb=1
|
||||
SH.FSMC_A18.0=FSMC_A18,19b-a1
|
||||
SH.FSMC_A18.ConfNb=1
|
||||
SH.FSMC_A2.0=FSMC_A2,19b-a1
|
||||
SH.FSMC_A2.ConfNb=1
|
||||
SH.FSMC_A3.0=FSMC_A3,19b-a1
|
||||
SH.FSMC_A3.ConfNb=1
|
||||
SH.FSMC_A4.0=FSMC_A4,19b-a1
|
||||
SH.FSMC_A4.ConfNb=1
|
||||
SH.FSMC_A5.0=FSMC_A5,19b-a1
|
||||
SH.FSMC_A5.ConfNb=1
|
||||
SH.FSMC_A6.0=FSMC_A6,19b-a1
|
||||
SH.FSMC_A6.ConfNb=1
|
||||
SH.FSMC_A7.0=FSMC_A7,19b-a1
|
||||
SH.FSMC_A7.ConfNb=1
|
||||
SH.FSMC_A8.0=FSMC_A8,19b-a1
|
||||
SH.FSMC_A8.ConfNb=1
|
||||
SH.FSMC_A9.0=FSMC_A9,19b-a1
|
||||
SH.FSMC_A9.ConfNb=1
|
||||
SH.FSMC_D0_DA0.0=FSMC_D0,16b-d1
|
||||
SH.FSMC_D0_DA0.ConfNb=1
|
||||
SH.FSMC_D10_DA10.0=FSMC_D10,16b-d1
|
||||
SH.FSMC_D10_DA10.ConfNb=1
|
||||
SH.FSMC_D11_DA11.0=FSMC_D11,16b-d1
|
||||
SH.FSMC_D11_DA11.ConfNb=1
|
||||
SH.FSMC_D12_DA12.0=FSMC_D12,16b-d1
|
||||
SH.FSMC_D12_DA12.ConfNb=1
|
||||
SH.FSMC_D13_DA13.0=FSMC_D13,16b-d1
|
||||
SH.FSMC_D13_DA13.ConfNb=1
|
||||
SH.FSMC_D14_DA14.0=FSMC_D14,16b-d1
|
||||
SH.FSMC_D14_DA14.ConfNb=1
|
||||
SH.FSMC_D15_DA15.0=FSMC_D15,16b-d1
|
||||
SH.FSMC_D15_DA15.ConfNb=1
|
||||
SH.FSMC_D1_DA1.0=FSMC_D1,16b-d1
|
||||
SH.FSMC_D1_DA1.ConfNb=1
|
||||
SH.FSMC_D2_DA2.0=FSMC_D2,16b-d1
|
||||
SH.FSMC_D2_DA2.ConfNb=1
|
||||
SH.FSMC_D3_DA3.0=FSMC_D3,16b-d1
|
||||
SH.FSMC_D3_DA3.ConfNb=1
|
||||
SH.FSMC_D4_DA4.0=FSMC_D4,16b-d1
|
||||
SH.FSMC_D4_DA4.ConfNb=1
|
||||
SH.FSMC_D5_DA5.0=FSMC_D5,16b-d1
|
||||
SH.FSMC_D5_DA5.ConfNb=1
|
||||
SH.FSMC_D6_DA6.0=FSMC_D6,16b-d1
|
||||
SH.FSMC_D6_DA6.ConfNb=1
|
||||
SH.FSMC_D7_DA7.0=FSMC_D7,16b-d1
|
||||
SH.FSMC_D7_DA7.ConfNb=1
|
||||
SH.FSMC_D8_DA8.0=FSMC_D8,16b-d1
|
||||
SH.FSMC_D8_DA8.ConfNb=1
|
||||
SH.FSMC_D9_DA9.0=FSMC_D9,16b-d1
|
||||
SH.FSMC_D9_DA9.ConfNb=1
|
||||
SH.FSMC_NBL0.0=FSMC_NBL0,2ByteEnable1
|
||||
SH.FSMC_NBL0.ConfNb=1
|
||||
SH.FSMC_NBL1.0=FSMC_NBL1,2ByteEnable1
|
||||
SH.FSMC_NBL1.ConfNb=1
|
||||
SH.FSMC_NOE.0=FSMC_NOE,Sram1
|
||||
SH.FSMC_NOE.ConfNb=1
|
||||
SH.FSMC_NWE.0=FSMC_NWE,Sram1
|
||||
SH.FSMC_NWE.ConfNb=1
|
||||
SPI1.CalculateBaudRate=42.0 MBits/s
|
||||
SPI1.Direction=SPI_DIRECTION_2LINES
|
||||
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate
|
||||
SPI1.Mode=SPI_MODE_MASTER
|
||||
SPI1.VirtualType=VM_MASTER
|
||||
SPI2.CalculateBaudRate=21.0 MBits/s
|
||||
SPI2.Direction=SPI_DIRECTION_2LINES
|
||||
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate
|
||||
SPI2.Mode=SPI_MODE_MASTER
|
||||
SPI2.VirtualType=VM_MASTER
|
||||
SPI3.CalculateBaudRate=21.0 MBits/s
|
||||
SPI3.Direction=SPI_DIRECTION_2LINES
|
||||
SPI3.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate
|
||||
SPI3.Mode=SPI_MODE_MASTER
|
||||
SPI3.VirtualType=VM_MASTER
|
||||
UART4.IPParameters=VirtualMode
|
||||
UART4.VirtualMode=Asynchronous
|
||||
USART1.IPParameters=VirtualMode
|
||||
USART1.VirtualMode=VM_ASYNC
|
||||
USART2.IPParameters=VirtualMode
|
||||
USART2.VirtualMode=VM_ASYNC
|
||||
USART3.IPParameters=VirtualMode
|
||||
USART3.VirtualMode=VM_ASYNC
|
||||
VP_IWDG_VS_IWDG.Mode=IWDG_Activate
|
||||
VP_IWDG_VS_IWDG.Signal=IWDG_VS_IWDG
|
||||
VP_RTC_VS_RTC_Activate.Mode=RTC_Enabled
|
||||
VP_RTC_VS_RTC_Activate.Signal=RTC_VS_RTC_Activate
|
||||
VP_SYS_VS_Systick.Mode=SysTick
|
||||
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
|
||||
VP_TIM11_VS_ClockSourceINT.Mode=Enable_Timer
|
||||
VP_TIM11_VS_ClockSourceINT.Signal=TIM11_VS_ClockSourceINT
|
||||
VP_TIM13_VS_ClockSourceINT.Mode=Enable_Timer
|
||||
VP_TIM13_VS_ClockSourceINT.Signal=TIM13_VS_ClockSourceINT
|
||||
VP_TIM14_VS_ClockSourceINT.Mode=Enable_Timer
|
||||
VP_TIM14_VS_ClockSourceINT.Signal=TIM14_VS_ClockSourceINT
|
||||
VP_TIM2_VS_ClockSourceINT.Mode=Internal
|
||||
VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT
|
||||
board=custom
|
|
@ -0,0 +1,91 @@
|
|||
/* USER CODE BEGIN Header */
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file : main.h
|
||||
* @brief : Header for main.c file.
|
||||
* This file contains the common defines of the application.
|
||||
******************************************************************************
|
||||
** This notice applies to any and all portions of this file
|
||||
* that are not between comment pairs USER CODE BEGIN and
|
||||
* USER CODE END. Other portions of this file, whether
|
||||
* inserted by the user or by software development tools
|
||||
* are owned by their respective copyright owners.
|
||||
*
|
||||
* COPYRIGHT(c) 2018 STMicroelectronics
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. 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.
|
||||
* 3. Neither the name of STMicroelectronics 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 HOLDER 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/* USER CODE END Header */
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __MAIN_H
|
||||
#define __MAIN_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "stm32f4xx_hal.h"
|
||||
|
||||
/* Private includes ----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN Includes */
|
||||
#include <rtthread.h>
|
||||
/* USER CODE END Includes */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN ET */
|
||||
|
||||
/* USER CODE END ET */
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* USER CODE BEGIN EC */
|
||||
|
||||
/* USER CODE END EC */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN EM */
|
||||
|
||||
/* USER CODE END EM */
|
||||
|
||||
/* Exported functions prototypes ---------------------------------------------*/
|
||||
void Error_Handler(void);
|
||||
|
||||
/* USER CODE BEGIN EFP */
|
||||
|
||||
/* USER CODE END EFP */
|
||||
|
||||
/* Private defines -----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN Private defines */
|
||||
|
||||
/* USER CODE END Private defines */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __MAIN_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,442 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f4xx_hal_conf_template.h
|
||||
* @author MCD Application Team
|
||||
* @brief HAL configuration template file.
|
||||
* This file should be copied to the application folder and renamed
|
||||
* to stm32f4xx_hal_conf.h.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2017 STMicroelectronics.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* This software component is licensed by ST under BSD 3-Clause license,
|
||||
* the "License"; You may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at:
|
||||
* opensource.org/licenses/BSD-3-Clause
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F4xx_HAL_CONF_H
|
||||
#define __STM32F4xx_HAL_CONF_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* ########################## Module Selection ############################## */
|
||||
/**
|
||||
* @brief This is the list of modules to be used in the HAL driver
|
||||
*/
|
||||
#define HAL_MODULE_ENABLED
|
||||
|
||||
/* #define HAL_ADC_MODULE_ENABLED */
|
||||
/* #define HAL_CRYP_MODULE_ENABLED */
|
||||
#define HAL_CAN_MODULE_ENABLED
|
||||
/* #define HAL_CRC_MODULE_ENABLED */
|
||||
/* #define HAL_CRYP_MODULE_ENABLED */
|
||||
/* #define HAL_DAC_MODULE_ENABLED */
|
||||
/* #define HAL_DCMI_MODULE_ENABLED */
|
||||
/* #define HAL_DMA2D_MODULE_ENABLED */
|
||||
/* #define HAL_ETH_MODULE_ENABLED */
|
||||
/* #define HAL_NAND_MODULE_ENABLED */
|
||||
/* #define HAL_NOR_MODULE_ENABLED */
|
||||
/* #define HAL_PCCARD_MODULE_ENABLED */
|
||||
#define HAL_SRAM_MODULE_ENABLED
|
||||
/* #define HAL_SDRAM_MODULE_ENABLED */
|
||||
/* #define HAL_HASH_MODULE_ENABLED */
|
||||
#define HAL_I2C_MODULE_ENABLED
|
||||
/* #define HAL_I2S_MODULE_ENABLED */
|
||||
#define HAL_IWDG_MODULE_ENABLED
|
||||
/* #define HAL_LTDC_MODULE_ENABLED */
|
||||
/* #define HAL_RNG_MODULE_ENABLED */
|
||||
#define HAL_RTC_MODULE_ENABLED
|
||||
/* #define HAL_SAI_MODULE_ENABLED */
|
||||
#define HAL_SD_MODULE_ENABLED
|
||||
/* #define HAL_MMC_MODULE_ENABLED */
|
||||
#define HAL_SPI_MODULE_ENABLED
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
#define HAL_UART_MODULE_ENABLED
|
||||
/* #define HAL_USART_MODULE_ENABLED */
|
||||
/* #define HAL_IRDA_MODULE_ENABLED */
|
||||
/* #define HAL_SMARTCARD_MODULE_ENABLED */
|
||||
/* #define HAL_SMBUS_MODULE_ENABLED */
|
||||
/* #define HAL_WWDG_MODULE_ENABLED */
|
||||
/* #define HAL_PCD_MODULE_ENABLED */
|
||||
/* #define HAL_HCD_MODULE_ENABLED */
|
||||
/* #define HAL_DSI_MODULE_ENABLED */
|
||||
/* #define HAL_QSPI_MODULE_ENABLED */
|
||||
/* #define HAL_QSPI_MODULE_ENABLED */
|
||||
/* #define HAL_CEC_MODULE_ENABLED */
|
||||
/* #define HAL_FMPI2C_MODULE_ENABLED */
|
||||
/* #define HAL_SPDIFRX_MODULE_ENABLED */
|
||||
/* #define HAL_DFSDM_MODULE_ENABLED */
|
||||
/* #define HAL_LPTIM_MODULE_ENABLED */
|
||||
#define HAL_GPIO_MODULE_ENABLED
|
||||
#define HAL_EXTI_MODULE_ENABLED
|
||||
#define HAL_DMA_MODULE_ENABLED
|
||||
#define HAL_RCC_MODULE_ENABLED
|
||||
#define HAL_FLASH_MODULE_ENABLED
|
||||
#define HAL_PWR_MODULE_ENABLED
|
||||
#define HAL_CORTEX_MODULE_ENABLED
|
||||
|
||||
/* ########################## HSE/HSI Values adaptation ##################### */
|
||||
/**
|
||||
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSE is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||
#define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */
|
||||
#endif /* HSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief Internal High Speed oscillator (HSI) value.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSI is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* HSI_VALUE */
|
||||
|
||||
/**
|
||||
* @brief Internal Low Speed oscillator (LSI) value.
|
||||
*/
|
||||
#if !defined (LSI_VALUE)
|
||||
#define LSI_VALUE ((uint32_t)32000U) /*!< LSI Typical Value in Hz*/
|
||||
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
|
||||
The real value may vary depending on the variations
|
||||
in voltage and temperature.*/
|
||||
/**
|
||||
* @brief External Low Speed oscillator (LSE) value.
|
||||
*/
|
||||
#if !defined (LSE_VALUE)
|
||||
#define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */
|
||||
#endif /* LSE_VALUE */
|
||||
|
||||
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */
|
||||
#endif /* LSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief External clock source for I2S peripheral
|
||||
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||
*/
|
||||
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||
#define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the External audio frequency in Hz*/
|
||||
#endif /* EXTERNAL_CLOCK_VALUE */
|
||||
|
||||
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||
|
||||
/* ########################### System Configuration ######################### */
|
||||
/**
|
||||
* @brief This is the HAL system configuration section
|
||||
*/
|
||||
#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
|
||||
#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */
|
||||
#define USE_RTOS 0U
|
||||
#define PREFETCH_ENABLE 1U
|
||||
#define INSTRUCTION_CACHE_ENABLE 1U
|
||||
#define DATA_CACHE_ENABLE 1U
|
||||
|
||||
/* ########################## Assert Selection ############################## */
|
||||
/**
|
||||
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||
* HAL drivers code
|
||||
*/
|
||||
/* #define USE_FULL_ASSERT 1U */
|
||||
|
||||
/* ################## Ethernet peripheral configuration ##################### */
|
||||
|
||||
/* Section 1 : Ethernet peripheral configuration */
|
||||
|
||||
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
|
||||
#define MAC_ADDR0 2U
|
||||
#define MAC_ADDR1 0U
|
||||
#define MAC_ADDR2 0U
|
||||
#define MAC_ADDR3 0U
|
||||
#define MAC_ADDR4 0U
|
||||
#define MAC_ADDR5 0U
|
||||
|
||||
/* Definition of the Ethernet driver buffers size and count */
|
||||
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
|
||||
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
|
||||
#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
|
||||
#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
|
||||
|
||||
/* Section 2: PHY configuration section */
|
||||
|
||||
/* DP83848_PHY_ADDRESS Address*/
|
||||
#define DP83848_PHY_ADDRESS 0x01U
|
||||
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
|
||||
#define PHY_RESET_DELAY ((uint32_t)0x000000FFU)
|
||||
/* PHY Configuration delay */
|
||||
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFFU)
|
||||
|
||||
#define PHY_READ_TO ((uint32_t)0x0000FFFFU)
|
||||
#define PHY_WRITE_TO ((uint32_t)0x0000FFFFU)
|
||||
|
||||
/* Section 3: Common PHY Registers */
|
||||
|
||||
#define PHY_BCR ((uint16_t)0x0000U) /*!< Transceiver Basic Control Register */
|
||||
#define PHY_BSR ((uint16_t)0x0001U) /*!< Transceiver Basic Status Register */
|
||||
|
||||
#define PHY_RESET ((uint16_t)0x8000U) /*!< PHY Reset */
|
||||
#define PHY_LOOPBACK ((uint16_t)0x4000U) /*!< Select loop-back mode */
|
||||
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100U) /*!< Set the full-duplex mode at 100 Mb/s */
|
||||
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000U) /*!< Set the half-duplex mode at 100 Mb/s */
|
||||
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100U) /*!< Set the full-duplex mode at 10 Mb/s */
|
||||
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000U) /*!< Set the half-duplex mode at 10 Mb/s */
|
||||
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000U) /*!< Enable auto-negotiation function */
|
||||
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200U) /*!< Restart auto-negotiation function */
|
||||
#define PHY_POWERDOWN ((uint16_t)0x0800U) /*!< Select the power down mode */
|
||||
#define PHY_ISOLATE ((uint16_t)0x0400U) /*!< Isolate PHY from MII */
|
||||
|
||||
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020U) /*!< Auto-Negotiation process completed */
|
||||
#define PHY_LINKED_STATUS ((uint16_t)0x0004U) /*!< Valid link established */
|
||||
#define PHY_JABBER_DETECTION ((uint16_t)0x0002U) /*!< Jabber condition detected */
|
||||
|
||||
/* Section 4: Extended PHY Registers */
|
||||
#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */
|
||||
|
||||
#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */
|
||||
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */
|
||||
|
||||
/* ################## SPI peripheral configuration ########################## */
|
||||
|
||||
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
|
||||
* Activated: CRC code is present inside driver
|
||||
* Deactivated: CRC code cleaned from driver
|
||||
*/
|
||||
|
||||
#define USE_SPI_CRC 0U
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Include module's header file
|
||||
*/
|
||||
|
||||
#ifdef HAL_RCC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_rcc.h"
|
||||
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_EXTI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_exti.h"
|
||||
#endif /* HAL_EXTI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_gpio.h"
|
||||
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DMA_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dma.h"
|
||||
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_cortex.h"
|
||||
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ADC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_adc.h"
|
||||
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CAN_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_can.h"
|
||||
#endif /* HAL_CAN_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_crc.h"
|
||||
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRYP_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_cryp.h"
|
||||
#endif /* HAL_CRYP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMBUS_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_smbus.h"
|
||||
#endif /* HAL_SMBUS_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DMA2D_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dma2d.h"
|
||||
#endif /* HAL_DMA2D_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DAC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dac.h"
|
||||
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DCMI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dcmi.h"
|
||||
#endif /* HAL_DCMI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ETH_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_eth.h"
|
||||
#endif /* HAL_ETH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_flash.h"
|
||||
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sram.h"
|
||||
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NOR_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_nor.h"
|
||||
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NAND_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_nand.h"
|
||||
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCCARD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_pccard.h"
|
||||
#endif /* HAL_PCCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SDRAM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sdram.h"
|
||||
#endif /* HAL_SDRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_HASH_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_hash.h"
|
||||
#endif /* HAL_HASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_i2c.h"
|
||||
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2S_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_i2s.h"
|
||||
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_iwdg.h"
|
||||
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_LTDC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_ltdc.h"
|
||||
#endif /* HAL_LTDC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PWR_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_pwr.h"
|
||||
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RNG_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_rng.h"
|
||||
#endif /* HAL_RNG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RTC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_rtc.h"
|
||||
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SAI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sai.h"
|
||||
#endif /* HAL_SAI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sd.h"
|
||||
#endif /* HAL_SD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_MMC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_mmc.h"
|
||||
#endif /* HAL_MMC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_spi.h"
|
||||
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_TIM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_tim.h"
|
||||
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_uart.h"
|
||||
#endif /* HAL_UART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_USART_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_usart.h"
|
||||
#endif /* HAL_USART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_irda.h"
|
||||
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_smartcard.h"
|
||||
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_wwdg.h"
|
||||
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_pcd.h"
|
||||
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_HCD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_hcd.h"
|
||||
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DSI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dsi.h"
|
||||
#endif /* HAL_DSI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_QSPI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_qspi.h"
|
||||
#endif /* HAL_QSPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CEC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_cec.h"
|
||||
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FMPI2C_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_fmpi2c.h"
|
||||
#endif /* HAL_FMPI2C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SPDIFRX_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_spdifrx.h"
|
||||
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DFSDM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dfsdm.h"
|
||||
#endif /* HAL_DFSDM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_LPTIM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_lptim.h"
|
||||
#endif /* HAL_LPTIM_MODULE_ENABLED */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert_failed(uint8_t* file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0U)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __STM32F4xx_HAL_CONF_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,84 @@
|
|||
/* USER CODE BEGIN Header */
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f4xx_it.h
|
||||
* @brief This file contains the headers of the interrupt handlers.
|
||||
******************************************************************************
|
||||
*
|
||||
* COPYRIGHT(c) 2018 STMicroelectronics
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. 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.
|
||||
* 3. Neither the name of STMicroelectronics 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 HOLDER 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/* USER CODE END Header */
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F4xx_IT_H
|
||||
#define __STM32F4xx_IT_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Private includes ----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN Includes */
|
||||
|
||||
/* USER CODE END Includes */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN ET */
|
||||
|
||||
/* USER CODE END ET */
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* USER CODE BEGIN EC */
|
||||
|
||||
/* USER CODE END EC */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN EM */
|
||||
|
||||
/* USER CODE END EM */
|
||||
|
||||
/* Exported functions prototypes ---------------------------------------------*/
|
||||
void NMI_Handler(void);
|
||||
void HardFault_Handler(void);
|
||||
void MemManage_Handler(void);
|
||||
void BusFault_Handler(void);
|
||||
void UsageFault_Handler(void);
|
||||
void SVC_Handler(void);
|
||||
void DebugMon_Handler(void);
|
||||
void PendSV_Handler(void);
|
||||
void SysTick_Handler(void);
|
||||
/* USER CODE BEGIN EFP */
|
||||
|
||||
/* USER CODE END EFP */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __STM32F4xx_IT_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,920 @@
|
|||
/* USER CODE BEGIN Header */
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file : main.c
|
||||
* @brief : Main program body
|
||||
******************************************************************************
|
||||
** This notice applies to any and all portions of this file
|
||||
* that are not between comment pairs USER CODE BEGIN and
|
||||
* USER CODE END. Other portions of this file, whether
|
||||
* inserted by the user or by software development tools
|
||||
* are owned by their respective copyright owners.
|
||||
*
|
||||
* COPYRIGHT(c) 2018 STMicroelectronics
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. 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.
|
||||
* 3. Neither the name of STMicroelectronics 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 HOLDER 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/* USER CODE END Header */
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "main.h"
|
||||
|
||||
/* Private includes ----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN Includes */
|
||||
|
||||
/* USER CODE END Includes */
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN PTD */
|
||||
|
||||
/* USER CODE END PTD */
|
||||
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN PD */
|
||||
|
||||
/* USER CODE END PD */
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN PM */
|
||||
|
||||
/* USER CODE END PM */
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
CAN_HandleTypeDef hcan1;
|
||||
|
||||
I2C_HandleTypeDef hi2c1;
|
||||
|
||||
IWDG_HandleTypeDef hiwdg;
|
||||
|
||||
RTC_HandleTypeDef hrtc;
|
||||
|
||||
SD_HandleTypeDef hsd;
|
||||
|
||||
SPI_HandleTypeDef hspi1;
|
||||
SPI_HandleTypeDef hspi2;
|
||||
SPI_HandleTypeDef hspi3;
|
||||
|
||||
TIM_HandleTypeDef htim2;
|
||||
TIM_HandleTypeDef htim11;
|
||||
TIM_HandleTypeDef htim13;
|
||||
TIM_HandleTypeDef htim14;
|
||||
|
||||
UART_HandleTypeDef huart4;
|
||||
UART_HandleTypeDef huart1;
|
||||
UART_HandleTypeDef huart2;
|
||||
UART_HandleTypeDef huart3;
|
||||
|
||||
SRAM_HandleTypeDef hsram1;
|
||||
|
||||
/* USER CODE BEGIN PV */
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
|
||||
/* USER CODE END PV */
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
void SystemClock_Config(void);
|
||||
static void MX_GPIO_Init(void);
|
||||
static void MX_USART1_UART_Init(void);
|
||||
static void MX_USART3_UART_Init(void);
|
||||
static void MX_RTC_Init(void);
|
||||
static void MX_IWDG_Init(void);
|
||||
static void MX_TIM14_Init(void);
|
||||
static void MX_TIM13_Init(void);
|
||||
static void MX_TIM11_Init(void);
|
||||
static void MX_SDIO_SD_Init(void);
|
||||
static void MX_TIM2_Init(void);
|
||||
static void MX_SPI2_Init(void);
|
||||
static void MX_FSMC_Init(void);
|
||||
static void MX_UART4_Init(void);
|
||||
static void MX_USART2_UART_Init(void);
|
||||
static void MX_CAN1_Init(void);
|
||||
static void MX_I2C1_Init(void);
|
||||
static void MX_SPI1_Init(void);
|
||||
static void MX_SPI3_Init(void);
|
||||
/* USER CODE BEGIN PFP */
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
|
||||
/* USER CODE END PFP */
|
||||
|
||||
/* Private user code ---------------------------------------------------------*/
|
||||
/* USER CODE BEGIN 0 */
|
||||
|
||||
/* USER CODE END 0 */
|
||||
|
||||
/**
|
||||
* @brief The application entry point.
|
||||
* @retval int
|
||||
*/
|
||||
int main(void)
|
||||
{
|
||||
/* USER CODE BEGIN 1 */
|
||||
|
||||
/* USER CODE END 1 */
|
||||
|
||||
/* MCU Configuration--------------------------------------------------------*/
|
||||
|
||||
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
|
||||
HAL_Init();
|
||||
|
||||
/* USER CODE BEGIN Init */
|
||||
|
||||
/* USER CODE END Init */
|
||||
|
||||
/* Configure the system clock */
|
||||
SystemClock_Config();
|
||||
|
||||
/* USER CODE BEGIN SysInit */
|
||||
|
||||
/* USER CODE END SysInit */
|
||||
|
||||
/* Initialize all configured peripherals */
|
||||
MX_GPIO_Init();
|
||||
MX_USART1_UART_Init();
|
||||
MX_USART3_UART_Init();
|
||||
MX_RTC_Init();
|
||||
MX_IWDG_Init();
|
||||
MX_TIM14_Init();
|
||||
MX_TIM13_Init();
|
||||
MX_TIM11_Init();
|
||||
MX_SDIO_SD_Init();
|
||||
MX_TIM2_Init();
|
||||
MX_SPI2_Init();
|
||||
MX_FSMC_Init();
|
||||
MX_UART4_Init();
|
||||
MX_USART2_UART_Init();
|
||||
MX_CAN1_Init();
|
||||
MX_I2C1_Init();
|
||||
MX_SPI1_Init();
|
||||
MX_SPI3_Init();
|
||||
/* USER CODE BEGIN 2 */
|
||||
|
||||
/* USER CODE END 2 */
|
||||
|
||||
/* Infinite loop */
|
||||
/* USER CODE BEGIN WHILE */
|
||||
while (1)
|
||||
{
|
||||
|
||||
/* USER CODE END WHILE */
|
||||
|
||||
/* USER CODE BEGIN 3 */
|
||||
|
||||
}
|
||||
/* USER CODE END 3 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief System Clock Configuration
|
||||
* @retval None
|
||||
*/
|
||||
void SystemClock_Config(void)
|
||||
{
|
||||
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
|
||||
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
|
||||
|
||||
/** Configure the main internal regulator output voltage
|
||||
*/
|
||||
__HAL_RCC_PWR_CLK_ENABLE();
|
||||
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
|
||||
/** Initializes the CPU, AHB and APB busses clocks
|
||||
*/
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE
|
||||
|RCC_OSCILLATORTYPE_LSE;
|
||||
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
|
||||
RCC_OscInitStruct.LSEState = RCC_LSE_ON;
|
||||
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
|
||||
RCC_OscInitStruct.PLL.PLLM = 4;
|
||||
RCC_OscInitStruct.PLL.PLLN = 168;
|
||||
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = 7;
|
||||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/** Initializes the CPU, AHB and APB busses clocks
|
||||
*/
|
||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|
||||
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
|
||||
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
|
||||
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
|
||||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
|
||||
|
||||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC;
|
||||
PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief CAN1 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_CAN1_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN CAN1_Init 0 */
|
||||
|
||||
/* USER CODE END CAN1_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN CAN1_Init 1 */
|
||||
|
||||
/* USER CODE END CAN1_Init 1 */
|
||||
hcan1.Instance = CAN1;
|
||||
hcan1.Init.Prescaler = 16;
|
||||
hcan1.Init.Mode = CAN_MODE_NORMAL;
|
||||
hcan1.Init.SyncJumpWidth = CAN_SJW_1TQ;
|
||||
hcan1.Init.TimeSeg1 = CAN_BS1_1TQ;
|
||||
hcan1.Init.TimeSeg2 = CAN_BS2_1TQ;
|
||||
hcan1.Init.TimeTriggeredMode = DISABLE;
|
||||
hcan1.Init.AutoBusOff = DISABLE;
|
||||
hcan1.Init.AutoWakeUp = DISABLE;
|
||||
hcan1.Init.AutoRetransmission = DISABLE;
|
||||
hcan1.Init.ReceiveFifoLocked = DISABLE;
|
||||
hcan1.Init.TransmitFifoPriority = DISABLE;
|
||||
if (HAL_CAN_Init(&hcan1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN CAN1_Init 2 */
|
||||
|
||||
/* USER CODE END CAN1_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief I2C1 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_I2C1_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN I2C1_Init 0 */
|
||||
|
||||
/* USER CODE END I2C1_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN I2C1_Init 1 */
|
||||
|
||||
/* USER CODE END I2C1_Init 1 */
|
||||
hi2c1.Instance = I2C1;
|
||||
hi2c1.Init.ClockSpeed = 100000;
|
||||
hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2;
|
||||
hi2c1.Init.OwnAddress1 = 0;
|
||||
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
|
||||
hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
|
||||
hi2c1.Init.OwnAddress2 = 0;
|
||||
hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
|
||||
hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
|
||||
if (HAL_I2C_Init(&hi2c1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN I2C1_Init 2 */
|
||||
|
||||
/* USER CODE END I2C1_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief IWDG Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_IWDG_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN IWDG_Init 0 */
|
||||
|
||||
/* USER CODE END IWDG_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN IWDG_Init 1 */
|
||||
|
||||
/* USER CODE END IWDG_Init 1 */
|
||||
hiwdg.Instance = IWDG;
|
||||
hiwdg.Init.Prescaler = IWDG_PRESCALER_4;
|
||||
hiwdg.Init.Reload = 4095;
|
||||
if (HAL_IWDG_Init(&hiwdg) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN IWDG_Init 2 */
|
||||
|
||||
/* USER CODE END IWDG_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief RTC Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_RTC_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN RTC_Init 0 */
|
||||
|
||||
/* USER CODE END RTC_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN RTC_Init 1 */
|
||||
|
||||
/* USER CODE END RTC_Init 1 */
|
||||
/** Initialize RTC Only
|
||||
*/
|
||||
hrtc.Instance = RTC;
|
||||
hrtc.Init.HourFormat = RTC_HOURFORMAT_24;
|
||||
hrtc.Init.AsynchPrediv = 127;
|
||||
hrtc.Init.SynchPrediv = 255;
|
||||
hrtc.Init.OutPut = RTC_OUTPUT_DISABLE;
|
||||
hrtc.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH;
|
||||
hrtc.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN;
|
||||
if (HAL_RTC_Init(&hrtc) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN RTC_Init 2 */
|
||||
|
||||
/* USER CODE END RTC_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SDIO Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_SDIO_SD_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN SDIO_Init 0 */
|
||||
|
||||
/* USER CODE END SDIO_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN SDIO_Init 1 */
|
||||
|
||||
/* USER CODE END SDIO_Init 1 */
|
||||
hsd.Instance = SDIO;
|
||||
hsd.Init.ClockEdge = SDIO_CLOCK_EDGE_RISING;
|
||||
hsd.Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE;
|
||||
hsd.Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE;
|
||||
hsd.Init.BusWide = SDIO_BUS_WIDE_1B;
|
||||
hsd.Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE;
|
||||
hsd.Init.ClockDiv = 0;
|
||||
if (HAL_SD_Init(&hsd) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
if (HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN SDIO_Init 2 */
|
||||
|
||||
/* USER CODE END SDIO_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SPI1 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_SPI1_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN SPI1_Init 0 */
|
||||
|
||||
/* USER CODE END SPI1_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN SPI1_Init 1 */
|
||||
|
||||
/* USER CODE END SPI1_Init 1 */
|
||||
/* SPI1 parameter configuration*/
|
||||
hspi1.Instance = SPI1;
|
||||
hspi1.Init.Mode = SPI_MODE_MASTER;
|
||||
hspi1.Init.Direction = SPI_DIRECTION_2LINES;
|
||||
hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||
hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
|
||||
hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||
hspi1.Init.NSS = SPI_NSS_SOFT;
|
||||
hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
|
||||
hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||
hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
|
||||
hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||
hspi1.Init.CRCPolynomial = 10;
|
||||
if (HAL_SPI_Init(&hspi1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN SPI1_Init 2 */
|
||||
|
||||
/* USER CODE END SPI1_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SPI2 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_SPI2_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN SPI2_Init 0 */
|
||||
|
||||
/* USER CODE END SPI2_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN SPI2_Init 1 */
|
||||
|
||||
/* USER CODE END SPI2_Init 1 */
|
||||
/* SPI2 parameter configuration*/
|
||||
hspi2.Instance = SPI2;
|
||||
hspi2.Init.Mode = SPI_MODE_MASTER;
|
||||
hspi2.Init.Direction = SPI_DIRECTION_2LINES;
|
||||
hspi2.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||
hspi2.Init.CLKPolarity = SPI_POLARITY_LOW;
|
||||
hspi2.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||
hspi2.Init.NSS = SPI_NSS_SOFT;
|
||||
hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
|
||||
hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||
hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
|
||||
hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||
hspi2.Init.CRCPolynomial = 10;
|
||||
if (HAL_SPI_Init(&hspi2) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN SPI2_Init 2 */
|
||||
|
||||
/* USER CODE END SPI2_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SPI3 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_SPI3_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN SPI3_Init 0 */
|
||||
|
||||
/* USER CODE END SPI3_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN SPI3_Init 1 */
|
||||
|
||||
/* USER CODE END SPI3_Init 1 */
|
||||
/* SPI3 parameter configuration*/
|
||||
hspi3.Instance = SPI3;
|
||||
hspi3.Init.Mode = SPI_MODE_MASTER;
|
||||
hspi3.Init.Direction = SPI_DIRECTION_2LINES;
|
||||
hspi3.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||
hspi3.Init.CLKPolarity = SPI_POLARITY_LOW;
|
||||
hspi3.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||
hspi3.Init.NSS = SPI_NSS_SOFT;
|
||||
hspi3.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
|
||||
hspi3.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||
hspi3.Init.TIMode = SPI_TIMODE_DISABLE;
|
||||
hspi3.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||
hspi3.Init.CRCPolynomial = 10;
|
||||
if (HAL_SPI_Init(&hspi3) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN SPI3_Init 2 */
|
||||
|
||||
/* USER CODE END SPI3_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM2 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_TIM2_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN TIM2_Init 0 */
|
||||
|
||||
/* USER CODE END TIM2_Init 0 */
|
||||
|
||||
TIM_ClockConfigTypeDef sClockSourceConfig = {0};
|
||||
TIM_MasterConfigTypeDef sMasterConfig = {0};
|
||||
|
||||
/* USER CODE BEGIN TIM2_Init 1 */
|
||||
|
||||
/* USER CODE END TIM2_Init 1 */
|
||||
htim2.Instance = TIM2;
|
||||
htim2.Init.Prescaler = 0;
|
||||
htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
htim2.Init.Period = 0;
|
||||
htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||
if (HAL_TIM_Base_Init(&htim2) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
|
||||
if (HAL_TIM_ConfigClockSource(&htim2, &sClockSourceConfig) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
|
||||
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
|
||||
if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN TIM2_Init 2 */
|
||||
|
||||
/* USER CODE END TIM2_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM11 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_TIM11_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN TIM11_Init 0 */
|
||||
|
||||
/* USER CODE END TIM11_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN TIM11_Init 1 */
|
||||
|
||||
/* USER CODE END TIM11_Init 1 */
|
||||
htim11.Instance = TIM11;
|
||||
htim11.Init.Prescaler = 0;
|
||||
htim11.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
htim11.Init.Period = 0;
|
||||
htim11.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
htim11.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||
if (HAL_TIM_Base_Init(&htim11) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN TIM11_Init 2 */
|
||||
|
||||
/* USER CODE END TIM11_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM13 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_TIM13_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN TIM13_Init 0 */
|
||||
|
||||
/* USER CODE END TIM13_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN TIM13_Init 1 */
|
||||
|
||||
/* USER CODE END TIM13_Init 1 */
|
||||
htim13.Instance = TIM13;
|
||||
htim13.Init.Prescaler = 0;
|
||||
htim13.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
htim13.Init.Period = 0;
|
||||
htim13.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
htim13.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||
if (HAL_TIM_Base_Init(&htim13) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN TIM13_Init 2 */
|
||||
|
||||
/* USER CODE END TIM13_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM14 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_TIM14_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN TIM14_Init 0 */
|
||||
|
||||
/* USER CODE END TIM14_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN TIM14_Init 1 */
|
||||
|
||||
/* USER CODE END TIM14_Init 1 */
|
||||
htim14.Instance = TIM14;
|
||||
htim14.Init.Prescaler = 0;
|
||||
htim14.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
htim14.Init.Period = 0;
|
||||
htim14.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
htim14.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||
if (HAL_TIM_Base_Init(&htim14) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN TIM14_Init 2 */
|
||||
|
||||
/* USER CODE END TIM14_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief UART4 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_UART4_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN UART4_Init 0 */
|
||||
|
||||
/* USER CODE END UART4_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN UART4_Init 1 */
|
||||
|
||||
/* USER CODE END UART4_Init 1 */
|
||||
huart4.Instance = UART4;
|
||||
huart4.Init.BaudRate = 115200;
|
||||
huart4.Init.WordLength = UART_WORDLENGTH_8B;
|
||||
huart4.Init.StopBits = UART_STOPBITS_1;
|
||||
huart4.Init.Parity = UART_PARITY_NONE;
|
||||
huart4.Init.Mode = UART_MODE_TX_RX;
|
||||
huart4.Init.HwFlowCtl = UART_HWCONTROL_NONE;
|
||||
huart4.Init.OverSampling = UART_OVERSAMPLING_16;
|
||||
if (HAL_UART_Init(&huart4) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN UART4_Init 2 */
|
||||
|
||||
/* USER CODE END UART4_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USART1 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_USART1_UART_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN USART1_Init 0 */
|
||||
|
||||
/* USER CODE END USART1_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN USART1_Init 1 */
|
||||
|
||||
/* USER CODE END USART1_Init 1 */
|
||||
huart1.Instance = USART1;
|
||||
huart1.Init.BaudRate = 115200;
|
||||
huart1.Init.WordLength = UART_WORDLENGTH_8B;
|
||||
huart1.Init.StopBits = UART_STOPBITS_1;
|
||||
huart1.Init.Parity = UART_PARITY_NONE;
|
||||
huart1.Init.Mode = UART_MODE_TX_RX;
|
||||
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
|
||||
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
|
||||
if (HAL_UART_Init(&huart1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN USART1_Init 2 */
|
||||
|
||||
/* USER CODE END USART1_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USART2 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_USART2_UART_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN USART2_Init 0 */
|
||||
|
||||
/* USER CODE END USART2_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN USART2_Init 1 */
|
||||
|
||||
/* USER CODE END USART2_Init 1 */
|
||||
huart2.Instance = USART2;
|
||||
huart2.Init.BaudRate = 115200;
|
||||
huart2.Init.WordLength = UART_WORDLENGTH_8B;
|
||||
huart2.Init.StopBits = UART_STOPBITS_1;
|
||||
huart2.Init.Parity = UART_PARITY_NONE;
|
||||
huart2.Init.Mode = UART_MODE_TX_RX;
|
||||
huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
|
||||
huart2.Init.OverSampling = UART_OVERSAMPLING_16;
|
||||
if (HAL_UART_Init(&huart2) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN USART2_Init 2 */
|
||||
|
||||
/* USER CODE END USART2_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USART3 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_USART3_UART_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN USART3_Init 0 */
|
||||
|
||||
/* USER CODE END USART3_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN USART3_Init 1 */
|
||||
|
||||
/* USER CODE END USART3_Init 1 */
|
||||
huart3.Instance = USART3;
|
||||
huart3.Init.BaudRate = 115200;
|
||||
huart3.Init.WordLength = UART_WORDLENGTH_8B;
|
||||
huart3.Init.StopBits = UART_STOPBITS_1;
|
||||
huart3.Init.Parity = UART_PARITY_NONE;
|
||||
huart3.Init.Mode = UART_MODE_TX_RX;
|
||||
huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
|
||||
huart3.Init.OverSampling = UART_OVERSAMPLING_16;
|
||||
if (HAL_UART_Init(&huart3) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN USART3_Init 2 */
|
||||
|
||||
/* USER CODE END USART3_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief GPIO Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_GPIO_Init(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||
|
||||
/* GPIO Ports Clock Enable */
|
||||
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOF_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOH_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOG_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOE_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOD_CLK_ENABLE();
|
||||
|
||||
/*Configure GPIO pin Output Level */
|
||||
HAL_GPIO_WritePin(GPIOG, GPIO_PIN_11|GPIO_PIN_14, GPIO_PIN_RESET);
|
||||
|
||||
/*Configure GPIO pins : PG11 PG14 */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_14;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
|
||||
|
||||
/*Configure GPIO pin : PG13 */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_13;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF11_ETH;
|
||||
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
|
||||
|
||||
}
|
||||
|
||||
/* FSMC initialization function */
|
||||
static void MX_FSMC_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN FSMC_Init 0 */
|
||||
|
||||
/* USER CODE END FSMC_Init 0 */
|
||||
|
||||
FSMC_NORSRAM_TimingTypeDef Timing = {0};
|
||||
|
||||
/* USER CODE BEGIN FSMC_Init 1 */
|
||||
|
||||
/* USER CODE END FSMC_Init 1 */
|
||||
|
||||
/** Perform the SRAM1 memory initialization sequence
|
||||
*/
|
||||
hsram1.Instance = FSMC_NORSRAM_DEVICE;
|
||||
hsram1.Extended = FSMC_NORSRAM_EXTENDED_DEVICE;
|
||||
/* hsram1.Init */
|
||||
hsram1.Init.NSBank = FSMC_NORSRAM_BANK3;
|
||||
hsram1.Init.DataAddressMux = FSMC_DATA_ADDRESS_MUX_DISABLE;
|
||||
hsram1.Init.MemoryType = FSMC_MEMORY_TYPE_SRAM;
|
||||
hsram1.Init.MemoryDataWidth = FSMC_NORSRAM_MEM_BUS_WIDTH_16;
|
||||
hsram1.Init.BurstAccessMode = FSMC_BURST_ACCESS_MODE_DISABLE;
|
||||
hsram1.Init.WaitSignalPolarity = FSMC_WAIT_SIGNAL_POLARITY_LOW;
|
||||
hsram1.Init.WrapMode = FSMC_WRAP_MODE_DISABLE;
|
||||
hsram1.Init.WaitSignalActive = FSMC_WAIT_TIMING_BEFORE_WS;
|
||||
hsram1.Init.WriteOperation = FSMC_WRITE_OPERATION_ENABLE;
|
||||
hsram1.Init.WaitSignal = FSMC_WAIT_SIGNAL_DISABLE;
|
||||
hsram1.Init.ExtendedMode = FSMC_EXTENDED_MODE_DISABLE;
|
||||
hsram1.Init.AsynchronousWait = FSMC_ASYNCHRONOUS_WAIT_DISABLE;
|
||||
hsram1.Init.WriteBurst = FSMC_WRITE_BURST_DISABLE;
|
||||
hsram1.Init.PageSize = FSMC_PAGE_SIZE_NONE;
|
||||
/* Timing */
|
||||
Timing.AddressSetupTime = 15;
|
||||
Timing.AddressHoldTime = 15;
|
||||
Timing.DataSetupTime = 255;
|
||||
Timing.BusTurnAroundDuration = 15;
|
||||
Timing.CLKDivision = 16;
|
||||
Timing.DataLatency = 17;
|
||||
Timing.AccessMode = FSMC_ACCESS_MODE_A;
|
||||
/* ExtTiming */
|
||||
|
||||
if (HAL_SRAM_Init(&hsram1, &Timing, NULL) != HAL_OK)
|
||||
{
|
||||
Error_Handler( );
|
||||
}
|
||||
|
||||
/* USER CODE BEGIN FSMC_Init 2 */
|
||||
|
||||
/* USER CODE END FSMC_Init 2 */
|
||||
}
|
||||
|
||||
/* USER CODE BEGIN 4 */
|
||||
|
||||
/* USER CODE END 4 */
|
||||
|
||||
/**
|
||||
* @brief This function is executed in case of error occurrence.
|
||||
* @retval None
|
||||
*/
|
||||
void Error_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN Error_Handler_Debug */
|
||||
/* User can add his own implementation to report the HAL error return state */
|
||||
while(1)
|
||||
{
|
||||
}
|
||||
/* USER CODE END Error_Handler_Debug */
|
||||
}
|
||||
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief Reports the name of the source file and the source line number
|
||||
* where the assert_param error has occurred.
|
||||
* @param file: pointer to the source file name
|
||||
* @param line: assert_param error line source number
|
||||
* @retval None
|
||||
*/
|
||||
void assert_failed(uint8_t *file, uint32_t line)
|
||||
{
|
||||
/* USER CODE BEGIN 6 */
|
||||
/* User can add his own implementation to report the file name and line number,
|
||||
tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
|
||||
/* USER CODE END 6 */
|
||||
}
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,218 @@
|
|||
/* USER CODE BEGIN Header */
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f4xx_it.c
|
||||
* @brief Interrupt Service Routines.
|
||||
******************************************************************************
|
||||
*
|
||||
* COPYRIGHT(c) 2018 STMicroelectronics
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. 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.
|
||||
* 3. Neither the name of STMicroelectronics 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 HOLDER 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/* USER CODE END Header */
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "main.h"
|
||||
#include "stm32f4xx_it.h"
|
||||
/* Private includes ----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN Includes */
|
||||
/* USER CODE END Includes */
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN TD */
|
||||
|
||||
/* USER CODE END TD */
|
||||
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN PD */
|
||||
|
||||
/* USER CODE END PD */
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* USER CODE BEGIN PM */
|
||||
|
||||
/* USER CODE END PM */
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* USER CODE BEGIN PV */
|
||||
|
||||
/* USER CODE END PV */
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* USER CODE BEGIN PFP */
|
||||
|
||||
/* USER CODE END PFP */
|
||||
|
||||
/* Private user code ---------------------------------------------------------*/
|
||||
/* USER CODE BEGIN 0 */
|
||||
|
||||
/* USER CODE END 0 */
|
||||
|
||||
/* External variables --------------------------------------------------------*/
|
||||
|
||||
/* USER CODE BEGIN EV */
|
||||
|
||||
/* USER CODE END EV */
|
||||
|
||||
/******************************************************************************/
|
||||
/* Cortex-M4 Processor Interruption and Exception Handlers */
|
||||
/******************************************************************************/
|
||||
/**
|
||||
* @brief This function handles Non maskable interrupt.
|
||||
*/
|
||||
void NMI_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
|
||||
|
||||
/* USER CODE END NonMaskableInt_IRQn 0 */
|
||||
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
|
||||
|
||||
/* USER CODE END NonMaskableInt_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles Hard fault interrupt.
|
||||
*/
|
||||
void HardFault_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN HardFault_IRQn 0 */
|
||||
|
||||
/* USER CODE END HardFault_IRQn 0 */
|
||||
while (1)
|
||||
{
|
||||
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
|
||||
/* USER CODE END W1_HardFault_IRQn 0 */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles Memory management fault.
|
||||
*/
|
||||
void MemManage_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN MemoryManagement_IRQn 0 */
|
||||
|
||||
/* USER CODE END MemoryManagement_IRQn 0 */
|
||||
while (1)
|
||||
{
|
||||
/* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
|
||||
/* USER CODE END W1_MemoryManagement_IRQn 0 */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles Pre-fetch fault, memory access fault.
|
||||
*/
|
||||
void BusFault_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN BusFault_IRQn 0 */
|
||||
|
||||
/* USER CODE END BusFault_IRQn 0 */
|
||||
while (1)
|
||||
{
|
||||
/* USER CODE BEGIN W1_BusFault_IRQn 0 */
|
||||
/* USER CODE END W1_BusFault_IRQn 0 */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles Undefined instruction or illegal state.
|
||||
*/
|
||||
void UsageFault_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN UsageFault_IRQn 0 */
|
||||
|
||||
/* USER CODE END UsageFault_IRQn 0 */
|
||||
while (1)
|
||||
{
|
||||
/* USER CODE BEGIN W1_UsageFault_IRQn 0 */
|
||||
/* USER CODE END W1_UsageFault_IRQn 0 */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles System service call via SWI instruction.
|
||||
*/
|
||||
void SVC_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN SVCall_IRQn 0 */
|
||||
|
||||
/* USER CODE END SVCall_IRQn 0 */
|
||||
/* USER CODE BEGIN SVCall_IRQn 1 */
|
||||
|
||||
/* USER CODE END SVCall_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles Debug monitor.
|
||||
*/
|
||||
void DebugMon_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN DebugMonitor_IRQn 0 */
|
||||
|
||||
/* USER CODE END DebugMonitor_IRQn 0 */
|
||||
/* USER CODE BEGIN DebugMonitor_IRQn 1 */
|
||||
|
||||
/* USER CODE END DebugMonitor_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles Pendable request for system service.
|
||||
*/
|
||||
void PendSV_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN PendSV_IRQn 0 */
|
||||
|
||||
/* USER CODE END PendSV_IRQn 0 */
|
||||
/* USER CODE BEGIN PendSV_IRQn 1 */
|
||||
|
||||
/* USER CODE END PendSV_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles System tick timer.
|
||||
*/
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN SysTick_IRQn 0 */
|
||||
|
||||
/* USER CODE END SysTick_IRQn 0 */
|
||||
HAL_IncTick();
|
||||
/* USER CODE BEGIN SysTick_IRQn 1 */
|
||||
|
||||
/* USER CODE END SysTick_IRQn 1 */
|
||||
}
|
||||
|
||||
/******************************************************************************/
|
||||
/* STM32F4xx Peripheral Interrupt Handlers */
|
||||
/* Add here the Interrupt Handlers for the used peripherals. */
|
||||
/* For the available peripheral interrupt handler names, */
|
||||
/* please refer to the startup file (startup_stm32f4xx.s). */
|
||||
/******************************************************************************/
|
||||
|
||||
/* USER CODE BEGIN 1 */
|
||||
|
||||
/* USER CODE END 1 */
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,761 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f4xx.c
|
||||
* @author MCD Application Team
|
||||
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||
*
|
||||
* This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - SystemInit(): This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32f4xx.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
*
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2017 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. 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.
|
||||
* 3. Neither the name of STMicroelectronics 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 HOLDER 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f4xx_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
#include "stm32f4xx.h"
|
||||
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE ((uint32_t)25000000) /*!< Default value of the External oscillator in Hz */
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* HSI_VALUE */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
|
||||
/************************* Miscellaneous Configuration ************************/
|
||||
/*!< Uncomment the following line if you need to use external SRAM or SDRAM as data memory */
|
||||
#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx)\
|
||||
|| defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|
||||
|| defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx)
|
||||
/* #define DATA_IN_ExtSRAM */
|
||||
#endif /* STM32F40xxx || STM32F41xxx || STM32F42xxx || STM32F43xxx || STM32F469xx || STM32F479xx ||\
|
||||
STM32F412Zx || STM32F412Vx */
|
||||
|
||||
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|
||||
|| defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
|
||||
/* #define DATA_IN_ExtSDRAM */
|
||||
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\
|
||||
STM32F479xx */
|
||||
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
/******************************************************************************/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
/* This variable is updated in three ways:
|
||||
1) by calling CMSIS function SystemCoreClockUpdate()
|
||||
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
|
||||
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
|
||||
Note: If you use this function to configure the system clock; then there
|
||||
is no need to call the 2 first functions listed above, since SystemCoreClock
|
||||
variable is updated automatically.
|
||||
*/
|
||||
uint32_t SystemCoreClock = 16000000;
|
||||
const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
|
||||
static void SystemInit_ExtMemCtl(void);
|
||||
#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system
|
||||
* Initialize the FPU setting, vector table location and External memory
|
||||
* configuration.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemInit(void)
|
||||
{
|
||||
/* FPU settings ------------------------------------------------------------*/
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||
#endif
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR |= (uint32_t)0x00000001;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR = 0x00000000;
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||
|
||||
/* Reset PLLCFGR register */
|
||||
RCC->PLLCFGR = 0x24003010;
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIR = 0x00000000;
|
||||
|
||||
#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
|
||||
SystemInit_ExtMemCtl();
|
||||
#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
|
||||
|
||||
/* Configure the Vector Table location add offset address ------------------*/
|
||||
#ifdef VECT_TAB_SRAM
|
||||
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
|
||||
#else
|
||||
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value
|
||||
* 16 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (its value
|
||||
* depends on the application requirements), user has to ensure that HSE_VALUE
|
||||
* is same as the real frequency of the crystal used. Otherwise, this function
|
||||
* may have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate(void)
|
||||
{
|
||||
uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00: /* HSI used as system clock source */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04: /* HSE used as system clock source */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08: /* PLL used as system clock source */
|
||||
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
|
||||
SYSCLK = PLL_VCO / PLL_P
|
||||
*/
|
||||
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
|
||||
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
|
||||
|
||||
if (pllsource != 0)
|
||||
{
|
||||
/* HSE used as PLL clock source */
|
||||
pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* HSI used as PLL clock source */
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
|
||||
pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
|
||||
SystemCoreClock = pllvco/pllp;
|
||||
break;
|
||||
default:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK frequency --------------------------------------------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||
/* HCLK frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
#if defined (DATA_IN_ExtSRAM) && defined (DATA_IN_ExtSDRAM)
|
||||
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|
||||
|| defined(STM32F469xx) || defined(STM32F479xx)
|
||||
/**
|
||||
* @brief Setup the external memory controller.
|
||||
* Called in startup_stm32f4xx.s before jump to main.
|
||||
* This function configures the external memories (SRAM/SDRAM)
|
||||
* This SRAM/SDRAM will be used as program data memory (including heap and stack).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemInit_ExtMemCtl(void)
|
||||
{
|
||||
__IO uint32_t tmp = 0x00;
|
||||
|
||||
register uint32_t tmpreg = 0, timeout = 0xFFFF;
|
||||
register __IO uint32_t index;
|
||||
|
||||
/* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface clock */
|
||||
RCC->AHB1ENR |= 0x000001F8;
|
||||
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);
|
||||
|
||||
/* Connect PDx pins to FMC Alternate function */
|
||||
GPIOD->AFR[0] = 0x00CCC0CC;
|
||||
GPIOD->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PDx pins in Alternate function mode */
|
||||
GPIOD->MODER = 0xAAAA0A8A;
|
||||
/* Configure PDx pins speed to 100 MHz */
|
||||
GPIOD->OSPEEDR = 0xFFFF0FCF;
|
||||
/* Configure PDx pins Output type to push-pull */
|
||||
GPIOD->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PDx pins */
|
||||
GPIOD->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PEx pins to FMC Alternate function */
|
||||
GPIOE->AFR[0] = 0xC00CC0CC;
|
||||
GPIOE->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PEx pins in Alternate function mode */
|
||||
GPIOE->MODER = 0xAAAA828A;
|
||||
/* Configure PEx pins speed to 100 MHz */
|
||||
GPIOE->OSPEEDR = 0xFFFFC3CF;
|
||||
/* Configure PEx pins Output type to push-pull */
|
||||
GPIOE->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PEx pins */
|
||||
GPIOE->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PFx pins to FMC Alternate function */
|
||||
GPIOF->AFR[0] = 0xCCCCCCCC;
|
||||
GPIOF->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PFx pins in Alternate function mode */
|
||||
GPIOF->MODER = 0xAA800AAA;
|
||||
/* Configure PFx pins speed to 50 MHz */
|
||||
GPIOF->OSPEEDR = 0xAA800AAA;
|
||||
/* Configure PFx pins Output type to push-pull */
|
||||
GPIOF->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PFx pins */
|
||||
GPIOF->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PGx pins to FMC Alternate function */
|
||||
GPIOG->AFR[0] = 0xCCCCCCCC;
|
||||
GPIOG->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PGx pins in Alternate function mode */
|
||||
GPIOG->MODER = 0xAAAAAAAA;
|
||||
/* Configure PGx pins speed to 50 MHz */
|
||||
GPIOG->OSPEEDR = 0xAAAAAAAA;
|
||||
/* Configure PGx pins Output type to push-pull */
|
||||
GPIOG->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PGx pins */
|
||||
GPIOG->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PHx pins to FMC Alternate function */
|
||||
GPIOH->AFR[0] = 0x00C0CC00;
|
||||
GPIOH->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PHx pins in Alternate function mode */
|
||||
GPIOH->MODER = 0xAAAA08A0;
|
||||
/* Configure PHx pins speed to 50 MHz */
|
||||
GPIOH->OSPEEDR = 0xAAAA08A0;
|
||||
/* Configure PHx pins Output type to push-pull */
|
||||
GPIOH->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PHx pins */
|
||||
GPIOH->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PIx pins to FMC Alternate function */
|
||||
GPIOI->AFR[0] = 0xCCCCCCCC;
|
||||
GPIOI->AFR[1] = 0x00000CC0;
|
||||
/* Configure PIx pins in Alternate function mode */
|
||||
GPIOI->MODER = 0x0028AAAA;
|
||||
/* Configure PIx pins speed to 50 MHz */
|
||||
GPIOI->OSPEEDR = 0x0028AAAA;
|
||||
/* Configure PIx pins Output type to push-pull */
|
||||
GPIOI->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PIx pins */
|
||||
GPIOI->PUPDR = 0x00000000;
|
||||
|
||||
/*-- FMC Configuration -------------------------------------------------------*/
|
||||
/* Enable the FMC interface clock */
|
||||
RCC->AHB3ENR |= 0x00000001;
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
|
||||
|
||||
FMC_Bank5_6->SDCR[0] = 0x000019E4;
|
||||
FMC_Bank5_6->SDTR[0] = 0x01115351;
|
||||
|
||||
/* SDRAM initialization sequence */
|
||||
/* Clock enable command */
|
||||
FMC_Bank5_6->SDCMR = 0x00000011;
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* Delay */
|
||||
for (index = 0; index<1000; index++);
|
||||
|
||||
/* PALL command */
|
||||
FMC_Bank5_6->SDCMR = 0x00000012;
|
||||
timeout = 0xFFFF;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* Auto refresh command */
|
||||
FMC_Bank5_6->SDCMR = 0x00000073;
|
||||
timeout = 0xFFFF;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* MRD register program */
|
||||
FMC_Bank5_6->SDCMR = 0x00046014;
|
||||
timeout = 0xFFFF;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* Set refresh count */
|
||||
tmpreg = FMC_Bank5_6->SDRTR;
|
||||
FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
|
||||
|
||||
/* Disable write protection */
|
||||
tmpreg = FMC_Bank5_6->SDCR[0];
|
||||
FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
|
||||
|
||||
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)
|
||||
/* Configure and enable Bank1_SRAM2 */
|
||||
FMC_Bank1->BTCR[2] = 0x00001011;
|
||||
FMC_Bank1->BTCR[3] = 0x00000201;
|
||||
FMC_Bank1E->BWTR[2] = 0x0fffffff;
|
||||
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */
|
||||
#if defined(STM32F469xx) || defined(STM32F479xx)
|
||||
/* Configure and enable Bank1_SRAM2 */
|
||||
FMC_Bank1->BTCR[2] = 0x00001091;
|
||||
FMC_Bank1->BTCR[3] = 0x00110212;
|
||||
FMC_Bank1E->BWTR[2] = 0x0fffffff;
|
||||
#endif /* STM32F469xx || STM32F479xx */
|
||||
|
||||
(void)(tmp);
|
||||
}
|
||||
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */
|
||||
#elif defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
|
||||
/**
|
||||
* @brief Setup the external memory controller.
|
||||
* Called in startup_stm32f4xx.s before jump to main.
|
||||
* This function configures the external memories (SRAM/SDRAM)
|
||||
* This SRAM/SDRAM will be used as program data memory (including heap and stack).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemInit_ExtMemCtl(void)
|
||||
{
|
||||
__IO uint32_t tmp = 0x00;
|
||||
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|
||||
|| defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
|
||||
#if defined (DATA_IN_ExtSDRAM)
|
||||
register uint32_t tmpreg = 0, timeout = 0xFFFF;
|
||||
register __IO uint32_t index;
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
/* Enable GPIOA, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG interface
|
||||
clock */
|
||||
RCC->AHB1ENR |= 0x0000007D;
|
||||
#else
|
||||
/* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
|
||||
clock */
|
||||
RCC->AHB1ENR |= 0x000001F8;
|
||||
#endif /* STM32F446xx */
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
/* Connect PAx pins to FMC Alternate function */
|
||||
GPIOA->AFR[0] |= 0xC0000000;
|
||||
GPIOA->AFR[1] |= 0x00000000;
|
||||
/* Configure PDx pins in Alternate function mode */
|
||||
GPIOA->MODER |= 0x00008000;
|
||||
/* Configure PDx pins speed to 50 MHz */
|
||||
GPIOA->OSPEEDR |= 0x00008000;
|
||||
/* Configure PDx pins Output type to push-pull */
|
||||
GPIOA->OTYPER |= 0x00000000;
|
||||
/* No pull-up, pull-down for PDx pins */
|
||||
GPIOA->PUPDR |= 0x00000000;
|
||||
|
||||
/* Connect PCx pins to FMC Alternate function */
|
||||
GPIOC->AFR[0] |= 0x00CC0000;
|
||||
GPIOC->AFR[1] |= 0x00000000;
|
||||
/* Configure PDx pins in Alternate function mode */
|
||||
GPIOC->MODER |= 0x00000A00;
|
||||
/* Configure PDx pins speed to 50 MHz */
|
||||
GPIOC->OSPEEDR |= 0x00000A00;
|
||||
/* Configure PDx pins Output type to push-pull */
|
||||
GPIOC->OTYPER |= 0x00000000;
|
||||
/* No pull-up, pull-down for PDx pins */
|
||||
GPIOC->PUPDR |= 0x00000000;
|
||||
#endif /* STM32F446xx */
|
||||
|
||||
/* Connect PDx pins to FMC Alternate function */
|
||||
GPIOD->AFR[0] = 0x000000CC;
|
||||
GPIOD->AFR[1] = 0xCC000CCC;
|
||||
/* Configure PDx pins in Alternate function mode */
|
||||
GPIOD->MODER = 0xA02A000A;
|
||||
/* Configure PDx pins speed to 50 MHz */
|
||||
GPIOD->OSPEEDR = 0xA02A000A;
|
||||
/* Configure PDx pins Output type to push-pull */
|
||||
GPIOD->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PDx pins */
|
||||
GPIOD->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PEx pins to FMC Alternate function */
|
||||
GPIOE->AFR[0] = 0xC00000CC;
|
||||
GPIOE->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PEx pins in Alternate function mode */
|
||||
GPIOE->MODER = 0xAAAA800A;
|
||||
/* Configure PEx pins speed to 50 MHz */
|
||||
GPIOE->OSPEEDR = 0xAAAA800A;
|
||||
/* Configure PEx pins Output type to push-pull */
|
||||
GPIOE->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PEx pins */
|
||||
GPIOE->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PFx pins to FMC Alternate function */
|
||||
GPIOF->AFR[0] = 0xCCCCCCCC;
|
||||
GPIOF->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PFx pins in Alternate function mode */
|
||||
GPIOF->MODER = 0xAA800AAA;
|
||||
/* Configure PFx pins speed to 50 MHz */
|
||||
GPIOF->OSPEEDR = 0xAA800AAA;
|
||||
/* Configure PFx pins Output type to push-pull */
|
||||
GPIOF->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PFx pins */
|
||||
GPIOF->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PGx pins to FMC Alternate function */
|
||||
GPIOG->AFR[0] = 0xCCCCCCCC;
|
||||
GPIOG->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PGx pins in Alternate function mode */
|
||||
GPIOG->MODER = 0xAAAAAAAA;
|
||||
/* Configure PGx pins speed to 50 MHz */
|
||||
GPIOG->OSPEEDR = 0xAAAAAAAA;
|
||||
/* Configure PGx pins Output type to push-pull */
|
||||
GPIOG->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PGx pins */
|
||||
GPIOG->PUPDR = 0x00000000;
|
||||
|
||||
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|
||||
|| defined(STM32F469xx) || defined(STM32F479xx)
|
||||
/* Connect PHx pins to FMC Alternate function */
|
||||
GPIOH->AFR[0] = 0x00C0CC00;
|
||||
GPIOH->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PHx pins in Alternate function mode */
|
||||
GPIOH->MODER = 0xAAAA08A0;
|
||||
/* Configure PHx pins speed to 50 MHz */
|
||||
GPIOH->OSPEEDR = 0xAAAA08A0;
|
||||
/* Configure PHx pins Output type to push-pull */
|
||||
GPIOH->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PHx pins */
|
||||
GPIOH->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PIx pins to FMC Alternate function */
|
||||
GPIOI->AFR[0] = 0xCCCCCCCC;
|
||||
GPIOI->AFR[1] = 0x00000CC0;
|
||||
/* Configure PIx pins in Alternate function mode */
|
||||
GPIOI->MODER = 0x0028AAAA;
|
||||
/* Configure PIx pins speed to 50 MHz */
|
||||
GPIOI->OSPEEDR = 0x0028AAAA;
|
||||
/* Configure PIx pins Output type to push-pull */
|
||||
GPIOI->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PIx pins */
|
||||
GPIOI->PUPDR = 0x00000000;
|
||||
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */
|
||||
|
||||
/*-- FMC Configuration -------------------------------------------------------*/
|
||||
/* Enable the FMC interface clock */
|
||||
RCC->AHB3ENR |= 0x00000001;
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
|
||||
|
||||
/* Configure and enable SDRAM bank1 */
|
||||
#if defined(STM32F446xx)
|
||||
FMC_Bank5_6->SDCR[0] = 0x00001954;
|
||||
#else
|
||||
FMC_Bank5_6->SDCR[0] = 0x000019E4;
|
||||
#endif /* STM32F446xx */
|
||||
FMC_Bank5_6->SDTR[0] = 0x01115351;
|
||||
|
||||
/* SDRAM initialization sequence */
|
||||
/* Clock enable command */
|
||||
FMC_Bank5_6->SDCMR = 0x00000011;
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* Delay */
|
||||
for (index = 0; index<1000; index++);
|
||||
|
||||
/* PALL command */
|
||||
FMC_Bank5_6->SDCMR = 0x00000012;
|
||||
timeout = 0xFFFF;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* Auto refresh command */
|
||||
#if defined(STM32F446xx)
|
||||
FMC_Bank5_6->SDCMR = 0x000000F3;
|
||||
#else
|
||||
FMC_Bank5_6->SDCMR = 0x00000073;
|
||||
#endif /* STM32F446xx */
|
||||
timeout = 0xFFFF;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* MRD register program */
|
||||
#if defined(STM32F446xx)
|
||||
FMC_Bank5_6->SDCMR = 0x00044014;
|
||||
#else
|
||||
FMC_Bank5_6->SDCMR = 0x00046014;
|
||||
#endif /* STM32F446xx */
|
||||
timeout = 0xFFFF;
|
||||
while((tmpreg != 0) && (timeout-- > 0))
|
||||
{
|
||||
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
|
||||
}
|
||||
|
||||
/* Set refresh count */
|
||||
tmpreg = FMC_Bank5_6->SDRTR;
|
||||
#if defined(STM32F446xx)
|
||||
FMC_Bank5_6->SDRTR = (tmpreg | (0x0000050C<<1));
|
||||
#else
|
||||
FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
|
||||
#endif /* STM32F446xx */
|
||||
|
||||
/* Disable write protection */
|
||||
tmpreg = FMC_Bank5_6->SDCR[0];
|
||||
FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
|
||||
#endif /* DATA_IN_ExtSDRAM */
|
||||
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */
|
||||
|
||||
#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx)\
|
||||
|| defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|
||||
|| defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx)
|
||||
|
||||
#if defined(DATA_IN_ExtSRAM)
|
||||
/*-- GPIOs Configuration -----------------------------------------------------*/
|
||||
/* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
|
||||
RCC->AHB1ENR |= 0x00000078;
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);
|
||||
|
||||
/* Connect PDx pins to FMC Alternate function */
|
||||
GPIOD->AFR[0] = 0x00CCC0CC;
|
||||
GPIOD->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PDx pins in Alternate function mode */
|
||||
GPIOD->MODER = 0xAAAA0A8A;
|
||||
/* Configure PDx pins speed to 100 MHz */
|
||||
GPIOD->OSPEEDR = 0xFFFF0FCF;
|
||||
/* Configure PDx pins Output type to push-pull */
|
||||
GPIOD->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PDx pins */
|
||||
GPIOD->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PEx pins to FMC Alternate function */
|
||||
GPIOE->AFR[0] = 0xC00CC0CC;
|
||||
GPIOE->AFR[1] = 0xCCCCCCCC;
|
||||
/* Configure PEx pins in Alternate function mode */
|
||||
GPIOE->MODER = 0xAAAA828A;
|
||||
/* Configure PEx pins speed to 100 MHz */
|
||||
GPIOE->OSPEEDR = 0xFFFFC3CF;
|
||||
/* Configure PEx pins Output type to push-pull */
|
||||
GPIOE->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PEx pins */
|
||||
GPIOE->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PFx pins to FMC Alternate function */
|
||||
GPIOF->AFR[0] = 0x00CCCCCC;
|
||||
GPIOF->AFR[1] = 0xCCCC0000;
|
||||
/* Configure PFx pins in Alternate function mode */
|
||||
GPIOF->MODER = 0xAA000AAA;
|
||||
/* Configure PFx pins speed to 100 MHz */
|
||||
GPIOF->OSPEEDR = 0xFF000FFF;
|
||||
/* Configure PFx pins Output type to push-pull */
|
||||
GPIOF->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PFx pins */
|
||||
GPIOF->PUPDR = 0x00000000;
|
||||
|
||||
/* Connect PGx pins to FMC Alternate function */
|
||||
GPIOG->AFR[0] = 0x00CCCCCC;
|
||||
GPIOG->AFR[1] = 0x000000C0;
|
||||
/* Configure PGx pins in Alternate function mode */
|
||||
GPIOG->MODER = 0x00085AAA;
|
||||
/* Configure PGx pins speed to 100 MHz */
|
||||
GPIOG->OSPEEDR = 0x000CAFFF;
|
||||
/* Configure PGx pins Output type to push-pull */
|
||||
GPIOG->OTYPER = 0x00000000;
|
||||
/* No pull-up, pull-down for PGx pins */
|
||||
GPIOG->PUPDR = 0x00000000;
|
||||
|
||||
/*-- FMC/FSMC Configuration --------------------------------------------------*/
|
||||
/* Enable the FMC/FSMC interface clock */
|
||||
RCC->AHB3ENR |= 0x00000001;
|
||||
|
||||
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
|
||||
/* Configure and enable Bank1_SRAM2 */
|
||||
FMC_Bank1->BTCR[2] = 0x00001011;
|
||||
FMC_Bank1->BTCR[3] = 0x00000201;
|
||||
FMC_Bank1E->BWTR[2] = 0x0fffffff;
|
||||
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */
|
||||
#if defined(STM32F469xx) || defined(STM32F479xx)
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
|
||||
/* Configure and enable Bank1_SRAM2 */
|
||||
FMC_Bank1->BTCR[2] = 0x00001091;
|
||||
FMC_Bank1->BTCR[3] = 0x00110212;
|
||||
FMC_Bank1E->BWTR[2] = 0x0fffffff;
|
||||
#endif /* STM32F469xx || STM32F479xx */
|
||||
#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx)\
|
||||
|| defined(STM32F412Zx) || defined(STM32F412Vx)
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);
|
||||
/* Configure and enable Bank1_SRAM2 */
|
||||
FSMC_Bank1->BTCR[2] = 0x00001011;
|
||||
FSMC_Bank1->BTCR[3] = 0x00000201;
|
||||
FSMC_Bank1E->BWTR[2] = 0x0FFFFFFF;
|
||||
#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx */
|
||||
|
||||
#endif /* DATA_IN_ExtSRAM */
|
||||
#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\
|
||||
STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx */
|
||||
(void)(tmp);
|
||||
}
|
||||
#endif /* DATA_IN_ExtSRAM && DATA_IN_ExtSDRAM */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,64 @@
|
|||
menu"Hardware Drivers Config"
|
||||
|
||||
menuconfig SOC_STM32F407ZG
|
||||
bool
|
||||
select SOC_SERIES_STM32F4
|
||||
select RT_USING_COMPONENTS_INIT
|
||||
select RT_USING_USER_MAIN
|
||||
default y
|
||||
|
||||
config BSP_USING_GPIO
|
||||
bool "Enable GPIO"
|
||||
select RT_USING_PIN
|
||||
default y
|
||||
|
||||
|
||||
menuconfig BSP_USING_UART
|
||||
bool "Using UART device"
|
||||
default y
|
||||
select RT_USING_SERIAL
|
||||
if BSP_USING_UART
|
||||
source "$BSP_DIR/board/ports/uart/Kconfig"
|
||||
endif
|
||||
|
||||
|
||||
menuconfig BSP_USING_I2C1
|
||||
bool "Using I2C device"
|
||||
default n
|
||||
select RT_USING_I2C
|
||||
select RT_USING_I2C_BITOPS
|
||||
select RT_USING_PIN
|
||||
if BSP_USING_I2C1
|
||||
source "$BSP_DIR/board/ports/I2c/Kconfig"
|
||||
endif
|
||||
|
||||
menuconfig BSP_USING_SPI
|
||||
bool "Using SPI BUS"
|
||||
default n
|
||||
select RT_USING_SPI
|
||||
if BSP_USING_SPI
|
||||
source "$BSP_DIR/board/ports/spi/Kconfig"
|
||||
endif
|
||||
|
||||
|
||||
menuconfig BSP_USING_CH438
|
||||
bool "Using CH438 device"
|
||||
default y
|
||||
if BSP_USING_CH438
|
||||
source "$BSP_DIR/board/ports/ch438/Kconfig"
|
||||
endif
|
||||
|
||||
menuconfig BSP_USING_USB
|
||||
bool "Using USB device"
|
||||
default n
|
||||
select BSP_USING_STM32_USBH
|
||||
select RESOURCES_USB
|
||||
select RESOURCES_USB_HOST
|
||||
select USBH_MSTORAGE
|
||||
select RESOURCES_USB_DEVICE
|
||||
if BSP_USING_USB
|
||||
source "$BSP_DIR/board/ports/usb/Kconfig"
|
||||
endif
|
||||
|
||||
source "$RTT_DIR/bsp/stm32/libraries/HAL_Drivers/Kconfig"
|
||||
endmenu
|
|
@ -0,0 +1,31 @@
|
|||
import os
|
||||
import rtconfig
|
||||
from building import *
|
||||
|
||||
Import('SDK_LIB')
|
||||
|
||||
cwd = GetCurrentDir()
|
||||
|
||||
# add general drivers
|
||||
src = Split('''
|
||||
board.c
|
||||
CubeMX_Config/Src/stm32f4xx_hal_msp.c
|
||||
''')
|
||||
|
||||
path = [cwd]
|
||||
path += [cwd + '/CubeMX_Config/Inc']
|
||||
path += [cwd + '/ports']
|
||||
|
||||
startup_path_prefix = SDK_LIB
|
||||
|
||||
if rtconfig.CROSS_TOOL == 'gcc':
|
||||
src += [startup_path_prefix + '/STM32F4xx_HAL/CMSIS/Device/ST/STM32F4xx/Source/Templates/gcc/startup_stm32f407xx.s']
|
||||
elif rtconfig.CROSS_TOOL == 'keil':
|
||||
src += [startup_path_prefix + '/STM32F4xx_HAL/CMSIS/Device/ST/STM32F4xx/Source/Templates/arm/startup_stm32f407xx.s']
|
||||
elif rtconfig.CROSS_TOOL == 'iar':
|
||||
src += [startup_path_prefix + '/STM32F4xx_HAL/CMSIS/Device/ST/STM32F4xx/Source/Templates/iar/startup_stm32f407xx.s']
|
||||
|
||||
CPPDEFINES = ['STM32F407xx']
|
||||
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES)
|
||||
|
||||
Return('group')
|
|
@ -0,0 +1,59 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2018, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2018-11-06 SummerGift first version
|
||||
*/
|
||||
|
||||
#include "board.h"
|
||||
|
||||
void SystemClock_Config(void)
|
||||
{
|
||||
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
|
||||
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
|
||||
|
||||
/**Configure the main internal regulator output voltage
|
||||
*/
|
||||
__HAL_RCC_PWR_CLK_ENABLE();
|
||||
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
|
||||
/**Initializes the CPU, AHB and APB busses clocks
|
||||
*/
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE
|
||||
|RCC_OSCILLATORTYPE_LSE;
|
||||
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
|
||||
RCC_OscInitStruct.LSEState = RCC_LSE_ON;
|
||||
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
|
||||
RCC_OscInitStruct.PLL.PLLM = 4;
|
||||
RCC_OscInitStruct.PLL.PLLN = 168;
|
||||
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = 7;
|
||||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/**Initializes the CPU, AHB and APB busses clocks
|
||||
*/
|
||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|
||||
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
|
||||
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
|
||||
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
|
||||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
|
||||
|
||||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC;
|
||||
PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
}
|
|
@ -0,0 +1,50 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2018, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2018-11-5 SummerGift first version
|
||||
*/
|
||||
|
||||
#ifndef __BOARD_H__
|
||||
#define __BOARD_H__
|
||||
|
||||
#include <rtthread.h>
|
||||
#include <stm32f4xx.h>
|
||||
#include "drv_common.h"
|
||||
#include "drv_gpio.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define STM32_SRAM_SIZE (128)
|
||||
#define STM32_SRAM_END (0x20000000 + STM32_SRAM_SIZE * 1024)
|
||||
|
||||
#define STM32_FLASH_START_ADRESS ((uint32_t)0x08000000)
|
||||
#define STM32_FLASH_SIZE (1024 * 1024)
|
||||
#define STM32_FLASH_END_ADDRESS ((uint32_t)(STM32_FLASH_START_ADRESS + STM32_FLASH_SIZE))
|
||||
|
||||
#if defined(__CC_ARM) || defined(__CLANG_ARM)
|
||||
extern int Image$$RW_IRAM1$$ZI$$Limit;
|
||||
#define HEAP_BEGIN ((void *)&Image$$RW_IRAM1$$ZI$$Limit)
|
||||
#elif __ICCARM__
|
||||
#pragma section="CSTACK"
|
||||
#define HEAP_BEGIN (__segment_end("CSTACK"))
|
||||
#else
|
||||
extern int __bss_end;
|
||||
#define HEAP_BEGIN ((void *)&__bss_end)
|
||||
#endif
|
||||
|
||||
#define HEAP_END STM32_SRAM_END
|
||||
|
||||
void SystemClock_Config(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,243 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2022, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2020-07-27 thread-liu the first version
|
||||
*/
|
||||
|
||||
#include "board.h"
|
||||
#ifdef BSP_USING_DCMI
|
||||
#include <drv_dcmi.h>
|
||||
#ifdef RT_USING_POSIX
|
||||
#include <dfs_posix.h>
|
||||
#include <dfs_poll.h>
|
||||
#ifdef RT_USING_POSIX_TERMIOS
|
||||
#include <posix_termios.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define DRV_DEBUG
|
||||
#define LOG_TAG "drv.dcmi"
|
||||
#include <drv_log.h>
|
||||
static void (*dcmi_irq_callback)(void) = NULL;
|
||||
|
||||
static struct stm32_dcmi rt_dcmi = {0};
|
||||
DMA_HandleTypeDef hdma_dcmi;
|
||||
static void rt_hw_dcmi_dma_init(void)
|
||||
{
|
||||
__HAL_RCC_DMA2_CLK_ENABLE();
|
||||
hdma_dcmi.Instance = DMA2_Stream1;
|
||||
hdma_dcmi.Init.Channel = DMA_CHANNEL_1;
|
||||
hdma_dcmi.Init.Direction = DMA_PERIPH_TO_MEMORY;
|
||||
hdma_dcmi.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||
hdma_dcmi.Init.MemInc = DMA_MINC_ENABLE;
|
||||
hdma_dcmi.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
|
||||
hdma_dcmi.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
|
||||
hdma_dcmi.Init.Mode = DMA_NORMAL;
|
||||
hdma_dcmi.Init.Priority = DMA_PRIORITY_HIGH;
|
||||
hdma_dcmi.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
|
||||
hdma_dcmi.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
|
||||
hdma_dcmi.Init.MemBurst = DMA_MBURST_SINGLE;
|
||||
hdma_dcmi.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||
HAL_DMA_Init(&hdma_dcmi);
|
||||
__HAL_LINKDMA(&rt_dcmi.DCMI_Handle, DMA_Handle, hdma_dcmi);
|
||||
__HAL_DMA_ENABLE_IT(&hdma_dcmi,DMA_IT_TC);
|
||||
HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 0x00, 0x00);
|
||||
HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn);;
|
||||
}
|
||||
/*
|
||||
DMA multi_buffer DMA Transfer.
|
||||
*/
|
||||
void rt_hw_dcmi_dma_config(rt_uint32_t dst_addr1, rt_uint32_t dst_addr2, rt_uint32_t len)
|
||||
{
|
||||
HAL_DMAEx_MultiBufferStart(&hdma_dcmi, (rt_uint32_t)&DCMI->DR, dst_addr1, dst_addr2, len);
|
||||
|
||||
__HAL_DMA_ENABLE_IT(&hdma_dcmi, DMA_IT_TC);
|
||||
}
|
||||
|
||||
static rt_err_t rt_hw_dcmi_init(DCMI_HandleTypeDef *device)
|
||||
{
|
||||
RT_ASSERT(device != RT_NULL);
|
||||
|
||||
device->Instance = DCMI;
|
||||
device->Init.SynchroMode = DCMI_SYNCHRO_HARDWARE;
|
||||
device->Init.PCKPolarity = DCMI_PCKPOLARITY_RISING;
|
||||
device->Init.VSPolarity = DCMI_VSPOLARITY_LOW;
|
||||
device->Init.HSPolarity = DCMI_HSPOLARITY_LOW;
|
||||
device->Init.CaptureRate = DCMI_CR_ALL_FRAME;
|
||||
device->Init.ExtendedDataMode = DCMI_EXTEND_DATA_8B;
|
||||
device->Init.JPEGMode = DCMI_JPEG_ENABLE;
|
||||
#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
|
||||
device->Init.ByteSelectMode = DCMI_BSM_ALL;
|
||||
device->Init.ByteSelectStart = DCMI_OEBS_ODD;
|
||||
device->Init.LineSelectMode = DCMI_LSM_ALL;
|
||||
device->Init.LineSelectStart = DCMI_OELS_ODD;
|
||||
#endif
|
||||
if(HAL_DCMI_Init(device) != HAL_OK)
|
||||
{
|
||||
LOG_E("dcmi init error!");
|
||||
return RT_ERROR;
|
||||
}
|
||||
else
|
||||
{
|
||||
LOG_I("dcmi HAL_DCMI_Init success");
|
||||
}
|
||||
DCMI->IER = 0x0;
|
||||
__HAL_DCMI_ENABLE_IT(device, DCMI_IT_FRAME);
|
||||
__HAL_DCMI_ENABLE(device);
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
void DCMI_IRQHandler(void)
|
||||
{
|
||||
/* enter interrupt */
|
||||
rt_interrupt_enter();
|
||||
HAL_DCMI_IRQHandler(&rt_dcmi.DCMI_Handle);
|
||||
/* leave interrupt */
|
||||
rt_interrupt_leave();
|
||||
}
|
||||
/*
|
||||
the camera starts transfering photos
|
||||
*/
|
||||
void rt_dcmi_start(uint32_t pData, uint32_t Length)
|
||||
{
|
||||
HAL_DCMI_Start_DMA(&rt_dcmi.DCMI_Handle,DCMI_MODE_SNAPSHOT,pData, Length);
|
||||
}
|
||||
|
||||
/*
|
||||
the camera stops transfering photos
|
||||
*/
|
||||
void rt_dcmi_stop(void)
|
||||
{
|
||||
HAL_DCMI_Stop(&rt_dcmi.DCMI_Handle);//
|
||||
}
|
||||
|
||||
|
||||
/* Capture a frame of the image */
|
||||
void HAL_DCMI_FrameEventCallback(DCMI_HandleTypeDef *hdcmi)
|
||||
{
|
||||
rt_interrupt_enter();
|
||||
__HAL_DCMI_ENABLE_IT(&rt_dcmi.DCMI_Handle, DCMI_IT_FRAME);
|
||||
rt_dcmi_stop();
|
||||
if(NULL != dcmi_irq_callback)
|
||||
{
|
||||
(*dcmi_irq_callback)();
|
||||
}
|
||||
rt_interrupt_leave();
|
||||
}
|
||||
|
||||
void DMA2_Stream1_IRQHandler(void)
|
||||
{
|
||||
extern void camera_dma_data_process(void);
|
||||
/* enter interrupt */
|
||||
rt_interrupt_enter();
|
||||
|
||||
if (__HAL_DMA_GET_FLAG(&hdma_dcmi, DMA_FLAG_TCIF1_5) != RESET)
|
||||
{
|
||||
__HAL_DMA_CLEAR_FLAG(&hdma_dcmi, DMA_FLAG_TCIF1_5);
|
||||
}
|
||||
|
||||
/* leave interrupt */
|
||||
rt_interrupt_leave();
|
||||
}
|
||||
|
||||
static rt_err_t rt_dcmi_init(rt_device_t dev)
|
||||
{
|
||||
RT_ASSERT(dev != RT_NULL);
|
||||
rt_err_t result = RT_EOK;
|
||||
result = rt_hw_dcmi_init(&rt_dcmi.DCMI_Handle);
|
||||
if (result != RT_EOK)
|
||||
{
|
||||
return result;
|
||||
}
|
||||
|
||||
rt_hw_dcmi_dma_init();
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
static rt_err_t rt_dcmi_open(rt_device_t dev, rt_uint16_t oflag)
|
||||
{
|
||||
RT_ASSERT(dev != RT_NULL);
|
||||
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
static rt_err_t rt_dcmi_close(rt_device_t dev)
|
||||
{
|
||||
RT_ASSERT(dev != RT_NULL);
|
||||
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
static rt_err_t rt_dcmi_control(rt_device_t dev, int cmd, void *args)
|
||||
{
|
||||
RT_ASSERT(dev != RT_NULL);
|
||||
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
static rt_size_t rt_dcmi_read(rt_device_t dev, rt_off_t pos, void *buffer, rt_size_t size)
|
||||
{
|
||||
RT_ASSERT(dev != RT_NULL);
|
||||
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
static rt_size_t rt_dcmi_write(rt_device_t dev, rt_off_t pos, const void *buffer, rt_size_t size)
|
||||
{
|
||||
RT_ASSERT(dev != RT_NULL);
|
||||
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
rt_err_t rt_set_irq_dcmi_callback_hander(void (*p)(void))
|
||||
{
|
||||
if(NULL == p)
|
||||
{
|
||||
LOG_E("set irq dcmi callback hander is NULL");
|
||||
return RT_ERROR;
|
||||
}
|
||||
dcmi_irq_callback = p;
|
||||
return RT_EOK;
|
||||
|
||||
}
|
||||
int dcmi_init(void)
|
||||
{
|
||||
int ret = 0;
|
||||
rt_device_t dcmi_dev = RT_NULL;
|
||||
rt_dcmi.dev.parent.type = RT_Device_Class_Miscellaneous;
|
||||
rt_dcmi.dev.parent.init = rt_dcmi_init;
|
||||
rt_dcmi.dev.parent.open = rt_dcmi_open;
|
||||
rt_dcmi.dev.parent.close = rt_dcmi_close;
|
||||
rt_dcmi.dev.parent.read = rt_dcmi_read;
|
||||
rt_dcmi.dev.parent.write = rt_dcmi_write;
|
||||
rt_dcmi.dev.parent.control = rt_dcmi_control;
|
||||
rt_dcmi.dev.parent.user_data = RT_NULL;
|
||||
ret = rt_device_register(&rt_dcmi.dev.parent, "dcmi", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_REMOVABLE | RT_DEVICE_FLAG_STANDALONE);
|
||||
if(ret != RT_EOK)
|
||||
{
|
||||
LOG_E("dcmi registered fail!!\n\r");
|
||||
return -RT_ERROR;
|
||||
}
|
||||
LOG_I("dcmi registered successfully!");
|
||||
dcmi_dev = rt_device_find("dcmi");
|
||||
if (dcmi_dev == RT_NULL)
|
||||
{
|
||||
LOG_E("can't find dcmi device!");
|
||||
return RT_ERROR;
|
||||
}
|
||||
ret = rt_device_open(dcmi_dev, RT_DEVICE_FLAG_RDWR);
|
||||
if(ret != RT_EOK)
|
||||
{
|
||||
LOG_E("can't open dcmi device!");
|
||||
return RT_ERROR;
|
||||
}
|
||||
LOG_I("dcmi open successfully");
|
||||
return RT_EOK;
|
||||
}
|
||||
INIT_BOARD_EXPORT(dcmi_init);
|
||||
#endif
|
|
@ -0,0 +1,37 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2022, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2020-07-27 thread-liu the first version
|
||||
*/
|
||||
|
||||
#ifndef __DRV_DCMI_H__
|
||||
#define __DRV_DCMI_H__
|
||||
#include "board.h"
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
struct rt_dcmi_device
|
||||
{
|
||||
struct rt_device parent;
|
||||
};
|
||||
struct stm32_dcmi
|
||||
{
|
||||
DCMI_HandleTypeDef DCMI_Handle;
|
||||
struct rt_dcmi_device dev;
|
||||
};
|
||||
|
||||
extern DMA_HandleTypeDef hdma_dcmi;
|
||||
extern void DCMI_IRQHandler(void);
|
||||
extern void rt_hw_dcmi_dma_config(rt_uint32_t dst_addr1, rt_uint32_t dst_addr2, rt_uint32_t len);
|
||||
extern void rt_dcmi_start(uint32_t pData, uint32_t Length);
|
||||
extern void rt_dcmi_stop(void);
|
||||
extern rt_err_t rt_set_irq_dcmi_callback_hander(void (*p)(void));
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,159 @@
|
|||
/*
|
||||
* linker script for STM32F4xx with GNU ld
|
||||
* bernard.xiong 2009-10-14
|
||||
* flybreak 2018-11-19 Add support for RAM2
|
||||
*/
|
||||
|
||||
/* Program Entry, set to mark it as "used" and avoid gc */
|
||||
MEMORY
|
||||
{
|
||||
CODE (rx) : ORIGIN = 0x08000000, LENGTH = 1024k /* 1024KB flash */
|
||||
RAM1 (rw) : ORIGIN = 0x20000000, LENGTH = 128k /* 128K sram */
|
||||
RAM2 (rw) : ORIGIN = 0x10000000, LENGTH = 64k /* 64K sram */
|
||||
}
|
||||
ENTRY(Reset_Handler)
|
||||
_system_stack_size = 0x200;
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_stext = .;
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
|
||||
. = ALIGN(4);
|
||||
*(.text) /* remaining code */
|
||||
*(.text.*) /* remaining code */
|
||||
*(.rodata) /* read-only data (constants) */
|
||||
*(.rodata*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.gnu.linkonce.t*)
|
||||
|
||||
/* section information for finsh shell */
|
||||
. = ALIGN(4);
|
||||
__fsymtab_start = .;
|
||||
KEEP(*(FSymTab))
|
||||
__fsymtab_end = .;
|
||||
|
||||
. = ALIGN(4);
|
||||
__vsymtab_start = .;
|
||||
KEEP(*(VSymTab))
|
||||
__vsymtab_end = .;
|
||||
|
||||
/* section information for initial. */
|
||||
. = ALIGN(4);
|
||||
__rt_init_start = .;
|
||||
KEEP(*(SORT(.rti_fn*)))
|
||||
__rt_init_end = .;
|
||||
|
||||
. = ALIGN(4);
|
||||
|
||||
PROVIDE(__ctors_start__ = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array))
|
||||
PROVIDE(__ctors_end__ = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
|
||||
_etext = .;
|
||||
} > CODE = 0
|
||||
|
||||
/* .ARM.exidx is sorted, so has to go in its own output section. */
|
||||
__exidx_start = .;
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
|
||||
/* This is used by the startup in order to initialize the .data secion */
|
||||
_sidata = .;
|
||||
} > CODE
|
||||
__exidx_end = .;
|
||||
|
||||
/* .data section which is used for initialized data */
|
||||
|
||||
.data : AT (_sidata)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
/* This is used by the startup in order to initialize the .data secion */
|
||||
_sdata = . ;
|
||||
|
||||
*(.data)
|
||||
*(.data.*)
|
||||
*(.gnu.linkonce.d*)
|
||||
|
||||
PROVIDE(__dtors_start__ = .);
|
||||
KEEP(*(SORT(.dtors.*)))
|
||||
KEEP(*(.dtors))
|
||||
PROVIDE(__dtors_end__ = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* This is used by the startup in order to initialize the .data secion */
|
||||
_edata = . ;
|
||||
} >RAM1
|
||||
|
||||
.stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sstack = .;
|
||||
. = . + _system_stack_size;
|
||||
. = ALIGN(4);
|
||||
_estack = .;
|
||||
} >RAM1
|
||||
|
||||
__bss_start = .;
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .;
|
||||
|
||||
*(.bss)
|
||||
*(.bss.*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_ebss = . ;
|
||||
|
||||
*(.bss.init)
|
||||
} > RAM1
|
||||
__bss_end = .;
|
||||
|
||||
_end = .;
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
/* DWARF debug sections.
|
||||
* Symbols in the DWARF debugging sections are relative to the beginning
|
||||
* of the section so we begin them at 0. */
|
||||
/* DWARF 1 */
|
||||
.debug 0 : { *(.debug) }
|
||||
.line 0 : { *(.line) }
|
||||
/* GNU DWARF 1 extensions */
|
||||
.debug_srcinfo 0 : { *(.debug_srcinfo) }
|
||||
.debug_sfnames 0 : { *(.debug_sfnames) }
|
||||
/* DWARF 1.1 and DWARF 2 */
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
/* DWARF 2 */
|
||||
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_frame 0 : { *(.debug_frame) }
|
||||
.debug_str 0 : { *(.debug_str) }
|
||||
.debug_loc 0 : { *(.debug_loc) }
|
||||
.debug_macinfo 0 : { *(.debug_macinfo) }
|
||||
/* SGI/MIPS DWARF 2 extensions */
|
||||
.debug_weaknames 0 : { *(.debug_weaknames) }
|
||||
.debug_funcnames 0 : { *(.debug_funcnames) }
|
||||
.debug_typenames 0 : { *(.debug_typenames) }
|
||||
.debug_varnames 0 : { *(.debug_varnames) }
|
||||
}
|
|
@ -0,0 +1,13 @@
|
|||
config BSP_USING_I2C1
|
||||
bool "Enable I2C1 BUS (software simulation)"
|
||||
default y
|
||||
if BSP_USING_I2C1
|
||||
config BSP_I2C1_SCL_PIN
|
||||
int "I2C scl pin number"
|
||||
range 0 143
|
||||
default 24
|
||||
config BSP_I2C1_SDA_PIN
|
||||
int "I2C sda pin number"
|
||||
range 0 143
|
||||
default 25
|
||||
endif
|
|
@ -0,0 +1,11 @@
|
|||
config CAN_BUS_NAME_1
|
||||
string "can bus name"
|
||||
default "can1"
|
||||
|
||||
config CAN_DRIVER_NAME
|
||||
string "can driver name"
|
||||
default "can1_drv"
|
||||
|
||||
config CAN_1_DEVICE_NAME_1
|
||||
string "can bus 1 device 1 name"
|
||||
default "can1_dev1"
|
|
@ -0,0 +1,39 @@
|
|||
config CH438_BUS_NAME
|
||||
string
|
||||
default "extuart"
|
||||
|
||||
config CH438_DRIVER_NAME
|
||||
string
|
||||
default "extuart_drv"
|
||||
|
||||
config CH438_DEVICE_NAME_0
|
||||
string
|
||||
default "extuart_dev0"
|
||||
|
||||
config CH438_DEVICE_NAME_1
|
||||
string
|
||||
default "extuart_dev1"
|
||||
|
||||
config CH438_DEVICE_NAME_2
|
||||
string
|
||||
default "extuart_dev2"
|
||||
|
||||
config CH438_DEVICE_NAME_3
|
||||
string
|
||||
default "extuart_dev3"
|
||||
|
||||
config CH438_DEVICE_NAME_4
|
||||
string
|
||||
default "extuart_dev4"
|
||||
|
||||
config CH438_DEVICE_NAME_5
|
||||
string
|
||||
default "extuart_dev5"
|
||||
|
||||
config CH438_DEVICE_NAME_6
|
||||
string
|
||||
default "extuart_dev6"
|
||||
|
||||
config CH438_DEVICE_NAME_7
|
||||
string
|
||||
default "extuart_dev7"
|
|
@ -0,0 +1,4 @@
|
|||
config BSP_USING_GPIO
|
||||
bool "Enable GPIO"
|
||||
default y
|
||||
|
|
@ -0,0 +1,46 @@
|
|||
config BSP_USING_SPI1
|
||||
bool "Enable SPI1 BUS"
|
||||
default n
|
||||
|
||||
config BSP_SPI1_TX_USING_DMA
|
||||
bool "Enable SPI1 TX DMA"
|
||||
depends on BSP_USING_SPI1
|
||||
default n
|
||||
|
||||
config BSP_SPI1_RX_USING_DMA
|
||||
bool "Enable SPI1 RX DMA"
|
||||
depends on BSP_USING_SPI1
|
||||
select BSP_SPI1_TX_USING_DMA
|
||||
default n
|
||||
|
||||
config BSP_USING_SPI2
|
||||
bool "Enable SPI2 BUS"
|
||||
default n
|
||||
|
||||
config BSP_SPI2_TX_USING_DMA
|
||||
bool "Enable SPI2 TX DMA"
|
||||
depends on BSP_USING_SPI2
|
||||
default n
|
||||
|
||||
config BSP_SPI2_RX_USING_DMA
|
||||
bool "Enable SPI2 RX DMA"
|
||||
depends on BSP_USING_SPI2
|
||||
select BSP_SPI2_TX_USING_DMA
|
||||
default n
|
||||
|
||||
|
||||
config BSP_USING_SPI3
|
||||
bool "Enable SPI3 BUS"
|
||||
default n
|
||||
|
||||
config BSP_SPI3_TX_USING_DMA
|
||||
bool "Enable SPI3 TX DMA"
|
||||
depends on BSP_USING_SPI3
|
||||
default n
|
||||
|
||||
config BSP_SPI3_RX_USING_DMA
|
||||
bool "Enable SPI3 RX DMA"
|
||||
depends on BSP_USING_SPI3
|
||||
select BSP_SPI3_TX_USING_DMA
|
||||
default n
|
||||
|
|
@ -0,0 +1,21 @@
|
|||
config BSP_USING_UART1
|
||||
bool "Enable UART1"
|
||||
default y
|
||||
|
||||
config BSP_USING_UART2
|
||||
bool "Enable UART2"
|
||||
default n
|
||||
|
||||
config BSP_USING_UART3
|
||||
bool "Enable UART3"
|
||||
default n
|
||||
|
||||
config BSP_USING_UART4
|
||||
bool "Enable UART4"
|
||||
default n
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,15 @@
|
|||
config BSP_USING_STM32_USBH
|
||||
bool "Using usb host"
|
||||
default y
|
||||
if BSP_USING_STM32_USBH
|
||||
config USB_BUS_NAME
|
||||
string "usb bus name"
|
||||
default "usb"
|
||||
config USB_DRIVER_NAME
|
||||
string "usb bus driver name"
|
||||
default "usb_drv"
|
||||
config USB_DEVICE_NAME
|
||||
string "usb bus device name"
|
||||
default "usb_dev"
|
||||
endif
|
||||
|
|
@ -0,0 +1,226 @@
|
|||
#ifndef RT_CONFIG_H__
|
||||
#define RT_CONFIG_H__
|
||||
|
||||
/* Automatically generated file; DO NOT EDIT. */
|
||||
/* RT-Thread Configuration */
|
||||
|
||||
#define ROOT_DIR "../../../.."
|
||||
#define BSP_DIR "."
|
||||
#define RT_Thread_DIR "../.."
|
||||
#define RTT_DIR "../../rt-thread"
|
||||
|
||||
/* RT-Thread Kernel */
|
||||
|
||||
#define RT_NAME_MAX 8
|
||||
#define RT_ALIGN_SIZE 4
|
||||
#define RT_THREAD_PRIORITY_32
|
||||
#define RT_THREAD_PRIORITY_MAX 32
|
||||
#define RT_TICK_PER_SECOND 1000
|
||||
#define RT_USING_OVERFLOW_CHECK
|
||||
#define RT_USING_HOOK
|
||||
#define RT_USING_IDLE_HOOK
|
||||
#define RT_IDLE_HOOK_LIST_SIZE 4
|
||||
#define IDLE_THREAD_STACK_SIZE 256
|
||||
#define RT_USING_TIMER_SOFT
|
||||
#define RT_TIMER_THREAD_PRIO 4
|
||||
#define RT_TIMER_THREAD_STACK_SIZE 512
|
||||
|
||||
/* kservice optimization */
|
||||
|
||||
#define RT_DEBUG
|
||||
#define RT_DEBUG_COLOR
|
||||
|
||||
/* Inter-Thread communication */
|
||||
|
||||
#define RT_USING_SEMAPHORE
|
||||
#define RT_USING_MUTEX
|
||||
#define RT_USING_EVENT
|
||||
#define RT_USING_MAILBOX
|
||||
#define RT_USING_MESSAGEQUEUE
|
||||
|
||||
/* Memory Management */
|
||||
|
||||
#define RT_USING_MEMPOOL
|
||||
#define RT_USING_MEMHEAP
|
||||
#define RT_USING_MEMHEAP_AUTO_BINDING
|
||||
#define RT_USING_MEMHEAP_AS_HEAP
|
||||
#define RT_USING_HEAP
|
||||
|
||||
/* Kernel Device Object */
|
||||
|
||||
#define RT_USING_DEVICE
|
||||
#define RT_USING_CONSOLE
|
||||
#define RT_CONSOLEBUF_SIZE 128
|
||||
#define RT_CONSOLE_DEVICE_NAME "uart1"
|
||||
#define RT_VER_NUM 0x40004
|
||||
#define ARCH_ARM
|
||||
#define RT_USING_CPU_FFS
|
||||
#define ARCH_ARM_CORTEX_M
|
||||
#define ARCH_ARM_CORTEX_M4
|
||||
|
||||
/* RT-Thread Components */
|
||||
|
||||
#define RT_USING_COMPONENTS_INIT
|
||||
#define RT_USING_USER_MAIN
|
||||
#define RT_MAIN_THREAD_STACK_SIZE 2048
|
||||
#define RT_MAIN_THREAD_PRIORITY 10
|
||||
|
||||
/* C++ features */
|
||||
|
||||
|
||||
/* Command shell */
|
||||
|
||||
#define RT_USING_FINSH
|
||||
#define RT_USING_MSH
|
||||
#define FINSH_USING_MSH
|
||||
#define FINSH_THREAD_NAME "tshell"
|
||||
#define FINSH_THREAD_PRIORITY 20
|
||||
#define FINSH_THREAD_STACK_SIZE 4096
|
||||
#define FINSH_USING_HISTORY
|
||||
#define FINSH_HISTORY_LINES 5
|
||||
#define FINSH_USING_SYMTAB
|
||||
#define FINSH_CMD_SIZE 80
|
||||
#define MSH_USING_BUILT_IN_COMMANDS
|
||||
#define FINSH_USING_DESCRIPTION
|
||||
#define FINSH_ARG_MAX 10
|
||||
|
||||
/* Device virtual file system */
|
||||
|
||||
#define RT_USING_DFS
|
||||
#define DFS_USING_WORKDIR
|
||||
#define DFS_FILESYSTEMS_MAX 4
|
||||
#define DFS_FILESYSTEM_TYPES_MAX 4
|
||||
#define DFS_FD_MAX 16
|
||||
#define RT_USING_DFS_ELMFAT
|
||||
|
||||
/* elm-chan's FatFs, Generic FAT Filesystem Module */
|
||||
|
||||
#define RT_DFS_ELM_CODE_PAGE 437
|
||||
#define RT_DFS_ELM_WORD_ACCESS
|
||||
#define RT_DFS_ELM_USE_LFN_3
|
||||
#define RT_DFS_ELM_USE_LFN 3
|
||||
#define RT_DFS_ELM_LFN_UNICODE_0
|
||||
#define RT_DFS_ELM_LFN_UNICODE 0
|
||||
#define RT_DFS_ELM_MAX_LFN 255
|
||||
#define RT_DFS_ELM_DRIVES 2
|
||||
#define RT_DFS_ELM_MAX_SECTOR_SIZE 4096
|
||||
#define RT_DFS_ELM_REENTRANT
|
||||
#define RT_DFS_ELM_MUTEX_TIMEOUT 3000
|
||||
#define RT_USING_DFS_DEVFS
|
||||
#define RT_USING_DFS_ROMFS
|
||||
|
||||
/* Device Drivers */
|
||||
|
||||
#define RT_USING_DEVICE_IPC
|
||||
#define RT_PIPE_BUFSZ 512
|
||||
#define RT_USING_SYSTEM_WORKQUEUE
|
||||
#define RT_SYSTEM_WORKQUEUE_STACKSIZE 2048
|
||||
#define RT_SYSTEM_WORKQUEUE_PRIORITY 23
|
||||
#define RT_USING_SERIAL
|
||||
#define RT_USING_SERIAL_V1
|
||||
#define RT_SERIAL_RB_BUFSZ 64
|
||||
#define RT_USING_CAN
|
||||
#define RT_USING_I2C
|
||||
#define RT_USING_I2C_BITOPS
|
||||
#define RT_USING_PIN
|
||||
#define RT_USING_RTC
|
||||
#define RT_USING_SPI
|
||||
#define RT_USING_SPI_MSD
|
||||
#define RT_USING_SFUD
|
||||
#define RT_SFUD_USING_SFDP
|
||||
#define RT_SFUD_USING_FLASH_INFO_TABLE
|
||||
#define RT_SFUD_SPI_MAX_HZ 50000000
|
||||
|
||||
/* Using USB */
|
||||
|
||||
|
||||
/* POSIX layer and C standard library */
|
||||
|
||||
#define RT_USING_LIBC
|
||||
#define RT_USING_PTHREADS
|
||||
#define PTHREAD_NUM_MAX 8
|
||||
#define RT_USING_POSIX
|
||||
#define RT_LIBC_USING_TIME
|
||||
#define RT_LIBC_DEFAULT_TIMEZONE 8
|
||||
|
||||
/* Network */
|
||||
|
||||
/* Socket abstraction layer */
|
||||
|
||||
|
||||
/* Network interface device */
|
||||
|
||||
|
||||
/* light weight TCP/IP stack */
|
||||
|
||||
|
||||
/* AT commands */
|
||||
|
||||
|
||||
/* VBUS(Virtual Software BUS) */
|
||||
|
||||
|
||||
/* Utilities */
|
||||
|
||||
|
||||
/* RT-Thread Utestcases */
|
||||
|
||||
#define SOC_FAMILY_STM32
|
||||
#define SOC_SERIES_STM32F4
|
||||
|
||||
/* Hardware Drivers Config */
|
||||
|
||||
#define SOC_STM32F407ZG
|
||||
#define BSP_USING_GPIO
|
||||
#define BSP_USING_UART
|
||||
#define BSP_USING_UART1
|
||||
#define BSP_USING_USB
|
||||
#define BSP_USING_STM32_USBH
|
||||
#define USB_BUS_NAME "usb"
|
||||
#define USB_DRIVER_NAME "usb_drv"
|
||||
#define USB_DEVICE_NAME "usb_dev"
|
||||
|
||||
/* MicroPython */
|
||||
|
||||
|
||||
/* More Drivers */
|
||||
|
||||
|
||||
/* APP_Framework */
|
||||
|
||||
/* Framework */
|
||||
|
||||
#define TRANSFORM_LAYER_ATTRIUBUTE
|
||||
#define ADD_XIZI_FETURES
|
||||
|
||||
/* Security */
|
||||
|
||||
|
||||
/* Applications */
|
||||
|
||||
/* config stack size and priority of main task */
|
||||
|
||||
#define MAIN_KTASK_STACK_SIZE 1024
|
||||
|
||||
/* ota app */
|
||||
|
||||
|
||||
/* test app */
|
||||
|
||||
|
||||
/* connection app */
|
||||
|
||||
|
||||
/* control app */
|
||||
|
||||
/* knowing app */
|
||||
|
||||
|
||||
/* sensor app */
|
||||
|
||||
|
||||
/* lib */
|
||||
|
||||
#define APP_SELECT_NEWLIB
|
||||
|
||||
#endif
|
|
@ -0,0 +1,151 @@
|
|||
import os
|
||||
SRC_APP_DIR = '../../../../APP_Framework'
|
||||
# toolchains options
|
||||
ARCH='arm'
|
||||
CPU='cortex-m4'
|
||||
CROSS_TOOL='gcc'
|
||||
|
||||
# bsp lib config
|
||||
BSP_LIBRARY_TYPE = None
|
||||
|
||||
if os.getenv('RTT_CC'):
|
||||
CROSS_TOOL = os.getenv('RTT_CC')
|
||||
if os.getenv('RTT_ROOT'):
|
||||
RTT_ROOT = os.getenv('RTT_ROOT')
|
||||
|
||||
# cross_tool provides the cross compiler
|
||||
# EXEC_PATH is the compiler execute path, for example, CodeSourcery, Keil MDK, IAR
|
||||
if CROSS_TOOL == 'gcc':
|
||||
PLATFORM = 'gcc'
|
||||
EXEC_PATH = r'/opt/gcc-arm-none-eabi-7-2018-q2-update/bin'
|
||||
elif CROSS_TOOL == 'keil':
|
||||
PLATFORM = 'armcc'
|
||||
EXEC_PATH = r'C:/Keil_v5'
|
||||
elif CROSS_TOOL == 'iar':
|
||||
PLATFORM = 'iar'
|
||||
EXEC_PATH = r'C:/Program Files (x86)/IAR Systems/Embedded Workbench 8.0'
|
||||
|
||||
if os.getenv('RTT_EXEC_PATH'):
|
||||
EXEC_PATH = os.getenv('RTT_EXEC_PATH')
|
||||
|
||||
BUILD = 'debug'
|
||||
|
||||
if PLATFORM == 'gcc':
|
||||
# toolchains
|
||||
PREFIX = 'arm-none-eabi-'
|
||||
CC = PREFIX + 'gcc'
|
||||
AS = PREFIX + 'gcc'
|
||||
AR = PREFIX + 'ar'
|
||||
CXX = PREFIX + 'g++'
|
||||
LINK = PREFIX + 'gcc'
|
||||
TARGET_EXT = 'elf'
|
||||
SIZE = PREFIX + 'size'
|
||||
OBJDUMP = PREFIX + 'objdump'
|
||||
OBJCPY = PREFIX + 'objcopy'
|
||||
|
||||
DEVICE = ' -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard -ffunction-sections -fdata-sections'
|
||||
CFLAGS = DEVICE + ' -Dgcc'
|
||||
AFLAGS = ' -c' + DEVICE + ' -x assembler-with-cpp -Wa,-mimplicit-it=thumb '
|
||||
LFLAGS = DEVICE + ' -Wl,--gc-sections,-Map=rt-thread.map,-cref,-u,Reset_Handler -T board/linker_scripts/link.lds'
|
||||
|
||||
CPATH = ''
|
||||
LPATH = ''
|
||||
|
||||
if BUILD == 'debug':
|
||||
CFLAGS += ' -O0 -gdwarf-2 -g'
|
||||
AFLAGS += ' -gdwarf-2'
|
||||
else:
|
||||
CFLAGS += ' -O2'
|
||||
|
||||
CXXFLAGS = CFLAGS
|
||||
CXXFLAGS += ' -std=gnu++11'
|
||||
|
||||
POST_ACTION = OBJCPY + ' -O binary $TARGET rtthread.bin\n' + SIZE + ' $TARGET \n'
|
||||
|
||||
elif PLATFORM == 'armcc':
|
||||
# toolchains
|
||||
CC = 'armcc'
|
||||
CXX = 'armcc'
|
||||
AS = 'armasm'
|
||||
AR = 'armar'
|
||||
LINK = 'armlink'
|
||||
TARGET_EXT = 'axf'
|
||||
|
||||
DEVICE = ' --cpu Cortex-M4.fp '
|
||||
CFLAGS = '-c ' + DEVICE + ' --apcs=interwork --c99'
|
||||
AFLAGS = DEVICE + ' --apcs=interwork '
|
||||
LFLAGS = DEVICE + ' --scatter "board\linker_scripts\link.sct" --info sizes --info totals --info unused --info veneers --list rt-thread.map --strict'
|
||||
CFLAGS += ' -I' + EXEC_PATH + '/ARM/ARMCC/include'
|
||||
LFLAGS += ' --libpath=' + EXEC_PATH + '/ARM/ARMCC/lib'
|
||||
|
||||
CFLAGS += ' -D__MICROLIB '
|
||||
AFLAGS += ' --pd "__MICROLIB SETA 1" '
|
||||
LFLAGS += ' --library_type=microlib '
|
||||
EXEC_PATH += '/ARM/ARMCC/bin/'
|
||||
|
||||
if BUILD == 'debug':
|
||||
CFLAGS += ' -g -O0'
|
||||
AFLAGS += ' -g'
|
||||
else:
|
||||
CFLAGS += ' -O2'
|
||||
|
||||
CXXFLAGS = CFLAGS
|
||||
CFLAGS += ' -std=c99'
|
||||
|
||||
POST_ACTION = 'fromelf --bin $TARGET --output rtthread.bin \nfromelf -z $TARGET'
|
||||
|
||||
elif PLATFORM == 'iar':
|
||||
# toolchains
|
||||
CC = 'iccarm'
|
||||
CXX = 'iccarm'
|
||||
AS = 'iasmarm'
|
||||
AR = 'iarchive'
|
||||
LINK = 'ilinkarm'
|
||||
TARGET_EXT = 'out'
|
||||
|
||||
DEVICE = '-Dewarm'
|
||||
|
||||
CFLAGS = DEVICE
|
||||
CFLAGS += ' --diag_suppress Pa050'
|
||||
CFLAGS += ' --no_cse'
|
||||
CFLAGS += ' --no_unroll'
|
||||
CFLAGS += ' --no_inline'
|
||||
CFLAGS += ' --no_code_motion'
|
||||
CFLAGS += ' --no_tbaa'
|
||||
CFLAGS += ' --no_clustering'
|
||||
CFLAGS += ' --no_scheduling'
|
||||
CFLAGS += ' --endian=little'
|
||||
CFLAGS += ' --cpu=Cortex-M4'
|
||||
CFLAGS += ' -e'
|
||||
CFLAGS += ' --fpu=VFPv4_sp'
|
||||
CFLAGS += ' --dlib_config "' + EXEC_PATH + '/arm/INC/c/DLib_Config_Normal.h"'
|
||||
CFLAGS += ' --silent'
|
||||
|
||||
AFLAGS = DEVICE
|
||||
AFLAGS += ' -s+'
|
||||
AFLAGS += ' -w+'
|
||||
AFLAGS += ' -r'
|
||||
AFLAGS += ' --cpu Cortex-M4'
|
||||
AFLAGS += ' --fpu VFPv4_sp'
|
||||
AFLAGS += ' -S'
|
||||
|
||||
if BUILD == 'debug':
|
||||
CFLAGS += ' --debug'
|
||||
CFLAGS += ' -On'
|
||||
else:
|
||||
CFLAGS += ' -Oh'
|
||||
|
||||
LFLAGS = ' --config "board/linker_scripts/link.icf"'
|
||||
LFLAGS += ' --entry __iar_program_start'
|
||||
|
||||
CXXFLAGS = CFLAGS
|
||||
|
||||
EXEC_PATH = EXEC_PATH + '/arm/bin/'
|
||||
POST_ACTION = 'ielftool --bin $TARGET rtthread.bin'
|
||||
|
||||
def dist_handle(BSP_ROOT, dist_dir):
|
||||
import sys
|
||||
cwd_path = os.getcwd()
|
||||
sys.path.append(os.path.join(os.path.dirname(BSP_ROOT), 'tools'))
|
||||
from sdk_dist import dist_do_building
|
||||
dist_do_building(BSP_ROOT, dist_dir)
|
|
@ -11,7 +11,6 @@ CONFIG_RTT_DIR="../../rt-thread"
|
|||
# RT-Thread Kernel
|
||||
#
|
||||
CONFIG_RT_NAME_MAX=8
|
||||
# CONFIG_RT_USING_BIG_ENDIAN is not set
|
||||
# CONFIG_RT_USING_ARCH_DATA_TYPE is not set
|
||||
# CONFIG_RT_USING_SMP is not set
|
||||
CONFIG_RT_ALIGN_SIZE=4
|
||||
|
@ -22,6 +21,7 @@ CONFIG_RT_THREAD_PRIORITY_MAX=32
|
|||
CONFIG_RT_TICK_PER_SECOND=1000
|
||||
CONFIG_RT_USING_OVERFLOW_CHECK=y
|
||||
CONFIG_RT_USING_HOOK=y
|
||||
CONFIG_RT_HOOK_USING_FUNC_PTR=y
|
||||
CONFIG_RT_USING_IDLE_HOOK=y
|
||||
CONFIG_RT_IDLE_HOOK_LIST_SIZE=4
|
||||
CONFIG_IDLE_THREAD_STACK_SIZE=256
|
||||
|
@ -32,7 +32,8 @@ CONFIG_IDLE_THREAD_STACK_SIZE=256
|
|||
#
|
||||
# CONFIG_RT_KSERVICE_USING_STDLIB is not set
|
||||
# CONFIG_RT_KSERVICE_USING_TINY_SIZE is not set
|
||||
# CONFIG_RT_USING_ASM_MEMCPY is not set
|
||||
# CONFIG_RT_USING_TINY_FFS is not set
|
||||
# CONFIG_RT_KPRINTF_USING_LONGLONG is not set
|
||||
CONFIG_RT_DEBUG=y
|
||||
CONFIG_RT_DEBUG_COLOR=y
|
||||
# CONFIG_RT_DEBUG_INIT_CONFIG is not set
|
||||
|
@ -60,14 +61,19 @@ CONFIG_RT_USING_MESSAGEQUEUE=y
|
|||
# Memory Management
|
||||
#
|
||||
CONFIG_RT_USING_MEMPOOL=y
|
||||
CONFIG_RT_USING_MEMHEAP=y
|
||||
CONFIG_RT_USING_MEMHEAP_AUTO_BINDING=y
|
||||
# CONFIG_RT_USING_NOHEAP is not set
|
||||
# CONFIG_RT_USING_SMALL_MEM is not set
|
||||
# CONFIG_RT_USING_SLAB is not set
|
||||
CONFIG_RT_USING_MEMHEAP=y
|
||||
CONFIG_RT_MEMHEAP_FAST_MODE=y
|
||||
# CONFIG_RT_MEMHEAP_BSET_MODE is not set
|
||||
# CONFIG_RT_USING_SMALL_MEM_AS_HEAP is not set
|
||||
CONFIG_RT_USING_MEMHEAP_AS_HEAP=y
|
||||
CONFIG_RT_USING_MEMHEAP_AUTO_BINDING=y
|
||||
# CONFIG_RT_USING_SLAB_AS_HEAP is not set
|
||||
# CONFIG_RT_USING_USERHEAP is not set
|
||||
# CONFIG_RT_USING_NOHEAP is not set
|
||||
# CONFIG_RT_USING_MEMTRACE is not set
|
||||
# CONFIG_RT_USING_HEAP_ISR is not set
|
||||
CONFIG_RT_USING_HEAP=y
|
||||
|
||||
#
|
||||
|
@ -79,8 +85,7 @@ CONFIG_RT_USING_DEVICE=y
|
|||
CONFIG_RT_USING_CONSOLE=y
|
||||
CONFIG_RT_CONSOLEBUF_SIZE=256
|
||||
CONFIG_RT_CONSOLE_DEVICE_NAME="uart1"
|
||||
# CONFIG_RT_PRINTF_LONGLONG is not set
|
||||
CONFIG_RT_VER_NUM=0x40004
|
||||
CONFIG_RT_VER_NUM=0x40100
|
||||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_RT_USING_CPU_FFS=y
|
||||
CONFIG_ARCH_ARM_CORTEX_M=y
|
||||
|
@ -94,18 +99,9 @@ CONFIG_RT_USING_COMPONENTS_INIT=y
|
|||
CONFIG_RT_USING_USER_MAIN=y
|
||||
CONFIG_RT_MAIN_THREAD_STACK_SIZE=2048
|
||||
CONFIG_RT_MAIN_THREAD_PRIORITY=10
|
||||
|
||||
#
|
||||
# C++ features
|
||||
#
|
||||
CONFIG_RT_USING_CPLUSPLUS=y
|
||||
# CONFIG_RT_USING_CPLUSPLUS11 is not set
|
||||
|
||||
#
|
||||
# Command shell
|
||||
#
|
||||
CONFIG_RT_USING_FINSH=y
|
||||
# CONFIG_RT_USING_LEGACY is not set
|
||||
CONFIG_RT_USING_MSH=y
|
||||
CONFIG_RT_USING_FINSH=y
|
||||
CONFIG_FINSH_USING_MSH=y
|
||||
CONFIG_FINSH_THREAD_NAME="tshell"
|
||||
CONFIG_FINSH_THREAD_PRIORITY=20
|
||||
|
@ -119,11 +115,8 @@ CONFIG_FINSH_USING_DESCRIPTION=y
|
|||
# CONFIG_FINSH_ECHO_DISABLE_DEFAULT is not set
|
||||
# CONFIG_FINSH_USING_AUTH is not set
|
||||
CONFIG_FINSH_ARG_MAX=10
|
||||
|
||||
#
|
||||
# Device virtual file system
|
||||
#
|
||||
CONFIG_RT_USING_DFS=y
|
||||
CONFIG_DFS_USING_POSIX=y
|
||||
CONFIG_DFS_USING_WORKDIR=y
|
||||
CONFIG_DFS_FILESYSTEMS_MAX=4
|
||||
CONFIG_DFS_FILESYSTEM_TYPES_MAX=4
|
||||
|
@ -153,14 +146,15 @@ CONFIG_RT_DFS_ELM_MAX_SECTOR_SIZE=4096
|
|||
CONFIG_RT_DFS_ELM_REENTRANT=y
|
||||
CONFIG_RT_DFS_ELM_MUTEX_TIMEOUT=3000
|
||||
CONFIG_RT_USING_DFS_DEVFS=y
|
||||
CONFIG_RT_USING_DFS_ROMFS=y
|
||||
# CONFIG_RT_USING_DFS_RAMFS is not set
|
||||
# CONFIG_RT_USING_DFS_ROMFS is not set
|
||||
CONFIG_RT_USING_DFS_RAMFS=y
|
||||
# CONFIG_RT_USING_FAL is not set
|
||||
# CONFIG_RT_USING_LWP is not set
|
||||
|
||||
#
|
||||
# Device Drivers
|
||||
#
|
||||
CONFIG_RT_USING_DEVICE_IPC=y
|
||||
CONFIG_RT_PIPE_BUFSZ=512
|
||||
# CONFIG_RT_USING_SYSTEM_WORKQUEUE is not set
|
||||
CONFIG_RT_USING_SERIAL=y
|
||||
CONFIG_RT_USING_SERIAL_V1=y
|
||||
|
@ -179,9 +173,28 @@ CONFIG_RT_USING_PIN=y
|
|||
# CONFIG_RT_USING_MTD_NOR is not set
|
||||
# CONFIG_RT_USING_MTD_NAND is not set
|
||||
# CONFIG_RT_USING_PM is not set
|
||||
# CONFIG_RT_USING_RTC is not set
|
||||
# CONFIG_RT_USING_SDIO is not set
|
||||
# CONFIG_RT_USING_SPI is not set
|
||||
CONFIG_RT_USING_RTC=y
|
||||
# CONFIG_RT_USING_ALARM is not set
|
||||
# CONFIG_RT_USING_SOFT_RTC is not set
|
||||
CONFIG_RT_USING_SDIO=y
|
||||
CONFIG_RT_SDIO_STACK_SIZE=512
|
||||
CONFIG_RT_SDIO_THREAD_PRIORITY=15
|
||||
CONFIG_RT_MMCSD_STACK_SIZE=1024
|
||||
CONFIG_RT_MMCSD_THREAD_PREORITY=22
|
||||
CONFIG_RT_MMCSD_MAX_PARTITION=16
|
||||
# CONFIG_RT_SDIO_DEBUG is not set
|
||||
CONFIG_RT_USING_SPI=y
|
||||
# CONFIG_RT_USING_SPI_BITOPS is not set
|
||||
CONFIG_RT_USING_QSPI=y
|
||||
# CONFIG_RT_USING_SPI_MSD is not set
|
||||
CONFIG_RT_USING_SFUD=y
|
||||
CONFIG_RT_SFUD_USING_SFDP=y
|
||||
CONFIG_RT_SFUD_USING_FLASH_INFO_TABLE=y
|
||||
CONFIG_RT_SFUD_USING_QSPI=y
|
||||
CONFIG_RT_SFUD_SPI_MAX_HZ=50000000
|
||||
# CONFIG_RT_DEBUG_SFUD is not set
|
||||
# CONFIG_RT_USING_ENC28J60 is not set
|
||||
# CONFIG_RT_USING_SPI_WIFI is not set
|
||||
# CONFIG_RT_USING_WDT is not set
|
||||
# CONFIG_RT_USING_AUDIO is not set
|
||||
# CONFIG_RT_USING_SENSOR is not set
|
||||
|
@ -194,53 +207,64 @@ CONFIG_RT_USING_PIN=y
|
|||
#
|
||||
# Using USB
|
||||
#
|
||||
CONFIG_RT_USING_USB=y
|
||||
# CONFIG_RT_USING_USB_HOST is not set
|
||||
# CONFIG_RT_USING_USB_DEVICE is not set
|
||||
CONFIG_RT_USING_USB_DEVICE=y
|
||||
CONFIG_RT_USBD_THREAD_STACK_SZ=4096
|
||||
CONFIG_USB_VENDOR_ID=0x0FFE
|
||||
CONFIG_USB_PRODUCT_ID=0x0001
|
||||
# CONFIG_RT_USB_DEVICE_COMPOSITE is not set
|
||||
# CONFIG__RT_USB_DEVICE_NONE is not set
|
||||
CONFIG__RT_USB_DEVICE_CDC=y
|
||||
# CONFIG__RT_USB_DEVICE_MSTORAGE is not set
|
||||
# CONFIG__RT_USB_DEVICE_HID is not set
|
||||
# CONFIG__RT_USB_DEVICE_WINUSB is not set
|
||||
# CONFIG__RT_USB_DEVICE_AUDIO is not set
|
||||
CONFIG_RT_USB_DEVICE_CDC=y
|
||||
CONFIG_RT_VCOM_TASK_STK_SIZE=512
|
||||
CONFIG_RT_CDC_RX_BUFSIZE=128
|
||||
# CONFIG_RT_VCOM_TX_USE_DMA is not set
|
||||
CONFIG_RT_VCOM_SERNO="32021919830108"
|
||||
CONFIG_RT_VCOM_SER_LEN=14
|
||||
CONFIG_RT_VCOM_TX_TIMEOUT=1000
|
||||
|
||||
#
|
||||
# POSIX layer and C standard library
|
||||
# C/C++ and POSIX layer
|
||||
#
|
||||
CONFIG_RT_USING_LIBC=y
|
||||
CONFIG_RT_LIBC_DEFAULT_TIMEZONE=8
|
||||
|
||||
#
|
||||
# POSIX (Portable Operating System Interface) layer
|
||||
#
|
||||
# CONFIG_RT_USING_POSIX_FS is not set
|
||||
CONFIG_RT_USING_POSIX_DELAY=y
|
||||
CONFIG_RT_USING_POSIX_CLOCK=y
|
||||
# CONFIG_RT_USING_POSIX_TIMER is not set
|
||||
CONFIG_RT_USING_PTHREADS=y
|
||||
CONFIG_PTHREAD_NUM_MAX=8
|
||||
CONFIG_RT_USING_POSIX=y
|
||||
# CONFIG_RT_USING_POSIX_MMAP is not set
|
||||
# CONFIG_RT_USING_POSIX_TERMIOS is not set
|
||||
# CONFIG_RT_USING_POSIX_GETLINE is not set
|
||||
# CONFIG_RT_USING_POSIX_AIO is not set
|
||||
CONFIG_RT_LIBC_USING_TIME=y
|
||||
# CONFIG_RT_USING_MODULE is not set
|
||||
CONFIG_RT_LIBC_DEFAULT_TIMEZONE=8
|
||||
|
||||
#
|
||||
# Interprocess Communication (IPC)
|
||||
#
|
||||
# CONFIG_RT_USING_POSIX_PIPE is not set
|
||||
# CONFIG_RT_USING_POSIX_MESSAGE_QUEUE is not set
|
||||
# CONFIG_RT_USING_POSIX_MESSAGE_SEMAPHORE is not set
|
||||
|
||||
#
|
||||
# Socket is in the 'Network' category
|
||||
#
|
||||
CONFIG_RT_USING_CPLUSPLUS=y
|
||||
# CONFIG_RT_USING_CPLUSPLUS11 is not set
|
||||
|
||||
#
|
||||
# Network
|
||||
#
|
||||
|
||||
#
|
||||
# Socket abstraction layer
|
||||
#
|
||||
# CONFIG_RT_USING_SAL is not set
|
||||
|
||||
#
|
||||
# Network interface device
|
||||
#
|
||||
# CONFIG_RT_USING_NETDEV is not set
|
||||
|
||||
#
|
||||
# light weight TCP/IP stack
|
||||
#
|
||||
# CONFIG_RT_USING_LWIP is not set
|
||||
|
||||
#
|
||||
# AT commands
|
||||
#
|
||||
# CONFIG_RT_USING_AT is not set
|
||||
|
||||
#
|
||||
# VBUS(Virtual Software BUS)
|
||||
#
|
||||
# CONFIG_RT_USING_VBUS is not set
|
||||
|
||||
#
|
||||
# Utilities
|
||||
#
|
||||
|
@ -249,7 +273,7 @@ CONFIG_RT_LIBC_DEFAULT_TIMEZONE=8
|
|||
# CONFIG_RT_USING_UTEST is not set
|
||||
# CONFIG_RT_USING_VAR_EXPORT is not set
|
||||
# CONFIG_RT_USING_RT_LINK is not set
|
||||
# CONFIG_RT_USING_LWP is not set
|
||||
# CONFIG_RT_USING_VBUS is not set
|
||||
|
||||
#
|
||||
# RT-Thread Utestcases
|
||||
|
@ -272,11 +296,20 @@ CONFIG_BSP_USING_UART1=y
|
|||
# CONFIG_BSP_UART1_RX_USING_DMA is not set
|
||||
# CONFIG_BSP_USING_UART2 is not set
|
||||
# CONFIG_BSP_USING_LPUART1 is not set
|
||||
CONFIG_BSP_USING_SDRAM=y
|
||||
CONFIG_BSP_USING_QSPI=y
|
||||
CONFIG_BSP_USING_ONCHIP_RTC=y
|
||||
# CONFIG_BSP_USING_CRC is not set
|
||||
# CONFIG_BSP_USING_RNG is not set
|
||||
# CONFIG_BSP_USING_UDID is not set
|
||||
|
||||
#
|
||||
# Onboard Peripheral Drivers
|
||||
#
|
||||
CONFIG_BSP_USING_SDRAM=y
|
||||
# CONFIG_BSP_USING_QSPI_FLASH is not set
|
||||
CONFIG_BSP_USING_SDMMC=y
|
||||
CONFIG_BSP_USING_USBD=y
|
||||
|
||||
#
|
||||
# More Drivers
|
||||
#
|
||||
|
|
|
@ -83,3 +83,32 @@
|
|||
| PG8 | FMC_SDCLK |
|
||||
| PG15 | FMC_SDNCAS |
|
||||
| PF11 | FMC_SDNRAS |
|
||||
|
||||
### QSPI FLASH W25Q256JV
|
||||
|
||||
| 引脚 | 作用 |
|
||||
| ---- | --------------- |
|
||||
| PF6 | QUADSPI_BK1_IO3 |
|
||||
| PF7 | QUADSPI_BK1_IO2 |
|
||||
| PF8 | QUADSPI_BK1_IO0 |
|
||||
| PF9 | QUADSPI_BK1_IO1 |
|
||||
| PF10 | QUADSPI_CLK |
|
||||
| PG6 | QUADSPI_BK1_NCS |
|
||||
|
||||
### SDIO USD-1040310811
|
||||
|
||||
| 引脚 | 作用 |
|
||||
| ---- | ---------- |
|
||||
| PC8 | SDMMC1_D0 |
|
||||
| PC9 | SDMMC1_D1 |
|
||||
| PC10 | SDMMC1_D2 |
|
||||
| PC11 | SDMMC1_D3 |
|
||||
| PC12 | SDMMC1_CK |
|
||||
| PD2 | SDMMC1_CMD |
|
||||
|
||||
### USBCDC
|
||||
|
||||
| 引脚 | 作用 |
|
||||
| ---- | ------------- |
|
||||
| PA11 | USB_OTG_FS_DM |
|
||||
| PA12 | USB_OTG_FS_DP |
|
|
@ -31,9 +31,11 @@ extern int FrameworkInit();
|
|||
int main(void)
|
||||
{
|
||||
rt_pin_mode(LEDR_PIN, PIN_MODE_OUTPUT);
|
||||
rt_thread_mdelay(100);
|
||||
FrameworkInit();
|
||||
printf("XIUOS stm32h7 build %s %s\n",__DATE__,__TIME__);
|
||||
#ifdef BSP_USING_USBD
|
||||
//rt_console_set_device("vcom");
|
||||
#endif
|
||||
while (1)
|
||||
{
|
||||
rt_pin_write(LEDR_PIN, PIN_HIGH);
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -49,6 +49,8 @@ extern "C" {
|
|||
|
||||
/* USER CODE END EM */
|
||||
|
||||
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
|
||||
|
||||
/* Exported functions prototypes ---------------------------------------------*/
|
||||
void Error_Handler(void);
|
||||
|
||||
|
@ -59,10 +61,6 @@ void Error_Handler(void);
|
|||
/* Private defines -----------------------------------------------------------*/
|
||||
#define LED_RED_Pin GPIO_PIN_0
|
||||
#define LED_RED_GPIO_Port GPIOC
|
||||
#define LED_GREEN_Pin GPIO_PIN_1
|
||||
#define LED_GREEN_GPIO_Port GPIOC
|
||||
#define LED_BLUE_Pin GPIO_PIN_2
|
||||
#define LED_BLUE_GPIO_Port GPIOC
|
||||
/* USER CODE BEGIN Private defines */
|
||||
|
||||
/* USER CODE END Private defines */
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
/* #define HAL_CRC_MODULE_ENABLED */
|
||||
/* #define HAL_CRYP_MODULE_ENABLED */
|
||||
/* #define HAL_DAC_MODULE_ENABLED */
|
||||
/* #define HAL_DCMI_MODULE_ENABLED */
|
||||
#define HAL_DCMI_MODULE_ENABLED
|
||||
/* #define HAL_DMA2D_MODULE_ENABLED */
|
||||
/* #define HAL_ETH_MODULE_ENABLED */
|
||||
/* #define HAL_NAND_MODULE_ENABLED */
|
||||
|
@ -64,23 +64,23 @@
|
|||
/* #define HAL_IWDG_MODULE_ENABLED */
|
||||
/* #define HAL_LPTIM_MODULE_ENABLED */
|
||||
/* #define HAL_LTDC_MODULE_ENABLED */
|
||||
/* #define HAL_QSPI_MODULE_ENABLED */
|
||||
#define HAL_QSPI_MODULE_ENABLED
|
||||
/* #define HAL_RAMECC_MODULE_ENABLED */
|
||||
/* #define HAL_RNG_MODULE_ENABLED */
|
||||
/* #define HAL_RTC_MODULE_ENABLED */
|
||||
#define HAL_RTC_MODULE_ENABLED
|
||||
/* #define HAL_SAI_MODULE_ENABLED */
|
||||
/* #define HAL_SD_MODULE_ENABLED */
|
||||
#define HAL_SD_MODULE_ENABLED
|
||||
/* #define HAL_MMC_MODULE_ENABLED */
|
||||
/* #define HAL_SPDIFRX_MODULE_ENABLED */
|
||||
/* #define HAL_SPI_MODULE_ENABLED */
|
||||
/* #define HAL_SWPMI_MODULE_ENABLED */
|
||||
/* #define HAL_TIM_MODULE_ENABLED */
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
#define HAL_UART_MODULE_ENABLED
|
||||
/* #define HAL_USART_MODULE_ENABLED */
|
||||
/* #define HAL_IRDA_MODULE_ENABLED */
|
||||
/* #define HAL_SMARTCARD_MODULE_ENABLED */
|
||||
/* #define HAL_WWDG_MODULE_ENABLED */
|
||||
/* #define HAL_PCD_MODULE_ENABLED */
|
||||
#define HAL_PCD_MODULE_ENABLED
|
||||
/* #define HAL_HCD_MODULE_ENABLED */
|
||||
/* #define HAL_DFSDM_MODULE_ENABLED */
|
||||
/* #define HAL_DSI_MODULE_ENABLED */
|
||||
|
@ -168,7 +168,7 @@
|
|||
#define TICK_INT_PRIORITY (15UL) /*!< tick interrupt priority */
|
||||
#define USE_RTOS 0
|
||||
#define USE_SD_TRANSCEIVER 0U /*!< use uSD Transceiver */
|
||||
#define USE_SPI_CRC 0U /*!< use CRC in SPI */
|
||||
#define USE_SPI_CRC 0U /*!< use CRC in SPI */
|
||||
|
||||
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
|
||||
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
|
||||
|
|
|
@ -55,6 +55,11 @@ void SVC_Handler(void);
|
|||
void DebugMon_Handler(void);
|
||||
void PendSV_Handler(void);
|
||||
void SysTick_Handler(void);
|
||||
void DMA1_Stream3_IRQHandler(void);
|
||||
void SDMMC1_IRQHandler(void);
|
||||
void DCMI_IRQHandler(void);
|
||||
void OTG_FS_EP1_OUT_IRQHandler(void);
|
||||
void OTG_FS_EP1_IN_IRQHandler(void);
|
||||
/* USER CODE BEGIN EFP */
|
||||
|
||||
/* USER CODE END EFP */
|
||||
|
|
|
@ -40,8 +40,21 @@
|
|||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
|
||||
DCMI_HandleTypeDef hdcmi;
|
||||
DMA_HandleTypeDef hdma_dcmi;
|
||||
|
||||
QSPI_HandleTypeDef hqspi;
|
||||
|
||||
RTC_HandleTypeDef hrtc;
|
||||
|
||||
SD_HandleTypeDef hsd1;
|
||||
|
||||
TIM_HandleTypeDef htim1;
|
||||
|
||||
UART_HandleTypeDef huart1;
|
||||
|
||||
PCD_HandleTypeDef hpcd_USB_OTG_FS;
|
||||
|
||||
SDRAM_HandleTypeDef hsdram1;
|
||||
|
||||
/* USER CODE BEGIN PV */
|
||||
|
@ -53,6 +66,13 @@ void SystemClock_Config(void);
|
|||
static void MX_GPIO_Init(void);
|
||||
static void MX_USART1_UART_Init(void);
|
||||
static void MX_FMC_Init(void);
|
||||
static void MX_QUADSPI_Init(void);
|
||||
static void MX_SDMMC1_SD_Init(void);
|
||||
static void MX_DMA_Init(void);
|
||||
static void MX_RTC_Init(void);
|
||||
static void MX_DCMI_Init(void);
|
||||
static void MX_USB_OTG_FS_PCD_Init(void);
|
||||
static void MX_TIM1_Init(void);
|
||||
/* USER CODE BEGIN PFP */
|
||||
|
||||
/* USER CODE END PFP */
|
||||
|
@ -72,6 +92,12 @@ int main(void)
|
|||
|
||||
/* USER CODE END 1 */
|
||||
|
||||
/* Enable I-Cache---------------------------------------------------------*/
|
||||
SCB_EnableICache();
|
||||
|
||||
/* Enable D-Cache---------------------------------------------------------*/
|
||||
SCB_EnableDCache();
|
||||
|
||||
/* MCU Configuration--------------------------------------------------------*/
|
||||
|
||||
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
|
||||
|
@ -92,6 +118,13 @@ int main(void)
|
|||
MX_GPIO_Init();
|
||||
MX_USART1_UART_Init();
|
||||
MX_FMC_Init();
|
||||
MX_QUADSPI_Init();
|
||||
MX_SDMMC1_SD_Init();
|
||||
MX_DMA_Init();
|
||||
MX_RTC_Init();
|
||||
MX_DCMI_Init();
|
||||
MX_USB_OTG_FS_PCD_Init();
|
||||
MX_TIM1_Init();
|
||||
/* USER CODE BEGIN 2 */
|
||||
|
||||
/* USER CODE END 2 */
|
||||
|
@ -119,24 +152,25 @@ void SystemClock_Config(void)
|
|||
/** Supply configuration update enable
|
||||
*/
|
||||
HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
|
||||
|
||||
/** Configure the main internal regulator output voltage
|
||||
*/
|
||||
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
|
||||
|
||||
while(!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {}
|
||||
|
||||
/** Initializes the RCC Oscillators according to the specified parameters
|
||||
* in the RCC_OscInitTypeDef structure.
|
||||
*/
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48|RCC_OSCILLATORTYPE_LSI
|
||||
|RCC_OSCILLATORTYPE_HSE;
|
||||
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
|
||||
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
|
||||
RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
|
||||
RCC_OscInitStruct.PLL.PLLM = 3;
|
||||
RCC_OscInitStruct.PLL.PLLN = 200;
|
||||
RCC_OscInitStruct.PLL.PLLP = 2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = 2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = 4;
|
||||
RCC_OscInitStruct.PLL.PLLR = 2;
|
||||
RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2;
|
||||
RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
|
||||
|
@ -145,7 +179,6 @@ void SystemClock_Config(void)
|
|||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/** Initializes the CPU, AHB and APB buses clocks
|
||||
*/
|
||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|
||||
|
@ -165,6 +198,242 @@ void SystemClock_Config(void)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCMI Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_DCMI_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN DCMI_Init 0 */
|
||||
|
||||
/* USER CODE END DCMI_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN DCMI_Init 1 */
|
||||
|
||||
/* USER CODE END DCMI_Init 1 */
|
||||
hdcmi.Instance = DCMI;
|
||||
hdcmi.Init.SynchroMode = DCMI_SYNCHRO_HARDWARE;
|
||||
hdcmi.Init.PCKPolarity = DCMI_PCKPOLARITY_FALLING;
|
||||
hdcmi.Init.VSPolarity = DCMI_VSPOLARITY_LOW;
|
||||
hdcmi.Init.HSPolarity = DCMI_HSPOLARITY_LOW;
|
||||
hdcmi.Init.CaptureRate = DCMI_CR_ALL_FRAME;
|
||||
hdcmi.Init.ExtendedDataMode = DCMI_EXTEND_DATA_8B;
|
||||
hdcmi.Init.JPEGMode = DCMI_JPEG_ENABLE;
|
||||
hdcmi.Init.ByteSelectMode = DCMI_BSM_ALL;
|
||||
hdcmi.Init.ByteSelectStart = DCMI_OEBS_ODD;
|
||||
hdcmi.Init.LineSelectMode = DCMI_LSM_ALL;
|
||||
hdcmi.Init.LineSelectStart = DCMI_OELS_ODD;
|
||||
if (HAL_DCMI_Init(&hdcmi) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN DCMI_Init 2 */
|
||||
|
||||
/* USER CODE END DCMI_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief QUADSPI Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_QUADSPI_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN QUADSPI_Init 0 */
|
||||
|
||||
/* USER CODE END QUADSPI_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN QUADSPI_Init 1 */
|
||||
|
||||
/* USER CODE END QUADSPI_Init 1 */
|
||||
/* QUADSPI parameter configuration*/
|
||||
hqspi.Instance = QUADSPI;
|
||||
hqspi.Init.ClockPrescaler = 1;
|
||||
hqspi.Init.FifoThreshold = 3;
|
||||
hqspi.Init.SampleShifting = QSPI_SAMPLE_SHIFTING_HALFCYCLE;
|
||||
hqspi.Init.FlashSize = 24;
|
||||
hqspi.Init.ChipSelectHighTime = QSPI_CS_HIGH_TIME_2_CYCLE;
|
||||
hqspi.Init.ClockMode = QSPI_CLOCK_MODE_0;
|
||||
hqspi.Init.FlashID = QSPI_FLASH_ID_1;
|
||||
hqspi.Init.DualFlash = QSPI_DUALFLASH_DISABLE;
|
||||
if (HAL_QSPI_Init(&hqspi) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN QUADSPI_Init 2 */
|
||||
|
||||
/* USER CODE END QUADSPI_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief RTC Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_RTC_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN RTC_Init 0 */
|
||||
|
||||
/* USER CODE END RTC_Init 0 */
|
||||
|
||||
RTC_TimeTypeDef sTime = {0};
|
||||
RTC_DateTypeDef sDate = {0};
|
||||
|
||||
/* USER CODE BEGIN RTC_Init 1 */
|
||||
|
||||
/* USER CODE END RTC_Init 1 */
|
||||
/** Initialize RTC Only
|
||||
*/
|
||||
hrtc.Instance = RTC;
|
||||
hrtc.Init.HourFormat = RTC_HOURFORMAT_24;
|
||||
hrtc.Init.AsynchPrediv = 127;
|
||||
hrtc.Init.SynchPrediv = 255;
|
||||
hrtc.Init.OutPut = RTC_OUTPUT_DISABLE;
|
||||
hrtc.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH;
|
||||
hrtc.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN;
|
||||
hrtc.Init.OutPutRemap = RTC_OUTPUT_REMAP_NONE;
|
||||
if (HAL_RTC_Init(&hrtc) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/* USER CODE BEGIN Check_RTC_BKUP */
|
||||
|
||||
/* USER CODE END Check_RTC_BKUP */
|
||||
|
||||
/** Initialize RTC and set the Time and Date
|
||||
*/
|
||||
sTime.Hours = 0x0;
|
||||
sTime.Minutes = 0x0;
|
||||
sTime.Seconds = 0x0;
|
||||
sTime.DayLightSaving = RTC_DAYLIGHTSAVING_NONE;
|
||||
sTime.StoreOperation = RTC_STOREOPERATION_RESET;
|
||||
if (HAL_RTC_SetTime(&hrtc, &sTime, RTC_FORMAT_BCD) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
sDate.WeekDay = RTC_WEEKDAY_MONDAY;
|
||||
sDate.Month = RTC_MONTH_JANUARY;
|
||||
sDate.Date = 0x1;
|
||||
sDate.Year = 0x0;
|
||||
|
||||
if (HAL_RTC_SetDate(&hrtc, &sDate, RTC_FORMAT_BCD) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN RTC_Init 2 */
|
||||
|
||||
/* USER CODE END RTC_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SDMMC1 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_SDMMC1_SD_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN SDMMC1_Init 0 */
|
||||
|
||||
/* USER CODE END SDMMC1_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN SDMMC1_Init 1 */
|
||||
|
||||
/* USER CODE END SDMMC1_Init 1 */
|
||||
hsd1.Instance = SDMMC1;
|
||||
hsd1.Init.ClockEdge = SDMMC_CLOCK_EDGE_RISING;
|
||||
hsd1.Init.ClockPowerSave = SDMMC_CLOCK_POWER_SAVE_DISABLE;
|
||||
hsd1.Init.BusWide = SDMMC_BUS_WIDE_4B;
|
||||
hsd1.Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_DISABLE;
|
||||
hsd1.Init.ClockDiv = 4;
|
||||
if (HAL_SD_Init(&hsd1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN SDMMC1_Init 2 */
|
||||
|
||||
/* USER CODE END SDMMC1_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM1 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_TIM1_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN TIM1_Init 0 */
|
||||
|
||||
/* USER CODE END TIM1_Init 0 */
|
||||
|
||||
TIM_MasterConfigTypeDef sMasterConfig = {0};
|
||||
TIM_OC_InitTypeDef sConfigOC = {0};
|
||||
TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
|
||||
|
||||
/* USER CODE BEGIN TIM1_Init 1 */
|
||||
|
||||
/* USER CODE END TIM1_Init 1 */
|
||||
htim1.Instance = TIM1;
|
||||
htim1.Init.Prescaler = 0;
|
||||
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
htim1.Init.Period = 7;
|
||||
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
htim1.Init.RepetitionCounter = 0;
|
||||
htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
|
||||
if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
|
||||
sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
|
||||
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
|
||||
if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
sConfigOC.OCMode = TIM_OCMODE_PWM1;
|
||||
sConfigOC.Pulse = 3;
|
||||
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
|
||||
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
|
||||
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
|
||||
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
|
||||
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
|
||||
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
|
||||
sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
|
||||
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
|
||||
sBreakDeadTimeConfig.DeadTime = 0;
|
||||
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
|
||||
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
|
||||
sBreakDeadTimeConfig.BreakFilter = 0;
|
||||
sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE;
|
||||
sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH;
|
||||
sBreakDeadTimeConfig.Break2Filter = 0;
|
||||
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
|
||||
if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN TIM1_Init 2 */
|
||||
|
||||
/* USER CODE END TIM1_Init 2 */
|
||||
HAL_TIM_MspPostInit(&htim1);
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USART1 Initialization Function
|
||||
* @param None
|
||||
|
@ -213,6 +482,58 @@ static void MX_USART1_UART_Init(void)
|
|||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_FS Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_USB_OTG_FS_PCD_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN USB_OTG_FS_Init 0 */
|
||||
|
||||
/* USER CODE END USB_OTG_FS_Init 0 */
|
||||
|
||||
/* USER CODE BEGIN USB_OTG_FS_Init 1 */
|
||||
|
||||
/* USER CODE END USB_OTG_FS_Init 1 */
|
||||
hpcd_USB_OTG_FS.Instance = USB_OTG_FS;
|
||||
hpcd_USB_OTG_FS.Init.dev_endpoints = 9;
|
||||
hpcd_USB_OTG_FS.Init.speed = PCD_SPEED_FULL;
|
||||
hpcd_USB_OTG_FS.Init.dma_enable = DISABLE;
|
||||
hpcd_USB_OTG_FS.Init.phy_itface = PCD_PHY_EMBEDDED;
|
||||
hpcd_USB_OTG_FS.Init.Sof_enable = DISABLE;
|
||||
hpcd_USB_OTG_FS.Init.low_power_enable = DISABLE;
|
||||
hpcd_USB_OTG_FS.Init.lpm_enable = DISABLE;
|
||||
hpcd_USB_OTG_FS.Init.battery_charging_enable = DISABLE;
|
||||
hpcd_USB_OTG_FS.Init.vbus_sensing_enable = DISABLE;
|
||||
hpcd_USB_OTG_FS.Init.use_dedicated_ep1 = DISABLE;
|
||||
if (HAL_PCD_Init(&hpcd_USB_OTG_FS) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN USB_OTG_FS_Init 2 */
|
||||
|
||||
/* USER CODE END USB_OTG_FS_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable DMA controller clock
|
||||
*/
|
||||
static void MX_DMA_Init(void)
|
||||
{
|
||||
|
||||
/* DMA controller clock enable */
|
||||
__HAL_RCC_DMA1_CLK_ENABLE();
|
||||
|
||||
/* DMA interrupt init */
|
||||
/* DMA1_Stream3_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(DMA1_Stream3_IRQn, 0, 0);
|
||||
HAL_NVIC_EnableIRQ(DMA1_Stream3_IRQn);
|
||||
|
||||
}
|
||||
|
||||
/* FMC initialization function */
|
||||
static void MX_FMC_Init(void)
|
||||
{
|
||||
|
@ -271,24 +592,24 @@ static void MX_GPIO_Init(void)
|
|||
|
||||
/* GPIO Ports Clock Enable */
|
||||
__HAL_RCC_GPIOE_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOG_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOD_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOI_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOH_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOF_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||
|
||||
/*Configure GPIO pin Output Level */
|
||||
HAL_GPIO_WritePin(GPIOC, LED_RED_Pin|LED_GREEN_Pin|LED_BLUE_Pin, GPIO_PIN_RESET);
|
||||
HAL_GPIO_WritePin(LED_RED_GPIO_Port, LED_RED_Pin, GPIO_PIN_RESET);
|
||||
|
||||
/*Configure GPIO pins : LED_RED_Pin LED_GREEN_Pin LED_BLUE_Pin */
|
||||
GPIO_InitStruct.Pin = LED_RED_Pin|LED_GREEN_Pin|LED_BLUE_Pin;
|
||||
/*Configure GPIO pin : LED_RED_Pin */
|
||||
GPIO_InitStruct.Pin = LED_RED_Pin;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||
HAL_GPIO_Init(LED_RED_GPIO_Port, &GPIO_InitStruct);
|
||||
|
||||
}
|
||||
|
||||
|
@ -327,3 +648,4 @@ void assert_failed(uint8_t *file, uint32_t line)
|
|||
/* USER CODE END 6 */
|
||||
}
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
#include "drv_common.h"
|
||||
#endif
|
||||
/* USER CODE END Includes */
|
||||
extern DMA_HandleTypeDef hdma_dcmi;
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* USER CODE BEGIN TD */
|
||||
|
@ -59,7 +60,9 @@
|
|||
/* USER CODE BEGIN 0 */
|
||||
|
||||
/* USER CODE END 0 */
|
||||
/**
|
||||
|
||||
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
|
||||
/**
|
||||
* Initializes the Global MSP.
|
||||
*/
|
||||
void HAL_MspInit(void)
|
||||
|
@ -77,6 +80,484 @@ void HAL_MspInit(void)
|
|||
/* USER CODE END MspInit 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCMI MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
* @param hdcmi: DCMI handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_DCMI_MspInit(DCMI_HandleTypeDef* hdcmi)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||
if(hdcmi->Instance==DCMI)
|
||||
{
|
||||
/* USER CODE BEGIN DCMI_MspInit 0 */
|
||||
|
||||
/* USER CODE END DCMI_MspInit 0 */
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_DCMI_CLK_ENABLE();
|
||||
|
||||
__HAL_RCC_GPIOE_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOG_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
/**DCMI GPIO Configuration
|
||||
PE4 ------> DCMI_D4
|
||||
PE5 ------> DCMI_D6
|
||||
PE6 ------> DCMI_D7
|
||||
PB7 ------> DCMI_VSYNC
|
||||
PB6 ------> DCMI_D5
|
||||
PG11 ------> DCMI_D3
|
||||
PG10 ------> DCMI_D2
|
||||
PC7 ------> DCMI_D1
|
||||
PC6 ------> DCMI_D0
|
||||
PA4 ------> DCMI_HSYNC
|
||||
PA6 ------> DCMI_PIXCLK
|
||||
*/
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF13_DCMI;
|
||||
HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_7|GPIO_PIN_6;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF13_DCMI;
|
||||
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_10;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF13_DCMI;
|
||||
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_7|GPIO_PIN_6;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF13_DCMI;
|
||||
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_6;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF13_DCMI;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
/* DCMI DMA Init */
|
||||
/* DCMI Init */
|
||||
hdma_dcmi.Instance = DMA1_Stream3;
|
||||
hdma_dcmi.Init.Request = DMA_REQUEST_DCMI;
|
||||
hdma_dcmi.Init.Direction = DMA_PERIPH_TO_MEMORY;
|
||||
hdma_dcmi.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||
hdma_dcmi.Init.MemInc = DMA_MINC_ENABLE;
|
||||
hdma_dcmi.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
|
||||
hdma_dcmi.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
|
||||
hdma_dcmi.Init.Mode = DMA_CIRCULAR;
|
||||
hdma_dcmi.Init.Priority = DMA_PRIORITY_HIGH;
|
||||
hdma_dcmi.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
|
||||
hdma_dcmi.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
|
||||
hdma_dcmi.Init.MemBurst = DMA_MBURST_SINGLE;
|
||||
hdma_dcmi.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||
if (HAL_DMA_Init(&hdma_dcmi) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
__HAL_LINKDMA(hdcmi,DMA_Handle,hdma_dcmi);
|
||||
|
||||
/* DCMI interrupt Init */
|
||||
HAL_NVIC_SetPriority(DCMI_IRQn, 0, 0);
|
||||
HAL_NVIC_EnableIRQ(DCMI_IRQn);
|
||||
/* USER CODE BEGIN DCMI_MspInit 1 */
|
||||
|
||||
/* USER CODE END DCMI_MspInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCMI MSP De-Initialization
|
||||
* This function freeze the hardware resources used in this example
|
||||
* @param hdcmi: DCMI handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_DCMI_MspDeInit(DCMI_HandleTypeDef* hdcmi)
|
||||
{
|
||||
if(hdcmi->Instance==DCMI)
|
||||
{
|
||||
/* USER CODE BEGIN DCMI_MspDeInit 0 */
|
||||
|
||||
/* USER CODE END DCMI_MspDeInit 0 */
|
||||
/* Peripheral clock disable */
|
||||
__HAL_RCC_DCMI_CLK_DISABLE();
|
||||
|
||||
/**DCMI GPIO Configuration
|
||||
PE4 ------> DCMI_D4
|
||||
PE5 ------> DCMI_D6
|
||||
PE6 ------> DCMI_D7
|
||||
PB7 ------> DCMI_VSYNC
|
||||
PB6 ------> DCMI_D5
|
||||
PG11 ------> DCMI_D3
|
||||
PG10 ------> DCMI_D2
|
||||
PC7 ------> DCMI_D1
|
||||
PC6 ------> DCMI_D0
|
||||
PA4 ------> DCMI_HSYNC
|
||||
PA6 ------> DCMI_PIXCLK
|
||||
*/
|
||||
HAL_GPIO_DeInit(GPIOE, GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6);
|
||||
|
||||
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_7|GPIO_PIN_6);
|
||||
|
||||
HAL_GPIO_DeInit(GPIOG, GPIO_PIN_11|GPIO_PIN_10);
|
||||
|
||||
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_7|GPIO_PIN_6);
|
||||
|
||||
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_4|GPIO_PIN_6);
|
||||
|
||||
/* DCMI DMA DeInit */
|
||||
HAL_DMA_DeInit(hdcmi->DMA_Handle);
|
||||
|
||||
/* DCMI interrupt DeInit */
|
||||
HAL_NVIC_DisableIRQ(DCMI_IRQn);
|
||||
/* USER CODE BEGIN DCMI_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END DCMI_MspDeInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief QSPI MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
* @param hqspi: QSPI handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_QSPI_MspInit(QSPI_HandleTypeDef* hqspi)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
|
||||
if(hqspi->Instance==QUADSPI)
|
||||
{
|
||||
/* USER CODE BEGIN QUADSPI_MspInit 0 */
|
||||
|
||||
/* USER CODE END QUADSPI_MspInit 0 */
|
||||
/** Initializes the peripherals clock
|
||||
*/
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_QSPI;
|
||||
PeriphClkInitStruct.QspiClockSelection = RCC_QSPICLKSOURCE_D1HCLK;
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_QSPI_CLK_ENABLE();
|
||||
|
||||
__HAL_RCC_GPIOG_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOF_CLK_ENABLE();
|
||||
/**QUADSPI GPIO Configuration
|
||||
PG6 ------> QUADSPI_BK1_NCS
|
||||
PF7 ------> QUADSPI_BK1_IO2
|
||||
PF6 ------> QUADSPI_BK1_IO3
|
||||
PF10 ------> QUADSPI_CLK
|
||||
PF9 ------> QUADSPI_BK1_IO1
|
||||
PF8 ------> QUADSPI_BK1_IO0
|
||||
*/
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_6;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_QUADSPI;
|
||||
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_7|GPIO_PIN_6|GPIO_PIN_10;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF9_QUADSPI;
|
||||
HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_9|GPIO_PIN_8;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_QUADSPI;
|
||||
HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
|
||||
|
||||
/* USER CODE BEGIN QUADSPI_MspInit 1 */
|
||||
|
||||
/* USER CODE END QUADSPI_MspInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief QSPI MSP De-Initialization
|
||||
* This function freeze the hardware resources used in this example
|
||||
* @param hqspi: QSPI handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef* hqspi)
|
||||
{
|
||||
if(hqspi->Instance==QUADSPI)
|
||||
{
|
||||
/* USER CODE BEGIN QUADSPI_MspDeInit 0 */
|
||||
|
||||
/* USER CODE END QUADSPI_MspDeInit 0 */
|
||||
/* Peripheral clock disable */
|
||||
__HAL_RCC_QSPI_CLK_DISABLE();
|
||||
|
||||
/**QUADSPI GPIO Configuration
|
||||
PG6 ------> QUADSPI_BK1_NCS
|
||||
PF7 ------> QUADSPI_BK1_IO2
|
||||
PF6 ------> QUADSPI_BK1_IO3
|
||||
PF10 ------> QUADSPI_CLK
|
||||
PF9 ------> QUADSPI_BK1_IO1
|
||||
PF8 ------> QUADSPI_BK1_IO0
|
||||
*/
|
||||
HAL_GPIO_DeInit(GPIOG, GPIO_PIN_6);
|
||||
|
||||
HAL_GPIO_DeInit(GPIOF, GPIO_PIN_7|GPIO_PIN_6|GPIO_PIN_10|GPIO_PIN_9
|
||||
|GPIO_PIN_8);
|
||||
|
||||
/* USER CODE BEGIN QUADSPI_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END QUADSPI_MspDeInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief RTC MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
* @param hrtc: RTC handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_RTC_MspInit(RTC_HandleTypeDef* hrtc)
|
||||
{
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
|
||||
if(hrtc->Instance==RTC)
|
||||
{
|
||||
/* USER CODE BEGIN RTC_MspInit 0 */
|
||||
|
||||
/* USER CODE END RTC_MspInit 0 */
|
||||
/** Initializes the peripherals clock
|
||||
*/
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC;
|
||||
PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSI;
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_RTC_ENABLE();
|
||||
/* USER CODE BEGIN RTC_MspInit 1 */
|
||||
|
||||
/* USER CODE END RTC_MspInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief RTC MSP De-Initialization
|
||||
* This function freeze the hardware resources used in this example
|
||||
* @param hrtc: RTC handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_RTC_MspDeInit(RTC_HandleTypeDef* hrtc)
|
||||
{
|
||||
if(hrtc->Instance==RTC)
|
||||
{
|
||||
/* USER CODE BEGIN RTC_MspDeInit 0 */
|
||||
|
||||
/* USER CODE END RTC_MspDeInit 0 */
|
||||
/* Peripheral clock disable */
|
||||
__HAL_RCC_RTC_DISABLE();
|
||||
/* USER CODE BEGIN RTC_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END RTC_MspDeInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SD MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
* @param hsd: SD handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_SD_MspInit(SD_HandleTypeDef* hsd)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
|
||||
if(hsd->Instance==SDMMC1)
|
||||
{
|
||||
/* USER CODE BEGIN SDMMC1_MspInit 0 */
|
||||
|
||||
/* USER CODE END SDMMC1_MspInit 0 */
|
||||
/** Initializes the peripherals clock
|
||||
*/
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_SDMMC;
|
||||
PeriphClkInitStruct.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL;
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_SDMMC1_CLK_ENABLE();
|
||||
|
||||
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOD_CLK_ENABLE();
|
||||
/**SDMMC1 GPIO Configuration
|
||||
PC12 ------> SDMMC1_CK
|
||||
PC11 ------> SDMMC1_D3
|
||||
PC10 ------> SDMMC1_D2
|
||||
PD2 ------> SDMMC1_CMD
|
||||
PC9 ------> SDMMC1_D1
|
||||
PC8 ------> SDMMC1_D0
|
||||
*/
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_12|GPIO_PIN_11|GPIO_PIN_10|GPIO_PIN_9
|
||||
|GPIO_PIN_8;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO1;
|
||||
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_2;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO1;
|
||||
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
|
||||
|
||||
/* SDMMC1 interrupt Init */
|
||||
HAL_NVIC_SetPriority(SDMMC1_IRQn, 0, 0);
|
||||
HAL_NVIC_EnableIRQ(SDMMC1_IRQn);
|
||||
/* USER CODE BEGIN SDMMC1_MspInit 1 */
|
||||
|
||||
/* USER CODE END SDMMC1_MspInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SD MSP De-Initialization
|
||||
* This function freeze the hardware resources used in this example
|
||||
* @param hsd: SD handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_SD_MspDeInit(SD_HandleTypeDef* hsd)
|
||||
{
|
||||
if(hsd->Instance==SDMMC1)
|
||||
{
|
||||
/* USER CODE BEGIN SDMMC1_MspDeInit 0 */
|
||||
|
||||
/* USER CODE END SDMMC1_MspDeInit 0 */
|
||||
/* Peripheral clock disable */
|
||||
__HAL_RCC_SDMMC1_CLK_DISABLE();
|
||||
|
||||
/**SDMMC1 GPIO Configuration
|
||||
PC12 ------> SDMMC1_CK
|
||||
PC11 ------> SDMMC1_D3
|
||||
PC10 ------> SDMMC1_D2
|
||||
PD2 ------> SDMMC1_CMD
|
||||
PC9 ------> SDMMC1_D1
|
||||
PC8 ------> SDMMC1_D0
|
||||
*/
|
||||
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_12|GPIO_PIN_11|GPIO_PIN_10|GPIO_PIN_9
|
||||
|GPIO_PIN_8);
|
||||
|
||||
HAL_GPIO_DeInit(GPIOD, GPIO_PIN_2);
|
||||
|
||||
/* SDMMC1 interrupt DeInit */
|
||||
HAL_NVIC_DisableIRQ(SDMMC1_IRQn);
|
||||
/* USER CODE BEGIN SDMMC1_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END SDMMC1_MspDeInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM_PWM MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
* @param htim_pwm: TIM_PWM handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm)
|
||||
{
|
||||
if(htim_pwm->Instance==TIM1)
|
||||
{
|
||||
/* USER CODE BEGIN TIM1_MspInit 0 */
|
||||
|
||||
/* USER CODE END TIM1_MspInit 0 */
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_TIM1_CLK_ENABLE();
|
||||
/* USER CODE BEGIN TIM1_MspInit 1 */
|
||||
|
||||
/* USER CODE END TIM1_MspInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||
if(htim->Instance==TIM1)
|
||||
{
|
||||
/* USER CODE BEGIN TIM1_MspPostInit 0 */
|
||||
|
||||
/* USER CODE END TIM1_MspPostInit 0 */
|
||||
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
/**TIM1 GPIO Configuration
|
||||
PA8 ------> TIM1_CH1
|
||||
*/
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_8;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF1_TIM1;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
/* USER CODE BEGIN TIM1_MspPostInit 1 */
|
||||
|
||||
/* USER CODE END TIM1_MspPostInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
/**
|
||||
* @brief TIM_PWM MSP De-Initialization
|
||||
* This function freeze the hardware resources used in this example
|
||||
* @param htim_pwm: TIM_PWM handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* htim_pwm)
|
||||
{
|
||||
if(htim_pwm->Instance==TIM1)
|
||||
{
|
||||
/* USER CODE BEGIN TIM1_MspDeInit 0 */
|
||||
|
||||
/* USER CODE END TIM1_MspDeInit 0 */
|
||||
/* Peripheral clock disable */
|
||||
__HAL_RCC_TIM1_CLK_DISABLE();
|
||||
/* USER CODE BEGIN TIM1_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END TIM1_MspDeInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief UART MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
|
@ -92,7 +573,6 @@ void HAL_UART_MspInit(UART_HandleTypeDef* huart)
|
|||
/* USER CODE BEGIN USART1_MspInit 0 */
|
||||
|
||||
/* USER CODE END USART1_MspInit 0 */
|
||||
|
||||
/** Initializes the peripherals clock
|
||||
*/
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1;
|
||||
|
@ -153,6 +633,91 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
|
|||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief PCD MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
* @param hpcd: PCD handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_MspInit(PCD_HandleTypeDef* hpcd)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
|
||||
if(hpcd->Instance==USB_OTG_FS)
|
||||
{
|
||||
/* USER CODE BEGIN USB_OTG_FS_MspInit 0 */
|
||||
|
||||
/* USER CODE END USB_OTG_FS_MspInit 0 */
|
||||
/** Initializes the peripherals clock
|
||||
*/
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB;
|
||||
PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/** Enable USB Voltage detector
|
||||
*/
|
||||
HAL_PWREx_EnableUSBVoltageDetector();
|
||||
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
/**USB_OTG_FS GPIO Configuration
|
||||
PA12 ------> USB_OTG_FS_DP
|
||||
PA11 ------> USB_OTG_FS_DM
|
||||
*/
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_12|GPIO_PIN_11;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_FS;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
|
||||
/* USB_OTG_FS interrupt Init */
|
||||
HAL_NVIC_SetPriority(OTG_FS_EP1_OUT_IRQn, 0, 0);
|
||||
HAL_NVIC_EnableIRQ(OTG_FS_EP1_OUT_IRQn);
|
||||
HAL_NVIC_SetPriority(OTG_FS_EP1_IN_IRQn, 0, 0);
|
||||
HAL_NVIC_EnableIRQ(OTG_FS_EP1_IN_IRQn);
|
||||
/* USER CODE BEGIN USB_OTG_FS_MspInit 1 */
|
||||
|
||||
/* USER CODE END USB_OTG_FS_MspInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief PCD MSP De-Initialization
|
||||
* This function freeze the hardware resources used in this example
|
||||
* @param hpcd: PCD handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_MspDeInit(PCD_HandleTypeDef* hpcd)
|
||||
{
|
||||
if(hpcd->Instance==USB_OTG_FS)
|
||||
{
|
||||
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 0 */
|
||||
|
||||
/* USER CODE END USB_OTG_FS_MspDeInit 0 */
|
||||
/* Peripheral clock disable */
|
||||
__HAL_RCC_USB_OTG_FS_CLK_DISABLE();
|
||||
|
||||
/**USB_OTG_FS GPIO Configuration
|
||||
PA12 ------> USB_OTG_FS_DP
|
||||
PA11 ------> USB_OTG_FS_DM
|
||||
*/
|
||||
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_12|GPIO_PIN_11);
|
||||
|
||||
/* USB_OTG_FS interrupt DeInit */
|
||||
HAL_NVIC_DisableIRQ(OTG_FS_EP1_OUT_IRQn);
|
||||
HAL_NVIC_DisableIRQ(OTG_FS_EP1_IN_IRQn);
|
||||
/* USER CODE BEGIN USB_OTG_FS_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END USB_OTG_FS_MspDeInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static uint32_t FMC_Initialized = 0;
|
||||
|
||||
static void HAL_FMC_MspInit(void){
|
||||
|
@ -430,3 +995,4 @@ void HAL_SDRAM_MspDeInit(SDRAM_HandleTypeDef* hsdram){
|
|||
/* USER CODE BEGIN 1 */
|
||||
|
||||
/* USER CODE END 1 */
|
||||
|
||||
|
|
|
@ -1,4 +1,32 @@
|
|||
#MicroXplorer Configuration settings - do not modify
|
||||
CORTEX_M7.CPU_DCache=Enabled
|
||||
CORTEX_M7.CPU_ICache=Enabled
|
||||
CORTEX_M7.IPParameters=CPU_ICache,CPU_DCache
|
||||
DCMI.IPParameters=JPEGMode
|
||||
DCMI.JPEGMode=DCMI_JPEG_ENABLE
|
||||
Dma.DCMI.0.Direction=DMA_PERIPH_TO_MEMORY
|
||||
Dma.DCMI.0.EventEnable=DISABLE
|
||||
Dma.DCMI.0.FIFOMode=DMA_FIFOMODE_ENABLE
|
||||
Dma.DCMI.0.FIFOThreshold=DMA_FIFO_THRESHOLD_FULL
|
||||
Dma.DCMI.0.Instance=DMA1_Stream3
|
||||
Dma.DCMI.0.MemBurst=DMA_MBURST_SINGLE
|
||||
Dma.DCMI.0.MemDataAlignment=DMA_MDATAALIGN_WORD
|
||||
Dma.DCMI.0.MemInc=DMA_MINC_ENABLE
|
||||
Dma.DCMI.0.Mode=DMA_CIRCULAR
|
||||
Dma.DCMI.0.PeriphBurst=DMA_PBURST_SINGLE
|
||||
Dma.DCMI.0.PeriphDataAlignment=DMA_PDATAALIGN_WORD
|
||||
Dma.DCMI.0.PeriphInc=DMA_PINC_DISABLE
|
||||
Dma.DCMI.0.Polarity=HAL_DMAMUX_REQ_GEN_RISING
|
||||
Dma.DCMI.0.Priority=DMA_PRIORITY_HIGH
|
||||
Dma.DCMI.0.RequestNumber=1
|
||||
Dma.DCMI.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,FIFOThreshold,MemBurst,PeriphBurst,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
|
||||
Dma.DCMI.0.SignalID=NONE
|
||||
Dma.DCMI.0.SyncEnable=DISABLE
|
||||
Dma.DCMI.0.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT
|
||||
Dma.DCMI.0.SyncRequestNumber=1
|
||||
Dma.DCMI.0.SyncSignalID=NONE
|
||||
Dma.Request0=DCMI
|
||||
Dma.RequestsNb=1
|
||||
FMC.BankMapConfig=FMC_SWAPBMAP_DISABLE
|
||||
FMC.CASLatency1=FMC_SDRAM_CAS_LATENCY_2
|
||||
FMC.ColumnBitsNumber1=FMC_SDRAM_COLUMN_BITS_NUM_9
|
||||
|
@ -18,117 +46,189 @@ KeepUserPlacement=false
|
|||
Mcu.CPN=STM32H743IIK6
|
||||
Mcu.Family=STM32H7
|
||||
Mcu.IP0=CORTEX_M7
|
||||
Mcu.IP1=FMC
|
||||
Mcu.IP2=NVIC
|
||||
Mcu.IP3=RCC
|
||||
Mcu.IP4=SYS
|
||||
Mcu.IP5=USART1
|
||||
Mcu.IPNb=6
|
||||
Mcu.IP1=DCMI
|
||||
Mcu.IP10=TIM1
|
||||
Mcu.IP11=USART1
|
||||
Mcu.IP12=USB_OTG_FS
|
||||
Mcu.IP2=DMA
|
||||
Mcu.IP3=FMC
|
||||
Mcu.IP4=NVIC
|
||||
Mcu.IP5=QUADSPI
|
||||
Mcu.IP6=RCC
|
||||
Mcu.IP7=RTC
|
||||
Mcu.IP8=SDMMC1
|
||||
Mcu.IP9=SYS
|
||||
Mcu.IPNb=13
|
||||
Mcu.Name=STM32H743IIKx
|
||||
Mcu.Package=UFBGA176
|
||||
Mcu.Pin0=PE1
|
||||
Mcu.Pin1=PE0
|
||||
Mcu.Pin10=PI9
|
||||
Mcu.Pin11=PI4
|
||||
Mcu.Pin12=PH15
|
||||
Mcu.Pin13=PI1
|
||||
Mcu.Pin14=PF0
|
||||
Mcu.Pin15=PI10
|
||||
Mcu.Pin16=PH13
|
||||
Mcu.Pin17=PH14
|
||||
Mcu.Pin18=PI0
|
||||
Mcu.Pin19=PH0-OSC_IN (PH0)
|
||||
Mcu.Pin2=PG15
|
||||
Mcu.Pin20=PH1-OSC_OUT (PH1)
|
||||
Mcu.Pin21=PF2
|
||||
Mcu.Pin22=PF1
|
||||
Mcu.Pin23=PG8
|
||||
Mcu.Pin24=PF3
|
||||
Mcu.Pin25=PF4
|
||||
Mcu.Pin26=PF5
|
||||
Mcu.Pin27=PH12
|
||||
Mcu.Pin28=PG5
|
||||
Mcu.Pin29=PG4
|
||||
Mcu.Pin3=PD0
|
||||
Mcu.Pin30=PH11
|
||||
Mcu.Pin31=PH10
|
||||
Mcu.Pin32=PD15
|
||||
Mcu.Pin33=PC0
|
||||
Mcu.Pin34=PC1
|
||||
Mcu.Pin35=PC2_C
|
||||
Mcu.Pin36=PG1
|
||||
Mcu.Pin37=PH8
|
||||
Mcu.Pin38=PH9
|
||||
Mcu.Pin39=PD14
|
||||
Mcu.Pin4=PI7
|
||||
Mcu.Pin40=PC4
|
||||
Mcu.Pin41=PF13
|
||||
Mcu.Pin42=PG0
|
||||
Mcu.Pin43=PE13
|
||||
Mcu.Pin44=PD10
|
||||
Mcu.Pin45=PC5
|
||||
Mcu.Pin46=PF12
|
||||
Mcu.Pin47=PF15
|
||||
Mcu.Pin48=PE8
|
||||
Mcu.Pin49=PE9
|
||||
Mcu.Pin5=PI6
|
||||
Mcu.Pin50=PE11
|
||||
Mcu.Pin51=PE14
|
||||
Mcu.Pin52=PD9
|
||||
Mcu.Pin53=PD8
|
||||
Mcu.Pin54=PA7
|
||||
Mcu.Pin55=PF11
|
||||
Mcu.Pin56=PF14
|
||||
Mcu.Pin57=PE7
|
||||
Mcu.Pin58=PE10
|
||||
Mcu.Pin59=PE12
|
||||
Mcu.Pin6=PI5
|
||||
Mcu.Pin60=PE15
|
||||
Mcu.Pin61=PB14
|
||||
Mcu.Pin62=PB15
|
||||
Mcu.Pin63=VP_SYS_VS_Systick
|
||||
Mcu.Pin7=PD1
|
||||
Mcu.Pin8=PI3
|
||||
Mcu.Pin9=PI2
|
||||
Mcu.PinsNb=64
|
||||
Mcu.Pin10=PG10
|
||||
Mcu.Pin11=PD0
|
||||
Mcu.Pin12=PC11
|
||||
Mcu.Pin13=PC10
|
||||
Mcu.Pin14=PA12
|
||||
Mcu.Pin15=PI7
|
||||
Mcu.Pin16=PI6
|
||||
Mcu.Pin17=PI5
|
||||
Mcu.Pin18=PD1
|
||||
Mcu.Pin19=PI3
|
||||
Mcu.Pin2=PC12
|
||||
Mcu.Pin20=PI2
|
||||
Mcu.Pin21=PA11
|
||||
Mcu.Pin22=PI9
|
||||
Mcu.Pin23=PI4
|
||||
Mcu.Pin24=PD2
|
||||
Mcu.Pin25=PH15
|
||||
Mcu.Pin26=PI1
|
||||
Mcu.Pin27=PF0
|
||||
Mcu.Pin28=PI10
|
||||
Mcu.Pin29=PH13
|
||||
Mcu.Pin3=PE4
|
||||
Mcu.Pin30=PH14
|
||||
Mcu.Pin31=PI0
|
||||
Mcu.Pin32=PC9
|
||||
Mcu.Pin33=PA8
|
||||
Mcu.Pin34=PH0-OSC_IN (PH0)
|
||||
Mcu.Pin35=PC8
|
||||
Mcu.Pin36=PC7
|
||||
Mcu.Pin37=PH1-OSC_OUT (PH1)
|
||||
Mcu.Pin38=PF2
|
||||
Mcu.Pin39=PF1
|
||||
Mcu.Pin4=PE5
|
||||
Mcu.Pin40=PG8
|
||||
Mcu.Pin41=PC6
|
||||
Mcu.Pin42=PF3
|
||||
Mcu.Pin43=PF4
|
||||
Mcu.Pin44=PG6
|
||||
Mcu.Pin45=PF7
|
||||
Mcu.Pin46=PF6
|
||||
Mcu.Pin47=PF5
|
||||
Mcu.Pin48=PH12
|
||||
Mcu.Pin49=PG5
|
||||
Mcu.Pin5=PE6
|
||||
Mcu.Pin50=PG4
|
||||
Mcu.Pin51=PF10
|
||||
Mcu.Pin52=PF9
|
||||
Mcu.Pin53=PF8
|
||||
Mcu.Pin54=PH11
|
||||
Mcu.Pin55=PH10
|
||||
Mcu.Pin56=PD15
|
||||
Mcu.Pin57=PC0
|
||||
Mcu.Pin58=PG1
|
||||
Mcu.Pin59=PH8
|
||||
Mcu.Pin6=PB7
|
||||
Mcu.Pin60=PH9
|
||||
Mcu.Pin61=PD14
|
||||
Mcu.Pin62=PA4
|
||||
Mcu.Pin63=PC4
|
||||
Mcu.Pin64=PF13
|
||||
Mcu.Pin65=PG0
|
||||
Mcu.Pin66=PE13
|
||||
Mcu.Pin67=PD10
|
||||
Mcu.Pin68=PA6
|
||||
Mcu.Pin69=PC5
|
||||
Mcu.Pin7=PB6
|
||||
Mcu.Pin70=PF12
|
||||
Mcu.Pin71=PF15
|
||||
Mcu.Pin72=PE8
|
||||
Mcu.Pin73=PE9
|
||||
Mcu.Pin74=PE11
|
||||
Mcu.Pin75=PE14
|
||||
Mcu.Pin76=PD9
|
||||
Mcu.Pin77=PD8
|
||||
Mcu.Pin78=PA7
|
||||
Mcu.Pin79=PF11
|
||||
Mcu.Pin8=PG15
|
||||
Mcu.Pin80=PF14
|
||||
Mcu.Pin81=PE7
|
||||
Mcu.Pin82=PE10
|
||||
Mcu.Pin83=PE12
|
||||
Mcu.Pin84=PE15
|
||||
Mcu.Pin85=PB14
|
||||
Mcu.Pin86=PB15
|
||||
Mcu.Pin87=VP_RTC_VS_RTC_Activate
|
||||
Mcu.Pin88=VP_RTC_VS_RTC_Calendar
|
||||
Mcu.Pin89=VP_SYS_VS_Systick
|
||||
Mcu.Pin9=PG11
|
||||
Mcu.PinsNb=90
|
||||
Mcu.ThirdPartyNb=0
|
||||
Mcu.UserConstants=
|
||||
Mcu.UserName=STM32H743IIKx
|
||||
MxCube.Version=6.5.0
|
||||
MxDb.Version=DB.6.0.50
|
||||
MxCube.Version=6.4.0
|
||||
MxDb.Version=DB.6.0.40
|
||||
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.DCMI_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
|
||||
NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
|
||||
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.ForceEnableDMAVector=true
|
||||
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.OTG_FS_EP1_IN_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
|
||||
NVIC.OTG_FS_EP1_OUT_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
|
||||
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
|
||||
NVIC.SDMMC1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
|
||||
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:true
|
||||
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
PA11.GPIOParameters=GPIO_Speed
|
||||
PA11.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PA11.Mode=Device_Only
|
||||
PA11.Signal=USB_OTG_FS_DM
|
||||
PA12.GPIOParameters=GPIO_Speed
|
||||
PA12.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PA12.Mode=Device_Only
|
||||
PA12.Signal=USB_OTG_FS_DP
|
||||
PA4.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PA4.GPIO_PuPd=GPIO_PULLUP
|
||||
PA4.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PA4.Locked=true
|
||||
PA4.Mode=Slave_8_bits_External_Synchro
|
||||
PA4.Signal=DCMI_HSYNC
|
||||
PA6.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PA6.GPIO_PuPd=GPIO_PULLUP
|
||||
PA6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PA6.Locked=true
|
||||
PA6.Mode=Slave_8_bits_External_Synchro
|
||||
PA6.Signal=DCMI_PIXCLK
|
||||
PA7.GPIOParameters=GPIO_PuPd
|
||||
PA7.GPIO_PuPd=GPIO_PULLUP
|
||||
PA7.Locked=true
|
||||
PA7.Signal=FMC_SDNWE
|
||||
PA8.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PA8.GPIO_PuPd=GPIO_PULLUP
|
||||
PA8.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PA8.Signal=S_TIM1_CH1
|
||||
PB14.Locked=true
|
||||
PB14.Mode=Asynchronous
|
||||
PB14.Signal=USART1_TX
|
||||
PB15.Locked=true
|
||||
PB15.Mode=Asynchronous
|
||||
PB15.Signal=USART1_RX
|
||||
PB6.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PB6.GPIO_PuPd=GPIO_PULLUP
|
||||
PB6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PB6.Locked=true
|
||||
PB6.Mode=Slave_8_bits_External_Synchro
|
||||
PB6.Signal=DCMI_D5
|
||||
PB7.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PB7.GPIO_PuPd=GPIO_PULLUP
|
||||
PB7.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PB7.Locked=true
|
||||
PB7.Mode=Slave_8_bits_External_Synchro
|
||||
PB7.Signal=DCMI_VSYNC
|
||||
PC0.GPIOParameters=GPIO_Label
|
||||
PC0.GPIO_Label=LED_RED
|
||||
PC0.Locked=true
|
||||
PC0.Signal=GPIO_Output
|
||||
PC1.GPIOParameters=GPIO_Label
|
||||
PC1.GPIO_Label=LED_GREEN
|
||||
PC1.Locked=true
|
||||
PC1.Signal=GPIO_Output
|
||||
PC2_C.GPIOParameters=GPIO_Label
|
||||
PC2_C.GPIO_Label=LED_BLUE
|
||||
PC2_C.Locked=true
|
||||
PC2_C.Signal=GPIO_Output
|
||||
PC10.Mode=SD_4_bits_Wide_bus
|
||||
PC10.Signal=SDMMC1_D2
|
||||
PC11.Mode=SD_4_bits_Wide_bus
|
||||
PC11.Signal=SDMMC1_D3
|
||||
PC12.Mode=SD_4_bits_Wide_bus
|
||||
PC12.Signal=SDMMC1_CK
|
||||
PC4.GPIOParameters=GPIO_PuPd
|
||||
PC4.GPIO_PuPd=GPIO_PULLUP
|
||||
PC4.Locked=true
|
||||
|
@ -139,6 +239,22 @@ PC5.GPIO_PuPd=GPIO_PULLUP
|
|||
PC5.Locked=true
|
||||
PC5.Mode=SdramChipSelect1_1
|
||||
PC5.Signal=FMC_SDCKE0
|
||||
PC6.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PC6.GPIO_PuPd=GPIO_PULLUP
|
||||
PC6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PC6.Locked=true
|
||||
PC6.Mode=Slave_8_bits_External_Synchro
|
||||
PC6.Signal=DCMI_D0
|
||||
PC7.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PC7.GPIO_PuPd=GPIO_PULLUP
|
||||
PC7.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PC7.Locked=true
|
||||
PC7.Mode=Slave_8_bits_External_Synchro
|
||||
PC7.Signal=DCMI_D1
|
||||
PC8.Mode=SD_4_bits_Wide_bus
|
||||
PC8.Signal=SDMMC1_D0
|
||||
PC9.Mode=SD_4_bits_Wide_bus
|
||||
PC9.Signal=SDMMC1_D1
|
||||
PD0.GPIOParameters=GPIO_PuPd
|
||||
PD0.GPIO_PuPd=GPIO_PULLUP
|
||||
PD0.Signal=FMC_D2_DA2
|
||||
|
@ -154,6 +270,8 @@ PD14.Signal=FMC_D0_DA0
|
|||
PD15.GPIOParameters=GPIO_PuPd
|
||||
PD15.GPIO_PuPd=GPIO_PULLUP
|
||||
PD15.Signal=FMC_D1_DA1
|
||||
PD2.Mode=SD_4_bits_Wide_bus
|
||||
PD2.Signal=SDMMC1_CMD
|
||||
PD8.GPIOParameters=GPIO_PuPd
|
||||
PD8.GPIO_PuPd=GPIO_PULLUP
|
||||
PD8.Signal=FMC_D13_DA13
|
||||
|
@ -184,6 +302,24 @@ PE14.Signal=FMC_D11_DA11
|
|||
PE15.GPIOParameters=GPIO_PuPd
|
||||
PE15.GPIO_PuPd=GPIO_PULLUP
|
||||
PE15.Signal=FMC_D12_DA12
|
||||
PE4.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PE4.GPIO_PuPd=GPIO_PULLUP
|
||||
PE4.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PE4.Locked=true
|
||||
PE4.Mode=Slave_8_bits_External_Synchro
|
||||
PE4.Signal=DCMI_D4
|
||||
PE5.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PE5.GPIO_PuPd=GPIO_PULLUP
|
||||
PE5.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PE5.Locked=true
|
||||
PE5.Mode=Slave_8_bits_External_Synchro
|
||||
PE5.Signal=DCMI_D6
|
||||
PE6.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PE6.GPIO_PuPd=GPIO_PULLUP
|
||||
PE6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PE6.Locked=true
|
||||
PE6.Mode=Slave_8_bits_External_Synchro
|
||||
PE6.Signal=DCMI_D7
|
||||
PE7.GPIOParameters=GPIO_PuPd
|
||||
PE7.GPIO_PuPd=GPIO_PULLUP
|
||||
PE7.Signal=FMC_D4_DA4
|
||||
|
@ -199,6 +335,11 @@ PF0.Signal=FMC_A0
|
|||
PF1.GPIOParameters=GPIO_PuPd
|
||||
PF1.GPIO_PuPd=GPIO_PULLUP
|
||||
PF1.Signal=FMC_A1
|
||||
PF10.GPIOParameters=GPIO_Speed
|
||||
PF10.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
|
||||
PF10.Locked=true
|
||||
PF10.Mode=Single Bank 1
|
||||
PF10.Signal=QUADSPI_CLK
|
||||
PF11.GPIOParameters=GPIO_PuPd
|
||||
PF11.GPIO_PuPd=GPIO_PULLUP
|
||||
PF11.Signal=FMC_SDNRAS
|
||||
|
@ -226,12 +367,44 @@ PF4.Signal=FMC_A4
|
|||
PF5.GPIOParameters=GPIO_PuPd
|
||||
PF5.GPIO_PuPd=GPIO_PULLUP
|
||||
PF5.Signal=FMC_A5
|
||||
PF6.GPIOParameters=GPIO_Speed
|
||||
PF6.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
|
||||
PF6.Locked=true
|
||||
PF6.Mode=Single Bank 1
|
||||
PF6.Signal=QUADSPI_BK1_IO3
|
||||
PF7.GPIOParameters=GPIO_Speed
|
||||
PF7.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
|
||||
PF7.Locked=true
|
||||
PF7.Mode=Single Bank 1
|
||||
PF7.Signal=QUADSPI_BK1_IO2
|
||||
PF8.GPIOParameters=GPIO_Speed
|
||||
PF8.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
|
||||
PF8.Locked=true
|
||||
PF8.Mode=Single Bank 1
|
||||
PF8.Signal=QUADSPI_BK1_IO0
|
||||
PF9.GPIOParameters=GPIO_Speed
|
||||
PF9.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
|
||||
PF9.Locked=true
|
||||
PF9.Mode=Single Bank 1
|
||||
PF9.Signal=QUADSPI_BK1_IO1
|
||||
PG0.GPIOParameters=GPIO_PuPd
|
||||
PG0.GPIO_PuPd=GPIO_PULLUP
|
||||
PG0.Signal=FMC_A10
|
||||
PG1.GPIOParameters=GPIO_PuPd
|
||||
PG1.GPIO_PuPd=GPIO_PULLUP
|
||||
PG1.Signal=FMC_A11
|
||||
PG10.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PG10.GPIO_PuPd=GPIO_PULLUP
|
||||
PG10.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PG10.Locked=true
|
||||
PG10.Mode=Slave_8_bits_External_Synchro
|
||||
PG10.Signal=DCMI_D2
|
||||
PG11.GPIOParameters=GPIO_Speed,GPIO_PuPd
|
||||
PG11.GPIO_PuPd=GPIO_PULLUP
|
||||
PG11.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
PG11.Locked=true
|
||||
PG11.Mode=Slave_8_bits_External_Synchro
|
||||
PG11.Signal=DCMI_D3
|
||||
PG15.GPIOParameters=GPIO_PuPd
|
||||
PG15.GPIO_PuPd=GPIO_PULLUP
|
||||
PG15.Signal=FMC_SDNCAS
|
||||
|
@ -241,6 +414,11 @@ PG4.Signal=FMC_A14_BA0
|
|||
PG5.GPIOParameters=GPIO_PuPd
|
||||
PG5.GPIO_PuPd=GPIO_PULLUP
|
||||
PG5.Signal=FMC_A15_BA1
|
||||
PG6.GPIOParameters=GPIO_PuPd
|
||||
PG6.GPIO_PuPd=GPIO_PULLUP
|
||||
PG6.Locked=true
|
||||
PG6.Mode=Single Bank 1
|
||||
PG6.Signal=QUADSPI_BK1_NCS
|
||||
PG8.GPIOParameters=GPIO_PuPd
|
||||
PG8.GPIO_PuPd=GPIO_PULLUP
|
||||
PG8.Signal=FMC_SDCLK
|
||||
|
@ -313,7 +491,7 @@ ProjectManager.CustomerFirmwarePackage=
|
|||
ProjectManager.DefaultFWLocation=true
|
||||
ProjectManager.DeletePrevious=true
|
||||
ProjectManager.DeviceId=STM32H743IIKx
|
||||
ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.10.0
|
||||
ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.9.0
|
||||
ProjectManager.FreePins=false
|
||||
ProjectManager.HalAssertFull=false
|
||||
ProjectManager.HeapSize=0x200
|
||||
|
@ -331,7 +509,13 @@ ProjectManager.StackSize=0x400
|
|||
ProjectManager.TargetToolchain=MDK-ARM V5.32
|
||||
ProjectManager.ToolChainLocation=
|
||||
ProjectManager.UnderRoot=false
|
||||
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_USART1_UART_Init-USART1-false-HAL-true,4-MX_FMC_Init-FMC-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true
|
||||
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_USART1_UART_Init-USART1-false-HAL-true,4-MX_FMC_Init-FMC-false-HAL-true,5-MX_QUADSPI_Init-QUADSPI-false-HAL-true,6-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,7-MX_DMA_Init-DMA-false-HAL-true,8-MX_RTC_Init-RTC-false-HAL-true,9-MX_DCMI_Init-DCMI-false-HAL-true,10-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true
|
||||
QUADSPI.ChipSelectHighTime=QSPI_CS_HIGH_TIME_2_CYCLE
|
||||
QUADSPI.ClockPrescaler=1
|
||||
QUADSPI.FifoThreshold=3
|
||||
QUADSPI.FlashSize=24
|
||||
QUADSPI.IPParameters=ClockPrescaler,FifoThreshold,SampleShifting,FlashSize,ChipSelectHighTime
|
||||
QUADSPI.SampleShifting=QSPI_SAMPLE_SHIFTING_HALFCYCLE
|
||||
RCC.ADCFreq_Value=24187500
|
||||
RCC.AHB12Freq_Value=200000000
|
||||
RCC.AHB4Freq_Value=200000000
|
||||
|
@ -349,20 +533,21 @@ RCC.D1PPRE=RCC_APB3_DIV2
|
|||
RCC.D2PPRE1=RCC_APB1_DIV2
|
||||
RCC.D2PPRE2=RCC_APB2_DIV2
|
||||
RCC.D3PPRE=RCC_APB4_DIV2
|
||||
RCC.DFSDMACLkFreq_Value=400000000
|
||||
RCC.DFSDMACLkFreq_Value=200000000
|
||||
RCC.DFSDMFreq_Value=100000000
|
||||
RCC.DIVM1=3
|
||||
RCC.DIVN1=200
|
||||
RCC.DIVP1Freq_Value=400000000
|
||||
RCC.DIVP2Freq_Value=24187500
|
||||
RCC.DIVP3Freq_Value=24187500
|
||||
RCC.DIVQ1Freq_Value=400000000
|
||||
RCC.DIVQ1=4
|
||||
RCC.DIVQ1Freq_Value=200000000
|
||||
RCC.DIVQ2Freq_Value=24187500
|
||||
RCC.DIVQ3Freq_Value=24187500
|
||||
RCC.DIVR1Freq_Value=400000000
|
||||
RCC.DIVR2Freq_Value=24187500
|
||||
RCC.DIVR3Freq_Value=24187500
|
||||
RCC.FDCANFreq_Value=400000000
|
||||
RCC.FDCANFreq_Value=200000000
|
||||
RCC.FMCFreq_Value=200000000
|
||||
RCC.FamilyName=M
|
||||
RCC.HCLK3ClockFreq_Value=200000000
|
||||
|
@ -372,7 +557,7 @@ RCC.HRTIMFreq_Value=200000000
|
|||
RCC.HSE_VALUE=12000000
|
||||
RCC.I2C123Freq_Value=100000000
|
||||
RCC.I2C4Freq_Value=100000000
|
||||
RCC.IPParameters=ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVN1,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3Freq_Value,DIVQ1Freq_Value,DIVQ2Freq_Value,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2Freq_Value,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,I2C123Freq_Value,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2FRACN,PLL3FRACN,PLLFRACN,PLLSourceVirtual,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value
|
||||
RCC.IPParameters=ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVN1,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2Freq_Value,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2Freq_Value,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,I2C123Freq_Value,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2FRACN,PLL3FRACN,PLLFRACN,PLLSourceVirtual,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value
|
||||
RCC.LPTIM1Freq_Value=100000000
|
||||
RCC.LPTIM2Freq_Value=100000000
|
||||
RCC.LPTIM345Freq_Value=100000000
|
||||
|
@ -387,13 +572,13 @@ RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
|
|||
RCC.QSPIFreq_Value=200000000
|
||||
RCC.RNGFreq_Value=48000000
|
||||
RCC.RTCFreq_Value=32000
|
||||
RCC.SAI1Freq_Value=400000000
|
||||
RCC.SAI23Freq_Value=400000000
|
||||
RCC.SAI4AFreq_Value=400000000
|
||||
RCC.SAI4BFreq_Value=400000000
|
||||
RCC.SDMMCFreq_Value=400000000
|
||||
RCC.SPDIFRXFreq_Value=400000000
|
||||
RCC.SPI123Freq_Value=400000000
|
||||
RCC.SAI1Freq_Value=200000000
|
||||
RCC.SAI23Freq_Value=200000000
|
||||
RCC.SAI4AFreq_Value=200000000
|
||||
RCC.SAI4BFreq_Value=200000000
|
||||
RCC.SDMMCFreq_Value=200000000
|
||||
RCC.SPDIFRXFreq_Value=200000000
|
||||
RCC.SPI123Freq_Value=200000000
|
||||
RCC.SPI45Freq_Value=100000000
|
||||
RCC.SPI6Freq_Value=100000000
|
||||
RCC.SWPMI1Freq_Value=100000000
|
||||
|
@ -404,13 +589,16 @@ RCC.Tim2OutputFreq_Value=200000000
|
|||
RCC.TraceFreq_Value=64000000
|
||||
RCC.USART16Freq_Value=100000000
|
||||
RCC.USART234578Freq_Value=100000000
|
||||
RCC.USBFreq_Value=400000000
|
||||
RCC.USBCLockSelection=RCC_USBCLKSOURCE_HSI48
|
||||
RCC.USBFreq_Value=48000000
|
||||
RCC.VCO1OutputFreq_Value=800000000
|
||||
RCC.VCO2OutputFreq_Value=48375000
|
||||
RCC.VCO3OutputFreq_Value=48375000
|
||||
RCC.VCOInput1Freq_Value=4000000
|
||||
RCC.VCOInput2Freq_Value=375000
|
||||
RCC.VCOInput3Freq_Value=375000
|
||||
SDMMC1.ClockDiv=4
|
||||
SDMMC1.IPParameters=ClockDiv
|
||||
SH.FMC_A0.0=FMC_A0,12b-sda1
|
||||
SH.FMC_A0.ConfNb=1
|
||||
SH.FMC_A1.0=FMC_A1,12b-sda1
|
||||
|
@ -519,8 +707,21 @@ SH.FMC_SDNRAS.0=FMC_SDNRAS,12b-sda1
|
|||
SH.FMC_SDNRAS.ConfNb=1
|
||||
SH.FMC_SDNWE.0=FMC_SDNWE,12b-sda1
|
||||
SH.FMC_SDNWE.ConfNb=1
|
||||
SH.S_TIM1_CH1.0=TIM1_CH1,PWM Generation1 CH1
|
||||
SH.S_TIM1_CH1.ConfNb=1
|
||||
TIM1.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
|
||||
TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
|
||||
TIM1.IPParameters=Channel-PWM Generation1 CH1,Period,AutoReloadPreload,Pulse-PWM Generation1 CH1
|
||||
TIM1.Period=7
|
||||
TIM1.Pulse-PWM\ Generation1\ CH1=3
|
||||
USART1.IPParameters=VirtualMode-Asynchronous
|
||||
USART1.VirtualMode-Asynchronous=VM_ASYNC
|
||||
USB_OTG_FS.IPParameters=VirtualMode
|
||||
USB_OTG_FS.VirtualMode=Device_Only
|
||||
VP_RTC_VS_RTC_Activate.Mode=RTC_Enabled
|
||||
VP_RTC_VS_RTC_Activate.Signal=RTC_VS_RTC_Activate
|
||||
VP_RTC_VS_RTC_Calendar.Mode=RTC_Calendar
|
||||
VP_RTC_VS_RTC_Calendar.Signal=RTC_VS_RTC_Calendar
|
||||
VP_SYS_VS_Systick.Mode=SysTick
|
||||
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
|
||||
board=custom
|
||||
|
|
|
@ -38,7 +38,7 @@ menu "On-chip Peripheral Drivers"
|
|||
depends on BSP_USING_UART2 && RT_SERIAL_USING_DMA
|
||||
default n
|
||||
|
||||
config BSP_USING_LPUART1
|
||||
config BSP_USING_LPUART1
|
||||
bool "Enable LPUART1"
|
||||
default n
|
||||
|
||||
|
@ -48,12 +48,46 @@ menu "On-chip Peripheral Drivers"
|
|||
default n
|
||||
endif
|
||||
|
||||
config BSP_USING_SDRAM
|
||||
bool "Enable SDRAM"
|
||||
default n
|
||||
config BSP_USING_QSPI
|
||||
bool "Enable QSPI BUS"
|
||||
select RT_USING_QSPI
|
||||
select RT_USING_SPI
|
||||
default n
|
||||
|
||||
config BSP_USING_ONCHIP_RTC
|
||||
bool "Enable RTC"
|
||||
select RT_USING_RTC
|
||||
default n
|
||||
|
||||
source "$RTT_DIR/bsp/stm32/libraries/HAL_Drivers/Kconfig"
|
||||
|
||||
endmenu
|
||||
endmenu
|
||||
|
||||
menu "Onboard Peripheral Drivers"
|
||||
|
||||
config BSP_USING_SDRAM
|
||||
bool "Enable SDRAM"
|
||||
default n
|
||||
|
||||
config BSP_USING_QSPI_FLASH
|
||||
bool "Enable QSPI FLASH (W25Q256 qspi)"
|
||||
select BSP_USING_QSPI
|
||||
select RT_USING_SFUD
|
||||
select RT_SFUD_USING_QSPI
|
||||
default n
|
||||
|
||||
config BSP_USING_SDMMC
|
||||
bool "Enable SDMMC (SD card)"
|
||||
select RT_USING_SDIO
|
||||
select RT_USING_DFS
|
||||
select RT_USING_DFS_ELMFAT
|
||||
default n
|
||||
|
||||
config BSP_USING_USBD
|
||||
bool "Enable OTGFS as USB device"
|
||||
select RT_USING_USB_DEVICE
|
||||
default n
|
||||
|
||||
endmenu
|
||||
|
||||
endmenu
|
||||
|
|
|
@ -14,6 +14,15 @@ CubeMX_Config/Core/Src/stm32h7xx_hal_msp.c
|
|||
|
||||
if GetDepend(['BSP_USING_SDRAM']):
|
||||
src += Glob('ports/sdram_test.c')
|
||||
if GetDepend(['BSP_USING_QSPI_FLASH']):
|
||||
src += ['ports/drv_qspi_flash.c']
|
||||
if GetDepend(['BSP_USING_SDMMC']):
|
||||
src += ['ports/drv_sdio.c']
|
||||
if GetDepend(['RT_USING_DFS_ROMFS']):
|
||||
src += ['ports/romfs.c']
|
||||
src += ['ports/mnt_romfs.c']
|
||||
if GetDepend(['RT_USING_DFS_RAMFS']):
|
||||
src += ['ports/mnt_ramfs.c']
|
||||
|
||||
path = [cwd]
|
||||
path += [cwd + '/CubeMX_Config/Core/Inc']
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2021, RT-Thread Development Team
|
||||
* Copyright (c) 2006-2022, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
|
@ -28,14 +28,15 @@ void SystemClock_Config(void)
|
|||
/** Initializes the RCC Oscillators according to the specified parameters
|
||||
* in the RCC_OscInitTypeDef structure.
|
||||
*/
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48|RCC_OSCILLATORTYPE_HSE;
|
||||
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
|
||||
RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
|
||||
RCC_OscInitStruct.PLL.PLLM = 3;
|
||||
RCC_OscInitStruct.PLL.PLLN = 200;
|
||||
RCC_OscInitStruct.PLL.PLLP = 2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = 2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = 4;
|
||||
RCC_OscInitStruct.PLL.PLLR = 2;
|
||||
RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2;
|
||||
RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2021, RT-Thread Development Team
|
||||
* Copyright (c) 2006-2022, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2021-12-14 supperthomas first version
|
||||
* 2022-03-14 wwt add sram2
|
||||
* 2022-03-16 Miaowulue add sram2
|
||||
*/
|
||||
|
||||
|
||||
|
|
|
@ -0,0 +1,99 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2022, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2018-11-27 zylx first version
|
||||
* 2022-03-16 Miaowulue add dfs mount
|
||||
*/
|
||||
|
||||
#include <board.h>
|
||||
#include <drv_qspi.h>
|
||||
#include <rtdevice.h>
|
||||
#include <rthw.h>
|
||||
#include <finsh.h>
|
||||
#include <dfs_elm.h>
|
||||
#include <dfs_fs.h>
|
||||
|
||||
#ifdef BSP_USING_QSPI_FLASH
|
||||
|
||||
#include "spi_flash.h"
|
||||
#include "spi_flash_sfud.h"
|
||||
|
||||
char w25qxx_read_status_register2(struct rt_qspi_device *device)
|
||||
{
|
||||
/* 0x35 read status register2 */
|
||||
char instruction = 0x35, status;
|
||||
|
||||
rt_qspi_send_then_recv(device, &instruction, 1, &status, 1);
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
void w25qxx_write_enable(struct rt_qspi_device *device)
|
||||
{
|
||||
/* 0x06 write enable */
|
||||
char instruction = 0x06;
|
||||
|
||||
rt_qspi_send(device, &instruction, 1);
|
||||
}
|
||||
|
||||
void w25qxx_enter_qspi_mode(struct rt_qspi_device *device)
|
||||
{
|
||||
char status = 0;
|
||||
/* 0x38 enter qspi mode */
|
||||
char instruction = 0x38;
|
||||
char write_status2_buf[2] = {0};
|
||||
|
||||
/* 0x31 write status register2 */
|
||||
write_status2_buf[0] = 0x31;
|
||||
|
||||
status = w25qxx_read_status_register2(device);
|
||||
if (!(status & 0x02))
|
||||
{
|
||||
status |= 1 << 1;
|
||||
w25qxx_write_enable(device);
|
||||
write_status2_buf[1] = status;
|
||||
rt_qspi_send(device, &write_status2_buf, 2);
|
||||
rt_qspi_send(device, &instruction, 1);
|
||||
rt_kprintf("flash already enter qspi mode\n");
|
||||
rt_thread_mdelay(10);
|
||||
}
|
||||
}
|
||||
|
||||
static int rt_hw_qspi_flash_with_sfud_init(void)
|
||||
{
|
||||
stm32_qspi_bus_attach_device("qspi1", "qspi10", RT_NULL, 4, w25qxx_enter_qspi_mode, RT_NULL);
|
||||
|
||||
/* init W25Q256 */
|
||||
if (RT_NULL == rt_sfud_flash_probe("W25Q256", "qspi10"))
|
||||
{
|
||||
return -RT_ERROR;
|
||||
}
|
||||
|
||||
return RT_EOK;
|
||||
}
|
||||
INIT_DEVICE_EXPORT(rt_hw_qspi_flash_with_sfud_init);
|
||||
|
||||
static int mnt_qspi_flash_init(void)
|
||||
{
|
||||
#ifdef RT_USING_DFS_ROMFS
|
||||
if (dfs_mount("W25Q256", "/FLASH", "elm", 0, 0) == RT_EOK)
|
||||
#else
|
||||
if (dfs_mount("W25Q256", "/", "elm", 0, 0) == RT_EOK)
|
||||
#endif
|
||||
{
|
||||
rt_kprintf("Mount spi flash successfully!\n");
|
||||
return RT_EOK;
|
||||
}
|
||||
else
|
||||
{
|
||||
rt_kprintf("Mount spi flash fail!\n");
|
||||
return -RT_ERROR;
|
||||
}
|
||||
}
|
||||
INIT_APP_EXPORT(mnt_qspi_flash_init);
|
||||
|
||||
#endif/* BSP_USING_QSPI_FLASH */
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue