forked from xuos/xiuos
merge upstream
This commit is contained in:
commit
618ca9d872
|
@ -22,9 +22,6 @@
|
|||
[submodule "Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/kendryte-sdk/kendryte-sdk-source"]
|
||||
path = Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/xidatong-riscv64/kendryte-sdk/kendryte-sdk-source
|
||||
url = https://www.gitlink.org.cn/chunyexixiaoyu/kendryte-sdk-source.git
|
||||
[submodule "APP_Framework/lib/lorawan/lora_radio_driver"]
|
||||
path = APP_Framework/lib/lorawan/lora_radio_driver
|
||||
url = https://gitlink.org.cn/xuos/lora_radio_driver
|
||||
[submodule "APP_Framework/lib/lorawan/lorawan_devicenode"]
|
||||
path = APP_Framework/lib/lorawan/lorawan_devicenode
|
||||
url = https://gitlink.org.cn/xuos/lorawan_devicenode.git
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include <transform.h>
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
|
||||
#define BSP_LED_PIN 29
|
||||
#define BSP_LED_PIN 134
|
||||
#define NULL_PARAMETER 0
|
||||
|
||||
static uint16_t pin_fd=0;
|
||||
|
@ -30,6 +30,7 @@ static struct PinStat pin_led;
|
|||
|
||||
void LedFlip(void *parameter)
|
||||
{
|
||||
printf("%s val %d time %d\n", __func__, pin_led.val, PrivGetTickTime());
|
||||
pin_led.pin = BSP_LED_PIN;
|
||||
pin_led.val = !pin_led.val;
|
||||
PrivWrite(pin_fd, &pin_led, NULL_PARAMETER);
|
||||
|
@ -37,7 +38,7 @@ void LedFlip(void *parameter)
|
|||
|
||||
void TestHwTimer(void)
|
||||
{
|
||||
x_ticks_t period = 1;
|
||||
uint32_t period_ms = 500;
|
||||
|
||||
pin_fd = PrivOpen(HWTIMER_PIN_DEV_DRIVER, O_RDWR);
|
||||
if(pin_fd<0) {
|
||||
|
@ -75,7 +76,7 @@ void TestHwTimer(void)
|
|||
return;
|
||||
}
|
||||
|
||||
ioctl_cfg.args = (void *).
|
||||
ioctl_cfg.args = (void *)&period_ms;
|
||||
if (0 != PrivIoctl(timer_fd, OPE_CFG, &ioctl_cfg)) {
|
||||
printf("timer pin fd error %d\n", pin_fd);
|
||||
PrivClose(pin_fd);
|
||||
|
|
|
@ -22,9 +22,13 @@ extern void ApplicationOtaTaskInit(void);
|
|||
extern int OtaTask(void);
|
||||
#endif
|
||||
|
||||
#ifdef USE_MONGOOSE
|
||||
extern int webserver(void);
|
||||
#endif
|
||||
|
||||
int main(void)
|
||||
{
|
||||
printf("Hello, world! \n");
|
||||
printf("\nHello, world!\n");
|
||||
FrameworkInit();
|
||||
#ifdef APPLICATION_OTA
|
||||
ApplicationOtaTaskInit();
|
||||
|
@ -33,6 +37,11 @@ int main(void)
|
|||
#ifdef OTA_BY_PLATFORM
|
||||
OtaTask();
|
||||
#endif
|
||||
|
||||
#ifdef USE_MONGOOSE
|
||||
webserver();
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
// int cppmain(void);
|
||||
|
|
|
@ -1,3 +1,11 @@
|
|||
menuconfig USE_MONGOOSE
|
||||
bool "Use mongoose as webserver"
|
||||
default n
|
||||
select BSP_USING_SDIO
|
||||
select BSP_USING_W5500
|
||||
select BSP_USING_ETHERNET
|
||||
select SUPPORT_CONNECTION_FRAMEWORK
|
||||
select CONNECTION_ADAPTER_4G
|
||||
select ADAPTER_EC200A
|
||||
select LIB_USING_LORAWAN
|
||||
select LIB_USING_LORA_RADIO
|
||||
|
|
|
@ -1,3 +1,3 @@
|
|||
SRC_FILES += project.c
|
||||
SRC_FILES += webserver_project.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1 @@
|
|||
mongoose.a基于工具链arm-none-eabi-gcc (15:6.3.1+svn253039-1build1) 6.3.1 20170620编译而来,若使用的arm工具链版本存在差异或使用的是RISC-V工具链,则需重新编译mongoose.a,避免遇到异常问题。
|
|
@ -1,3 +0,0 @@
|
|||
SRC_FILES += mongoose.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
Binary file not shown.
|
@ -1,142 +0,0 @@
|
|||
// Copyright (c) 2022 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
//
|
||||
// UI example
|
||||
// It implements the following endpoints:
|
||||
// /api/config/get - respond with current config
|
||||
// /api/config/set - POST a config change
|
||||
// any other URI serves static files from s_root_dir
|
||||
// Data and results are JSON strings
|
||||
|
||||
#include "ip_addr.h"
|
||||
#include "mongoose.h"
|
||||
#include "netdev.h"
|
||||
|
||||
char index_path[] = "login.html";
|
||||
|
||||
static const char* s_http_addr = "http://192.168.131.88:8000"; // HTTP port
|
||||
static const char* s_root_dir = "webserver";
|
||||
static const char* s_enable_hexdump = "no";
|
||||
static const char* s_ssi_pattern = "#.html";
|
||||
|
||||
static const char* device_type = "Edu-ARM32";
|
||||
static const char* web_version = "XUOS Webserver 1.0";
|
||||
static int enable_4g = 0;
|
||||
|
||||
static struct netdev* p_netdev;
|
||||
|
||||
static struct config {
|
||||
char *ip, *mask, *gw, *dns;
|
||||
} s_config;
|
||||
|
||||
// Try to update a single configuration value
|
||||
static void update_config(struct mg_str json, const char* path, char** value)
|
||||
{
|
||||
char* jval;
|
||||
if ((jval = mg_json_get_str(json, path)) != NULL) {
|
||||
free(*value);
|
||||
*value = strdup(jval);
|
||||
}
|
||||
}
|
||||
|
||||
static void fn(struct mg_connection* c, int ev, void* ev_data, void* fn_data)
|
||||
{
|
||||
if (ev == MG_EV_HTTP_MSG) {
|
||||
struct mg_http_message *hm = (struct mg_http_message*)ev_data, tmp = { 0 };
|
||||
if (mg_http_match_uri(hm, "/getSystemInfo")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%m, %m:%m, %m:%m, %m:%m, %m:%m, %m:%d}\n",
|
||||
MG_ESC("ip"), MG_ESC(s_config.ip),
|
||||
MG_ESC("deviceType"), MG_ESC(device_type),
|
||||
MG_ESC("deviceNo"), MG_ESC("0"),
|
||||
MG_ESC("systemTime"), MG_ESC("YYYY:MM:DD hh:mm:ss"),
|
||||
MG_ESC("webVersion"), MG_ESC(web_version),
|
||||
MG_ESC("statusOf4g"), enable_4g);
|
||||
} else if (mg_http_match_uri(hm, "/net/get4gInfo")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%m}\n",
|
||||
MG_ESC("enable4g"), MG_ESC(enable_4g));
|
||||
} else if (mg_http_match_uri(hm, "/net/set4gInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
enable_4g = mg_json_get_long(json, "$.enable4g", 0);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
printf("Get enable 4g setting: %d\n", enable_4g);
|
||||
} else if (mg_http_match_uri(hm, "/net/getEthernetInfo")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%m, %m:%m, %m:%m, %m:%m}\n",
|
||||
MG_ESC("ip"), MG_ESC(s_config.ip),
|
||||
MG_ESC("netmask"), MG_ESC(s_config.mask),
|
||||
MG_ESC("gateway"), MG_ESC(s_config.gw),
|
||||
MG_ESC("dns"), MG_ESC(s_config.dns));
|
||||
} else if (mg_http_match_uri(hm, "/net/setEthernetInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
printf("json: %s\n", json.ptr);
|
||||
update_config(json, "$.ip", &s_config.ip);
|
||||
update_config(json, "$.netmask", &s_config.mask);
|
||||
update_config(json, "$.gateway", &s_config.gw);
|
||||
update_config(json, "$.dns", &s_config.dns);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
|
||||
ip_addr_t ipaddr, maskaddr, gwaddr;
|
||||
inet_aton(s_config.ip, &ipaddr);
|
||||
inet_aton(s_config.mask, &maskaddr);
|
||||
inet_aton(s_config.gw, &gwaddr);
|
||||
p_netdev->ops->set_addr_info(p_netdev, &ipaddr, &maskaddr, &gwaddr);
|
||||
|
||||
printf("Board Net Configuration changed to [IP: %s, Mask: %s, GW: %s, DNS: %s]\n",
|
||||
s_config.ip,
|
||||
s_config.mask,
|
||||
s_config.gw,
|
||||
s_config.dns);
|
||||
} else {
|
||||
struct mg_str unknown = mg_str_n("?", 1), *cl;
|
||||
struct mg_http_serve_opts opts = { .root_dir = s_root_dir, .ssi_pattern = s_ssi_pattern };
|
||||
mg_http_serve_dir(c, hm, &opts);
|
||||
mg_http_parse((char*)c->send.buf, c->send.len, &tmp);
|
||||
cl = mg_http_get_header(&tmp, "Content-Length");
|
||||
if (cl == NULL)
|
||||
cl = &unknown;
|
||||
MG_INFO(("%.*s %.*s %.*s %.*s", (int)hm->method.len, hm->method.ptr,
|
||||
(int)hm->uri.len, hm->uri.ptr, (int)tmp.uri.len, tmp.uri.ptr,
|
||||
(int)cl->len, cl->ptr));
|
||||
}
|
||||
}
|
||||
(void)fn_data;
|
||||
}
|
||||
|
||||
static void* do_webserver_demo(void* none)
|
||||
{
|
||||
p_netdev = netdev_get_by_name("wz");
|
||||
if (p_netdev == NULL) {
|
||||
MG_INFO(("Did nto find wz netdev, use default.\n"));
|
||||
p_netdev = NETDEV_DEFAULT;
|
||||
}
|
||||
MG_INFO(("Use Netdev %s", p_netdev->name));
|
||||
s_config.ip = strdup(inet_ntoa(*p_netdev->ip_addr));
|
||||
s_config.mask = strdup(inet_ntoa(*p_netdev->netmask));
|
||||
s_config.gw = strdup(inet_ntoa(*p_netdev->gw));
|
||||
s_config.dns = strdup(inet_ntoa(p_netdev->dns_servers[0]));
|
||||
|
||||
struct mg_mgr mgr; // Event manager
|
||||
// mg_log_set(MG_LL_INFO); // Set to 3 to enable debug
|
||||
mg_log_set(MG_LL_DEBUG); // Set to 3 to enable debug
|
||||
mg_mgr_init(&mgr); // Initialise event manager
|
||||
mg_http_listen(&mgr, s_http_addr, fn, NULL); // Create HTTP listener
|
||||
for (;;)
|
||||
mg_mgr_poll(&mgr, 50); // Infinite event loop
|
||||
mg_mgr_free(&mgr);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
int webserver_demo(int argc, char* argv[])
|
||||
{
|
||||
pthread_t tid = -1;
|
||||
pthread_attr_t attr;
|
||||
attr.schedparam.sched_priority = 30;
|
||||
attr.stacksize = 0x2000;
|
||||
|
||||
PrivTaskCreate(&tid, &attr, do_webserver_demo, NULL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0) | SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN) | SHELL_CMD_PARAM_NUM(5), Webserver, webserver_demo, webserver for project);
|
|
@ -0,0 +1,723 @@
|
|||
// Copyright (c) 2022 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
//
|
||||
// UI example
|
||||
// It implements the following endpoints:
|
||||
// /api/config/get - respond with current config
|
||||
// /api/config/set - POST a config change
|
||||
// any other URI serves static files from s_root_dir
|
||||
// Data and results are JSON strings
|
||||
|
||||
/**
|
||||
* @file webserver_project.c
|
||||
* @brief support webserver_project for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-11-07
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: webserver_project.c
|
||||
Description: support webserver_project for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-11-07
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、support xishutong-arm32 board, using W5500 to support webserver.
|
||||
*************************************************/
|
||||
|
||||
|
||||
#include "ip_addr.h"
|
||||
#include "mongoose.h"
|
||||
#include "netdev.h"
|
||||
#include <sys_arch.h>
|
||||
#include <lwip/sockets.h>
|
||||
#include "lwip/sys.h"
|
||||
#include <adapter.h>
|
||||
|
||||
/*******************************************************************************
|
||||
* Local variable definitions ('static')
|
||||
******************************************************************************/
|
||||
char index_path[] = "login.html";
|
||||
|
||||
static const char* s_http_addr = "http://192.168.131.88:8000"; // HTTP port
|
||||
static const char* s_root_dir = "webserver";
|
||||
static const char* s_enable_hexdump = "no";
|
||||
static const char* s_ssi_pattern = "#.html";
|
||||
static const char* web_version = "XiUOS WebServer 1.0";
|
||||
|
||||
static struct netdev* p_netdev_webserver;
|
||||
static struct netdev* p_netdev_ethernet;
|
||||
static pthread_t tid;
|
||||
|
||||
#define WB_EVENT_TASK_STACK_SIZE 4096
|
||||
#define WB_EVENT_TASK_PRIO 20
|
||||
|
||||
#define WB_4G_CONNECT 0x0001
|
||||
#define WB_4G_DISCONNECT 0x0002
|
||||
#define WB_MQTT_CONNECT 0x0004
|
||||
#define WB_MQTT_DISCONNECT 0x0008
|
||||
#define WB_LORA_CONNECT 0x0010
|
||||
#define WB_LORA_DISCONNECT 0x0020
|
||||
#define WB_ETHERNET_CONNECT 0x0040
|
||||
#define WB_ETHERNET_DISCONNECT 0x0080
|
||||
#define WB_EVENT_ALL (WB_4G_CONNECT | WB_4G_DISCONNECT | \
|
||||
WB_MQTT_CONNECT | WB_MQTT_DISCONNECT | \
|
||||
WB_LORA_CONNECT | WB_LORA_DISCONNECT | \
|
||||
WB_ETHERNET_CONNECT | WB_ETHERNET_DISCONNECT)
|
||||
|
||||
static int wb_event;
|
||||
static unsigned int status = 0;
|
||||
static pthread_t wb_event_task;
|
||||
|
||||
/*define device info*/
|
||||
static const char* device_name = "矽数通4G";
|
||||
static const char* device_type = "xishutong-arm32";
|
||||
static const char* device_serial_num = "123456789";
|
||||
|
||||
/*define webserver info*/
|
||||
static struct webserver_config {
|
||||
char *ip, *mask, *gw, *dns;
|
||||
} webserver_config;
|
||||
|
||||
/*define interface info*/
|
||||
static struct rs485_config {
|
||||
int baud_rate;
|
||||
int data_bit;
|
||||
int stop_bit;
|
||||
int parity;
|
||||
} rs485_config;
|
||||
int rs485_uart_fd = -1;
|
||||
|
||||
#define RS485_DEVICE_PATH "/dev/usart4_dev4"
|
||||
|
||||
/*define net 4G info*/
|
||||
static struct net_4g_info {
|
||||
char map_ip[20];
|
||||
char connect_ip[20];
|
||||
char operator[20];
|
||||
char signal_strength[20];
|
||||
char connect_port[20];
|
||||
} net_4g_info;
|
||||
|
||||
struct Adapter* adapter;
|
||||
|
||||
static struct net_4g_mqtt_info {
|
||||
char topic[20];
|
||||
char username[20];
|
||||
char password[20];
|
||||
int client_id;
|
||||
int connect_status;
|
||||
} net_4g_mqtt_info;
|
||||
|
||||
/*define net LoRa info*/
|
||||
struct net_lora_info
|
||||
{
|
||||
uint32_t frequency; // frequency
|
||||
uint8_t sf; // spreadfactor
|
||||
uint8_t bw; // bandwidth
|
||||
|
||||
uint32_t connect_status; //connect status
|
||||
uint8_t lora_init_flag; //if 1 means already init
|
||||
} net_lora_info;
|
||||
|
||||
/*define net Ethernet info*/
|
||||
static struct net_ethernet_info {
|
||||
char ethernetIp[20];
|
||||
char ethernetNetmask[20];
|
||||
char ethernetGateway[20];
|
||||
char ethernetDNS[20];
|
||||
char targetIp[20];
|
||||
char targetPort[20];
|
||||
char targetGateway[20];
|
||||
char targetDNS[20];
|
||||
int connect_status;
|
||||
} net_ethernet_info;
|
||||
|
||||
static int socket_fd = -1;
|
||||
|
||||
static char tcp_ethernet_ipaddr[] = {192, 168, 130, 77};
|
||||
static char tcp_ethernet_netmask[] = {255, 255, 254, 0};
|
||||
static char tcp_ethernet_gwaddr[] = {192, 168, 130, 1};
|
||||
|
||||
static uint16_t tcp_socket_port = 8888;
|
||||
|
||||
/*define PLC info*/
|
||||
static char *plc_json;
|
||||
#define JSON_FILE_NAME "test_recipe.json"
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - define interface info
|
||||
******************************************************************************/
|
||||
static void Rs485InitConfigure(void)
|
||||
{
|
||||
rs485_uart_fd = PrivOpen(RS485_DEVICE_PATH, O_RDWR);
|
||||
if (rs485_uart_fd < 0) {
|
||||
printf("open rs485 %s fd error:%d\n", RS485_DEVICE_PATH, rs485_uart_fd);
|
||||
return;
|
||||
}
|
||||
printf("uart %s open success\n", RS485_DEVICE_PATH);
|
||||
|
||||
struct SerialDataCfg uart_cfg;
|
||||
memset(&uart_cfg, 0, sizeof(struct SerialDataCfg));
|
||||
|
||||
rs485_config.baud_rate = BAUD_RATE_115200;
|
||||
rs485_config.data_bit = DATA_BITS_8;
|
||||
rs485_config.stop_bit = STOP_BITS_1;
|
||||
rs485_config.parity = PARITY_NONE;
|
||||
|
||||
uart_cfg.serial_baud_rate = rs485_config.baud_rate;
|
||||
uart_cfg.serial_data_bits = rs485_config.data_bit;
|
||||
uart_cfg.serial_stop_bits = rs485_config.stop_bit;
|
||||
uart_cfg.serial_parity_mode = rs485_config.parity;
|
||||
uart_cfg.serial_bit_order = BIT_ORDER_LSB;
|
||||
uart_cfg.serial_invert_mode = NRZ_NORMAL;
|
||||
uart_cfg.serial_buffer_size = SERIAL_RB_BUFSZ;
|
||||
uart_cfg.serial_timeout = -1;
|
||||
uart_cfg.is_ext_uart = 0;
|
||||
uart_cfg.dev_recv_callback = NULL;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = (void *)&uart_cfg;
|
||||
|
||||
if (0 != PrivIoctl(rs485_uart_fd, OPE_INT, &ioctl_cfg)) {
|
||||
printf("ioctl uart fd error %d\n", rs485_uart_fd);
|
||||
PrivClose(rs485_uart_fd);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
static void Rs485Configure(int baud_rate, int data_bit, int stop_bit, int parity)
|
||||
{
|
||||
if (rs485_uart_fd < 0) {
|
||||
rs485_uart_fd = PrivOpen(RS485_DEVICE_PATH, O_RDWR);
|
||||
if (rs485_uart_fd < 0) {
|
||||
printf("open rs485 %s fd error:%d\n", RS485_DEVICE_PATH, rs485_uart_fd);
|
||||
return;
|
||||
}
|
||||
printf("uart %s open success\n", RS485_DEVICE_PATH);
|
||||
}
|
||||
|
||||
struct SerialDataCfg uart_cfg;
|
||||
memset(&uart_cfg, 0, sizeof(struct SerialDataCfg));
|
||||
|
||||
uart_cfg.serial_baud_rate = baud_rate;
|
||||
uart_cfg.serial_data_bits = data_bit;
|
||||
uart_cfg.serial_stop_bits = stop_bit;
|
||||
uart_cfg.serial_parity_mode = parity;
|
||||
uart_cfg.serial_bit_order = BIT_ORDER_LSB;
|
||||
uart_cfg.serial_invert_mode = NRZ_NORMAL;
|
||||
uart_cfg.serial_buffer_size = SERIAL_RB_BUFSZ;
|
||||
uart_cfg.serial_timeout = -1;
|
||||
uart_cfg.is_ext_uart = 0;
|
||||
uart_cfg.dev_recv_callback = NULL;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = (void *)&uart_cfg;
|
||||
|
||||
if (0 != PrivIoctl(rs485_uart_fd, OPE_INT, &ioctl_cfg)) {
|
||||
printf("ioctl uart fd error %d\n", rs485_uart_fd);
|
||||
PrivClose(rs485_uart_fd);
|
||||
return;
|
||||
}
|
||||
|
||||
printf("Board RS485 changed to [br: %d, data: %d, stop: %d, party: %d]\n",
|
||||
baud_rate, data_bit, stop_bit, parity);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - define net 4G info
|
||||
******************************************************************************/
|
||||
static void Net4gGetInfo(char *ip, char *operator, char *signal_strength)
|
||||
{
|
||||
//to do
|
||||
}
|
||||
|
||||
static void Net4gConnect(void)
|
||||
{
|
||||
int ec200a_baud_rate = 115200;
|
||||
const char *send_msg = "Adapter_4G Test";
|
||||
adapter->socket.socket_id = 0;
|
||||
|
||||
AdapterDeviceOpen(adapter);
|
||||
AdapterDeviceControl(adapter, OPE_INT, &ec200a_baud_rate);
|
||||
AdapterDeviceConnect(adapter, CLIENT, net_4g_info.connect_ip, net_4g_info.connect_port, IPV4);
|
||||
}
|
||||
|
||||
static void Net4gDisconnect(void)
|
||||
{
|
||||
uint8_t priv_net_group = IP_PROTOCOL;
|
||||
AdapterDeviceDisconnect(adapter, &priv_net_group);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - define net 4G MQTT info
|
||||
******************************************************************************/
|
||||
static void NetMqttConnect(void)
|
||||
{
|
||||
//to do
|
||||
}
|
||||
|
||||
static void NetMqttDisconnect(void)
|
||||
{
|
||||
//to do
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - define net LoRa info
|
||||
******************************************************************************/
|
||||
static void NetLoraConnect(void)
|
||||
{
|
||||
char* init_params[2] = {"TestLoraRadio", "probe"};
|
||||
char* tx_params[4] = {"TestLoraRadio", "tx", "1", "2000"};
|
||||
extern int TestLoraRadio(int argc, char *argv[]);
|
||||
|
||||
if (0 == net_lora_info.lora_init_flag) {
|
||||
TestLoraRadio(2, init_params);
|
||||
net_lora_info.lora_init_flag = 1;
|
||||
}
|
||||
|
||||
TestLoraRadio(4, tx_params);
|
||||
net_lora_info.connect_status = 1;
|
||||
}
|
||||
|
||||
static void NetLoraDisconnect(void)
|
||||
{
|
||||
char* disconnect_params[2] = {"TestLoraRadio", "txdone"};
|
||||
extern int TestLoraRadio(int argc, char *argv[]);
|
||||
TestLoraRadio(2, disconnect_params);
|
||||
net_lora_info.connect_status = 0;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - define net Ethernet info
|
||||
******************************************************************************/
|
||||
static void TcpClientConnect(void)
|
||||
{
|
||||
int cnt = 20;
|
||||
int ret;
|
||||
char send_msg[128];
|
||||
|
||||
sscanf(net_ethernet_info.targetPort, "%d", &tcp_socket_port);
|
||||
|
||||
memset(send_msg, 0, sizeof(send_msg));
|
||||
socket_fd = socket(AF_INET, SOCK_STREAM, 0);
|
||||
if (socket_fd < 0) {
|
||||
printf("Socket error\n");
|
||||
return;
|
||||
}
|
||||
|
||||
struct sockaddr_in tcp_sock;
|
||||
tcp_sock.sin_family = AF_INET;
|
||||
tcp_sock.sin_port = htons(tcp_socket_port);
|
||||
tcp_sock.sin_addr.s_addr = inet_addr(net_ethernet_info.targetIp);
|
||||
|
||||
memset(&(tcp_sock.sin_zero), 0, sizeof(tcp_sock.sin_zero));
|
||||
|
||||
int keepalive = 1;
|
||||
int keepidle = 30;
|
||||
int keepinterval = 5;
|
||||
int keepcount = 5;
|
||||
setsockopt(socket_fd,
|
||||
IPPROTO_TCP, /* set option at TCP level */
|
||||
TCP_KEEPALIVE, /* name of option */
|
||||
(void*)&keepalive, /* the cast is historical cruft */
|
||||
sizeof(keepalive)); /* length of option value */
|
||||
|
||||
setsockopt(socket_fd,
|
||||
IPPROTO_TCP, /* set option at TCP level */
|
||||
TCP_KEEPIDLE, /* name of option */
|
||||
(void*)&keepidle, /* the cast is historical cruft */
|
||||
sizeof(keepidle)); /* length of option value */
|
||||
|
||||
setsockopt(socket_fd,
|
||||
IPPROTO_TCP, /* set option at TCP level */
|
||||
TCP_KEEPINTVL, /* name of option */
|
||||
(void*)&keepinterval, /* the cast is historical cruft */
|
||||
sizeof(keepinterval)); /* length of option value */
|
||||
|
||||
setsockopt(socket_fd,
|
||||
IPPROTO_TCP, /* set option at TCP level */
|
||||
TCP_KEEPCNT, /* name of option */
|
||||
(void*)&keepcount, /* the cast is historical cruft */
|
||||
sizeof(keepcount)); /* length of option value */
|
||||
|
||||
ret = connect(socket_fd, (struct sockaddr *)&tcp_sock, sizeof(struct sockaddr));
|
||||
if (ret < 0) {
|
||||
printf("Unable to connect %s:%d = %d\n", net_ethernet_info.targetIp, tcp_socket_port, ret);
|
||||
closesocket(socket_fd);
|
||||
return;
|
||||
}
|
||||
|
||||
printf("TCP connect %s:%d success, start to send.\n", net_ethernet_info.targetIp, tcp_socket_port);
|
||||
net_ethernet_info.connect_status = 1;
|
||||
|
||||
while (cnt --) {
|
||||
printf("Lwip client is running.\n");
|
||||
snprintf(send_msg, sizeof(send_msg), "TCP test package times %d\r\n", cnt);
|
||||
send(socket_fd, send_msg, strlen(send_msg), 0);
|
||||
printf("Send tcp msg: %s ", send_msg);
|
||||
PrivTaskDelay(1000);
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
static void TcpClientDisconnect(void)
|
||||
{
|
||||
printf("TCP disconnect\n");
|
||||
closesocket(socket_fd);
|
||||
net_ethernet_info.connect_status = 0;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - define plc info
|
||||
******************************************************************************/
|
||||
static void PlcInfoWriteToSd(const char *json)
|
||||
{
|
||||
extern int GetSdMountStatus(void);
|
||||
if(GetSdMountStatus()) {
|
||||
KPrintf("------Start download json file !------\r\n");
|
||||
|
||||
FILE *fp = fopen(JSON_FILE_NAME, "w");
|
||||
if(fp == NULL) {
|
||||
printf("%s file create failed,please check!\r\n", JSON_FILE_NAME);
|
||||
} else {
|
||||
printf("%s file create success!\r\n", JSON_FILE_NAME);
|
||||
fprintf(fp, "%s", json);
|
||||
fclose(fp);
|
||||
}
|
||||
printf("------download %s file done!------\r\n", JSON_FILE_NAME);
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - WebserverEventTask
|
||||
******************************************************************************/
|
||||
static void *WebserverEventTask(void *arg)
|
||||
{
|
||||
wb_event = PrivEventCreate(LINKLIST_FLAG_FIFO);
|
||||
while(1) {
|
||||
if (0 == PrivEventProcess(wb_event, WB_EVENT_ALL, EVENT_OR | EVENT_AUTOCLEAN, 0, &status)) {
|
||||
switch( status ) {
|
||||
case WB_4G_CONNECT:
|
||||
Net4gConnect();
|
||||
break;
|
||||
case WB_4G_DISCONNECT:
|
||||
Net4gDisconnect();
|
||||
break;
|
||||
case WB_MQTT_CONNECT:
|
||||
NetMqttConnect();
|
||||
break;
|
||||
case WB_MQTT_DISCONNECT:
|
||||
NetMqttDisconnect();
|
||||
break;
|
||||
case WB_LORA_CONNECT:
|
||||
NetLoraConnect();
|
||||
break;
|
||||
case WB_LORA_DISCONNECT:
|
||||
NetLoraDisconnect();
|
||||
break;
|
||||
case WB_ETHERNET_CONNECT:
|
||||
TcpClientConnect();
|
||||
break;
|
||||
case WB_ETHERNET_DISCONNECT:
|
||||
TcpClientDisconnect();
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void WbEventInit(void)
|
||||
{
|
||||
char task_name[] = "wb_event_task";
|
||||
pthread_args_t args;
|
||||
args.pthread_name = task_name;
|
||||
|
||||
pthread_attr_t attr;
|
||||
attr.schedparam.sched_priority = WB_EVENT_TASK_PRIO;
|
||||
attr.stacksize = WB_EVENT_TASK_STACK_SIZE;
|
||||
|
||||
PrivTaskCreate(&wb_event_task, &attr, &WebserverEventTask, (void *)&args);
|
||||
PrivTaskStartup(&wb_event_task);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function implementation - webserver
|
||||
******************************************************************************/
|
||||
// Try to update a single configuration value
|
||||
static void update_config(struct mg_str json, const char* path, char** value)
|
||||
{
|
||||
char* jval;
|
||||
if ((jval = mg_json_get_str(json, path)) != NULL) {
|
||||
free(*value);
|
||||
*value = strdup(jval);
|
||||
}
|
||||
}
|
||||
|
||||
static void update_config_array(struct mg_str json, const char* path, char* value)
|
||||
{
|
||||
char* jval;
|
||||
if ((jval = mg_json_get_str(json, path)) != NULL) {
|
||||
sprintf(value, "%s", jval);
|
||||
}
|
||||
}
|
||||
|
||||
static void fn(struct mg_connection* c, int ev, void* ev_data, void* fn_data)
|
||||
{
|
||||
if (ev == MG_EV_HTTP_MSG) {
|
||||
struct mg_http_message *hm = (struct mg_http_message*)ev_data, tmp = { 0 };
|
||||
/*define device info*/
|
||||
if (mg_http_match_uri(hm, "/getSystemInfo")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%m, %m:%m, %m:%m, %m:%m, %m:%m, %m:%m}\n",
|
||||
MG_ESC("deviceName"), MG_ESC(device_name),
|
||||
MG_ESC("deviceType"), MG_ESC(device_type),
|
||||
MG_ESC("deviceNo"), MG_ESC(device_serial_num),
|
||||
MG_ESC("ip"), MG_ESC(webserver_config.ip),
|
||||
MG_ESC("netmask"), MG_ESC(webserver_config.mask),
|
||||
MG_ESC("gateway"), MG_ESC(webserver_config.gw));
|
||||
}
|
||||
/*define webserver info*/
|
||||
else if (mg_http_match_uri(hm, "/setNetInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
printf("json: %s\n", json.ptr);
|
||||
update_config(json, "$.ip", &webserver_config.ip);
|
||||
update_config(json, "$.netmask", &webserver_config.mask);
|
||||
update_config(json, "$.gateway", &webserver_config.gw);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
|
||||
ip_addr_t ipaddr, maskaddr, gwaddr;
|
||||
inet_aton(webserver_config.ip, &ipaddr);
|
||||
inet_aton(webserver_config.mask, &maskaddr);
|
||||
inet_aton(webserver_config.gw, &gwaddr);
|
||||
p_netdev_webserver->ops->set_addr_info(p_netdev_webserver, &ipaddr, &maskaddr, &gwaddr);
|
||||
|
||||
printf("Board Webserver Net changed to [IP: %s, Mask: %s, GW: %s]\n",
|
||||
webserver_config.ip,
|
||||
webserver_config.mask,
|
||||
webserver_config.gw);
|
||||
}
|
||||
/*define interface info*/
|
||||
else if (mg_http_match_uri(hm, "/interface/get485Info")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%d, %m:%d, %m:%d, %m:%d}\n",
|
||||
MG_ESC("baudRate"), rs485_config.baud_rate,
|
||||
MG_ESC("wordLength"), rs485_config.data_bit,
|
||||
MG_ESC("stopBits"), rs485_config.stop_bit,
|
||||
MG_ESC("parity"), rs485_config.parity);
|
||||
} else if (mg_http_match_uri(hm, "/interface/set485Info")) {
|
||||
struct mg_str json = hm->body;
|
||||
printf("json: %s\n", json.ptr);
|
||||
rs485_config.baud_rate = mg_json_get_long(json, "$.baudRate", 0);
|
||||
rs485_config.data_bit = mg_json_get_long(json, "$.wordLength", 0);
|
||||
rs485_config.stop_bit = mg_json_get_long(json, "$.stopBits", 0);
|
||||
rs485_config.parity = mg_json_get_long(json, "$.parity", 0);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
|
||||
Rs485Configure(rs485_config.baud_rate, rs485_config.data_bit, rs485_config.stop_bit, rs485_config.parity);
|
||||
}
|
||||
/*define net 4G info*/
|
||||
else if (mg_http_match_uri(hm, "/net/get4gInfo")) {
|
||||
|
||||
Net4gGetInfo(net_4g_info.map_ip, net_4g_info.operator, net_4g_info.signal_strength);
|
||||
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%m, %m:%m, %m:%d}\n",
|
||||
MG_ESC("mapIp"), MG_ESC(net_4g_info.map_ip),
|
||||
MG_ESC("operator"), MG_ESC(net_4g_info.operator),
|
||||
MG_ESC("signalIntensity"), MG_ESC(net_4g_info.signal_strength));
|
||||
} else if (mg_http_match_uri(hm, "/net/set4gInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
update_config_array(json, "$.publicIp", net_4g_info.connect_ip);
|
||||
update_config_array(json, "$.publicPort", net_4g_info.connect_port);
|
||||
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else if (mg_http_match_uri(hm, "/net/connect4G")) {
|
||||
//enable 4G connect function
|
||||
PrivEvenTrigger(wb_event, WB_4G_CONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else if (mg_http_match_uri(hm, "/net/disconnect4G")) {
|
||||
//disable 4G connect function
|
||||
PrivEvenTrigger(wb_event, WB_4G_CONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else if (mg_http_match_uri(hm, "/net/getMQTTInfo")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%m, %m:%m, %m:%m, %m:%d, %m:%d}\n",
|
||||
MG_ESC("topic"), MG_ESC(net_4g_mqtt_info.topic),
|
||||
MG_ESC("username"), MG_ESC(net_4g_mqtt_info.username),
|
||||
MG_ESC("password"), MG_ESC(net_4g_mqtt_info.password),
|
||||
MG_ESC("client_id"), net_4g_mqtt_info.client_id,
|
||||
MG_ESC("status"), net_4g_mqtt_info.connect_status);
|
||||
} else if (mg_http_match_uri(hm, "/net/setMQTTInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
update_config_array(json, "$.topic", net_4g_mqtt_info.topic);
|
||||
update_config_array(json, "$.username", net_4g_mqtt_info.username);
|
||||
update_config_array(json, "$.password", net_4g_mqtt_info.password);
|
||||
net_4g_mqtt_info.client_id = mg_json_get_long(json, "$.client_id", 0);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else if (mg_http_match_uri(hm, "/net/connectMQTT")) {
|
||||
//enable 4G MQTT connect function
|
||||
PrivEvenTrigger(wb_event, WB_MQTT_CONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else if (mg_http_match_uri(hm, "/net/disconnectMQTT")) {
|
||||
//disable 4G MQTT connect function
|
||||
PrivEvenTrigger(wb_event, WB_MQTT_DISCONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
}
|
||||
/*define net LoRa info*/
|
||||
else if (mg_http_match_uri(hm, "/net/getLoraInfo")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%d, %m:%d, %m:%d, %m:%d}\n",
|
||||
MG_ESC("range"), net_lora_info.frequency,
|
||||
MG_ESC("bandwidth"), net_lora_info.bw,
|
||||
MG_ESC("factor"), net_lora_info.sf,
|
||||
MG_ESC("status"), net_lora_info.connect_status);
|
||||
}
|
||||
else if (mg_http_match_uri(hm, "/net/setLoraInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
printf("json: %s\n", json.ptr);
|
||||
net_lora_info.frequency = mg_json_get_long(json, "$.range", 0);
|
||||
net_lora_info.sf = mg_json_get_long(json, "$.factor", 0);
|
||||
net_lora_info.bw = mg_json_get_long(json, "$.bandwidth", 0);
|
||||
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
|
||||
extern void LoraRadioParamsUpdate(uint32_t frequency, uint8_t sf, uint8_t bw);
|
||||
LoraRadioParamsUpdate(net_lora_info.frequency, net_lora_info.sf, net_lora_info.bw);
|
||||
} else if (mg_http_match_uri(hm, "/net/ConnectLora")) {
|
||||
//enable LoRa connect function
|
||||
PrivEvenTrigger(wb_event, WB_LORA_CONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else if (mg_http_match_uri(hm, "/net/DisonnectLora")) {
|
||||
//disable LoRa connect function
|
||||
PrivEvenTrigger(wb_event, WB_LORA_DISCONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
}
|
||||
/*define net Ethernet info*/
|
||||
else if (mg_http_match_uri(hm, "/net/getEthernetInfo")) {
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n",
|
||||
"{%m:%m, %m:%m, %m:%m, %m:%m, %m:%m, %m:%m, %m:%m, %m:%m, %m:%d}\n",
|
||||
MG_ESC("ethernetIp"), MG_ESC(net_ethernet_info.ethernetIp),
|
||||
MG_ESC("ethernetNetmask"), MG_ESC(net_ethernet_info.ethernetNetmask),
|
||||
MG_ESC("ethernetGateway"), MG_ESC(net_ethernet_info.ethernetGateway),
|
||||
MG_ESC("ethernetDNS"), MG_ESC(net_ethernet_info.ethernetDNS),
|
||||
MG_ESC("targetIp"), MG_ESC(net_ethernet_info.targetIp),
|
||||
MG_ESC("targetPort"), MG_ESC(net_ethernet_info.targetPort),
|
||||
MG_ESC("targetGateway"), MG_ESC(net_ethernet_info.targetGateway),
|
||||
MG_ESC("targetDNS"), MG_ESC(net_ethernet_info.targetDNS),
|
||||
MG_ESC("ethernetStatus"), net_ethernet_info.connect_status);
|
||||
} else if (mg_http_match_uri(hm, "/net/setEthernetInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
printf("json: %s\n", json.ptr);
|
||||
update_config_array(json, "$.ethernetIp", net_ethernet_info.ethernetIp);
|
||||
update_config_array(json, "$.ethernetNetmask", net_ethernet_info.ethernetNetmask);
|
||||
update_config_array(json, "$.ethernetGateway", net_ethernet_info.ethernetGateway);
|
||||
update_config_array(json, "$.ethernetDNS", net_ethernet_info.ethernetDNS);
|
||||
update_config_array(json, "$.targetIp", net_ethernet_info.targetIp);
|
||||
update_config_array(json, "$.targetPort", net_ethernet_info.targetPort);
|
||||
update_config_array(json, "$.targetGateway", net_ethernet_info.targetGateway);
|
||||
update_config_array(json, "$.targetDNS", net_ethernet_info.targetDNS);
|
||||
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
|
||||
p_netdev_ethernet = netdev_get_by_name("hd");
|
||||
if (p_netdev_ethernet) {
|
||||
ip_addr_t ipaddr, maskaddr, gwaddr;
|
||||
inet_aton(net_ethernet_info.ethernetIp, &ipaddr);
|
||||
inet_aton(net_ethernet_info.ethernetNetmask, &maskaddr);
|
||||
inet_aton(net_ethernet_info.ethernetGateway, &gwaddr);
|
||||
p_netdev_ethernet->ops->set_addr_info(p_netdev_ethernet, &ipaddr, &maskaddr, &gwaddr);
|
||||
|
||||
printf("Ethernet Configuration changed to [IP: %s, Mask: %s, GW: %s]\n",
|
||||
net_ethernet_info.ethernetIp, net_ethernet_info.ethernetNetmask,
|
||||
net_ethernet_info.ethernetGateway);
|
||||
}
|
||||
} else if (mg_http_match_uri(hm, "/net/connectEthernet")) {
|
||||
//enable Ethernet connect function
|
||||
PrivEvenTrigger(wb_event, WB_ETHERNET_CONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else if (mg_http_match_uri(hm, "/net/disconnectEthernet")) {
|
||||
//disable Ethernet connect function
|
||||
PrivEvenTrigger(wb_event, WB_ETHERNET_DISCONNECT);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
}
|
||||
/*define plc info*/
|
||||
else if (mg_http_match_uri(hm, "/control/setPLCInfo")) {
|
||||
struct mg_str json = hm->body;
|
||||
printf("json: %s\n", json.ptr);
|
||||
PlcInfoWriteToSd(json.ptr);
|
||||
mg_http_reply(c, 200, "Content-Type: application/json\r\n", "{\"status\":\"success\"}\r\n");
|
||||
} else {
|
||||
struct mg_str unknown = mg_str_n("?", 1), *cl;
|
||||
struct mg_http_serve_opts opts = { .root_dir = s_root_dir, .ssi_pattern = s_ssi_pattern };
|
||||
mg_http_serve_dir(c, hm, &opts);
|
||||
mg_http_parse((char*)c->send.buf, c->send.len, &tmp);
|
||||
cl = mg_http_get_header(&tmp, "Content-Length");
|
||||
if (cl == NULL)
|
||||
cl = &unknown;
|
||||
MG_INFO(("%.*s %.*s %.*s %.*s", (int)hm->method.len, hm->method.ptr,
|
||||
(int)hm->uri.len, hm->uri.ptr, (int)tmp.uri.len, tmp.uri.ptr,
|
||||
(int)cl->len, cl->ptr));
|
||||
}
|
||||
}
|
||||
(void)fn_data;
|
||||
}
|
||||
|
||||
static void* do_webserver(void* args)
|
||||
{
|
||||
p_netdev_webserver = netdev_get_by_name("wz");
|
||||
if (p_netdev_webserver == NULL) {
|
||||
MG_INFO(("Did not find wz netdev, use default.\n"));
|
||||
p_netdev_webserver = NETDEV_DEFAULT;
|
||||
}
|
||||
MG_INFO(("Webserver Use Netdev %s", p_netdev_webserver->name));
|
||||
webserver_config.ip = strdup(inet_ntoa(*p_netdev_webserver->ip_addr));
|
||||
webserver_config.mask = strdup(inet_ntoa(*p_netdev_webserver->netmask));
|
||||
webserver_config.gw = strdup(inet_ntoa(*p_netdev_webserver->gw));
|
||||
webserver_config.dns = strdup(inet_ntoa(p_netdev_webserver->dns_servers[0]));
|
||||
|
||||
#ifdef BSP_USING_RS485
|
||||
Rs485InitConfigure();
|
||||
#endif
|
||||
|
||||
adapter = AdapterDeviceFindByName(ADAPTER_4G_NAME);
|
||||
net_lora_info.lora_init_flag = 0;
|
||||
WbEventInit();
|
||||
|
||||
struct mg_mgr mgr; // Event manager
|
||||
// mg_log_set(MG_LL_INFO); // Set to 3 to enable debug
|
||||
mg_log_set(MG_LL_ERROR); // Set to 3 to enable debug
|
||||
mg_mgr_init(&mgr); // Initialise event manager
|
||||
mg_http_listen(&mgr, s_http_addr, fn, NULL); // Create HTTP listener
|
||||
for (;;)
|
||||
mg_mgr_poll(&mgr, 50); // Infinite event loop
|
||||
mg_mgr_free(&mgr);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
int webserver(void)
|
||||
{
|
||||
char* params[2] = {"LwipNetworkActive", "-a"};
|
||||
extern void LwipNetworkActive(int argc, char* argv[]);
|
||||
LwipNetworkActive(2, params);
|
||||
|
||||
pthread_attr_t attr;
|
||||
attr.schedparam.sched_priority = 30;
|
||||
attr.stacksize = 0x4000;
|
||||
|
||||
char task_name[] = "do_webserver";
|
||||
pthread_args_t args;
|
||||
args.pthread_name = task_name;
|
||||
|
||||
PrivTaskCreate(&tid, &attr, &do_webserver, (void *)&args);
|
||||
PrivTaskStartup(&tid);
|
||||
|
||||
return 0;
|
||||
}
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0) | SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN) | SHELL_CMD_PARAM_NUM(5),
|
||||
Webserver, webserver, webserver for project);
|
|
@ -8,9 +8,8 @@ endif
|
|||
|
||||
config ADAPTER_EC200A
|
||||
bool "Using 4G adapter device EC200A"
|
||||
default y
|
||||
default n
|
||||
|
||||
if ADAPTER_EC200A
|
||||
source "$APP_DIR/Framework/connection/4g/ec200a/Kconfig"
|
||||
endif
|
||||
|
||||
|
|
|
@ -3,6 +3,7 @@ config ADAPTER_4G_EC200A
|
|||
default "ec200a"
|
||||
|
||||
if ADD_XIZI_FEATURES
|
||||
<<<<<<< HEAD
|
||||
config ADAPTER_EC200A_USING_PWRKEY
|
||||
bool "EC200A using PWRKEY pin number"
|
||||
default n
|
||||
|
@ -102,3 +103,10 @@ if ADD_RTTHREAD_FEATURES
|
|||
|
||||
|
||||
endif
|
||||
=======
|
||||
config ADAPTER_EC200A_DRIVER
|
||||
string "EC200A device uart driver path"
|
||||
default "/dev/usart6_dev6"
|
||||
endif
|
||||
|
||||
>>>>>>> upstream/prepare_for_master
|
||||
|
|
|
@ -13,9 +13,9 @@
|
|||
/**
|
||||
* @file ec200a.c
|
||||
* @brief Implement the connection 4G adapter function, using EC200A device
|
||||
* @version 1.0
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023.11.23
|
||||
* @date 2023.12.22
|
||||
*/
|
||||
|
||||
#include <adapter.h>
|
||||
|
|
|
@ -36,7 +36,7 @@ menuconfig LIB_USING_LORAWAN
|
|||
select BSP_USING_SPI
|
||||
|
||||
if LIB_USING_LORA_RADIO
|
||||
|
||||
source "$APP_DIR/lib/lorawan/lora_radio_driver/Kconfig"
|
||||
endif
|
||||
endif
|
||||
|
||||
|
|
|
@ -1 +0,0 @@
|
|||
Subproject commit a94c007cb4ee726cc29b10626f8bbfc19c989b89
|
|
@ -0,0 +1,18 @@
|
|||
choice
|
||||
prompt "choose rtos for lora radio driver"
|
||||
default LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
bool "rtos select RT-Thread"
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
bool "rtos select XiUOS"
|
||||
endchoice
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_LORA_RADIO_DEBUG
|
||||
bool "lora radio driver debug printf"
|
||||
default y
|
||||
|
||||
if LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
source "$APP_DIR/lib/lorawan/lora_radio_driver/ports/lora-module/hc32_adapter/Kconfig"
|
||||
endif
|
|
@ -0,0 +1,3 @@
|
|||
SRC_DIR := lora-radio ports samples
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,5 @@
|
|||
# LoRa-Radio-Driver软件包 简介
|
||||
LoRa-Radio-Driver软件包是基于RTOS( RT-Thread、XiUOS ) 实现的LoRa Tranceiver芯片的驱动文件包,可用于快速搭建基于LoRa等通信的应用产品。
|
||||
|
||||
更多详细信息请查看[LoRa-Radio-Driver/doc](https://github.com/Forest-Rain/lora-radio-driver/tree/master/doc)
|
||||
|
|
@ -0,0 +1,12 @@
|
|||
import os
|
||||
from building import *
|
||||
|
||||
objs = []
|
||||
cwd = GetCurrentDir()
|
||||
list = os.listdir(cwd)
|
||||
|
||||
for item in list:
|
||||
if os.path.isfile(os.path.join(cwd, item, 'SConscript')):
|
||||
objs = objs + SConscript(os.path.join(item, 'SConscript'))
|
||||
|
||||
Return('objs')
|
|
@ -0,0 +1,381 @@
|
|||
# LoRa-Radio-Driver软件包使用说明
|
||||
|
||||
# 1 简介
|
||||
LoRa-Radio-Driver软件包是基于RTOS( RT-Thread ) 实现的LoRa Tranceiver芯片(SX126x、SX127x等)的驱动文件,该驱动文件通过SPI访问LoRa Tranceiver芯片,可用于快速搭建基于LoRa等通信的应用产品。
|
||||
LoRa-Radio-Driver软件包在LoRaWAN开源协议栈[LoRaMAC-Node中的radio](https://github.com/Forest-Rain/lora-radio-driver/blob/master/doc)基础上,进一步封装实现。
|
||||
|
||||
> LoRaMac\Radio
|
||||
> [https://github.com/Lora-net/LoRaMac-node/tree/master/src/radio](https://github.com/Lora-net/LoRaMac-node/tree/master/src/radio)
|
||||
|
||||
|
||||
- 主要特点:
|
||||
- 当前支持LoRa Transceiver(sx126x\sx127x )
|
||||
- 支持调制方式
|
||||
- [x] LoRa
|
||||
- [ ] FSK
|
||||
- 可通过EVN工具menuconfig直接定义LoRa模块的对外接口,降低入门门槛
|
||||
- 支持使用引脚号来定义GPIO
|
||||
- 支持使用引脚名来定义GPIO
|
||||
- 提供常用实例代码,可用于射频性能测试、空口数据包监听、双向通信测试等
|
||||
- 可作为phy层对接到LoRaWAN End-Device协议栈
|
||||
- 当前测试的LoRa 模块\芯片
|
||||
- LoRa Transceiver (SPI)
|
||||
- SX126X (SX1262\ASR6500S\LLCC68\SX1268..)
|
||||
- SX1268
|
||||
- [x] [LSD4RF-2R717N40](http://bbs.lierda.com/forum.php?mod=viewthread&tid=87)
|
||||
- SX1262
|
||||
- [x] ASR6500S
|
||||
- LLCC68
|
||||
- LR1110
|
||||
- SX127X (SX1272\SX1276\SX1278..)
|
||||
- SX1278
|
||||
- [x] [LSD4RF-2F717N20](http://bbs.lierda.com/forum.php?mod=viewthread&tid=87)
|
||||
- [x] [Ra-01](http://wiki.ai-thinker.com/lora/man)
|
||||
- [ ] SX1276
|
||||
- LoRa SIP\SoC
|
||||
- 当前测试的MCU平台
|
||||
- LoRa Radio Driver当前功能主要在STM32L平台测试通过,未来计划将适配更多的MCU平台(华大MCU、nRF、BK)
|
||||
- [x] STM32L0系列
|
||||
- [x] STM32L4系列
|
||||
- 当前支持的RTOS
|
||||
- [x] RT-Thread
|
||||
- [ ] RT-Thread Nano
|
||||
|
||||
# 2 LoRa Radio Driver 软件包组织结构
|
||||

|
||||
|
||||
- lora-radio
|
||||
- sx126x
|
||||
- lora-radio-sx126x.c
|
||||
- 对外提供了上层访问接口实现
|
||||
- lora-spi-sx126x.c
|
||||
- sx126x芯片的spi读写接口实现,独立于MCU平台
|
||||
- [x] rt_device
|
||||
- [ ] SPI裸机方式
|
||||
- sx126x.c
|
||||
- lora芯片sx126x底层驱动
|
||||
- sx127x
|
||||
- lora-radio-sx127x.c
|
||||
- 对外提供了上层访问接口
|
||||
- lora-spi-sx127x.c
|
||||
- sx127x芯片的spi读写接口实现,独立于MCU平台
|
||||
- [x] rt_device
|
||||
- [ ] SPI裸机方式
|
||||
- sx127x.c
|
||||
- lora芯片sx127x底层驱动
|
||||
- common
|
||||
- lora-radio-timer.c
|
||||
- 提供了lora-radio所需的定时服务接口,用于发送与接收超时等,基于RT-Thread内核rt_timer实现
|
||||
- 注意这种方式提供的定时最小颗粒度取决于系统tick RT_TICK_PER_SECOND
|
||||
- 注:如果使能了Multi-Rtimer软件包,则优先使用Multi-Rtimer提供定时\超时服务
|
||||
- include
|
||||
- lora-radio.h
|
||||
- 上层服务接口
|
||||
- lora-radio-debug.h
|
||||
- 根据需要使能输出lora-radio不同层级的调试信息
|
||||
- lora-radio-rtos-config.h
|
||||
- rtos适配层,选择,当前默认为RT-Thread
|
||||
- 未来支持RT-Thread-Nano、以及其他RTOS....
|
||||
- samples
|
||||
- lora radio driver示例文件
|
||||
- lora-radio-test-shell
|
||||
- shell示例,主要实现了射频性能测试、空口数据包监听、双向通信测试等shell命令,便于日常测试
|
||||
- port
|
||||
- 主要包含当前在不同MCU平台下支持的lora模块,lora-module文件夹中的xxxx-borad.c包含了与LoRa模块直接相关的主要硬件接口配置:
|
||||
- lora-module
|
||||
- stm32_adapter
|
||||
- lora-board-spi.c
|
||||
- STM32平台的SPI外设初始化等通用接口
|
||||
- LSD4RF-2F717N20 (SX1278 LoRa模块)
|
||||
- LSD4RF-2R717N40 (SX1268 LoRa模块)
|
||||
- Ra-01 (SX1278 LoRa模块)
|
||||
- xxxx-borad.c
|
||||
- LoRa模块功率输出方式(PA\RFO...)
|
||||
- LoRa模块的RF高频开关控制方式(TXE、RXE、无..)
|
||||
- LoRa模块的DIO口(DIO0、DIO1、DIO2....)
|
||||
- LoRa模块的工作频率限制等
|
||||
- xxx_adapter
|
||||
- 其他mcu平台下的硬件接口实现
|
||||
# 3 LoRa Radio Driver软件包使用说明
|
||||
## 3.1 依赖
|
||||
|
||||
- SPI外设——用户需根据实际MCU平台,自定义LoRa模块实际所需要使用的SPI外设
|
||||
- 选择SPI外设
|
||||
```
|
||||
Hardware Drivers Config --->
|
||||
On-chip Peripheral Drivers --->
|
||||
[*] Enable SPI --->
|
||||
--- Enable SPI
|
||||
[ ] Enable SPI1
|
||||
[ ] Enable SPI2
|
||||
[ ] Enable SPI3
|
||||
[ ] Enable SPI4
|
||||
[ ] Enable SPI5
|
||||
```
|
||||
- 在bsp\目标板XX\board\Kconfig增加如下定义
|
||||
```c
|
||||
menuconfig BSP_USING_SPI
|
||||
bool "Enable SPI"
|
||||
select RT_USING_SPI
|
||||
|
||||
if BSP_USING_SPI
|
||||
config BSP_USING_SPI1
|
||||
bool "Enable SPI1"
|
||||
default n
|
||||
if BSP_USING_SPI1
|
||||
config BSP_SPI1_RX_USING_DMA
|
||||
bool "Enable SPI1 RX DMA"
|
||||
default n
|
||||
config BSP_SPI1_TX_USING_DMA
|
||||
bool "Enable SPI1 TX DMA"
|
||||
default n
|
||||
endif
|
||||
|
||||
# 根据实际需要,增加其他BSP_USING_SPI2、BSP_USING_SPI3...
|
||||
endif
|
||||
```
|
||||
|
||||
- 定时服务——用于提供射频通信所需的定时\超时服务,目前支持以下两种方式,二选一
|
||||
- 内核 SOFT_TIMER
|
||||
- 若未选用Multi-Rtimer软件包,则默认采用内核的rt_timer来提供定时服务(lora-radio-timer.c)
|
||||
- 注意检测是否**开启RT-Thread内核的SOFT_TIMER**
|
||||
- M[ulti-Rtimer](https://github.com/Forest-Rain/multi-rtimer)软件包
|
||||
- 若使能multi-rtimer,lora-radio-driver优先使用multi-rtimer提供定时\超时服务。
|
||||
> 注:如果应用在工业温度范围、时间精度要求高(us\ms级别)的场景,建议使用multi-rtimer,并设置RTC时钟源为外部32768晶振,否则可能会出现下行丢包的情况。
|
||||
|
||||
```
|
||||
RT-Thread online packages --->
|
||||
peripheral libraries and drivers --->
|
||||
[*] multi_rtimer: a real-time and low power software timer module. --->
|
||||
Version (latest) --->
|
||||
multi_rtimer options --->
|
||||
[] multi_rtimer demo example
|
||||
```
|
||||
|
||||
- 可选内核组件
|
||||
- ulog组件——用于打印日志信息
|
||||
- 使能ulog
|
||||
- ulog缓存大小设置≥ 128 Byte
|
||||
- lora-raido-driver内部可看到更多LoRa底层的调试信息
|
||||
- lora-radio-test-shell.c使用ulog接口,用于打印调试信息、原始16进制数据等
|
||||
- 如果没有使用ulog,默认使用rt_kprintf来实现信息输出功能
|
||||
```
|
||||
RT-Thread Components --->
|
||||
Utiliess --->
|
||||
[*] Enable ulog
|
||||
[*] Enable ISR log.
|
||||
```
|
||||
|
||||
## 3.2 获取软件包
|
||||
使用 lora-radio-driver 软件包,需要在 RT-Thread 的包管理中选中它,具体路径如下:
|
||||
```c
|
||||
RT-Thread online packages --->
|
||||
peripheral libraries and drivers --->
|
||||
[*] lora_radio_driver: lora chipset(sx126x\sx127x.)driver. --->
|
||||
Select LoRa Radio Object Type (LoRa Radio Single-Instance)
|
||||
(lora-radio0)Setup LoRa Radio Device Name
|
||||
(spi3) Setup LoRa Radio Spi Name (Define BSP_USING_SPIx in [Target Platform]\Board\Kconfig)
|
||||
Select LoRa Chip Type (LoRa Transceiver [SX126X]) --->
|
||||
Select Supported LoRa Module [SX126X] --->
|
||||
[ ] Enable LoRa Radio Debug
|
||||
Select LoRa Radio Driver Sample --->
|
||||
Version (latest) --->
|
||||
```
|
||||
|
||||
1. Select LoRa Chip \ LoRa Module
|
||||
1. "Setup LoRa Radio Device Name"
|
||||
1. 设置LoRa Radio设备名称,缺省为"lora-radio0"
|
||||
2. "Setup LoRa Radio Spi Name"
|
||||
1. 设置LoRa Radio Spi名称
|
||||
1. 若在 [Target Platform]\Board\Kconfig提前设定好所使用的BSP_USING_SPIx,则会自动配置
|
||||
3. "Select LoRa Radio Single-Instance"
|
||||
1. 选择为单实例对象,当前只支持单个lora设备
|
||||
4. "Select LoRa Chip Type"
|
||||
1. 选择实际使用的LoRa芯片类型
|
||||
- 当前支持 SX126X、SX127x Transceiver
|
||||
5. "Select Supported LoRa Module"
|
||||
1. 选择lora模块,根据实际使用的MCU硬件平台与lora模块,配置关联的GPIO引脚等功能选项
|
||||
1. 设定LoRa模块的GPIO口(比如 RESET、NSS、BUSY、DIO1、TXE、RXE...)
|
||||
- " Select LoRa Chip GPIO by Pin Number "
|
||||
- 支持使用引脚号来定义GPIO,比如 输入 10 代表 A10
|
||||
- "Select LoRa Chip GPIO by Pin Name"
|
||||
- 支持使用引脚名来定义GPIO,比如 输入 A10 代表引脚GPIOA的PIN10脚 (STM32)
|
||||
2. Select LoRa Radio Driver Sample
|
||||
1. 根据实际情况,可选择测试示例
|
||||
## 3.3 新增LoRa模块
|
||||
在 lora-radio-driver\ports\lora-module文件下,参考已有模板,根据实际需要增加新的mcu平台适配文件、新的lora模块驱动文件xxxx-board.c
|
||||
|
||||
|
||||
# 4 使用示例
|
||||
|
||||
## 4.1 硬件测试平台
|
||||
当前所使用的硬件测试平台如下所示
|
||||
| 序号 | 硬件平台 | MCU | LoRa模块 | 主要用户接口 |
|
||||
| --- | --- | --- | --- | --- |
|
||||
| 1 | LSD4RF-TEST2002 | STM32L476VG | [LSD4RF-2R717N40](http://bbs.lierda.com/forum.php?mod=viewthread&tid=87)<br />[ ( SX1268 )](http://bbs.lierda.com/forum.php?mod=viewthread&tid=87) | <br />- 用户接口定义<br /> - VCC - 3.3V<br /> - GND<br /> - SCK - PC10 (SPI3)<br /> - MISO - PC11 (SPI3)<br /> - MOSI - PC12 (SPI3)<br /> - NSS - PA15<br /> - RESET - PA7<br /> - DIO0 - PB1<br /> - BUSY - PB2<br /> - RFSW1 - PB0<br /> - RFSW2 - PC5<br />- 射频开关TX trace<br /> - TX: RFSW1 = 1 , RFSW2 = 0<br /> - TX: RFSW1 = 0 , RFSW2 = 1<br /> |
|
||||
| 2 | LSD4RF-TEST2002 | STM32L476VG | [LSD4RF-2F717N20](http://bbs.lierda.com/forum.php?mod=viewthread&tid=87)<br />[ ( SX1278 )](http://bbs.lierda.com/forum.php?mod=viewthread&tid=87) | <br />- 用户接口定义<br /> - VCC - 3.3V<br /> - GND<br /> - SCK - PC10 (SPI3)<br /> - MISO - PC11 (SPI3)<br /> - MOSI - PC12 (SPI3)<br /> - NSS - PB6<br /> - RESET - PA7<br /> - DIO0 - PB1<br /> - DIO1 - PC4<br /> - DIO2 - PB2<br /> - DIO3 - NC<br /> - DIO4 - NC<br /> - RFSW1 - PB0<br /> - RFSW2 - PC5<br />- 射频开关TX trace<br /> - TX: RFSW1 = 1 , RFSW2 = 0<br /> - TX: RFSW1 = 0 , RFSW2 = 1<br /> |
|
||||
| 3 | Nucleo-L476RG | STM32L476RG | [Ra-01](http://wiki.ai-thinker.com/lora/man)<br />(RT-thread LoRa Adruino扩展板V1) | <br />- 用户接口定义<br /> - VCC - 3.3V<br /> - GND<br /> - SCK - PA5(SPI1)<br /> - MISO - PA6(SPI1)<br /> - MOSI - PA7(SPI1)<br /> - NSS - PB6<br /> - RESET - PC7<br /> - DIO0 - PA9<br /> - DIO1 - PA8<br /> |
|
||||
|
||||
## 4.2 Shell测试命令
|
||||
若使能 [* ] LoRa Radio Test Shell,则可以通过shell(finish)命令直接进行LoRa相关测试
|
||||
```c
|
||||
[*] Enable LoRa Radio Test Shell │ │
|
||||
Select the RF frequency (Region CN470) ---> │ │
|
||||
Select RF Modem (Modem LoRa) --->
|
||||
```
|
||||

|
||||
|
||||
| 序号 | finish命令 | 说明 |
|
||||
| --- | --- | --- |
|
||||
| 1 | lora probe | 测试lora设备(SPI)访问是否正常 |
|
||||
| 2 | lora cw <para1> <para2> | 输出CW,可用于测试发射功率、频点等<br />\<para1\>:频点,单位Hz<br>\<para2\>:功率,单位dBm |
|
||||
| 3 | lora ping <para1> <para2> | 单向\双向通信测试<br />\<para1\> : 主机\从机<br>-m 主机<br>-s 从机<br> \<para2\>: 发送数据包个数 |
|
||||
| 4 | lora rx | 接收(监听)数据包,同时以16进制格式与ASCII码显示数据内容 |
|
||||
| 5 | lora config <para1> <para2> | 配置射频参数<br />\<para1\>:radio参数,字符表示<br/> freq 表示频率,单位Hz<br/> power 表示发射功率,单位dbm<br/> sf 表示扩频因子,有效值: 7~12<br/> bw表示带宽,有效值: 0 (125kHz)、1 (250KHz)、2 (500KHz)<br/> public表示同步字,有效值: 0 (sync = 0x12), 1 (sync = 0x34)<br/> iq 表示iq反转,有效值: 0 (iq不反转),1 (iq反转)<br/>\<para2\>:radio参数的具体值 |
|
||||
|
||||

|
||||
lora ping 双向通信测试示例(SX1278 <-> SX1268)
|
||||

|
||||
lora rx 单向接收(监听)lora数据包测试示例 (SX1278 <- 或-> SX1268)
|
||||
|
||||
## 4.3 应用层调用说明
|
||||
用户层调用可以参考如下步骤
|
||||
|
||||
1. 定义射频DIO中断服务回调函数
|
||||
```c
|
||||
|
||||
/*!
|
||||
* \brief Function to be executed on Radio Tx Done event
|
||||
*/
|
||||
void OnTxDone( void );
|
||||
|
||||
/*!
|
||||
* \brief Function to be executed on Radio Rx Done event
|
||||
*/
|
||||
void OnRxDone( uint8_t *payload, uint16_t size, int16_t rssi, int8_t snr );
|
||||
|
||||
/*!
|
||||
* \brief Function executed on Radio Tx Timeout event
|
||||
*/
|
||||
void OnTxTimeout( void );
|
||||
|
||||
/*!
|
||||
* \brief Function executed on Radio Rx Timeout event
|
||||
*/
|
||||
void OnRxTimeout( void );
|
||||
|
||||
/*!
|
||||
* \brief Function executed on Radio Rx Error event
|
||||
*/
|
||||
void OnRxError( void );
|
||||
|
||||
```
|
||||
2. 调用lora-radio初始化
|
||||
```c
|
||||
void main(void)
|
||||
{
|
||||
// Radio initialization
|
||||
RadioEvents.TxDone = OnTxDone;
|
||||
RadioEvents.RxDone = OnRxDone;
|
||||
RadioEvents.TxTimeout = OnTxTimeout;
|
||||
RadioEvents.RxTimeout = OnRxTimeout;
|
||||
RadioEvents.RxError = OnRxError;
|
||||
|
||||
if(Radio.Init(&RadioEvents))
|
||||
{
|
||||
Radio.SetPublicNetwork( false );
|
||||
lora_chip_initialized = true;
|
||||
}
|
||||
//.....
|
||||
}
|
||||
```
|
||||
|
||||
3. 配置射频通信参数
|
||||
```c
|
||||
{
|
||||
Radio.SetChannel( lora_radio_test_paras.frequency );
|
||||
|
||||
if( lora_radio_test_paras.modem == MODEM_LORA )
|
||||
{
|
||||
Radio.SetTxConfig( MODEM_LORA, lora_radio_test_paras.txpower, 0, lora_radio_test_paras.bw,
|
||||
lora_radio_test_paras.sf, lora_radio_test_paras.cr,
|
||||
LORA_PREAMBLE_LENGTH, LORA_FIX_LENGTH_PAYLOAD_ON_DISABLE,
|
||||
true, 0, 0, LORA_IQ_INVERSION_ON_DISABLE, 3000 );
|
||||
|
||||
Radio.SetRxConfig( MODEM_LORA, lora_radio_test_paras.bw, lora_radio_test_paras.sf,
|
||||
lora_radio_test_paras.cr, 0, LORA_PREAMBLE_LENGTH,
|
||||
LORA_SYMBOL_TIMEOUT, LORA_FIX_LENGTH_PAYLOAD_ON_DISABLE,
|
||||
0, true, 0, 0, LORA_IQ_INVERSION_ON_DISABLE, true );
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
4. 数据发送
|
||||
```c
|
||||
Radio.Send( Buffer, len );
|
||||
```
|
||||
5. 数据接收
|
||||
```c
|
||||
void OnRxDone( uint8_t *payload, uint16_t size, int16_t rssi, int8_t snr )
|
||||
{
|
||||
Radio.Sleep( );
|
||||
BufferSize = size;
|
||||
rt_memcpy( Buffer, payload, BufferSize );
|
||||
rssi_value = rssi;
|
||||
snr_value = snr;
|
||||
// .....
|
||||
}
|
||||
```
|
||||
# 5 版本更新历史
|
||||
|
||||
- V1.0.0 版本 2020-06-20
|
||||
- 主体功能实现基于STM32平台
|
||||
- 支持SX126x、SX127x系列芯片
|
||||
- 测试LoRa芯片支持LSD4RF-2R717N40(SX1268)、SX1278、ASR6500S @ [**zyk6271**](https://github.com/zyk6271)
|
||||
- 支持基于RT-Thread内核rt_timer的lora-radio-timer接口@ [**AnswerInTheWind** ](https://github.com/AnswerInTheWind)
|
||||
- 优化日志换行功能@[**zyk6271**](https://github.com/zyk6271)
|
||||
- V1.1.0 版本 2020-08-30
|
||||
- 完善用户使用指南
|
||||
- .lora-radio-driver软件包
|
||||
- 新增日志输出选择 lora-radio-debug.h,可以按需开启调试日志,也可以用于适配不同日志输出方式
|
||||
- 新增rtos适配选择 lora-radio-rtos-config.h,便于未来适配RT-Thread-Nano、不同的RTOS平台
|
||||
- lora-radio(sx126x\sx127x)
|
||||
- 同步更新到lorawan4.4.4 release版本的radio
|
||||
- sx126x更新 SX126xSetLoRaSymbNumTimeout(同步到loramac-node-master)
|
||||
- sx126x更新 RadioRandom 与 SX126xGetRandom
|
||||
- 更新 RadioIrqProcess
|
||||
- 更新RadioTimeOnAir
|
||||
- RadioIrqProcess 增加 临界区保护,防止出现硬件异常
|
||||
- 调整lora-radio-driver软件包架构,便于未来适配不同的MCU平台
|
||||
- port目录下新增mcu平台适配层,如stm32_adapter
|
||||
- lora-radio-test-shell
|
||||
- 修复 PHY CRC Error后,没有重新进入接收问题
|
||||
- lora ping命令
|
||||
- 新增发送空口数据包的TOA时间显示
|
||||
- 新增主机侧接收到数据包后,seqno显示
|
||||
- [Kconfig](https://github.com/Forest-Rain/packages/blob/master/peripherals/lora_radio_driver)
|
||||
- 更新[lora-radio-driver\Kconfig](https://github.com/Forest-Rain/packages) 软件包配置文件
|
||||
- 区分单实例(单lora模块)与多实例(多lora模块)情况,目前支持单实例
|
||||
- 移除了Kconfig中对BSP_USING_SPIx的直接定义,BSP_USING_SPIx定义调整到[Target Platform]\Board\Kconfig)
|
||||
- 重命名宏定义REGION_X为PHY_REGION_X(如REGION_CN470 -> PHY_REGION_CN470),以便与LoRaWAN协议栈中缺省REGION_X共存
|
||||
|
||||
- V1.1.2 版本 2020-10-12
|
||||
- 修复Ra-01未同步与v1.1.1更新导致的问题
|
||||
- 优化 drv_gpio.h使用,兼容RT-Thread Studio
|
||||
- 优化 lora-radio-test-shell.c 功能
|
||||
- 新增接收超时时间设置
|
||||
- V1.2 版本 2020-10-14
|
||||
- 新增硬件测试平台
|
||||
- ART-Pi+LSD4RF-2F717N30(SX1268)模块平台 (470~510MHz频段)
|
||||
- ART-Pi+LSD4RF-2R717N40(SX1268)模块平台 (470~510MHz频段)
|
||||
- ART-Pi+LSD4RF-2R822N30(SX1262)模块平台 (868/915MHz频段)
|
||||
- V1.4.0 版本 2021-04-25
|
||||
- 重设计lora config命令,便于快速配置单个radio参数
|
||||
- ping数据包长度最大支持255Byte,可通过shell自定义ping测试数据包长度
|
||||
- shell新增加iq version、public network参数设置
|
||||
- 使用LORA_RADIO_DEBUG_LOG代替rt_kprintf
|
||||
- V1.5.0 版本 2021-11-15
|
||||
- 新增doxygen支持
|
||||
|
||||
# 6 问题和建议
|
||||
如果有什么问题或者建议欢迎提交 [Issue](https://github.com/Forest-Rain/lora-radio-driver/issues) 进行讨论。
|
Binary file not shown.
After Width: | Height: | Size: 53 KiB |
Binary file not shown.
After Width: | Height: | Size: 25 KiB |
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
* This file is only used for doxygen document generation.
|
||||
*/
|
||||
|
||||
/*!
|
||||
* @mainpage Introduce
|
||||
* @author wsn-hxj
|
||||
* @version v1.5.0
|
||||
* @date 2021-11-15
|
||||
*
|
||||
* lora-radio-driver软件包是基于RTOS( RT-Thread ) 实现的LoRa Tranceiver芯片(SX126x、SX127x等)的驱动文件,该驱动文件通过SPI读写LoRa Tranceiver芯片,可用于快速搭建基于LoRa等通信的应用产品。
|
||||
* 主要功能如下:
|
||||
* - 1. 当前支持LoRa Transceiver(sx126x\sx127x等)
|
||||
* - 支持Sub-1GHz频段
|
||||
* - 支持LoRa调制方式(SF5~SF12、BW125~BW500)
|
||||
* - 支持FSK调制方式
|
||||
* - 2. 可作为phy层对接到LoRaWAN End-Device协议栈
|
||||
* - 3. 提供常用实例代码tester,可用于射频性能测试、空口数据包监听、双向通信测试等
|
||||
* - 4. 当前支持的LoRa 模块\芯片,如
|
||||
* - LSD4RF-2R717N40 (SX1268 CN470频段)
|
||||
* - LSD4RF-2R822N300 (SX1262 868/915MHz频段)
|
||||
* - LSD4RF-2F717N30(SX1278 CN470频段)
|
||||
* - Ra-01(SX1278 CN470频段)等等
|
||||
* @section application_arch 01 功能框图
|
||||
*
|
||||
* lora-radio-driver功能框图:
|
||||
* @image html lora-radio-driver_func_arch.png "Figure 1: 功能框图"
|
||||
*
|
||||
* @section file_arch 02 文件结构
|
||||
*
|
||||
* lora-radio-driver文件结构:
|
||||
* @image html lora-radio-driver_file_arch.png "Figure 1: 文件结构"
|
||||
*
|
||||
* @section lora-radio-driver 03 用户接口API
|
||||
* 更多详细信息,请参考 @ref LORA_RADIO_UPPER_API
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
Binary file not shown.
After Width: | Height: | Size: 79 KiB |
Binary file not shown.
After Width: | Height: | Size: 21 KiB |
Binary file not shown.
After Width: | Height: | Size: 261 KiB |
Binary file not shown.
After Width: | Height: | Size: 263 KiB |
|
@ -0,0 +1,15 @@
|
|||
SRC_DIR := common
|
||||
|
||||
ifeq ($(CONFIG_LORA_RADIO_DRIVER_USING_RTOS_XIUOS),y)
|
||||
|
||||
ifeq ($(CONFIG_LORA_RADIO_DRIVER_USING_SX1268_E22400M30S),y)
|
||||
SRC_DIR += sx126x
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_LORA_RADIO_DRIVER_USING_SX1278_RA01),y)
|
||||
SRC_DIR += sx127x
|
||||
endif
|
||||
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,29 @@
|
|||
from building import *
|
||||
|
||||
src = []
|
||||
cwd = GetCurrentDir()
|
||||
include_path = [cwd]
|
||||
include_path += [cwd+'/include']
|
||||
include_path += [cwd+'/common']
|
||||
|
||||
# add lora radio driver.
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_CHIP_SX126X'):
|
||||
src = Split('''
|
||||
sx126x/lora-radio-sx126x.c
|
||||
sx126x/lora-spi-sx126x.c
|
||||
sx126x/sx126x.c
|
||||
''')
|
||||
include_path += [cwd+'/sx126x']
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_CHIP_SX127X'):
|
||||
src = Split('''
|
||||
sx127x/lora-radio-sx127x.c
|
||||
sx127x/lora-spi-sx127x.c
|
||||
sx127x/sx127x.c
|
||||
''')
|
||||
include_path += [cwd+'/sx127x']
|
||||
|
||||
src += ['common/lora-radio-timer.c']
|
||||
|
||||
group = DefineGroup('lora-radio-driver', src, depend = ['PKG_USING_LORA_RADIO_DRIVER'], CPPPATH = include_path)
|
||||
|
||||
Return('group')
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := lora-radio-timer.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,181 @@
|
|||
/*!
|
||||
* \file lora-radio-timer.c
|
||||
*
|
||||
* \brief lora-radio timer
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author DerekChen
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-radio-timer.c
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-08
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-radio-timer.c
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-08
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include <stdint.h>
|
||||
#include "lora-radio-timer.h"
|
||||
|
||||
#if defined ( LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD ) || defined ( LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD_NANO )
|
||||
#ifndef PKG_USING_MULTI_RTIMER
|
||||
|
||||
void rtick_timer_init( rtick_timer_event_t *obj, void ( *callback )( void ) )
|
||||
{
|
||||
int count = 0;
|
||||
|
||||
char name[RT_NAME_MAX];
|
||||
rt_snprintf(name,8,"rtk_%d",count++);
|
||||
|
||||
rt_timer_init(&(obj->timer),name,(void (*)(void*))callback,RT_NULL,1000,RT_TIMER_FLAG_ONE_SHOT|RT_TIMER_FLAG_SOFT_TIMER);
|
||||
}
|
||||
|
||||
void rtick_timer_start( rtick_timer_event_t *obj )
|
||||
{
|
||||
rt_timer_start(&(obj->timer));
|
||||
}
|
||||
|
||||
void rtick_timer_stop( rtick_timer_event_t *obj )
|
||||
{
|
||||
rt_timer_stop(&(obj->timer));
|
||||
}
|
||||
|
||||
void rtick_timer_reset( rtick_timer_event_t *obj )
|
||||
{
|
||||
rtick_timer_stop(obj);
|
||||
rtick_timer_start(obj);
|
||||
}
|
||||
|
||||
void rtick_timer_set_value( rtick_timer_event_t *obj, uint32_t value )
|
||||
{
|
||||
uint32_t tick = rt_tick_from_millisecond(value);
|
||||
rt_timer_control(&(obj->timer),RT_TIMER_CTRL_SET_TIME,&tick);
|
||||
}
|
||||
|
||||
TimerTime_t rtick_timer_get_current_time( void )
|
||||
{
|
||||
uint32_t now = rt_tick_get();
|
||||
return now;
|
||||
}
|
||||
|
||||
TimerTime_t rtick_timer_get_elapsed_time( TimerTime_t past )
|
||||
{
|
||||
return rt_tick_get() - past;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif // End Of ( LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD ) || defined ( LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD_NANO )
|
||||
|
||||
#if defined LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
|
||||
#define TIMER_NUM 20
|
||||
|
||||
typedef void (*timer_input_callback_entry)(void);
|
||||
typedef struct {
|
||||
timer_input_callback_entry callback_entry;
|
||||
}timer_input_callback_entry_fun;
|
||||
|
||||
static timer_input_callback_entry_fun g_timer_input_callback_entry_fun[TIMER_NUM];
|
||||
|
||||
static void timer_callback(union sigval sig_val)
|
||||
{
|
||||
uint8_t timer_id = *((uint8_t *)sig_val.sival_ptr);
|
||||
g_timer_input_callback_entry_fun[timer_id].callback_entry();
|
||||
}
|
||||
|
||||
void rtick_timer_init( rtick_timer_event_t *obj, void ( *callback )( void ) )
|
||||
{
|
||||
int ret = 0;
|
||||
int timer_flags;
|
||||
static int count = 0;
|
||||
|
||||
struct sigevent evp;
|
||||
memset(&evp, 0, sizeof(struct sigevent));
|
||||
|
||||
timer_flags = TIMER_TRIGGER_ONCE;
|
||||
|
||||
count++;
|
||||
|
||||
g_timer_input_callback_entry_fun[count].callback_entry = callback;
|
||||
evp.sigev_notify = SIGEV_THREAD;
|
||||
evp.sigev_notify_function = timer_callback;
|
||||
evp.sigev_notify_attributes = &timer_flags;
|
||||
|
||||
ret = PrivTimerCreate(count, &evp, &(obj->timer_id));
|
||||
if (ret < 0) {
|
||||
printf("%s create timer failed ret %d\n", __func__, ret);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void rtick_timer_start( rtick_timer_event_t *obj )
|
||||
{
|
||||
PrivTimerStartRun(obj->timer_id);
|
||||
}
|
||||
|
||||
void rtick_timer_stop( rtick_timer_event_t *obj )
|
||||
{
|
||||
PrivTimerQuitRun(obj->timer_id);
|
||||
}
|
||||
|
||||
void rtick_timer_reset( rtick_timer_event_t *obj )
|
||||
{
|
||||
rtick_timer_stop(obj);
|
||||
rtick_timer_start(obj);
|
||||
}
|
||||
|
||||
void rtick_timer_set_value( rtick_timer_event_t *obj, uint32_t value )
|
||||
{
|
||||
int ret;
|
||||
uint32_t input_value, ms_value, s_value;
|
||||
struct itimerspec it_value;
|
||||
//active time interval
|
||||
input_value = value;
|
||||
if (input_value >= 1000) {
|
||||
ms_value = input_value % 1000;
|
||||
s_value = (input_value - ms_value) / 1000;
|
||||
} else {
|
||||
ms_value = input_value;
|
||||
s_value = 0;
|
||||
}
|
||||
|
||||
it_value.it_interval.tv_sec = s_value;
|
||||
it_value.it_interval.tv_nsec = ms_value * 1000000;//1ms = 1000000ns
|
||||
|
||||
ret = PrivTimerModify(obj->timer_id, 0, &it_value, NULL);
|
||||
if (ret < 0) {
|
||||
printf("%s set timer time failed ret %d\n", __func__, ret);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
TimerTime_t rtick_timer_get_current_time( void )
|
||||
{
|
||||
uint32_t now = PRIV_SYSTICK_GET;
|
||||
return now;
|
||||
}
|
||||
|
||||
TimerTime_t rtick_timer_get_elapsed_time( TimerTime_t past )
|
||||
{
|
||||
return PRIV_SYSTICK_GET - past;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,216 @@
|
|||
#ifndef __LORA_RADIO_TIMER_H__
|
||||
#define __LORA_RADIO_TIMER_H__
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#ifdef PKG_USING_MULTI_RTIMER
|
||||
|
||||
#include "multi_rtimer.h"
|
||||
#include "hw_rtc_stm32.h"
|
||||
|
||||
#define LORA_RADIO_TIMESTAMP_TO_MS(x) (x)
|
||||
|
||||
#else
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
|
||||
/** @addtogroup LORA_RADIO_TIMER
|
||||
* @{
|
||||
*/
|
||||
|
||||
#define TimerInit rtick_timer_init
|
||||
#define TimerStart rtick_timer_start
|
||||
#define TimerStop rtick_timer_stop
|
||||
#define TimerReset rtick_timer_reset
|
||||
#define TimerSetValue rtick_timer_set_value
|
||||
#define TimerSetTimestamp rtick_timer_set_timestamp
|
||||
#define TimerGetCurrentTime rtick_timer_get_current_time
|
||||
#define TimerGetElapsedTime rtick_timer_get_elapsed_time
|
||||
#define TimerEvent_t rtick_timer_event_t
|
||||
|
||||
#define LORA_RADIO_TIMESTAMP_TO_MS(x) ((x) * 1000 / RT_TICK_PER_SECOND)
|
||||
/*!
|
||||
* \brief Timer object description
|
||||
*/
|
||||
typedef struct TimerEvent_s
|
||||
{
|
||||
struct rt_timer timer;
|
||||
}rtick_timer_event_t;
|
||||
|
||||
/*!
|
||||
* \brief Timer time variable definition
|
||||
*/
|
||||
#ifndef TimerTime_t
|
||||
typedef uint32_t TimerTime_t;
|
||||
#define TIMERTIME_T_MAX ( ( uint32_t )~0 )
|
||||
|
||||
/*!
|
||||
* \brief Initializes the timer object
|
||||
*
|
||||
* \remark TimerSetValue function must be called before starting the timer.
|
||||
* this function initializes timestamp and reload value at 0.
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
* \param [IN] callback Function callback called at the end of the timeout
|
||||
*/
|
||||
void rtick_timer_init( rtick_timer_event_t *obj, void ( *callback )( void ) );
|
||||
|
||||
/*!
|
||||
* \brief Starts and adds the timer object to the list of timer events
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
*/
|
||||
void rtick_timer_start( rtick_timer_event_t *obj );
|
||||
|
||||
/*!
|
||||
* \brief Stops and removes the timer object from the list of timer events
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
*/
|
||||
void rtick_timer_stop( rtick_timer_event_t *obj );
|
||||
|
||||
/*!
|
||||
* \brief Resets the timer object
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
*/
|
||||
void rtick_timer_reset( rtick_timer_event_t *obj );
|
||||
|
||||
/*!
|
||||
* \brief Set timer new timeout value
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
* \param [IN] value New timer timeout value
|
||||
*/
|
||||
void rtick_timer_set_value( rtick_timer_event_t *obj, uint32_t value );
|
||||
|
||||
void rtick_timer_set_timestamp( rtick_timer_event_t *obj, uint32_t value );
|
||||
|
||||
/*!
|
||||
* \brief Read the current time
|
||||
*
|
||||
* \retval time returns current time
|
||||
*/
|
||||
TimerTime_t rtick_timer_get_current_time( void );
|
||||
|
||||
/*!
|
||||
* \brief Return the Time elapsed since a fix moment in Time
|
||||
*
|
||||
* \remark TimerGetElapsedTime will return 0 for argument 0.
|
||||
*
|
||||
* \param [IN] past fix moment in Time
|
||||
* \retval time returns elapsed time
|
||||
*/
|
||||
TimerTime_t rtick_timer_get_elapsed_time( TimerTime_t past );
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
|
||||
/** @addtogroup LORA_RADIO_TIMER
|
||||
* @{
|
||||
*/
|
||||
|
||||
#define TimerInit rtick_timer_init
|
||||
#define TimerStart rtick_timer_start
|
||||
#define TimerStop rtick_timer_stop
|
||||
#define TimerReset rtick_timer_reset
|
||||
#define TimerSetValue rtick_timer_set_value
|
||||
#define TimerSetTimestamp rtick_timer_set_timestamp
|
||||
#define TimerGetCurrentTime rtick_timer_get_current_time
|
||||
#define TimerGetElapsedTime rtick_timer_get_elapsed_time
|
||||
#define TimerEvent_t rtick_timer_event_t
|
||||
|
||||
#define LORA_RADIO_TIMESTAMP_TO_MS(x) ((x) * 1000 / TICK_PER_SECOND)
|
||||
/*!
|
||||
* \brief Timer object description
|
||||
*/
|
||||
typedef struct TimerEvent_s
|
||||
{
|
||||
timer_t timer_id;
|
||||
}rtick_timer_event_t;
|
||||
|
||||
/*!
|
||||
* \brief Timer time variable definition
|
||||
*/
|
||||
#ifndef TimerTime_t
|
||||
typedef uint32_t TimerTime_t;
|
||||
#define TIMERTIME_T_MAX ( ( uint32_t )~0 )
|
||||
|
||||
/*!
|
||||
* \brief Initializes the timer object
|
||||
*
|
||||
* \remark TimerSetValue function must be called before starting the timer.
|
||||
* this function initializes timestamp and reload value at 0.
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
* \param [IN] callback Function callback called at the end of the timeout
|
||||
*/
|
||||
void rtick_timer_init( rtick_timer_event_t *obj, void ( *callback )( void ) );
|
||||
|
||||
/*!
|
||||
* \brief Starts and adds the timer object to the list of timer events
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
*/
|
||||
void rtick_timer_start( rtick_timer_event_t *obj );
|
||||
|
||||
/*!
|
||||
* \brief Stops and removes the timer object from the list of timer events
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
*/
|
||||
void rtick_timer_stop( rtick_timer_event_t *obj );
|
||||
|
||||
/*!
|
||||
* \brief Resets the timer object
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
*/
|
||||
void rtick_timer_reset( rtick_timer_event_t *obj );
|
||||
|
||||
/*!
|
||||
* \brief Set timer new timeout value
|
||||
*
|
||||
* \param [IN] obj Structure containing the timer object parameters
|
||||
* \param [IN] value New timer timeout value
|
||||
*/
|
||||
void rtick_timer_set_value( rtick_timer_event_t *obj, uint32_t value );
|
||||
|
||||
void rtick_timer_set_timestamp( rtick_timer_event_t *obj, uint32_t value );
|
||||
|
||||
/*!
|
||||
* \brief Read the current time
|
||||
*
|
||||
* \retval time returns current time
|
||||
*/
|
||||
TimerTime_t rtick_timer_get_current_time( void );
|
||||
|
||||
/*!
|
||||
* \brief Return the Time elapsed since a fix moment in Time
|
||||
*
|
||||
* \remark TimerGetElapsedTime will return 0 for argument 0.
|
||||
*
|
||||
* \param [IN] past fix moment in Time
|
||||
* \retval time returns elapsed time
|
||||
*/
|
||||
TimerTime_t rtick_timer_get_elapsed_time( TimerTime_t past );
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,122 @@
|
|||
/*!
|
||||
* \file lora-radio-debug.h
|
||||
*
|
||||
* \brief control all LoRa Radio Driver debug features.
|
||||
*
|
||||
* \copyright SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-radio-debug.h
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-07
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-radio-debug.h
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-07
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#ifndef __LORA_RADIO_DEBUG_H__
|
||||
#define __LORA_RADIO_DEBUG_H__
|
||||
|
||||
#include "lora-radio-rtos-config.h"
|
||||
|
||||
#if ( defined LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD ) || ( defined LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD_NANO )
|
||||
#include "rtconfig.h"
|
||||
#ifdef RT_USING_ULOG
|
||||
#include <rtdbg.h>
|
||||
#include <ulog.h>
|
||||
#else
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
//#define LORA_RADIO_DRIVER_USING_LORA_RADIO_DEBUG
|
||||
/* Using this macro to control all LoRa Radio Driver debug features. */
|
||||
#ifdef LORA_RADIO_DRIVER_USING_LORA_RADIO_DEBUG
|
||||
|
||||
/* Turn on some of these (set to non-zero) to debug LoRa Radio */
|
||||
|
||||
/* API interface */
|
||||
#ifndef LR_DBG_INTERFACE
|
||||
#define LR_DBG_INTERFACE 1
|
||||
#endif
|
||||
|
||||
/*lora chip driver, eg: sx126x.c\sx27x.c*/
|
||||
#ifndef LR_DBG_CHIP
|
||||
#define LR_DBG_CHIP 1
|
||||
#endif
|
||||
|
||||
/* spi driver ,eg: lora-spi-board.c*/
|
||||
#ifndef LR_DBG_SPI
|
||||
#define LR_DBG_SPI 1
|
||||
#endif
|
||||
|
||||
/* board driver ,eg: sx1268-board.c*/
|
||||
#ifndef LR_DBG_BOARD
|
||||
#define LR_DBG_BOARD 1
|
||||
#endif
|
||||
|
||||
#if ( defined LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD ) || ( defined LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD_NANO )
|
||||
|
||||
#if defined RT_USING_ULOG
|
||||
#define LORA_RADIO_DEBUG_LOG(type, level, ...) \
|
||||
do \
|
||||
{ \
|
||||
if (type) \
|
||||
{ \
|
||||
ulog_output(level, LOG_TAG, RT_TRUE, __VA_ARGS__); \
|
||||
} \
|
||||
} \
|
||||
while (0)
|
||||
|
||||
#else
|
||||
|
||||
#define LORA_RADIO_DEBUG_LOG(type, level, ...) \
|
||||
do \
|
||||
{ \
|
||||
if (type) \
|
||||
{ \
|
||||
rt_kprintf(__VA_ARGS__); \
|
||||
rt_kprintf("\r\n"); \
|
||||
} \
|
||||
} \
|
||||
while (0)
|
||||
#endif
|
||||
|
||||
#elif ( defined LORA_RADIO_DRIVER_USING_RTOS_XIUOS )
|
||||
|
||||
#define LORA_RADIO_DEBUG_LOG(type, level, ...) \
|
||||
do \
|
||||
{ \
|
||||
if (type) \
|
||||
{ \
|
||||
printf(__VA_ARGS__); \
|
||||
printf("\r\n"); \
|
||||
} \
|
||||
} \
|
||||
while (0)
|
||||
|
||||
#endif
|
||||
|
||||
#else /* LORA_RADIO_DEBUG */
|
||||
|
||||
#define LORA_RADIO_DEBUG_LOG(type, level, ...)
|
||||
|
||||
#endif /* LORA_RADIO_DEBUG */
|
||||
|
||||
#endif /* __LORA_RADIO_DEBUG_H__ */
|
|
@ -0,0 +1,72 @@
|
|||
/*!
|
||||
* \file lora-radio-rtos-config.h
|
||||
*
|
||||
* \brief adapter to different RTOS implementation
|
||||
*
|
||||
* \copyright SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-radio-rtos-config.h
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-07
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-radio-rtos-config.h
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-07
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#ifndef __LORA_RADIO_RTOS_CONFIG_H_
|
||||
#define __LORA_RADIO_RTOS_CONFIG_H_
|
||||
|
||||
#include <transform.h>
|
||||
|
||||
// default based on rt-thread
|
||||
//#define LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
//#define LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD_NANO
|
||||
//#define LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#elif defined LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD_NANO
|
||||
#elif defined LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
#else
|
||||
#error "Please Choose your RTOS setup!"
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#include "rtconfig.h"
|
||||
#include <rtthread.h>
|
||||
#include <rtdevice.h>
|
||||
#include "drv_spi.h"
|
||||
|
||||
#define LOG_LVL_ASSERT 0
|
||||
#define LOG_LVL_ERROR 3
|
||||
#define LOG_LVL_WARNING 4
|
||||
#define LOG_LVL_INFO 6
|
||||
#define LOG_LVL_DBG 7
|
||||
|
||||
#elif defined LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD_NANO
|
||||
#include <rtthread.h>
|
||||
|
||||
#elif defined LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
|
||||
#define LOG_LVL_ASSERT 0
|
||||
#define LOG_LVL_ERROR 3
|
||||
#define LOG_LVL_WARNING 4
|
||||
#define LOG_LVL_INFO 6
|
||||
#define LOG_LVL_DBG 7
|
||||
|
||||
#endif
|
||||
|
||||
#endif // end of __LORA_RADIO_RTOS_CONFIG_H_
|
|
@ -0,0 +1,549 @@
|
|||
/*!
|
||||
* \file lora-radio.h
|
||||
*
|
||||
* \brief LoRa Radio driver API definition
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author forest-rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-radio.h
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-07
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-radio.h
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-07
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#ifndef __LORA_RADIO_H__
|
||||
#define __LORA_RADIO_H__
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <transform.h>
|
||||
|
||||
/*!
|
||||
* LoRa Radio software version number
|
||||
*/
|
||||
#define LORA_RADIO_SW_VERSION "1.4.5"
|
||||
#define LORA_RADIO_SW_VERSION_NUM 0x10405
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
/*!
|
||||
* Begins critical section
|
||||
*/
|
||||
#define LORA_RADIO_CRITICAL_SECTION_BEGIN( ) register rt_base_t level; level = rt_hw_interrupt_disable()
|
||||
|
||||
/*!
|
||||
* Ends critical section
|
||||
*/
|
||||
#define LORA_RADIO_CRITICAL_SECTION_END( ) rt_hw_interrupt_enable(level)
|
||||
|
||||
#elif defined LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
/*!
|
||||
* Begins critical section
|
||||
*/
|
||||
#define LORA_RADIO_CRITICAL_SECTION_BEGIN( )
|
||||
|
||||
/*!
|
||||
* Ends critical section
|
||||
*/
|
||||
#define LORA_RADIO_CRITICAL_SECTION_END( )
|
||||
#else
|
||||
/*!
|
||||
* Begins critical section
|
||||
*/
|
||||
#define LORA_RADIO_CRITICAL_SECTION_BEGIN(x) register uint32_t level; level = __get_PRIMASK(); __disable_irq();
|
||||
|
||||
/*!
|
||||
* Ends critical section
|
||||
*/
|
||||
#define LORA_RADIO_CRITICAL_SECTION_END(x) __set_PRIMASK(level)
|
||||
#endif
|
||||
|
||||
/** @addtogroup LORA_RADIO_UPPER_API
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*!
|
||||
* Radio driver supported modems
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
MODEM_FSK = 0,
|
||||
MODEM_LORA,
|
||||
MODEM_BPSK, //!<for STM32WL
|
||||
MODEM_SIGFOX_TX, //!<for STM32WL
|
||||
MODEM_SIGFOX_RX, //!<for STM32WL
|
||||
}RadioModems_t;
|
||||
|
||||
/*!
|
||||
* Radio driver internal state machine states definition
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
RF_IDLE = 0, //!< The radio is idle
|
||||
RF_RX_RUNNING, //!< The radio is in reception state
|
||||
RF_TX_RUNNING, //!< The radio is in transmission state
|
||||
RF_CAD, //!< The radio is doing channel activity detection
|
||||
}RadioState_t;
|
||||
|
||||
/*!
|
||||
* Radio Dio Irq event definition
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
EV_LORA_RADIO_IRQ0_FIRED = 0x0001,
|
||||
EV_LORA_RADIO_IRQ1_FIRED = 0x0002,
|
||||
EV_LORA_RADIO_IRQ2_FIRED = 0x0004,
|
||||
EV_LORA_RADIO_IRQ3_FIRED = 0x0008,
|
||||
EV_LORA_RADIO_IRQ4_FIRED = 0x0010,
|
||||
EV_LORA_RADIO_IRQ5_FIRED = 0x0020,
|
||||
EV_LORA_RADIO_TIMEOUT_FIRED = 0x0040, //!< sx127x tx\rx timeout
|
||||
}RadioDioIrqEvent_t;
|
||||
|
||||
/*!
|
||||
* \brief Radio driver callback functions
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/*!
|
||||
* \brief Tx Done callback prototype.
|
||||
*/
|
||||
void ( *TxDone )( void );
|
||||
/*!
|
||||
* \brief Tx Timeout callback prototype.
|
||||
*/
|
||||
void ( *TxTimeout )( void );
|
||||
/*!
|
||||
* \brief Rx Done callback prototype.
|
||||
*
|
||||
* \param [IN] payload Received buffer pointer
|
||||
* \param [IN] size Received buffer size
|
||||
* \param [IN] rssi RSSI value computed while receiving the frame [dBm]
|
||||
* \param [IN] snr SNR value computed while receiving the frame [dB]
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: SNR value in dB
|
||||
*/
|
||||
void ( *RxDone )( uint8_t *payload, uint16_t size, int16_t rssi, int8_t snr );
|
||||
/*!
|
||||
* \brief Rx Timeout callback prototype.
|
||||
*/
|
||||
void ( *RxTimeout )( void );
|
||||
/*!
|
||||
* \brief Rx Error callback prototype.
|
||||
*/
|
||||
void ( *RxError )( void );
|
||||
/*!
|
||||
* \brief FHSS Change Channel callback prototype.
|
||||
*
|
||||
* \param [IN] currentChannel Index number of the current channel
|
||||
*/
|
||||
void ( *FhssChangeChannel )( uint8_t currentChannel );
|
||||
|
||||
/*!
|
||||
* \brief CAD Done callback prototype.
|
||||
*
|
||||
* \param [IN] channelDetected Channel Activity detected during the CAD
|
||||
*/
|
||||
void ( *CadDone ) ( bool channelActivityDetected );
|
||||
|
||||
}RadioEvents_t;
|
||||
|
||||
/*!
|
||||
* \brief Radio driver definition
|
||||
*/
|
||||
struct Radio_s
|
||||
{
|
||||
/*!
|
||||
* \brief Initializes the radio
|
||||
*
|
||||
* \param [IN] events Structure containing the driver callback functions
|
||||
*/
|
||||
bool ( *Init )( RadioEvents_t *events );
|
||||
/*!
|
||||
* Return current radio status
|
||||
*
|
||||
* \param status Radio status.[RF_IDLE, RF_RX_RUNNING, RF_TX_RUNNING]
|
||||
*/
|
||||
RadioState_t ( *GetStatus )( void );
|
||||
/*!
|
||||
* \brief Configures the radio with the given modem
|
||||
*
|
||||
* \param [IN] modem Modem to be used [0: FSK, 1: LoRa]
|
||||
*/
|
||||
void ( *SetModem )( RadioModems_t modem );
|
||||
/*!
|
||||
* \brief Sets the channel frequency
|
||||
*
|
||||
* \param [IN] freq Channel RF frequency
|
||||
*/
|
||||
void ( *SetChannel )( uint32_t freq );
|
||||
/*!
|
||||
* \brief Checks if the channel is free for the given time
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] freq Channel RF frequency
|
||||
* \param [IN] rssiThresh RSSI threshold
|
||||
* \param [IN] maxCarrierSenseTime Max time while the RSSI is measured
|
||||
*
|
||||
* \retval isFree [true: Channel is free, false: Channel is not free]
|
||||
*/
|
||||
bool ( *IsChannelFree )( RadioModems_t modem, uint32_t freq, int16_t rssiThresh, uint32_t maxCarrierSenseTime );
|
||||
/*!
|
||||
* \brief Generates a 32 bits random value based on the RSSI readings
|
||||
*
|
||||
* \remark This function sets the radio in LoRa modem mode and disables
|
||||
* all interrupts.
|
||||
* After calling this function either Radio.SetRxConfig or
|
||||
* Radio.SetTxConfig functions must be called.
|
||||
*
|
||||
* \retval randomValue 32 bits random value
|
||||
*/
|
||||
uint32_t ( *Random )( void );
|
||||
/*!
|
||||
* \brief Sets the reception parameters
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] bandwidth Sets the bandwidth
|
||||
* FSK : >= 2600 and <= 250000 Hz
|
||||
* LoRa: [0: 125 kHz, 1: 250 kHz,
|
||||
* 2: 500 kHz, 3: Reserved]
|
||||
* \param [IN] datarate Sets the Datarate
|
||||
* FSK : 600..300000 bits/s
|
||||
* LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
|
||||
* 10: 1024, 11: 2048, 12: 4096 chips]
|
||||
* \param [IN] coderate Sets the coding rate (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
|
||||
* \param [IN] bandwidthAfc Sets the AFC Bandwidth (FSK only)
|
||||
* FSK : >= 2600 and <= 250000 Hz
|
||||
* LoRa: N/A ( set to 0 )
|
||||
* \param [IN] preambleLen Sets the Preamble length
|
||||
* FSK : Number of bytes
|
||||
* LoRa: Length in symbols (the hardware adds 4 more symbols)
|
||||
* \param [IN] symbTimeout Sets the RxSingle timeout value
|
||||
* FSK : timeout in number of bytes
|
||||
* LoRa: timeout in symbols
|
||||
* \param [IN] fixLen Fixed length packets [0: variable, 1: fixed]
|
||||
* \param [IN] payloadLen Sets payload length when fixed length is used
|
||||
* \param [IN] crcOn Enables/Disables the CRC [0: OFF, 1: ON]
|
||||
* \param [IN] freqHopOn Enables disables the intra-packet frequency hopping
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: OFF, 1: ON]
|
||||
* \param [IN] hopPeriod Number of symbols between each hop
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: Number of symbols
|
||||
* \param [IN] iqInverted Inverts IQ signals (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: not inverted, 1: inverted]
|
||||
* \param [IN] rxContinuous Sets the reception in continuous mode
|
||||
* [false: single mode, true: continuous mode]
|
||||
*/
|
||||
void ( *SetRxConfig )( RadioModems_t modem, uint32_t bandwidth,
|
||||
uint32_t datarate, uint8_t coderate,
|
||||
uint32_t bandwidthAfc, uint16_t preambleLen,
|
||||
uint16_t symbTimeout, bool fixLen,
|
||||
uint8_t payloadLen,
|
||||
bool crcOn, bool freqHopOn, uint8_t hopPeriod,
|
||||
bool iqInverted, bool rxContinuous );
|
||||
/*!
|
||||
* \brief Sets the transmission parameters
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] power Sets the output power [dBm]
|
||||
* \param [IN] fdev Sets the frequency deviation (FSK only)
|
||||
* FSK : [Hz]
|
||||
* LoRa: 0
|
||||
* \param [IN] bandwidth Sets the bandwidth (LoRa only)
|
||||
* FSK : 0
|
||||
* LoRa: [0: 125 kHz, 1: 250 kHz,
|
||||
* 2: 500 kHz, 3: Reserved]
|
||||
* \param [IN] datarate Sets the Datarate
|
||||
* FSK : 600..300000 bits/s
|
||||
* LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
|
||||
* 10: 1024, 11: 2048, 12: 4096 chips]
|
||||
* \param [IN] coderate Sets the coding rate (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
|
||||
* \param [IN] preambleLen Sets the preamble length
|
||||
* FSK : Number of bytes
|
||||
* LoRa: Length in symbols (the hardware adds 4 more symbols)
|
||||
* \param [IN] fixLen Fixed length packets [0: variable, 1: fixed]
|
||||
* \param [IN] crcOn Enables disables the CRC [0: OFF, 1: ON]
|
||||
* \param [IN] freqHopOn Enables disables the intra-packet frequency hopping
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: OFF, 1: ON]
|
||||
* \param [IN] hopPeriod Number of symbols between each hop
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: Number of symbols
|
||||
* \param [IN] iqInverted Inverts IQ signals (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: not inverted, 1: inverted]
|
||||
* \param [IN] timeout Transmission timeout [ms]
|
||||
*/
|
||||
void ( *SetTxConfig )( RadioModems_t modem, int8_t power, uint32_t fdev,
|
||||
uint32_t bandwidth, uint32_t datarate,
|
||||
uint8_t coderate, uint16_t preambleLen,
|
||||
bool fixLen, bool crcOn, bool freqHopOn,
|
||||
uint8_t hopPeriod, bool iqInverted, uint32_t timeout );
|
||||
/*!
|
||||
* \brief Checks if the given RF frequency is supported by the hardware
|
||||
*
|
||||
* \param [IN] frequency RF frequency to be checked
|
||||
* \retval isSupported [true: supported, false: unsupported]
|
||||
*/
|
||||
bool ( *CheckRfFrequency )( uint32_t frequency );
|
||||
/*!
|
||||
* \brief Computes the packet time on air in ms for the given payload
|
||||
*
|
||||
* \Remark Can only be called once SetRxConfig or SetTxConfig have been called
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] bandwidth Sets the bandwidth
|
||||
* FSK : >= 2600 and <= 250000 Hz
|
||||
* LoRa: [0: 125 kHz, 1: 250 kHz,
|
||||
* 2: 500 kHz, 3: Reserved]
|
||||
* \param [IN] datarate Sets the Datarate
|
||||
* FSK : 600..300000 bits/s
|
||||
* LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
|
||||
* 10: 1024, 11: 2048, 12: 4096 chips]
|
||||
* \param [IN] coderate Sets the coding rate (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
|
||||
* \param [IN] preambleLen Sets the Preamble length
|
||||
* FSK : Number of bytes
|
||||
* LoRa: Length in symbols (the hardware adds 4 more symbols)
|
||||
* \param [IN] fixLen Fixed length packets [0: variable, 1: fixed]
|
||||
* \param [IN] payloadLen Sets payload length when fixed length is used
|
||||
* \param [IN] crcOn Enables/Disables the CRC [0: OFF, 1: ON]
|
||||
*
|
||||
* \retval airTime Computed airTime (ms) for the given packet payload length
|
||||
*/
|
||||
uint32_t ( *TimeOnAir )( RadioModems_t modem, uint32_t bandwidth,
|
||||
uint32_t datarate, uint8_t coderate,
|
||||
uint16_t preambleLen, bool fixLen, uint8_t payloadLen,
|
||||
bool crcOn );
|
||||
|
||||
/*!
|
||||
* \brief Sends the buffer of size. Prepares the packet to be sent and sets
|
||||
* the radio in transmission
|
||||
*
|
||||
* \param [IN]: buffer Buffer pointer
|
||||
* \param [IN]: size Buffer size
|
||||
*/
|
||||
void ( *Send )( uint8_t *buffer, uint8_t size );
|
||||
/*!
|
||||
* \brief Sets the radio in sleep mode
|
||||
*/
|
||||
void ( *Sleep )( void );
|
||||
/*!
|
||||
* \brief Sets the radio in standby mode
|
||||
*/
|
||||
void ( *Standby )( void );
|
||||
/*!
|
||||
* \brief Sets the radio in reception mode for the given time
|
||||
* \param [IN] timeout Reception timeout [ms]
|
||||
* [0: continuous, others timeout]
|
||||
*/
|
||||
void ( *Rx )( uint32_t timeout );
|
||||
/*!
|
||||
* \brief Start a Channel Activity Detection
|
||||
*/
|
||||
void ( *StartCad )( void );
|
||||
/*!
|
||||
* \brief Sets the radio in continuous wave transmission mode
|
||||
*
|
||||
* \param [IN]: freq Channel RF frequency
|
||||
* \param [IN]: power Sets the output power [dBm]
|
||||
* \param [IN]: time Transmission mode timeout [s]
|
||||
*/
|
||||
void ( *SetTxContinuousWave )( uint32_t freq, int8_t power, uint16_t time );
|
||||
/*!
|
||||
* \brief Reads the current RSSI value
|
||||
*
|
||||
* \retval rssiValue Current RSSI value in [dBm]
|
||||
*/
|
||||
int16_t ( *Rssi )( RadioModems_t modem );
|
||||
/*!
|
||||
* \brief Writes the radio register at the specified address
|
||||
*
|
||||
* \param [IN]: addr Register address
|
||||
* \param [IN]: data New register value
|
||||
*/
|
||||
void ( *Write )( uint16_t addr, uint8_t data );
|
||||
/*!
|
||||
* \brief Reads the radio register at the specified address
|
||||
*
|
||||
* \param [IN]: addr Register address
|
||||
* \retval data Register value
|
||||
*/
|
||||
uint8_t ( *Read )( uint16_t addr );
|
||||
/*!
|
||||
* \brief Writes multiple radio registers starting at address
|
||||
*
|
||||
* \param [IN] addr First Radio register address
|
||||
* \param [IN] buffer Buffer containing the new register's values
|
||||
* \param [IN] size Number of registers to be written
|
||||
*/
|
||||
//void ( *WriteBuffer )( uint16_t addr, uint8_t *buffer, uint8_t size );
|
||||
/*!
|
||||
* \brief Reads multiple radio registers starting at address
|
||||
*
|
||||
* \param [IN] addr First Radio register address
|
||||
* \param [OUT] buffer Buffer where to copy the registers data
|
||||
* \param [IN] size Number of registers to be read
|
||||
*/
|
||||
//void ( *ReadBuffer )( uint16_t addr, uint8_t *buffer, uint8_t size );
|
||||
/*!
|
||||
* \brief Sets the maximum payload length.
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] max Maximum payload length in bytes
|
||||
*/
|
||||
void ( *SetMaxPayloadLength )( RadioModems_t modem, uint8_t max );
|
||||
/*!
|
||||
* \brief Sets the network to public or private. Updates the sync byte.
|
||||
*
|
||||
* \remark Applies to LoRa modem only
|
||||
*
|
||||
* \param [IN] enable if true, it enables a public network
|
||||
*/
|
||||
void ( *SetPublicNetwork )( bool enable );
|
||||
/*!
|
||||
* \brief Gets the time required for the board plus radio to get out of sleep.[ms]
|
||||
*
|
||||
* \retval time Radio plus board wakeup time in ms.
|
||||
*/
|
||||
uint32_t ( *GetWakeupTime )( void );
|
||||
/*!
|
||||
* \brief Process radio irq
|
||||
*/
|
||||
void ( *IrqProcess )( void );
|
||||
/*!
|
||||
* \brief radio spi check
|
||||
*/
|
||||
uint8_t ( *Check )( void );
|
||||
|
||||
/*
|
||||
* The next functions are available only on SX126x radios.
|
||||
*/
|
||||
/*!
|
||||
* \brief Sets the radio in reception mode with Max LNA gain for the given time
|
||||
*
|
||||
* \remark Available on SX126x radios only.
|
||||
*
|
||||
* \param [IN] timeout Reception timeout [ms]
|
||||
* [0: continuous, others timeout]
|
||||
*/
|
||||
void ( *RxBoosted )( uint32_t timeout );
|
||||
/*!
|
||||
* \brief Sets the Rx duty cycle management parameters
|
||||
*
|
||||
* \remark Available on SX126x radios only.
|
||||
*
|
||||
* \param [in] rxTime Structure describing reception timeout value
|
||||
* \param [in] sleepTime Structure describing sleep timeout value
|
||||
*/
|
||||
void ( *SetRxDutyCycle ) ( uint32_t rxTime, uint32_t sleepTime );
|
||||
|
||||
/*!
|
||||
* @brief Sets the Transmitter in continuous PRBS mode for STM32WL
|
||||
*
|
||||
* \remark power and datarate shall be configured prior calling TxPrbs
|
||||
*/
|
||||
void (*TxPrbs) ( void );
|
||||
/*!
|
||||
* @brief Sets the Transmitter in continuous unmodulated Carrier mode for STM32WL
|
||||
*/
|
||||
void (*TxCw) ( int8_t power );
|
||||
|
||||
/*!
|
||||
* \brief radio rxdone timestamp
|
||||
*/
|
||||
uint32_t ( *GetRxdoneTimestamp )( void );
|
||||
|
||||
};
|
||||
|
||||
/*!
|
||||
* \brief Radio Parameter config definition
|
||||
*/
|
||||
typedef struct LoRaRadioConfig_s
|
||||
{
|
||||
RadioModems_t modem; // LoRa Modem \ FSK modem
|
||||
uint32_t frequency;
|
||||
int8_t txpower;
|
||||
|
||||
// LoRa
|
||||
uint8_t sf; // spreadfactor
|
||||
uint8_t bw; // bandwidth
|
||||
uint8_t cr; // coderate
|
||||
uint8_t hop_period;
|
||||
uint8_t symb_timeout;
|
||||
|
||||
union
|
||||
{
|
||||
struct
|
||||
{
|
||||
uint8_t iq_inverted:1;
|
||||
//uint8_t public_network:1;
|
||||
uint8_t fix_len_enable:1;
|
||||
uint8_t crc_on:1;
|
||||
uint8_t freq_hop_on:1;
|
||||
uint8_t rx_continuous:1;
|
||||
}bits;
|
||||
uint8_t byte;
|
||||
}rf_misc;
|
||||
|
||||
// FSK
|
||||
uint32_t fdev;
|
||||
uint32_t datarate;
|
||||
uint32_t fsk_bandwidth;
|
||||
uint32_t fsk_afc_bandwidth;
|
||||
|
||||
uint16_t preamble_len;
|
||||
|
||||
}LoRaRadioConfig_t;
|
||||
|
||||
/*!
|
||||
* \brief Radio driver
|
||||
*
|
||||
* \remark This variable is defined and initialized in the specific radio
|
||||
* board implementation
|
||||
*/
|
||||
extern const struct Radio_s Radio;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif // __RADIO_H__
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := sx126x.c lora-radio-sx126x.c lora-spi-sx126x.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,324 @@
|
|||
/*!
|
||||
* \file lora-spi-SX126x.c
|
||||
*
|
||||
* \brief spi driver implementation for SX126X
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-spi-SX126x.c
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-spi-SX126x.c
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#include <sx126x-board.h>
|
||||
|
||||
#define LOG_TAG "LoRa.SX126X.SPI"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include <lora-radio-debug.h>
|
||||
|
||||
void SX126xWakeup( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
uint8_t msg[2] = { RADIO_GET_STATUS, 0x00 };
|
||||
|
||||
rt_spi_transfer(SX126x.spi,msg,RT_NULL,2);
|
||||
|
||||
// Wait for chip to be ready.
|
||||
SX126xWaitOnBusy( );
|
||||
|
||||
// Update operating mode context variable
|
||||
SX126xSetOperatingMode( MODE_STDBY_RC );
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t msg[2] = { RADIO_GET_STATUS, 0x00 };
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, msg, 2);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
// Wait for chip to be ready.
|
||||
SX126xWaitOnBusy( );
|
||||
|
||||
// Update operating mode context variable
|
||||
SX126xSetOperatingMode( MODE_STDBY_RC );
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xWriteCommand( RadioCommands_t command, uint8_t *buffer, uint16_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
rt_spi_send_then_send(SX126x.spi,&command,1,buffer,size);
|
||||
|
||||
if( command != RADIO_SET_SLEEP )
|
||||
{
|
||||
SX126xWaitOnBusy( );
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, &command, 1);
|
||||
|
||||
PrivWrite(spi_fd, buffer, size);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
if( command != RADIO_SET_SLEEP )
|
||||
{
|
||||
SX126xWaitOnBusy( );
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t SX126xReadCommand( RadioCommands_t command, uint8_t *buffer, uint16_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
uint8_t status = 0;
|
||||
uint8_t buffer_temp[16] = {0}; // command size is 2 size
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
rt_spi_send_then_recv(SX126x.spi,&command,1,buffer_temp,size + 1);
|
||||
|
||||
status = buffer_temp[0];
|
||||
|
||||
rt_memcpy(buffer,buffer_temp+1,size);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
|
||||
return status;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t status = 0;
|
||||
uint8_t buffer_temp[16] = {0}; // command size is 2 size
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, &command, 1);
|
||||
|
||||
PrivRead(spi_fd, buffer_temp, size + 1);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
status = buffer_temp[0];
|
||||
|
||||
memcpy(buffer, buffer_temp + 1, size);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
|
||||
return status;
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xWriteRegisters( uint16_t address, uint8_t *buffer, uint16_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
uint8_t msg[3] = {0};
|
||||
|
||||
msg[0] = RADIO_WRITE_REGISTER;
|
||||
msg[1] = ( address & 0xFF00 ) >> 8;
|
||||
msg[2] = address & 0x00FF;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
rt_spi_send_then_send(SX126x.spi,msg,3,buffer,size);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t msg[3] = {0};
|
||||
|
||||
msg[0] = RADIO_WRITE_REGISTER;
|
||||
msg[1] = ( address & 0xFF00 ) >> 8;
|
||||
msg[2] = address & 0x00FF;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, msg, 3);
|
||||
|
||||
PrivWrite(spi_fd, buffer, size);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xWriteRegister( uint16_t address, uint8_t value )
|
||||
{
|
||||
SX126xWriteRegisters( address, &value, 1 );
|
||||
}
|
||||
|
||||
void SX126xReadRegisters( uint16_t address, uint8_t *buffer, uint16_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
uint8_t msg[4] = {0};
|
||||
|
||||
msg[0] = RADIO_READ_REGISTER;
|
||||
msg[1] = ( address & 0xFF00 ) >> 8;
|
||||
msg[2] = address & 0x00FF;
|
||||
msg[3] = 0;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
rt_spi_send_then_recv(SX126x.spi,msg,4,buffer,size);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t msg[4] = {0};
|
||||
|
||||
msg[0] = RADIO_READ_REGISTER;
|
||||
msg[1] = ( address & 0xFF00 ) >> 8;
|
||||
msg[2] = address & 0x00FF;
|
||||
msg[3] = 0;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, msg, 4);
|
||||
|
||||
PrivRead(spi_fd, buffer, size);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t SX126xReadRegister( uint16_t address )
|
||||
{
|
||||
uint8_t data;
|
||||
SX126xReadRegisters( address, &data, 1 );
|
||||
return data;
|
||||
}
|
||||
|
||||
void SX126xWriteBuffer( uint8_t offset, uint8_t *buffer, uint8_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
|
||||
uint8_t msg[2] = {0};
|
||||
|
||||
msg[0] = RADIO_WRITE_BUFFER;
|
||||
msg[1] = offset;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
rt_spi_send_then_send(SX126x.spi,msg,2,buffer,size);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t msg[2] = {0};
|
||||
|
||||
msg[0] = RADIO_WRITE_BUFFER;
|
||||
msg[1] = offset;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, msg, 2);
|
||||
|
||||
PrivWrite(spi_fd, buffer, size);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xReadBuffer( uint8_t offset, uint8_t *buffer, uint8_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
uint8_t msg[3] = {0};
|
||||
|
||||
msg[0] = RADIO_READ_BUFFER;
|
||||
msg[1] = offset;
|
||||
msg[2] = 0;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
rt_spi_send_then_recv(SX126x.spi,msg,3,buffer,size);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t msg[3] = {0};
|
||||
|
||||
msg[0] = RADIO_READ_BUFFER;
|
||||
msg[1] = offset;
|
||||
msg[2] = 0;
|
||||
|
||||
SX126xCheckDeviceReady( );
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, msg, 3);
|
||||
|
||||
PrivRead(spi_fd, buffer, size);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
SX126xWaitOnBusy( );
|
||||
#endif
|
||||
}
|
|
@ -0,0 +1,111 @@
|
|||
/*!
|
||||
* \file lora-spi-sx126x.h
|
||||
*
|
||||
* \brief SX126x spi interface
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#ifndef __LORA_SPI_SX126X_H__
|
||||
#define __LORA_SPI_SX126X_H__
|
||||
|
||||
#include "sx126x.h"
|
||||
|
||||
/** @addtogroup LORA_RADIO_SPI
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup SX126X_SPI
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*!
|
||||
* \brief Wakes up the radio
|
||||
*/
|
||||
void SX126xWakeup( void );
|
||||
|
||||
/*!
|
||||
* \brief Send a command that write data to the radio
|
||||
*
|
||||
* \param [in] opcode Opcode of the command
|
||||
* \param [in] buffer Buffer to be send to the radio
|
||||
* \param [in] size Size of the buffer to send
|
||||
*/
|
||||
void SX126xWriteCommand( RadioCommands_t opcode, uint8_t *buffer, uint16_t size );
|
||||
|
||||
/*!
|
||||
* \brief Send a command that read data from the radio
|
||||
*
|
||||
* \param [in] opcode Opcode of the command
|
||||
* \param [out] buffer Buffer holding data from the radio
|
||||
* \param [in] size Size of the buffer
|
||||
*
|
||||
* \retval status Return command radio status
|
||||
*/
|
||||
uint8_t SX126xReadCommand( RadioCommands_t opcode, uint8_t *buffer, uint16_t size );
|
||||
|
||||
/*!
|
||||
* \brief Write a single byte of data to the radio memory
|
||||
*
|
||||
* \param [in] address The address of the first byte to write in the radio
|
||||
* \param [in] value The data to be written in radio's memory
|
||||
*/
|
||||
void SX126xWriteRegister( uint16_t address, uint8_t value );
|
||||
|
||||
/*!
|
||||
* \brief Read a single byte of data from the radio memory
|
||||
*
|
||||
* \param [in] address The address of the first byte to write in the radio
|
||||
*
|
||||
* \retval value The value of the byte at the given address in radio's memory
|
||||
*/
|
||||
uint8_t SX126xReadRegister( uint16_t address );
|
||||
|
||||
/*!
|
||||
* \brief Write data to the radio memory
|
||||
*
|
||||
* \param [in] address The address of the first byte to write in the radio
|
||||
* \param [in] buffer The data to be written in radio's memory
|
||||
* \param [in] size The number of bytes to write in radio's memory
|
||||
*/
|
||||
void SX126xWriteRegisters( uint16_t address, uint8_t *buffer, uint16_t size );
|
||||
|
||||
/*!
|
||||
* \brief Read data from the radio memory
|
||||
*
|
||||
* \param [in] address The address of the first byte to read from the radio
|
||||
* \param [out] buffer The buffer that holds data read from radio
|
||||
* \param [in] size The number of bytes to read from radio's memory
|
||||
*/
|
||||
void SX126xReadRegisters( uint16_t address, uint8_t *buffer, uint16_t size );
|
||||
|
||||
/*!
|
||||
* \brief Write data to the buffer holding the payload in the radio
|
||||
*
|
||||
* \param [in] offset The offset to start writing the payload
|
||||
* \param [in] buffer The data to be written (the payload)
|
||||
* \param [in] size The number of byte to be written
|
||||
*/
|
||||
void SX126xWriteBuffer( uint8_t offset, uint8_t *buffer, uint8_t size );
|
||||
|
||||
/*!
|
||||
* \brief Read data from the buffer holding the payload in the radio
|
||||
*
|
||||
* \param [in] offset The offset to start reading the payload
|
||||
* \param [out] buffer A pointer to a buffer holding the data from the radio
|
||||
* \param [in] size The number of byte to be read
|
||||
*/
|
||||
void SX126xReadBuffer( uint8_t offset, uint8_t *buffer, uint8_t size );
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* __LORA_SPI_SX126X_H__ */
|
||||
|
||||
|
|
@ -0,0 +1,806 @@
|
|||
/*!
|
||||
* \file sx126x.c
|
||||
*
|
||||
* \brief SX126x driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*/
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include <board.h>
|
||||
#include <lora-radio-timer.h>
|
||||
#include <lora-radio.h>
|
||||
#include <lora-spi-sx126x.h>
|
||||
#include <sx126x-board.h>
|
||||
|
||||
/*!
|
||||
* \brief Radio registers definition
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint16_t Addr; //!< The address of the register
|
||||
uint8_t Value; //!< The value of the register
|
||||
}RadioRegisters_t;
|
||||
|
||||
/*!
|
||||
* \brief Holds the internal operating mode of the radio
|
||||
*/
|
||||
static RadioOperatingModes_t OperatingMode;
|
||||
|
||||
/*!
|
||||
* \brief Stores the current packet type set in the radio
|
||||
*/
|
||||
static RadioPacketTypes_t PacketType;
|
||||
|
||||
/*!
|
||||
* \brief Stores the current packet header type set in the radio
|
||||
*/
|
||||
static volatile RadioLoRaPacketLengthsMode_t LoRaHeaderType;
|
||||
|
||||
/*!
|
||||
* \brief Stores the last frequency error measured on LoRa received packet
|
||||
*/
|
||||
volatile uint32_t FrequencyError = 0;
|
||||
|
||||
/*!
|
||||
* \brief Hold the status of the Image calibration
|
||||
*/
|
||||
static bool ImageCalibrated = false;
|
||||
|
||||
/*
|
||||
* SX126x DIO IRQ callback functions prototype
|
||||
*/
|
||||
|
||||
/*!
|
||||
* \brief DIO 0 IRQ callback
|
||||
*/
|
||||
void SX126xOnDioIrq( void );
|
||||
|
||||
/*!
|
||||
* \brief DIO 0 IRQ callback
|
||||
*/
|
||||
void SX126xSetPollingMode( void );
|
||||
|
||||
/*!
|
||||
* \brief DIO 0 IRQ callback
|
||||
*/
|
||||
void SX126xSetInterruptMode( void );
|
||||
|
||||
/*
|
||||
* \brief Process the IRQ if handled by the driver
|
||||
*/
|
||||
void SX126xProcessIrqs( void );
|
||||
|
||||
void SX126xInit( DioIrqHandler dioIrq )
|
||||
{
|
||||
SX126xReset( );
|
||||
|
||||
SX126xIoIrqInit( dioIrq );
|
||||
|
||||
SX126xWakeup( );
|
||||
SX126xSetStandby( STDBY_RC );
|
||||
|
||||
// Initialize TCXO control
|
||||
SX126xIoTcxoInit( );
|
||||
|
||||
#ifdef LORA_RADIO_USE_DIO2_AS_RF_SWITCH_CTRL
|
||||
SX126xSetDio2AsRfSwitchCtrl( true );
|
||||
#endif
|
||||
|
||||
SX126xSetOperatingMode( MODE_STDBY_RC );
|
||||
}
|
||||
|
||||
RadioOperatingModes_t SX126xGetOperatingMode( void )
|
||||
{
|
||||
return OperatingMode;
|
||||
}
|
||||
|
||||
void SX126xSetOperatingMode( RadioOperatingModes_t mode )
|
||||
{
|
||||
OperatingMode = mode;
|
||||
|
||||
#if defined( LORA_RADIO_RFSW2_PIN ) && defined( LORA_RADIO_RFSW1_PIN )
|
||||
SX126xSetAntSw( mode );
|
||||
#endif
|
||||
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
switch( mode )
|
||||
{
|
||||
case MODE_TX:
|
||||
SX126xDbgPinTxWrite( 1 );
|
||||
SX126xDbgPinRxWrite( 0 );
|
||||
break;
|
||||
case MODE_RX:
|
||||
case MODE_RX_DC:
|
||||
SX126xDbgPinTxWrite( 0 );
|
||||
SX126xDbgPinRxWrite( 1 );
|
||||
break;
|
||||
default:
|
||||
SX126xDbgPinTxWrite( 0 );
|
||||
SX126xDbgPinRxWrite( 0 );
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xCheckDeviceReady( void )
|
||||
{
|
||||
if( ( SX126xGetOperatingMode( ) == MODE_SLEEP ) || ( SX126xGetOperatingMode( ) == MODE_RX_DC ) )
|
||||
{
|
||||
SX126xWakeup( );
|
||||
// Switch is turned off when device is in sleep mode and turned on is all other modes
|
||||
SX126xAntSwOn( );
|
||||
}
|
||||
SX126xWaitOnBusy( );
|
||||
}
|
||||
|
||||
void SX126xSetPayload( uint8_t *payload, uint8_t size )
|
||||
{
|
||||
SX126xWriteBuffer( 0x00, payload, size );
|
||||
}
|
||||
|
||||
uint8_t SX126xGetPayload( uint8_t *buffer, uint8_t *size, uint8_t maxSize )
|
||||
{
|
||||
uint8_t offset = 0;
|
||||
|
||||
SX126xGetRxBufferStatus( size, &offset );
|
||||
if( *size > maxSize )
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
SX126xReadBuffer( offset, buffer, *size );
|
||||
return 0;
|
||||
}
|
||||
|
||||
void SX126xSendPayload( uint8_t *payload, uint8_t size, uint32_t timeout )
|
||||
{
|
||||
SX126xSetPayload( payload, size );
|
||||
SX126xSetTx( timeout );
|
||||
}
|
||||
|
||||
uint8_t SX126xSetSyncWord( uint8_t *syncWord )
|
||||
{
|
||||
SX126xWriteRegisters( REG_LR_SYNCWORDBASEADDRESS, syncWord, 8 );
|
||||
return 0;
|
||||
}
|
||||
|
||||
void SX126xSetCrcSeed( uint16_t seed )
|
||||
{
|
||||
uint8_t buf[2];
|
||||
|
||||
buf[0] = ( uint8_t )( ( seed >> 8 ) & 0xFF );
|
||||
buf[1] = ( uint8_t )( seed & 0xFF );
|
||||
|
||||
switch( SX126xGetPacketType( ) )
|
||||
{
|
||||
case PACKET_TYPE_GFSK:
|
||||
SX126xWriteRegisters( REG_LR_CRCSEEDBASEADDR, buf, 2 );
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void SX126xSetCrcPolynomial( uint16_t polynomial )
|
||||
{
|
||||
uint8_t buf[2];
|
||||
|
||||
buf[0] = ( uint8_t )( ( polynomial >> 8 ) & 0xFF );
|
||||
buf[1] = ( uint8_t )( polynomial & 0xFF );
|
||||
|
||||
switch( SX126xGetPacketType( ) )
|
||||
{
|
||||
case PACKET_TYPE_GFSK:
|
||||
SX126xWriteRegisters( REG_LR_CRCPOLYBASEADDR, buf, 2 );
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void SX126xSetWhiteningSeed( uint16_t seed )
|
||||
{
|
||||
uint8_t regValue = 0;
|
||||
|
||||
switch( SX126xGetPacketType( ) )
|
||||
{
|
||||
case PACKET_TYPE_GFSK:
|
||||
regValue = SX126xReadRegister( REG_LR_WHITSEEDBASEADDR_MSB ) & 0xFE;
|
||||
regValue = ( ( seed >> 8 ) & 0x01 ) | regValue;
|
||||
SX126xWriteRegister( REG_LR_WHITSEEDBASEADDR_MSB, regValue ); // only 1 bit.
|
||||
SX126xWriteRegister( REG_LR_WHITSEEDBASEADDR_LSB, ( uint8_t )seed );
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t SX126xGetRandom( void )
|
||||
{
|
||||
uint32_t number = 0;
|
||||
uint8_t regAnaLna = 0;
|
||||
uint8_t regAnaMixer = 0;
|
||||
|
||||
regAnaLna = SX126xReadRegister( REG_ANA_LNA );
|
||||
SX126xWriteRegister( REG_ANA_LNA, regAnaLna & ~( 1 << 0 ) );
|
||||
|
||||
regAnaMixer = SX126xReadRegister( REG_ANA_MIXER );
|
||||
SX126xWriteRegister( REG_ANA_MIXER, regAnaMixer & ~( 1 << 7 ) );
|
||||
|
||||
// Set radio in continuous reception
|
||||
SX126xSetRx( 0xFFFFFF ); // Rx Continuous
|
||||
|
||||
SX126xReadRegisters( RANDOM_NUMBER_GENERATORBASEADDR, ( uint8_t* )&number, 4 );
|
||||
|
||||
SX126xSetStandby( STDBY_RC );
|
||||
|
||||
SX126xWriteRegister( REG_ANA_LNA, regAnaLna );
|
||||
SX126xWriteRegister( REG_ANA_MIXER, regAnaMixer );
|
||||
|
||||
return number;
|
||||
}
|
||||
|
||||
void SX126xSetSleep( SleepParams_t sleepConfig )
|
||||
{
|
||||
SX126xAntSwOff( );
|
||||
uint8_t value = ( ( ( uint8_t )sleepConfig.Fields.WarmStart << 2 ) |
|
||||
( ( uint8_t )sleepConfig.Fields.Reset << 1 ) |
|
||||
( ( uint8_t )sleepConfig.Fields.WakeUpRTC ) );
|
||||
SX126xWriteCommand( RADIO_SET_SLEEP, &value, 1 );
|
||||
SX126xSetOperatingMode( MODE_SLEEP );
|
||||
}
|
||||
|
||||
void SX126xSetStandby( RadioStandbyModes_t standbyConfig )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_STANDBY, ( uint8_t* )&standbyConfig, 1 );
|
||||
if( standbyConfig == STDBY_RC )
|
||||
{
|
||||
SX126xSetOperatingMode( MODE_STDBY_RC );
|
||||
}
|
||||
else
|
||||
{
|
||||
SX126xSetOperatingMode( MODE_STDBY_XOSC );
|
||||
}
|
||||
}
|
||||
|
||||
void SX126xSetFs( void )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_FS, 0, 0 );
|
||||
SX126xSetOperatingMode( MODE_FS );
|
||||
}
|
||||
|
||||
void SX126xSetTx( uint32_t timeout )
|
||||
{
|
||||
uint8_t buf[3];
|
||||
|
||||
SX126xSetOperatingMode( MODE_TX );
|
||||
|
||||
buf[0] = ( uint8_t )( ( timeout >> 16 ) & 0xFF );
|
||||
buf[1] = ( uint8_t )( ( timeout >> 8 ) & 0xFF );
|
||||
buf[2] = ( uint8_t )( timeout & 0xFF );
|
||||
SX126xWriteCommand( RADIO_SET_TX, buf, 3 );
|
||||
}
|
||||
|
||||
void SX126xSetRx( uint32_t timeout )
|
||||
{
|
||||
uint8_t buf[3];
|
||||
|
||||
SX126xSetOperatingMode( MODE_RX );
|
||||
|
||||
buf[0] = ( uint8_t )( ( timeout >> 16 ) & 0xFF );
|
||||
buf[1] = ( uint8_t )( ( timeout >> 8 ) & 0xFF );
|
||||
buf[2] = ( uint8_t )( timeout & 0xFF );
|
||||
SX126xWriteCommand( RADIO_SET_RX, buf, 3 );
|
||||
}
|
||||
|
||||
void SX126xSetRxBoosted( uint32_t timeout )
|
||||
{
|
||||
uint8_t buf[3];
|
||||
|
||||
SX126xSetOperatingMode( MODE_RX );
|
||||
|
||||
SX126xWriteRegister( REG_RX_GAIN, 0x96 ); // max LNA gain, increase current by ~2mA for around ~3dB in sensivity
|
||||
|
||||
buf[0] = ( uint8_t )( ( timeout >> 16 ) & 0xFF );
|
||||
buf[1] = ( uint8_t )( ( timeout >> 8 ) & 0xFF );
|
||||
buf[2] = ( uint8_t )( timeout & 0xFF );
|
||||
SX126xWriteCommand( RADIO_SET_RX, buf, 3 );
|
||||
}
|
||||
|
||||
void SX126xSetRxDutyCycle( uint32_t rxTime, uint32_t sleepTime )
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
buf[0] = ( uint8_t )( ( rxTime >> 16 ) & 0xFF );
|
||||
buf[1] = ( uint8_t )( ( rxTime >> 8 ) & 0xFF );
|
||||
buf[2] = ( uint8_t )( rxTime & 0xFF );
|
||||
buf[3] = ( uint8_t )( ( sleepTime >> 16 ) & 0xFF );
|
||||
buf[4] = ( uint8_t )( ( sleepTime >> 8 ) & 0xFF );
|
||||
buf[5] = ( uint8_t )( sleepTime & 0xFF );
|
||||
SX126xWriteCommand( RADIO_SET_RXDUTYCYCLE, buf, 6 );
|
||||
SX126xSetOperatingMode( MODE_RX_DC );
|
||||
}
|
||||
|
||||
void SX126xSetCad( void )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_CAD, 0, 0 );
|
||||
SX126xSetOperatingMode( MODE_CAD );
|
||||
}
|
||||
|
||||
void SX126xSetTxContinuousWave( void )
|
||||
{
|
||||
SX126xSetAntSw(MODE_TX);
|
||||
SX126xWriteCommand( RADIO_SET_TXCONTINUOUSWAVE, 0, 0 );
|
||||
}
|
||||
|
||||
void SX126xSetTxInfinitePreamble( void )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_TXCONTINUOUSPREAMBLE, 0, 0 );
|
||||
}
|
||||
|
||||
void SX126xSetStopRxTimerOnPreambleDetect( bool enable )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_STOPRXTIMERONPREAMBLE, ( uint8_t* )&enable, 1 );
|
||||
}
|
||||
|
||||
void SX126xSetLoRaSymbNumTimeout( uint8_t symbNum )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_LORASYMBTIMEOUT, &symbNum, 1 );
|
||||
|
||||
if( symbNum >= 64 )
|
||||
{
|
||||
uint8_t mant = symbNum >> 1;
|
||||
uint8_t exp = 0;
|
||||
uint8_t reg = 0;
|
||||
|
||||
while( mant > 31 )
|
||||
{
|
||||
mant >>= 2;
|
||||
exp++;
|
||||
}
|
||||
|
||||
reg = exp + ( mant << 3 );
|
||||
SX126xWriteRegister( REG_LR_SYNCH_TIMEOUT, reg );
|
||||
}
|
||||
}
|
||||
|
||||
void SX126xSetRegulatorMode( RadioRegulatorMode_t mode )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_REGULATORMODE, ( uint8_t* )&mode, 1 );
|
||||
}
|
||||
|
||||
void SX126xCalibrate( CalibrationParams_t calibParam )
|
||||
{
|
||||
uint8_t value = ( ( ( uint8_t )calibParam.Fields.ImgEnable << 6 ) |
|
||||
( ( uint8_t )calibParam.Fields.ADCBulkPEnable << 5 ) |
|
||||
( ( uint8_t )calibParam.Fields.ADCBulkNEnable << 4 ) |
|
||||
( ( uint8_t )calibParam.Fields.ADCPulseEnable << 3 ) |
|
||||
( ( uint8_t )calibParam.Fields.PLLEnable << 2 ) |
|
||||
( ( uint8_t )calibParam.Fields.RC13MEnable << 1 ) |
|
||||
( ( uint8_t )calibParam.Fields.RC64KEnable ) );
|
||||
|
||||
SX126xWriteCommand( RADIO_CALIBRATE, &value, 1 );
|
||||
}
|
||||
|
||||
void SX126xCalibrateImage( uint32_t freq )
|
||||
{
|
||||
uint8_t calFreq[2];
|
||||
|
||||
if( freq > 900000000 )
|
||||
{
|
||||
calFreq[0] = 0xE1;
|
||||
calFreq[1] = 0xE9;
|
||||
}
|
||||
else if( freq > 850000000 )
|
||||
{
|
||||
calFreq[0] = 0xD7;
|
||||
calFreq[1] = 0xDB;
|
||||
}
|
||||
else if( freq > 770000000 )
|
||||
{
|
||||
calFreq[0] = 0xC1;
|
||||
calFreq[1] = 0xC5;
|
||||
}
|
||||
else if( freq > 460000000 )
|
||||
{
|
||||
calFreq[0] = 0x75;
|
||||
calFreq[1] = 0x81;
|
||||
}
|
||||
else if( freq > 425000000 )
|
||||
{
|
||||
calFreq[0] = 0x6B;
|
||||
calFreq[1] = 0x6F;
|
||||
}
|
||||
SX126xWriteCommand( RADIO_CALIBRATEIMAGE, calFreq, 2 );
|
||||
}
|
||||
|
||||
void SX126xSetPaConfig( uint8_t paDutyCycle, uint8_t hpMax, uint8_t deviceSel, uint8_t paLut )
|
||||
{
|
||||
uint8_t buf[4];
|
||||
|
||||
buf[0] = paDutyCycle;
|
||||
buf[1] = hpMax;
|
||||
buf[2] = deviceSel;
|
||||
buf[3] = paLut;
|
||||
SX126xWriteCommand( RADIO_SET_PACONFIG, buf, 4 );
|
||||
}
|
||||
|
||||
void SX126xSetRxTxFallbackMode( uint8_t fallbackMode )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_TXFALLBACKMODE, &fallbackMode, 1 );
|
||||
}
|
||||
|
||||
void SX126xSetDioIrqParams( uint16_t irqMask, uint16_t dio1Mask, uint16_t dio2Mask, uint16_t dio3Mask )
|
||||
{
|
||||
uint8_t buf[8];
|
||||
|
||||
buf[0] = ( uint8_t )( ( irqMask >> 8 ) & 0x00FF );
|
||||
buf[1] = ( uint8_t )( irqMask & 0x00FF );
|
||||
buf[2] = ( uint8_t )( ( dio1Mask >> 8 ) & 0x00FF );
|
||||
buf[3] = ( uint8_t )( dio1Mask & 0x00FF );
|
||||
buf[4] = ( uint8_t )( ( dio2Mask >> 8 ) & 0x00FF );
|
||||
buf[5] = ( uint8_t )( dio2Mask & 0x00FF );
|
||||
buf[6] = ( uint8_t )( ( dio3Mask >> 8 ) & 0x00FF );
|
||||
buf[7] = ( uint8_t )( dio3Mask & 0x00FF );
|
||||
SX126xWriteCommand( RADIO_CFG_DIOIRQ, buf, 8 );
|
||||
}
|
||||
|
||||
uint16_t SX126xGetIrqStatus( void )
|
||||
{
|
||||
uint8_t irqStatus[2];
|
||||
|
||||
SX126xReadCommand( RADIO_GET_IRQSTATUS, irqStatus, 2 );
|
||||
return ( irqStatus[0] << 8 ) | irqStatus[1];
|
||||
}
|
||||
|
||||
void SX126xSetDio2AsRfSwitchCtrl( uint8_t enable )
|
||||
{
|
||||
SX126xWriteCommand( RADIO_SET_RFSWITCHMODE, &enable, 1 );
|
||||
}
|
||||
|
||||
void SX126xSetDio3AsTcxoCtrl( RadioTcxoCtrlVoltage_t tcxoVoltage, uint32_t timeout )
|
||||
{
|
||||
uint8_t buf[4];
|
||||
|
||||
buf[0] = tcxoVoltage & 0x07;
|
||||
buf[1] = ( uint8_t )( ( timeout >> 16 ) & 0xFF );
|
||||
buf[2] = ( uint8_t )( ( timeout >> 8 ) & 0xFF );
|
||||
buf[3] = ( uint8_t )( timeout & 0xFF );
|
||||
|
||||
SX126xWriteCommand( RADIO_SET_TCXOMODE, buf, 4 );
|
||||
}
|
||||
|
||||
void SX126xSetRfFrequency( uint32_t frequency )
|
||||
{
|
||||
uint8_t buf[4];
|
||||
uint32_t freq = 0;
|
||||
|
||||
if( ImageCalibrated == false )
|
||||
{
|
||||
SX126xCalibrateImage( frequency );
|
||||
ImageCalibrated = true;
|
||||
}
|
||||
|
||||
freq = ( uint32_t )( ( double )frequency / ( double )FREQ_STEP );
|
||||
buf[0] = ( uint8_t )( ( freq >> 24 ) & 0xFF );
|
||||
buf[1] = ( uint8_t )( ( freq >> 16 ) & 0xFF );
|
||||
buf[2] = ( uint8_t )( ( freq >> 8 ) & 0xFF );
|
||||
buf[3] = ( uint8_t )( freq & 0xFF );
|
||||
SX126xWriteCommand( RADIO_SET_RFFREQUENCY, buf, 4 );
|
||||
}
|
||||
|
||||
void SX126xSetPacketType( RadioPacketTypes_t packetType )
|
||||
{
|
||||
// Save packet type internally to avoid questioning the radio
|
||||
PacketType = packetType;
|
||||
SX126xWriteCommand( RADIO_SET_PACKETTYPE, ( uint8_t* )&packetType, 1 );
|
||||
}
|
||||
|
||||
RadioPacketTypes_t SX126xGetPacketType( void )
|
||||
{
|
||||
return PacketType;
|
||||
}
|
||||
|
||||
void SX126xSetTxParams( int8_t power, RadioRampTimes_t rampTime )
|
||||
{
|
||||
uint8_t buf[2];
|
||||
|
||||
//// if( SX126xGetDeviceId( ) == SX1261 )
|
||||
//// {
|
||||
//// if( power == 15 )
|
||||
//// {
|
||||
//// SX126xSetPaConfig( 0x06, 0x00, 0x01, 0x01 );
|
||||
//// }
|
||||
//// else
|
||||
//// {
|
||||
//// SX126xSetPaConfig( 0x04, 0x00, 0x01, 0x01 );
|
||||
//// }
|
||||
//// if( power >= 14 )
|
||||
//// {
|
||||
//// power = 14;
|
||||
//// }
|
||||
//// else if( power < -17 )
|
||||
//// {
|
||||
//// power = -17;
|
||||
//// }
|
||||
//// SX126xWriteRegister( REG_OCP, 0x18 ); // current max is 80 mA for the whole device
|
||||
//// }
|
||||
//// else // sx1262
|
||||
{
|
||||
// WORKAROUND - Better Resistance of the SX1262 Tx to Antenna Mismatch, see DS_SX1261-2_V1.2 datasheet chapter 15.2
|
||||
// RegTxClampConfig = @address 0x08D8
|
||||
SX126xWriteRegister( 0x08D8, SX126xReadRegister( 0x08D8 ) | ( 0x0F << 1 ) );
|
||||
// WORKAROUND END
|
||||
|
||||
SX126xSetPaConfig( 0x04, 0x07, 0x00, 0x01 );
|
||||
if( power > 22 )
|
||||
{
|
||||
power = 22;
|
||||
}
|
||||
else if( power < -9 )
|
||||
{
|
||||
power = -9;
|
||||
}
|
||||
SX126xWriteRegister( REG_OCP, 0x38 ); // current max 160mA for the whole device
|
||||
}
|
||||
buf[0] = power;
|
||||
buf[1] = ( uint8_t )rampTime;
|
||||
SX126xWriteCommand( RADIO_SET_TXPARAMS, buf, 2 );
|
||||
}
|
||||
|
||||
void SX126xSetRfTxPower( int8_t power )
|
||||
{
|
||||
SX126xSetTxParams( power, RADIO_RAMP_40_US );
|
||||
}
|
||||
|
||||
void SX126xSetModulationParams( ModulationParams_t *modulationParams )
|
||||
{
|
||||
uint8_t n;
|
||||
uint32_t tempVal = 0;
|
||||
uint8_t buf[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||
|
||||
// Check if required configuration corresponds to the stored packet type
|
||||
// If not, silently update radio packet type
|
||||
if( PacketType != modulationParams->PacketType )
|
||||
{
|
||||
SX126xSetPacketType( modulationParams->PacketType );
|
||||
}
|
||||
|
||||
switch( modulationParams->PacketType )
|
||||
{
|
||||
case PACKET_TYPE_GFSK:
|
||||
n = 8;
|
||||
tempVal = ( uint32_t )( 32 * ( ( double )XTAL_FREQ / ( double )modulationParams->Params.Gfsk.BitRate ) );
|
||||
buf[0] = ( tempVal >> 16 ) & 0xFF;
|
||||
buf[1] = ( tempVal >> 8 ) & 0xFF;
|
||||
buf[2] = tempVal & 0xFF;
|
||||
buf[3] = modulationParams->Params.Gfsk.ModulationShaping;
|
||||
buf[4] = modulationParams->Params.Gfsk.Bandwidth;
|
||||
tempVal = ( uint32_t )( ( double )modulationParams->Params.Gfsk.Fdev / ( double )FREQ_STEP );
|
||||
buf[5] = ( tempVal >> 16 ) & 0xFF;
|
||||
buf[6] = ( tempVal >> 8 ) & 0xFF;
|
||||
buf[7] = ( tempVal& 0xFF );
|
||||
SX126xWriteCommand( RADIO_SET_MODULATIONPARAMS, buf, n );
|
||||
break;
|
||||
case PACKET_TYPE_LORA:
|
||||
n = 4;
|
||||
buf[0] = modulationParams->Params.LoRa.SpreadingFactor;
|
||||
buf[1] = modulationParams->Params.LoRa.Bandwidth;
|
||||
buf[2] = modulationParams->Params.LoRa.CodingRate;
|
||||
buf[3] = modulationParams->Params.LoRa.LowDatarateOptimize;
|
||||
|
||||
SX126xWriteCommand( RADIO_SET_MODULATIONPARAMS, buf, n );
|
||||
|
||||
break;
|
||||
default:
|
||||
case PACKET_TYPE_NONE:
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void SX126xSetPacketParams( PacketParams_t *packetParams )
|
||||
{
|
||||
uint8_t n;
|
||||
uint8_t crcVal = 0;
|
||||
uint8_t buf[9] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||
|
||||
// Check if required configuration corresponds to the stored packet type
|
||||
// If not, silently update radio packet type
|
||||
if( PacketType != packetParams->PacketType )
|
||||
{
|
||||
SX126xSetPacketType( packetParams->PacketType );
|
||||
}
|
||||
|
||||
switch( packetParams->PacketType )
|
||||
{
|
||||
case PACKET_TYPE_GFSK:
|
||||
if( packetParams->Params.Gfsk.CrcLength == RADIO_CRC_2_BYTES_IBM )
|
||||
{
|
||||
SX126xSetCrcSeed( CRC_IBM_SEED );
|
||||
SX126xSetCrcPolynomial( CRC_POLYNOMIAL_IBM );
|
||||
crcVal = RADIO_CRC_2_BYTES;
|
||||
}
|
||||
else if( packetParams->Params.Gfsk.CrcLength == RADIO_CRC_2_BYTES_CCIT )
|
||||
{
|
||||
SX126xSetCrcSeed( CRC_CCITT_SEED );
|
||||
SX126xSetCrcPolynomial( CRC_POLYNOMIAL_CCITT );
|
||||
crcVal = RADIO_CRC_2_BYTES_INV;
|
||||
}
|
||||
else
|
||||
{
|
||||
crcVal = packetParams->Params.Gfsk.CrcLength;
|
||||
}
|
||||
n = 9;
|
||||
buf[0] = ( packetParams->Params.Gfsk.PreambleLength >> 8 ) & 0xFF;
|
||||
buf[1] = packetParams->Params.Gfsk.PreambleLength;
|
||||
buf[2] = packetParams->Params.Gfsk.PreambleMinDetect;
|
||||
buf[3] = ( packetParams->Params.Gfsk.SyncWordLength /*<< 3*/ ); // convert from byte to bit
|
||||
buf[4] = packetParams->Params.Gfsk.AddrComp;
|
||||
buf[5] = packetParams->Params.Gfsk.HeaderType;
|
||||
buf[6] = packetParams->Params.Gfsk.PayloadLength;
|
||||
buf[7] = crcVal;
|
||||
buf[8] = packetParams->Params.Gfsk.DcFree;
|
||||
break;
|
||||
case PACKET_TYPE_LORA:
|
||||
n = 6;
|
||||
buf[0] = ( packetParams->Params.LoRa.PreambleLength >> 8 ) & 0xFF;
|
||||
buf[1] = packetParams->Params.LoRa.PreambleLength;
|
||||
buf[2] = LoRaHeaderType = packetParams->Params.LoRa.HeaderType;
|
||||
buf[3] = packetParams->Params.LoRa.PayloadLength;
|
||||
buf[4] = packetParams->Params.LoRa.CrcMode;
|
||||
buf[5] = packetParams->Params.LoRa.InvertIQ;
|
||||
break;
|
||||
default:
|
||||
case PACKET_TYPE_NONE:
|
||||
return;
|
||||
}
|
||||
SX126xWriteCommand( RADIO_SET_PACKETPARAMS, buf, n );
|
||||
}
|
||||
|
||||
void SX126xSetCadParams( RadioLoRaCadSymbols_t cadSymbolNum, uint8_t cadDetPeak, uint8_t cadDetMin, RadioCadExitModes_t cadExitMode, uint32_t cadTimeout )
|
||||
{
|
||||
uint8_t buf[7];
|
||||
|
||||
buf[0] = ( uint8_t )cadSymbolNum;
|
||||
buf[1] = cadDetPeak;
|
||||
buf[2] = cadDetMin;
|
||||
buf[3] = ( uint8_t )cadExitMode;
|
||||
buf[4] = ( uint8_t )( ( cadTimeout >> 16 ) & 0xFF );
|
||||
buf[5] = ( uint8_t )( ( cadTimeout >> 8 ) & 0xFF );
|
||||
buf[6] = ( uint8_t )( cadTimeout & 0xFF );
|
||||
SX126xWriteCommand( RADIO_SET_CADPARAMS, buf, 7 );
|
||||
SX126xSetOperatingMode( MODE_CAD );
|
||||
}
|
||||
|
||||
void SX126xSetBufferBaseAddress( uint8_t txBaseAddress, uint8_t rxBaseAddress )
|
||||
{
|
||||
uint8_t buf[2];
|
||||
|
||||
buf[0] = txBaseAddress;
|
||||
buf[1] = rxBaseAddress;
|
||||
SX126xWriteCommand( RADIO_SET_BUFFERBASEADDRESS, buf, 2 );
|
||||
}
|
||||
|
||||
RadioStatus_t SX126xGetStatus( void )
|
||||
{
|
||||
uint8_t stat = 0;
|
||||
RadioStatus_t status = { .Value = 0 };
|
||||
|
||||
stat = SX126xReadCommand( RADIO_GET_STATUS, NULL, 0 );
|
||||
status.Fields.CmdStatus = ( stat & ( 0x07 << 1 ) ) >> 1;
|
||||
status.Fields.ChipMode = ( stat & ( 0x07 << 4 ) ) >> 4;
|
||||
return status;
|
||||
}
|
||||
|
||||
int8_t SX126xGetRssiInst( void )
|
||||
{
|
||||
uint8_t buf[1];
|
||||
int8_t rssi = 0;
|
||||
|
||||
SX126xReadCommand( RADIO_GET_RSSIINST, buf, 1 );
|
||||
rssi = -buf[0] >> 1;
|
||||
return rssi;
|
||||
}
|
||||
|
||||
void SX126xGetRxBufferStatus( uint8_t *payloadLength, uint8_t *rxStartBufferPointer )
|
||||
{
|
||||
uint8_t status[2];
|
||||
|
||||
SX126xReadCommand( RADIO_GET_RXBUFFERSTATUS, status, 2 );
|
||||
|
||||
// In case of LORA fixed header, the payloadLength is obtained by reading
|
||||
// the register REG_LR_PAYLOADLENGTH
|
||||
if( ( SX126xGetPacketType( ) == PACKET_TYPE_LORA ) && ( LoRaHeaderType == LORA_PACKET_FIXED_LENGTH ) )
|
||||
{
|
||||
*payloadLength = SX126xReadRegister( REG_LR_PAYLOADLENGTH );
|
||||
}
|
||||
else
|
||||
{
|
||||
*payloadLength = status[0];
|
||||
}
|
||||
*rxStartBufferPointer = status[1];
|
||||
}
|
||||
|
||||
void SX126xGetPacketStatus( PacketStatus_t *pktStatus )
|
||||
{
|
||||
uint8_t status[3];
|
||||
|
||||
SX126xReadCommand( RADIO_GET_PACKETSTATUS, status, 3 );
|
||||
|
||||
pktStatus->packetType = SX126xGetPacketType( );
|
||||
switch( pktStatus->packetType )
|
||||
{
|
||||
case PACKET_TYPE_GFSK:
|
||||
pktStatus->Params.Gfsk.RxStatus = status[0];
|
||||
pktStatus->Params.Gfsk.RssiSync = -status[1] >> 1;
|
||||
pktStatus->Params.Gfsk.RssiAvg = -status[2] >> 1;
|
||||
pktStatus->Params.Gfsk.FreqError = 0;
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_LORA:
|
||||
pktStatus->Params.LoRa.RssiPkt = -status[0] >> 1;
|
||||
// Returns SNR value [dB] rounded to the nearest integer value
|
||||
pktStatus->Params.LoRa.SnrPkt = ( ( ( int8_t )status[1] ) + 2 ) >> 2;
|
||||
pktStatus->Params.LoRa.SignalRssiPkt = -status[2] >> 1;
|
||||
pktStatus->Params.LoRa.FreqError = FrequencyError;
|
||||
break;
|
||||
|
||||
default:
|
||||
case PACKET_TYPE_NONE:
|
||||
// In that specific case, we set everything in the pktStatus to zeros
|
||||
// and reset the packet type accordingly
|
||||
memset( pktStatus, 0, sizeof( PacketStatus_t ) );
|
||||
pktStatus->packetType = PACKET_TYPE_NONE;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
RadioError_t SX126xGetDeviceErrors( void )
|
||||
{
|
||||
uint8_t err[] = { 0, 0 };
|
||||
RadioError_t error = { .Value = 0 };
|
||||
|
||||
SX126xReadCommand( RADIO_GET_ERROR, ( uint8_t* )err, 2 );
|
||||
error.Fields.PaRamp = ( err[0] & ( 1 << 0 ) ) >> 0;
|
||||
error.Fields.PllLock = ( err[1] & ( 1 << 6 ) ) >> 6;
|
||||
error.Fields.XoscStart = ( err[1] & ( 1 << 5 ) ) >> 5;
|
||||
error.Fields.ImgCalib = ( err[1] & ( 1 << 4 ) ) >> 4;
|
||||
error.Fields.AdcCalib = ( err[1] & ( 1 << 3 ) ) >> 3;
|
||||
error.Fields.PllCalib = ( err[1] & ( 1 << 2 ) ) >> 2;
|
||||
error.Fields.Rc13mCalib = ( err[1] & ( 1 << 1 ) ) >> 1;
|
||||
error.Fields.Rc64kCalib = ( err[1] & ( 1 << 0 ) ) >> 0;
|
||||
return error;
|
||||
}
|
||||
|
||||
void SX126xClearDeviceErrors( void )
|
||||
{
|
||||
uint8_t buf[2] = { 0x00, 0x00 };
|
||||
SX126xWriteCommand( RADIO_CLR_ERROR, buf, 2 );
|
||||
}
|
||||
|
||||
void SX126xClearIrqStatus( uint16_t irq )
|
||||
{
|
||||
uint8_t buf[2];
|
||||
|
||||
buf[0] = ( uint8_t )( ( ( uint16_t )irq >> 8 ) & 0x00FF );
|
||||
buf[1] = ( uint8_t )( ( uint16_t )irq & 0x00FF );
|
||||
SX126xWriteCommand( RADIO_CLR_IRQSTATUS, buf, 2 );
|
||||
}
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := sx127x.c lora-radio-sx127x.c lora-spi-sx127x.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,300 @@
|
|||
/*!
|
||||
* \file lora-radio.c for sx127x
|
||||
*
|
||||
* \brief LoRa Radio interface
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-radio-sx127x.c
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-radio-sx127x.c
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <lora-radio.h>
|
||||
#include "sx127x.h"
|
||||
#include <sx127x-board.h>
|
||||
|
||||
#ifdef RT_USING_PM
|
||||
#include "drivers/pm.h"
|
||||
#ifndef PM_RADIO_ID
|
||||
#define PM_RADIO_ID ( PM_MODULE_MAX_ID - 3 )
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define LOG_TAG "PHY.LoRa.SX127X"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include <lora-radio-debug.h>
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
|
||||
#define EV_LORA_RADIO_IRQ_MASK 0x0007 // DIO0 | DIO1 | DIO2 depend on board
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
static struct rt_event lora_radio_event;
|
||||
static struct rt_thread lora_radio_thread;
|
||||
static rt_uint8_t rt_lora_radio_thread_stack[4096];
|
||||
|
||||
extern struct rt_spi_device *lora_radio_spi_init(const char *bus_name, const char *lora_device_name, rt_uint8_t param);
|
||||
|
||||
#endif
|
||||
|
||||
#endif // end of LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
static pthread_t lora_radio_task;
|
||||
extern int lora_radio_spi_init(void);
|
||||
#endif
|
||||
|
||||
bool SX127xRadioInit( RadioEvents_t *events );
|
||||
|
||||
/*!
|
||||
* Radio driver structure initialization
|
||||
*/
|
||||
const struct Radio_s Radio =
|
||||
{
|
||||
SX127xRadioInit,
|
||||
SX127xGetStatus,
|
||||
SX127xSetModem,
|
||||
SX127xSetChannel,
|
||||
SX127xIsChannelFree,
|
||||
SX127xRandom,
|
||||
SX127xSetRxConfig,
|
||||
SX127xSetTxConfig,
|
||||
SX127xCheckRfFrequency,
|
||||
SX127xGetTimeOnAir,
|
||||
SX127xSend,
|
||||
SX127xSetSleep,
|
||||
SX127xSetStby,
|
||||
SX127xSetRx,
|
||||
SX127xStartCad,
|
||||
SX127xSetTxContinuousWave,
|
||||
SX127xReadRssi,
|
||||
SX127xWrite,
|
||||
SX127xRead,
|
||||
//SX127xWriteBuffer,
|
||||
//SX127xReadBuffer,
|
||||
SX127xSetMaxPayloadLength,
|
||||
SX127xSetPublicNetwork,
|
||||
SX127xGetWakeupTime,
|
||||
NULL, // void ( *IrqProcess )( void )
|
||||
SX127xCheck,
|
||||
//SX126x Only
|
||||
NULL, // void ( *RxBoosted )( uint32_t timeout )
|
||||
NULL, // void ( *SetRxDutyCycle )( uint32_t rxTime, uint32_t sleepTime )
|
||||
};
|
||||
|
||||
static bool lora_radio_init = false;
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
|
||||
static uint8_t get_irq_index(uint32_t ev)
|
||||
{
|
||||
uint32_t i = 0;
|
||||
for(i = 0; i < 32; i++)
|
||||
{
|
||||
if(ev & 0x01)
|
||||
{
|
||||
break;
|
||||
}
|
||||
ev >>= 1;
|
||||
}
|
||||
return i;
|
||||
}
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
/**
|
||||
* @brief lora_radio_thread_entry
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void lora_radio_thread_entry(void* parameter)
|
||||
{
|
||||
rt_uint32_t ev;
|
||||
|
||||
while(1)
|
||||
{
|
||||
if (rt_event_recv(&lora_radio_event, EV_LORA_RADIO_IRQ_MASK | EV_LORA_RADIO_TIMEOUT_FIRED,
|
||||
(RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR),
|
||||
RT_WAITING_FOREVER, &ev) == RT_EOK)
|
||||
{
|
||||
#ifdef RT_USING_PM
|
||||
rt_pm_module_request(PM_RADIO_ID, PM_SLEEP_MODE_NONE);
|
||||
RadioIrqProcess(get_irq_index(ev));
|
||||
rt_pm_module_release(PM_RADIO_ID, PM_SLEEP_MODE_NONE);
|
||||
#else
|
||||
RadioIrqProcess(get_irq_index(ev));
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
bool SX127xRadioInit( RadioEvents_t *events )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
if( lora_radio_init == false )
|
||||
{
|
||||
// Initialize spi bus
|
||||
SX127x.spi = lora_radio_spi_init(LORA_RADIO0_SPI_BUS_NAME, LORA_RADIO0_DEVICE_NAME, RT_NULL);
|
||||
if (SX127x.spi == RT_NULL)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_INTERFACE, LOG_LEVEL, "SX127x SPI Init Failed\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_INTERFACE, LOG_LEVEL, "SX127x SPI Init Succeed\n");
|
||||
|
||||
rt_event_init(&lora_radio_event, "ev_lora_phy", RT_IPC_FLAG_PRIO);//RT_IPC_FLAG_FIFO);
|
||||
|
||||
rt_thread_init(&lora_radio_thread,
|
||||
"lora-phy",
|
||||
lora_radio_thread_entry,
|
||||
RT_NULL,
|
||||
&rt_lora_radio_thread_stack[0],
|
||||
sizeof(rt_lora_radio_thread_stack),
|
||||
1, // highest priority
|
||||
20);
|
||||
|
||||
rt_thread_startup(&lora_radio_thread);
|
||||
|
||||
lora_radio_init = true;
|
||||
}
|
||||
#endif /* LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD */
|
||||
|
||||
SX127xIoInit();
|
||||
SX127xInit(events);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void SX127xOnDio0IrqEvent( void *args )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
rt_event_send(&lora_radio_event, EV_LORA_RADIO_IRQ0_FIRED);
|
||||
#endif
|
||||
}
|
||||
void SX127xOnDio1IrqEvent( void *args )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
rt_event_send(&lora_radio_event, EV_LORA_RADIO_IRQ1_FIRED);
|
||||
#endif
|
||||
}
|
||||
void SX127xOnDio2IrqEvent( void *args )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
rt_event_send(&lora_radio_event, EV_LORA_RADIO_IRQ2_FIRED);
|
||||
#endif
|
||||
}
|
||||
void SX127xOnDio3IrqEvent( void *args )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
rt_event_send(&lora_radio_event, EV_LORA_RADIO_IRQ3_FIRED);
|
||||
#endif
|
||||
}
|
||||
void SX127xOnDio4IrqEvent( void *args )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
rt_event_send(&lora_radio_event, EV_LORA_RADIO_IRQ4_FIRED);
|
||||
#endif
|
||||
}
|
||||
void SX127xOnDio5IrqEvent( void *args )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
rt_event_send(&lora_radio_event, EV_LORA_RADIO_IRQ5_FIRED);
|
||||
#endif
|
||||
}
|
||||
void SX127xOnTimeoutIrqEvent( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
rt_event_send(&lora_radio_event, EV_LORA_RADIO_TIMEOUT_FIRED);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
/**
|
||||
* @brief lora_radio_thread_entry
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void *lora_radio_thread_entry(void* parameter)
|
||||
{
|
||||
int ret;
|
||||
|
||||
while(1) {
|
||||
RadioIrqProcess(ret);
|
||||
}
|
||||
}
|
||||
|
||||
bool SX127xRadioInit( RadioEvents_t *events )
|
||||
{
|
||||
int ret;
|
||||
if( lora_radio_init == false ) {
|
||||
// Initialize spi bus
|
||||
ret = lora_radio_spi_init();
|
||||
if (ret < 0) {
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_INTERFACE, LOG_LEVEL, "SX127x SPI Init Failed\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_INTERFACE, LOG_LEVEL, "SX127x SPI Init Succeed\n");
|
||||
}
|
||||
|
||||
SX127xInit(events);
|
||||
|
||||
if ( lora_radio_init == false ) {
|
||||
pthread_attr_t attr;
|
||||
attr.schedparam.sched_priority = 20;
|
||||
attr.stacksize = 4096;
|
||||
|
||||
char task_name[] = "lora_radio_task";
|
||||
pthread_args_t args;
|
||||
args.pthread_name = task_name;
|
||||
|
||||
PrivTaskCreate(&lora_radio_task, &attr, &lora_radio_thread_entry, (void *)&args);
|
||||
PrivTaskStartup(&lora_radio_task);
|
||||
|
||||
lora_radio_init = true;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,120 @@
|
|||
/*!
|
||||
* \file lora-radio-spi-sx127x.c
|
||||
*
|
||||
* \brief sx127x spi driver implementation
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-radio-spi-sx127x.c
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-17
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-radio-spi-sx127x.c
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-17
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#include "sx127x.h"
|
||||
#include <sx127x-board.h>
|
||||
|
||||
void SX127xWriteBuffer( uint16_t addr, uint8_t *buffer, uint8_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
uint8_t msg[1] = {0};
|
||||
|
||||
msg[0] = (addr | 0x80);
|
||||
|
||||
rt_spi_send_then_send(SX127x.spi,msg,1,buffer,size);
|
||||
#else
|
||||
// uint8_t i;
|
||||
|
||||
// //NSS = 0;
|
||||
// GpioWrite( &SX127x.Spi.Nss, 0 );
|
||||
|
||||
// SpiInOut( &SX127x.Spi, addr | 0x80 );
|
||||
// for( i = 0; i < size; i++ )
|
||||
// {
|
||||
// SpiInOut( &SX127x.Spi, buffer[i] );
|
||||
// }
|
||||
|
||||
// //NSS = 1;
|
||||
// GpioWrite( &SX127x.Spi.Nss, 1 );
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t msg[1] = {0};
|
||||
|
||||
msg[0] = (addr | 0x80);
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, msg, 1);
|
||||
|
||||
PrivWrite(spi_fd, buffer, size);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void SX127xReadBuffer( uint16_t addr, uint8_t *buffer, uint8_t size )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef RT_USING_SPI
|
||||
uint8_t msg[1] = {0};
|
||||
|
||||
msg[0] = (addr & 0x7F);
|
||||
|
||||
rt_spi_send_then_recv(SX127x.spi,msg,1,buffer,size);
|
||||
#else
|
||||
// uint8_t i;
|
||||
|
||||
// //NSS = 0;
|
||||
// GpioWrite( &SX127x.Spi.Nss, 0 );
|
||||
|
||||
// SpiInOut( &SX127x.Spi, addr & 0x7F );
|
||||
|
||||
// for( i = 0; i < size; i++ )
|
||||
// {
|
||||
// buffer[i] = SpiInOut( &SX127x.Spi, 0 );
|
||||
// }
|
||||
|
||||
// //NSS = 1;
|
||||
// GpioWrite( &SX127x.Spi.Nss, 1 );
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int spi_fd;
|
||||
uint8_t msg[1] = {0};
|
||||
|
||||
msg[0] = (addr & 0x7F);
|
||||
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
|
||||
PrivWrite(spi_fd, msg, 1);
|
||||
|
||||
PrivRead(spi_fd, buffer, size);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
#endif
|
||||
|
||||
}
|
|
@ -0,0 +1,64 @@
|
|||
/*!
|
||||
* \file lora-spi-sx127x.h
|
||||
*
|
||||
* \brief SX127x spi interface
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#ifndef __LORA_SPI_SX127x_H__
|
||||
#define __LORA_SPI_SX127x_H__
|
||||
|
||||
/** @addtogroup LORA_RADIO_SPI
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup SX127X_SPI
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*!
|
||||
* \brief Writes the radio register at the specified address
|
||||
*
|
||||
* \param [IN]: addr Register address
|
||||
* \param [IN]: data New register value
|
||||
*/
|
||||
void SX127xWrite( uint16_t addr, uint8_t data );
|
||||
|
||||
/*!
|
||||
* \brief Reads the radio register at the specified address
|
||||
*
|
||||
* \param [IN]: addr Register address
|
||||
* \retval data Register value
|
||||
*/
|
||||
uint8_t SX127xRead( uint16_t addr );
|
||||
|
||||
/*!
|
||||
* \brief Writes multiple radio registers starting at address
|
||||
*
|
||||
* \param [IN] addr First Radio register address
|
||||
* \param [IN] buffer Buffer containing the new register's values
|
||||
* \param [IN] size Number of registers to be written
|
||||
*/
|
||||
void SX127xWriteBuffer( uint16_t addr, uint8_t *buffer, uint8_t size );
|
||||
|
||||
/*!
|
||||
* \brief Reads multiple radio registers starting at address
|
||||
*
|
||||
* \param [IN] addr First Radio register address
|
||||
* \param [OUT] buffer Buffer where to copy the registers data
|
||||
* \param [IN] size Number of registers to be read
|
||||
*/
|
||||
void SX127xReadBuffer( uint16_t addr, uint8_t *buffer, uint8_t size );
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
#endif // __LORA_SPI_SX127x_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,530 @@
|
|||
/*!
|
||||
* \file SX127x.h
|
||||
*
|
||||
* \brief SX127x driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#ifndef __SX127x_H__
|
||||
#define __SX127x_H__
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <lora-radio.h>
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include "sx127xRegs-Fsk.h"
|
||||
#include "sx127xRegs-LoRa.h"
|
||||
|
||||
/*!
|
||||
* Radio wake-up time from sleep
|
||||
*/
|
||||
#define RADIO_WAKEUP_TIME 1 // [ms]
|
||||
|
||||
/*!
|
||||
* Sync word for Private LoRa networks
|
||||
*/
|
||||
#define LORA_MAC_PRIVATE_SYNCWORD 0x12
|
||||
|
||||
/*!
|
||||
* Sync word for Public LoRa networks
|
||||
*/
|
||||
#define LORA_MAC_PUBLIC_SYNCWORD 0x34
|
||||
|
||||
/*!
|
||||
* Radio FSK modem parameters
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
int8_t Power;
|
||||
uint32_t Fdev;
|
||||
uint32_t Bandwidth;
|
||||
uint32_t BandwidthAfc;
|
||||
uint32_t Datarate;
|
||||
uint16_t PreambleLen;
|
||||
bool FixLen;
|
||||
uint8_t PayloadLen;
|
||||
bool CrcOn;
|
||||
bool IqInverted;
|
||||
bool RxContinuous;
|
||||
uint32_t TxTimeout;
|
||||
uint32_t RxSingleTimeout;
|
||||
}RadioFskSettings_t;
|
||||
|
||||
/*!
|
||||
* Radio FSK packet handler state
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t PreambleDetected;
|
||||
uint8_t SyncWordDetected;
|
||||
int8_t RssiValue;
|
||||
int32_t AfcValue;
|
||||
uint8_t RxGain;
|
||||
uint16_t Size;
|
||||
uint16_t NbBytes;
|
||||
uint8_t FifoThresh;
|
||||
uint8_t ChunkSize;
|
||||
}RadioFskPacketHandler_t;
|
||||
|
||||
/*!
|
||||
* Radio LoRa modem parameters
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
int8_t Power;
|
||||
uint32_t Bandwidth;
|
||||
uint32_t Datarate;
|
||||
bool LowDatarateOptimize;
|
||||
uint8_t Coderate;
|
||||
uint16_t PreambleLen;
|
||||
bool FixLen;
|
||||
uint8_t PayloadLen;
|
||||
bool CrcOn;
|
||||
bool FreqHopOn;
|
||||
uint8_t HopPeriod;
|
||||
bool IqInverted;
|
||||
bool RxContinuous;
|
||||
uint32_t TxTimeout;
|
||||
bool PublicNetwork;
|
||||
}RadioLoRaSettings_t;
|
||||
|
||||
/*!
|
||||
* Radio LoRa packet handler state
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
int8_t SnrValue;
|
||||
int16_t RssiValue;
|
||||
uint8_t Size;
|
||||
}RadioLoRaPacketHandler_t;
|
||||
|
||||
/*!
|
||||
* Radio Settings
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
RadioState_t State;
|
||||
RadioModems_t Modem;
|
||||
uint32_t Channel;
|
||||
#if defined( LORA_RADIO_DRIVER_USING_RF_MODEM_FSK )
|
||||
RadioFskSettings_t Fsk;
|
||||
RadioFskPacketHandler_t FskPacketHandler;
|
||||
#endif
|
||||
RadioLoRaSettings_t LoRa;
|
||||
RadioLoRaPacketHandler_t LoRaPacketHandler;
|
||||
}RadioSettings_t;
|
||||
|
||||
/*!
|
||||
* Radio hardware and global parameters
|
||||
*/
|
||||
typedef struct SX127x_s
|
||||
{
|
||||
// Gpio_t Reset;
|
||||
// Gpio_t DIO0;
|
||||
// Gpio_t DIO1;
|
||||
// Gpio_t DIO2;
|
||||
// Gpio_t DIO3;
|
||||
// Gpio_t DIO4;
|
||||
// Gpio_t DIO5;
|
||||
// Spi_t Spi;
|
||||
|
||||
/*!
|
||||
* Radio Spi bus
|
||||
*/
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
struct rt_spi_device *spi;
|
||||
#endif
|
||||
|
||||
RadioSettings_t Settings;
|
||||
}SX127x_t;
|
||||
|
||||
/*!
|
||||
* Hardware IO IRQ callback function definition
|
||||
*/
|
||||
typedef void ( DioIrqHandler )( void );
|
||||
|
||||
/*!
|
||||
* SX127x definitions
|
||||
*/
|
||||
#define XTAL_FREQ 32000000
|
||||
#define FREQ_STEP 61.03515625
|
||||
|
||||
#define RX_BUFFER_SIZE 256
|
||||
|
||||
/*!
|
||||
* \brief Radio hardware registers initialization definition
|
||||
*
|
||||
* \remark Can be automatically generated by the SX127x GUI (not yet implemented)
|
||||
*/
|
||||
#define RADIO_INIT_REGISTERS_VALUE \
|
||||
{ \
|
||||
{ MODEM_FSK , REG_LNA , 0x23 },\
|
||||
{ MODEM_FSK , REG_RXCONFIG , 0x1E },\
|
||||
{ MODEM_FSK , REG_RSSICONFIG , 0xD2 },\
|
||||
{ MODEM_FSK , REG_AFCFEI , 0x01 },\
|
||||
{ MODEM_FSK , REG_PREAMBLEDETECT , 0xAA },\
|
||||
{ MODEM_FSK , REG_OSC , 0x07 },\
|
||||
{ MODEM_FSK , REG_SYNCCONFIG , 0x12 },\
|
||||
{ MODEM_FSK , REG_SYNCVALUE1 , 0xC1 },\
|
||||
{ MODEM_FSK , REG_SYNCVALUE2 , 0x94 },\
|
||||
{ MODEM_FSK , REG_SYNCVALUE3 , 0xC1 },\
|
||||
{ MODEM_FSK , REG_PACKETCONFIG1 , 0xD8 },\
|
||||
{ MODEM_FSK , REG_FIFOTHRESH , 0x8F },\
|
||||
{ MODEM_FSK , REG_IMAGECAL , 0x02 },\
|
||||
{ MODEM_FSK , REG_DIOMAPPING1 , 0x00 },\
|
||||
{ MODEM_FSK , REG_DIOMAPPING2 , 0x30 },\
|
||||
{ MODEM_LORA, REG_LR_PAYLOADMAXLENGTH, 0x40 },\
|
||||
} \
|
||||
|
||||
#define RF_MID_BAND_THRESH 525000000
|
||||
|
||||
/** @addtogroup LORA_RADIO_CHIP_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup SX127X_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*!
|
||||
* ============================================================================
|
||||
* Public functions prototypes
|
||||
* ============================================================================
|
||||
*/
|
||||
|
||||
/*!
|
||||
* \brief Initializes the radio
|
||||
*
|
||||
* \param [IN] events Structure containing the driver callback functions
|
||||
*/
|
||||
void SX127xInit( RadioEvents_t *events );
|
||||
|
||||
/*!
|
||||
* Return current radio status
|
||||
*
|
||||
* \param status Radio status.[RF_IDLE, RF_RX_RUNNING, RF_TX_RUNNING]
|
||||
*/
|
||||
RadioState_t SX127xGetStatus( void );
|
||||
|
||||
/*!
|
||||
* \brief Configures the radio with the given modem
|
||||
*
|
||||
* \param [IN] modem Modem to be used [0: FSK, 1: LoRa]
|
||||
*/
|
||||
void SX127xSetModem( RadioModems_t modem );
|
||||
|
||||
/*!
|
||||
* \brief Sets the channel configuration
|
||||
*
|
||||
* \param [IN] freq Channel RF frequency
|
||||
*/
|
||||
void SX127xSetChannel( uint32_t freq );
|
||||
|
||||
/*!
|
||||
* \brief Sets the radio output power.
|
||||
*
|
||||
* \param [IN] power Sets the RF output power
|
||||
*/
|
||||
void SX127xSetRfTxPower( int8_t power );
|
||||
|
||||
/*!
|
||||
* \brief Checks if the channel is free for the given time
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] freq Channel RF frequency
|
||||
* \param [IN] rssiThresh RSSI threshold
|
||||
* \param [IN] maxCarrierSenseTime Max time while the RSSI is measured
|
||||
*
|
||||
* \retval isFree [true: Channel is free, false: Channel is not free]
|
||||
*/
|
||||
bool SX127xIsChannelFree( RadioModems_t modem, uint32_t freq, int16_t rssiThresh, uint32_t maxCarrierSenseTime );
|
||||
|
||||
/*!
|
||||
* \brief Generates a 32 bits random value based on the RSSI readings
|
||||
*
|
||||
* \remark This function sets the radio in LoRa modem mode and disables
|
||||
* all interrupts.
|
||||
* After calling this function either SX127xSetRxConfig or
|
||||
* SX127xSetTxConfig functions must be called.
|
||||
*
|
||||
* \retval randomValue 32 bits random value
|
||||
*/
|
||||
uint32_t SX127xRandom( void );
|
||||
|
||||
/*!
|
||||
* \brief Sets the reception parameters
|
||||
*
|
||||
* \remark When using LoRa modem only bandwidths 125, 250 and 500 kHz are supported
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] bandwidth Sets the bandwidth
|
||||
* FSK : >= 2600 and <= 250000 Hz
|
||||
* LoRa: [0: 125 kHz, 1: 250 kHz,
|
||||
* 2: 500 kHz, 3: Reserved]
|
||||
* \param [IN] datarate Sets the Datarate
|
||||
* FSK : 600..300000 bits/s
|
||||
* LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
|
||||
* 10: 1024, 11: 2048, 12: 4096 chips]
|
||||
* \param [IN] coderate Sets the coding rate (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
|
||||
* \param [IN] bandwidthAfc Sets the AFC Bandwidth (FSK only)
|
||||
* FSK : >= 2600 and <= 250000 Hz
|
||||
* LoRa: N/A ( set to 0 )
|
||||
* \param [IN] preambleLen Sets the Preamble length
|
||||
* FSK : Number of bytes
|
||||
* LoRa: Length in symbols (the hardware adds 4 more symbols)
|
||||
* \param [IN] symbTimeout Sets the RxSingle timeout value
|
||||
* FSK : timeout number of bytes
|
||||
* LoRa: timeout in symbols
|
||||
* \param [IN] fixLen Fixed length packets [0: variable, 1: fixed]
|
||||
* \param [IN] payloadLen Sets payload length when fixed length is used
|
||||
* \param [IN] crcOn Enables/Disables the CRC [0: OFF, 1: ON]
|
||||
* \param [IN] freqHopOn Enables disables the intra-packet frequency hopping
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: OFF, 1: ON]
|
||||
* \param [IN] hopPeriod Number of symbols between each hop
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: Number of symbols
|
||||
* \param [IN] iqInverted Inverts IQ signals (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: not inverted, 1: inverted]
|
||||
* \param [IN] rxContinuous Sets the reception in continuous mode
|
||||
* [false: single mode, true: continuous mode]
|
||||
*/
|
||||
void SX127xSetRxConfig( RadioModems_t modem, uint32_t bandwidth,
|
||||
uint32_t datarate, uint8_t coderate,
|
||||
uint32_t bandwidthAfc, uint16_t preambleLen,
|
||||
uint16_t symbTimeout, bool fixLen,
|
||||
uint8_t payloadLen,
|
||||
bool crcOn, bool freqHopOn, uint8_t hopPeriod,
|
||||
bool iqInverted, bool rxContinuous );
|
||||
|
||||
/*!
|
||||
* \brief Sets the transmission parameters
|
||||
*
|
||||
* \remark When using LoRa modem only bandwidths 125, 250 and 500 kHz are supported
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] power Sets the output power [dBm]
|
||||
* \param [IN] fdev Sets the frequency deviation (FSK only)
|
||||
* FSK : [Hz]
|
||||
* LoRa: 0
|
||||
* \param [IN] bandwidth Sets the bandwidth (LoRa only)
|
||||
* FSK : 0
|
||||
* LoRa: [0: 125 kHz, 1: 250 kHz,
|
||||
* 2: 500 kHz, 3: Reserved]
|
||||
* \param [IN] datarate Sets the Datarate
|
||||
* FSK : 600..300000 bits/s
|
||||
* LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
|
||||
* 10: 1024, 11: 2048, 12: 4096 chips]
|
||||
* \param [IN] coderate Sets the coding rate (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
|
||||
* \param [IN] preambleLen Sets the preamble length
|
||||
* FSK : Number of bytes
|
||||
* LoRa: Length in symbols (the hardware adds 4 more symbols)
|
||||
* \param [IN] fixLen Fixed length packets [0: variable, 1: fixed]
|
||||
* \param [IN] crcOn Enables disables the CRC [0: OFF, 1: ON]
|
||||
* \param [IN] freqHopOn Enables disables the intra-packet frequency hopping
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: OFF, 1: ON]
|
||||
* \param [IN] hopPeriod Number of symbols between each hop
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: Number of symbols
|
||||
* \param [IN] iqInverted Inverts IQ signals (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [0: not inverted, 1: inverted]
|
||||
* \param [IN] timeout Transmission timeout [ms]
|
||||
*/
|
||||
void SX127xSetTxConfig( RadioModems_t modem, int8_t power, uint32_t fdev,
|
||||
uint32_t bandwidth, uint32_t datarate,
|
||||
uint8_t coderate, uint16_t preambleLen,
|
||||
bool fixLen, bool crcOn, bool freqHopOn,
|
||||
uint8_t hopPeriod, bool iqInverted, uint32_t timeout );
|
||||
|
||||
/*!
|
||||
* \brief Computes the packet time on air in ms for the given payload
|
||||
*
|
||||
* \Remark Can only be called once SetRxConfig or SetTxConfig have been called
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] bandwidth Sets the bandwidth
|
||||
* FSK : >= 2600 and <= 250000 Hz
|
||||
* LoRa: [0: 125 kHz, 1: 250 kHz,
|
||||
* 2: 500 kHz, 3: Reserved]
|
||||
* \param [IN] datarate Sets the Datarate
|
||||
* FSK : 600..300000 bits/s
|
||||
* LoRa: [6: 64, 7: 128, 8: 256, 9: 512,
|
||||
* 10: 1024, 11: 2048, 12: 4096 chips]
|
||||
* \param [IN] coderate Sets the coding rate (LoRa only)
|
||||
* FSK : N/A ( set to 0 )
|
||||
* LoRa: [1: 4/5, 2: 4/6, 3: 4/7, 4: 4/8]
|
||||
* \param [IN] preambleLen Sets the Preamble length
|
||||
* FSK : Number of bytes
|
||||
* LoRa: Length in symbols (the hardware adds 4 more symbols)
|
||||
* \param [IN] fixLen Fixed length packets [0: variable, 1: fixed]
|
||||
* \param [IN] payloadLen Sets payload length when fixed length is used
|
||||
* \param [IN] crcOn Enables/Disables the CRC [0: OFF, 1: ON]
|
||||
*
|
||||
* \retval airTime Computed airTime (ms) for the given packet payload length
|
||||
*/
|
||||
uint32_t SX127xGetTimeOnAir( RadioModems_t modem, uint32_t bandwidth,
|
||||
uint32_t datarate, uint8_t coderate,
|
||||
uint16_t preambleLen, bool fixLen, uint8_t payloadLen,
|
||||
bool crcOn );
|
||||
|
||||
/*!
|
||||
* \brief Sends the buffer of size. Prepares the packet to be sent and sets
|
||||
* the radio in transmission
|
||||
*
|
||||
* \param [IN]: buffer Buffer pointer
|
||||
* \param [IN]: size Buffer size
|
||||
*/
|
||||
void SX127xSend( uint8_t *buffer, uint8_t size );
|
||||
|
||||
/*!
|
||||
* \brief Sets the radio in sleep mode
|
||||
*/
|
||||
void SX127xSetSleep( void );
|
||||
|
||||
/*!
|
||||
* \brief Sets the radio in standby mode
|
||||
*/
|
||||
void SX127xSetStby( void );
|
||||
|
||||
/*!
|
||||
* \brief Sets the radio in reception mode for the given time
|
||||
* \param [IN] timeout Reception timeout [ms] [0: continuous, others timeout]
|
||||
*/
|
||||
void SX127xSetRx( uint32_t timeout );
|
||||
|
||||
/*!
|
||||
* \brief Start a Channel Activity Detection
|
||||
*/
|
||||
void SX127xStartCad( void );
|
||||
|
||||
/*!
|
||||
* \brief Sets the radio in continuous wave transmission mode
|
||||
*
|
||||
* \param [IN]: freq Channel RF frequency
|
||||
* \param [IN]: power Sets the output power [dBm]
|
||||
* \param [IN]: time Transmission mode timeout [s]
|
||||
*/
|
||||
void SX127xSetTxContinuousWave( uint32_t freq, int8_t power, uint16_t time );
|
||||
|
||||
/*!
|
||||
* \brief Reads the current RSSI value
|
||||
*
|
||||
* \retval rssiValue Current RSSI value in [dBm]
|
||||
*/
|
||||
int16_t SX127xReadRssi( RadioModems_t modem );
|
||||
|
||||
/*!
|
||||
* \brief Writes the radio register at the specified address
|
||||
*
|
||||
* \param [IN]: addr Register address
|
||||
* \param [IN]: data New register value
|
||||
*/
|
||||
void SX127xWrite( uint16_t addr, uint8_t data );
|
||||
|
||||
/*!
|
||||
* \brief Reads the radio register at the specified address
|
||||
*
|
||||
* \param [IN]: addr Register address
|
||||
* \retval data Register value
|
||||
*/
|
||||
uint8_t SX127xRead( uint16_t addr );
|
||||
|
||||
/*!
|
||||
* \brief Writes multiple radio registers starting at address
|
||||
*
|
||||
* \param [IN] addr First Radio register address
|
||||
* \param [IN] buffer Buffer containing the new register's values
|
||||
* \param [IN] size Number of registers to be written
|
||||
*/
|
||||
void SX127xWriteBuffer( uint16_t addr, uint8_t *buffer, uint8_t size );
|
||||
|
||||
/*!
|
||||
* \brief Reads multiple radio registers starting at address
|
||||
*
|
||||
* \param [IN] addr First Radio register address
|
||||
* \param [OUT] buffer Buffer where to copy the registers data
|
||||
* \param [IN] size Number of registers to be read
|
||||
*/
|
||||
void SX127xReadBuffer( uint16_t addr, uint8_t *buffer, uint8_t size );
|
||||
|
||||
/*!
|
||||
* \brief Sets the maximum payload length.
|
||||
*
|
||||
* \param [IN] modem Radio modem to be used [0: FSK, 1: LoRa]
|
||||
* \param [IN] max Maximum payload length in bytes
|
||||
*/
|
||||
void SX127xSetMaxPayloadLength( RadioModems_t modem, uint8_t max );
|
||||
|
||||
/*!
|
||||
* \brief Sets the network to public or private. Updates the sync byte.
|
||||
*
|
||||
* \remark Applies to LoRa modem only
|
||||
*
|
||||
* \param [IN] enable if true, it enables a public network
|
||||
*/
|
||||
void SX127xSetPublicNetwork( bool enable );
|
||||
|
||||
/*!
|
||||
* \brief Gets the time required for the board plus radio to get out of sleep.[ms]
|
||||
*
|
||||
* \retval time Radio plus board wakeup time in ms.
|
||||
*/
|
||||
uint32_t SX127xGetWakeupTime( void );
|
||||
|
||||
/*!
|
||||
* \brief Check spi access
|
||||
*
|
||||
* \retval the .
|
||||
*/
|
||||
uint8_t SX127xCheck( void );
|
||||
|
||||
/*!
|
||||
* \brief Initializes DIO IRQ handlers
|
||||
*
|
||||
* \param [IN] irqHandlers Array containing the IRQ callback functions
|
||||
*/
|
||||
void SX127xIoIrqInit( DioIrqHandler **irqHandlers );
|
||||
|
||||
/*!
|
||||
* \brief Process radio irq
|
||||
*/
|
||||
void RadioIrqProcess( uint8_t irq_index );
|
||||
|
||||
/*!
|
||||
* Radio hardware and global parameters
|
||||
*/
|
||||
extern SX127x_t SX127x;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif // __SX127x_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,573 @@
|
|||
/*!
|
||||
* \file sx1276Regs-LoRa.h
|
||||
*
|
||||
* \brief SX1276 LoRa modem registers and bits definitions
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*/
|
||||
#ifndef __SX1276_REGS_LORA_H__
|
||||
#define __SX1276_REGS_LORA_H__
|
||||
|
||||
/*!
|
||||
* ============================================================================
|
||||
* SX1276 Internal registers Address
|
||||
* ============================================================================
|
||||
*/
|
||||
#define REG_LR_FIFO 0x00
|
||||
// Common settings
|
||||
#define REG_LR_OPMODE 0x01
|
||||
#define REG_LR_FRFMSB 0x06
|
||||
#define REG_LR_FRFMID 0x07
|
||||
#define REG_LR_FRFLSB 0x08
|
||||
// Tx settings
|
||||
#define REG_LR_PACONFIG 0x09
|
||||
#define REG_LR_PARAMP 0x0A
|
||||
#define REG_LR_OCP 0x0B
|
||||
// Rx settings
|
||||
#define REG_LR_LNA 0x0C
|
||||
// LoRa registers
|
||||
#define REG_LR_FIFOADDRPTR 0x0D
|
||||
#define REG_LR_FIFOTXBASEADDR 0x0E
|
||||
#define REG_LR_FIFORXBASEADDR 0x0F
|
||||
#define REG_LR_FIFORXCURRENTADDR 0x10
|
||||
#define REG_LR_IRQFLAGSMASK 0x11
|
||||
#define REG_LR_IRQFLAGS 0x12
|
||||
#define REG_LR_RXNBBYTES 0x13
|
||||
#define REG_LR_RXHEADERCNTVALUEMSB 0x14
|
||||
#define REG_LR_RXHEADERCNTVALUELSB 0x15
|
||||
#define REG_LR_RXPACKETCNTVALUEMSB 0x16
|
||||
#define REG_LR_RXPACKETCNTVALUELSB 0x17
|
||||
#define REG_LR_MODEMSTAT 0x18
|
||||
#define REG_LR_PKTSNRVALUE 0x19
|
||||
#define REG_LR_PKTRSSIVALUE 0x1A
|
||||
#define REG_LR_RSSIVALUE 0x1B
|
||||
#define REG_LR_HOPCHANNEL 0x1C
|
||||
#define REG_LR_MODEMCONFIG1 0x1D
|
||||
#define REG_LR_MODEMCONFIG2 0x1E
|
||||
#define REG_LR_SYMBTIMEOUTLSB 0x1F
|
||||
#define REG_LR_PREAMBLEMSB 0x20
|
||||
#define REG_LR_PREAMBLELSB 0x21
|
||||
#define REG_LR_PAYLOADLENGTH 0x22
|
||||
#define REG_LR_PAYLOADMAXLENGTH 0x23
|
||||
#define REG_LR_HOPPERIOD 0x24
|
||||
#define REG_LR_FIFORXBYTEADDR 0x25
|
||||
#define REG_LR_MODEMCONFIG3 0x26
|
||||
#define REG_LR_FEIMSB 0x28
|
||||
#define REG_LR_FEIMID 0x29
|
||||
#define REG_LR_FEILSB 0x2A
|
||||
#define REG_LR_RSSIWIDEBAND 0x2C
|
||||
#define REG_LR_IFFREQ1 0x2F
|
||||
#define REG_LR_IFFREQ2 0x30
|
||||
#define REG_LR_DETECTOPTIMIZE 0x31
|
||||
#define REG_LR_INVERTIQ 0x33
|
||||
#define REG_LR_HIGHBWOPTIMIZE1 0x36
|
||||
#define REG_LR_DETECTIONTHRESHOLD 0x37
|
||||
#define REG_LR_SYNCWORD 0x39
|
||||
#define REG_LR_HIGHBWOPTIMIZE2 0x3A
|
||||
#define REG_LR_INVERTIQ2 0x3B
|
||||
|
||||
// end of documented register in datasheet
|
||||
// I/O settings
|
||||
#define REG_LR_DIOMAPPING1 0x40
|
||||
#define REG_LR_DIOMAPPING2 0x41
|
||||
// Version
|
||||
#define REG_LR_VERSION 0x42
|
||||
// Additional settings
|
||||
#define REG_LR_PLLHOP 0x44
|
||||
#define REG_LR_TCXO 0x4B
|
||||
#define REG_LR_PADAC 0x4D
|
||||
#define REG_LR_FORMERTEMP 0x5B
|
||||
#define REG_LR_BITRATEFRAC 0x5D
|
||||
#define REG_LR_AGCREF 0x61
|
||||
#define REG_LR_AGCTHRESH1 0x62
|
||||
#define REG_LR_AGCTHRESH2 0x63
|
||||
#define REG_LR_AGCTHRESH3 0x64
|
||||
#define REG_LR_PLL 0x70
|
||||
|
||||
/*!
|
||||
* ============================================================================
|
||||
* SX1276 LoRa bits control definition
|
||||
* ============================================================================
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegFifo
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegOpMode
|
||||
*/
|
||||
#define RFLR_OPMODE_LONGRANGEMODE_MASK 0x7F
|
||||
#define RFLR_OPMODE_LONGRANGEMODE_OFF 0x00 // Default
|
||||
#define RFLR_OPMODE_LONGRANGEMODE_ON 0x80
|
||||
|
||||
#define RFLR_OPMODE_ACCESSSHAREDREG_MASK 0xBF
|
||||
#define RFLR_OPMODE_ACCESSSHAREDREG_ENABLE 0x40
|
||||
#define RFLR_OPMODE_ACCESSSHAREDREG_DISABLE 0x00 // Default
|
||||
|
||||
#define RFLR_OPMODE_FREQMODE_ACCESS_MASK 0xF7
|
||||
#define RFLR_OPMODE_FREQMODE_ACCESS_LF 0x08 // Default
|
||||
#define RFLR_OPMODE_FREQMODE_ACCESS_HF 0x00
|
||||
|
||||
#define RFLR_OPMODE_MASK 0xF8
|
||||
#define RFLR_OPMODE_SLEEP 0x00
|
||||
#define RFLR_OPMODE_STANDBY 0x01 // Default
|
||||
#define RFLR_OPMODE_SYNTHESIZER_TX 0x02
|
||||
#define RFLR_OPMODE_TRANSMITTER 0x03
|
||||
#define RFLR_OPMODE_SYNTHESIZER_RX 0x04
|
||||
#define RFLR_OPMODE_RECEIVER 0x05
|
||||
// LoRa specific modes
|
||||
#define RFLR_OPMODE_RECEIVER_SINGLE 0x06
|
||||
#define RFLR_OPMODE_CAD 0x07
|
||||
|
||||
/*!
|
||||
* RegFrf (MHz)
|
||||
*/
|
||||
#define RFLR_FRFMSB_434_MHZ 0x6C // Default
|
||||
#define RFLR_FRFMID_434_MHZ 0x80 // Default
|
||||
#define RFLR_FRFLSB_434_MHZ 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegPaConfig
|
||||
*/
|
||||
#define RFLR_PACONFIG_PASELECT_MASK 0x7F
|
||||
#define RFLR_PACONFIG_PASELECT_PABOOST 0x80
|
||||
#define RFLR_PACONFIG_PASELECT_RFO 0x00 // Default
|
||||
|
||||
#define RFLR_PACONFIG_MAX_POWER_MASK 0x8F
|
||||
|
||||
#define RFLR_PACONFIG_OUTPUTPOWER_MASK 0xF0
|
||||
|
||||
/*!
|
||||
* RegPaRamp
|
||||
*/
|
||||
#define RFLR_PARAMP_TXBANDFORCE_MASK 0xEF
|
||||
#define RFLR_PARAMP_TXBANDFORCE_BAND_SEL 0x10
|
||||
#define RFLR_PARAMP_TXBANDFORCE_AUTO 0x00 // Default
|
||||
|
||||
#define RFLR_PARAMP_MASK 0xF0
|
||||
#define RFLR_PARAMP_3400_US 0x00
|
||||
#define RFLR_PARAMP_2000_US 0x01
|
||||
#define RFLR_PARAMP_1000_US 0x02
|
||||
#define RFLR_PARAMP_0500_US 0x03
|
||||
#define RFLR_PARAMP_0250_US 0x04
|
||||
#define RFLR_PARAMP_0125_US 0x05
|
||||
#define RFLR_PARAMP_0100_US 0x06
|
||||
#define RFLR_PARAMP_0062_US 0x07
|
||||
#define RFLR_PARAMP_0050_US 0x08
|
||||
#define RFLR_PARAMP_0040_US 0x09 // Default
|
||||
#define RFLR_PARAMP_0031_US 0x0A
|
||||
#define RFLR_PARAMP_0025_US 0x0B
|
||||
#define RFLR_PARAMP_0020_US 0x0C
|
||||
#define RFLR_PARAMP_0015_US 0x0D
|
||||
#define RFLR_PARAMP_0012_US 0x0E
|
||||
#define RFLR_PARAMP_0010_US 0x0F
|
||||
|
||||
/*!
|
||||
* RegOcp
|
||||
*/
|
||||
#define RFLR_OCP_MASK 0xDF
|
||||
#define RFLR_OCP_ON 0x20 // Default
|
||||
#define RFLR_OCP_OFF 0x00
|
||||
|
||||
#define RFLR_OCP_TRIM_MASK 0xE0
|
||||
#define RFLR_OCP_TRIM_045_MA 0x00
|
||||
#define RFLR_OCP_TRIM_050_MA 0x01
|
||||
#define RFLR_OCP_TRIM_055_MA 0x02
|
||||
#define RFLR_OCP_TRIM_060_MA 0x03
|
||||
#define RFLR_OCP_TRIM_065_MA 0x04
|
||||
#define RFLR_OCP_TRIM_070_MA 0x05
|
||||
#define RFLR_OCP_TRIM_075_MA 0x06
|
||||
#define RFLR_OCP_TRIM_080_MA 0x07
|
||||
#define RFLR_OCP_TRIM_085_MA 0x08
|
||||
#define RFLR_OCP_TRIM_090_MA 0x09
|
||||
#define RFLR_OCP_TRIM_095_MA 0x0A
|
||||
#define RFLR_OCP_TRIM_100_MA 0x0B // Default
|
||||
#define RFLR_OCP_TRIM_105_MA 0x0C
|
||||
#define RFLR_OCP_TRIM_110_MA 0x0D
|
||||
#define RFLR_OCP_TRIM_115_MA 0x0E
|
||||
#define RFLR_OCP_TRIM_120_MA 0x0F
|
||||
#define RFLR_OCP_TRIM_130_MA 0x10
|
||||
#define RFLR_OCP_TRIM_140_MA 0x11
|
||||
#define RFLR_OCP_TRIM_150_MA 0x12
|
||||
#define RFLR_OCP_TRIM_160_MA 0x13
|
||||
#define RFLR_OCP_TRIM_170_MA 0x14
|
||||
#define RFLR_OCP_TRIM_180_MA 0x15
|
||||
#define RFLR_OCP_TRIM_190_MA 0x16
|
||||
#define RFLR_OCP_TRIM_200_MA 0x17
|
||||
#define RFLR_OCP_TRIM_210_MA 0x18
|
||||
#define RFLR_OCP_TRIM_220_MA 0x19
|
||||
#define RFLR_OCP_TRIM_230_MA 0x1A
|
||||
#define RFLR_OCP_TRIM_240_MA 0x1B
|
||||
|
||||
/*!
|
||||
* RegLna
|
||||
*/
|
||||
#define RFLR_LNA_GAIN_MASK 0x1F
|
||||
#define RFLR_LNA_GAIN_G1 0x20 // Default
|
||||
#define RFLR_LNA_GAIN_G2 0x40
|
||||
#define RFLR_LNA_GAIN_G3 0x60
|
||||
#define RFLR_LNA_GAIN_G4 0x80
|
||||
#define RFLR_LNA_GAIN_G5 0xA0
|
||||
#define RFLR_LNA_GAIN_G6 0xC0
|
||||
|
||||
#define RFLR_LNA_BOOST_LF_MASK 0xE7
|
||||
#define RFLR_LNA_BOOST_LF_DEFAULT 0x00 // Default
|
||||
|
||||
#define RFLR_LNA_BOOST_HF_MASK 0xFC
|
||||
#define RFLR_LNA_BOOST_HF_OFF 0x00 // Default
|
||||
#define RFLR_LNA_BOOST_HF_ON 0x03
|
||||
|
||||
/*!
|
||||
* RegFifoAddrPtr
|
||||
*/
|
||||
#define RFLR_FIFOADDRPTR 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegFifoTxBaseAddr
|
||||
*/
|
||||
#define RFLR_FIFOTXBASEADDR 0x80 // Default
|
||||
|
||||
/*!
|
||||
* RegFifoTxBaseAddr
|
||||
*/
|
||||
#define RFLR_FIFORXBASEADDR 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegFifoRxCurrentAddr (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegIrqFlagsMask
|
||||
*/
|
||||
#define RFLR_IRQFLAGS_RXTIMEOUT_MASK 0x80
|
||||
#define RFLR_IRQFLAGS_RXDONE_MASK 0x40
|
||||
#define RFLR_IRQFLAGS_PAYLOADCRCERROR_MASK 0x20
|
||||
#define RFLR_IRQFLAGS_VALIDHEADER_MASK 0x10
|
||||
#define RFLR_IRQFLAGS_TXDONE_MASK 0x08
|
||||
#define RFLR_IRQFLAGS_CADDONE_MASK 0x04
|
||||
#define RFLR_IRQFLAGS_FHSSCHANGEDCHANNEL_MASK 0x02
|
||||
#define RFLR_IRQFLAGS_CADDETECTED_MASK 0x01
|
||||
|
||||
/*!
|
||||
* RegIrqFlags
|
||||
*/
|
||||
#define RFLR_IRQFLAGS_RXTIMEOUT 0x80
|
||||
#define RFLR_IRQFLAGS_RXDONE 0x40
|
||||
#define RFLR_IRQFLAGS_PAYLOADCRCERROR 0x20
|
||||
#define RFLR_IRQFLAGS_VALIDHEADER 0x10
|
||||
#define RFLR_IRQFLAGS_TXDONE 0x08
|
||||
#define RFLR_IRQFLAGS_CADDONE 0x04
|
||||
#define RFLR_IRQFLAGS_FHSSCHANGEDCHANNEL 0x02
|
||||
#define RFLR_IRQFLAGS_CADDETECTED 0x01
|
||||
|
||||
/*!
|
||||
* RegFifoRxNbBytes (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegRxHeaderCntValueMsb (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegRxHeaderCntValueLsb (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegRxPacketCntValueMsb (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegRxPacketCntValueLsb (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegModemStat (Read Only)
|
||||
*/
|
||||
#define RFLR_MODEMSTAT_RX_CR_MASK 0x1F
|
||||
#define RFLR_MODEMSTAT_MODEM_STATUS_MASK 0xE0
|
||||
|
||||
/*!
|
||||
* RegPktSnrValue (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegPktRssiValue (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegRssiValue (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegHopChannel (Read Only)
|
||||
*/
|
||||
#define RFLR_HOPCHANNEL_PLL_LOCK_TIMEOUT_MASK 0x7F
|
||||
#define RFLR_HOPCHANNEL_PLL_LOCK_FAIL 0x80
|
||||
#define RFLR_HOPCHANNEL_PLL_LOCK_SUCCEED 0x00 // Default
|
||||
|
||||
#define RFLR_HOPCHANNEL_CRCONPAYLOAD_MASK 0xBF
|
||||
#define RFLR_HOPCHANNEL_CRCONPAYLOAD_ON 0x40
|
||||
#define RFLR_HOPCHANNEL_CRCONPAYLOAD_OFF 0x00 // Default
|
||||
|
||||
#define RFLR_HOPCHANNEL_CHANNEL_MASK 0x3F
|
||||
|
||||
/*!
|
||||
* RegModemConfig1
|
||||
*/
|
||||
#define RFLR_MODEMCONFIG1_BW_MASK 0x0F
|
||||
#define RFLR_MODEMCONFIG1_BW_7_81_KHZ 0x00
|
||||
#define RFLR_MODEMCONFIG1_BW_10_41_KHZ 0x10
|
||||
#define RFLR_MODEMCONFIG1_BW_15_62_KHZ 0x20
|
||||
#define RFLR_MODEMCONFIG1_BW_20_83_KHZ 0x30
|
||||
#define RFLR_MODEMCONFIG1_BW_31_25_KHZ 0x40
|
||||
#define RFLR_MODEMCONFIG1_BW_41_66_KHZ 0x50
|
||||
#define RFLR_MODEMCONFIG1_BW_62_50_KHZ 0x60
|
||||
#define RFLR_MODEMCONFIG1_BW_125_KHZ 0x70 // Default
|
||||
#define RFLR_MODEMCONFIG1_BW_250_KHZ 0x80
|
||||
#define RFLR_MODEMCONFIG1_BW_500_KHZ 0x90
|
||||
|
||||
#define RFLR_MODEMCONFIG1_CODINGRATE_MASK 0xF1
|
||||
#define RFLR_MODEMCONFIG1_CODINGRATE_4_5 0x02
|
||||
#define RFLR_MODEMCONFIG1_CODINGRATE_4_6 0x04 // Default
|
||||
#define RFLR_MODEMCONFIG1_CODINGRATE_4_7 0x06
|
||||
#define RFLR_MODEMCONFIG1_CODINGRATE_4_8 0x08
|
||||
|
||||
#define RFLR_MODEMCONFIG1_IMPLICITHEADER_MASK 0xFE
|
||||
#define RFLR_MODEMCONFIG1_IMPLICITHEADER_ON 0x01
|
||||
#define RFLR_MODEMCONFIG1_IMPLICITHEADER_OFF 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegModemConfig2
|
||||
*/
|
||||
#define RFLR_MODEMCONFIG2_SF_MASK 0x0F
|
||||
#define RFLR_MODEMCONFIG2_SF_6 0x60
|
||||
#define RFLR_MODEMCONFIG2_SF_7 0x70 // Default
|
||||
#define RFLR_MODEMCONFIG2_SF_8 0x80
|
||||
#define RFLR_MODEMCONFIG2_SF_9 0x90
|
||||
#define RFLR_MODEMCONFIG2_SF_10 0xA0
|
||||
#define RFLR_MODEMCONFIG2_SF_11 0xB0
|
||||
#define RFLR_MODEMCONFIG2_SF_12 0xC0
|
||||
|
||||
#define RFLR_MODEMCONFIG2_TXCONTINUOUSMODE_MASK 0xF7
|
||||
#define RFLR_MODEMCONFIG2_TXCONTINUOUSMODE_ON 0x08
|
||||
#define RFLR_MODEMCONFIG2_TXCONTINUOUSMODE_OFF 0x00
|
||||
|
||||
#define RFLR_MODEMCONFIG2_RXPAYLOADCRC_MASK 0xFB
|
||||
#define RFLR_MODEMCONFIG2_RXPAYLOADCRC_ON 0x04
|
||||
#define RFLR_MODEMCONFIG2_RXPAYLOADCRC_OFF 0x00 // Default
|
||||
|
||||
#define RFLR_MODEMCONFIG2_SYMBTIMEOUTMSB_MASK 0xFC
|
||||
#define RFLR_MODEMCONFIG2_SYMBTIMEOUTMSB 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegSymbTimeoutLsb
|
||||
*/
|
||||
#define RFLR_SYMBTIMEOUTLSB_SYMBTIMEOUT 0x64 // Default
|
||||
|
||||
/*!
|
||||
* RegPreambleLengthMsb
|
||||
*/
|
||||
#define RFLR_PREAMBLELENGTHMSB 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegPreambleLengthLsb
|
||||
*/
|
||||
#define RFLR_PREAMBLELENGTHLSB 0x08 // Default
|
||||
|
||||
/*!
|
||||
* RegPayloadLength
|
||||
*/
|
||||
#define RFLR_PAYLOADLENGTH 0x0E // Default
|
||||
|
||||
/*!
|
||||
* RegPayloadMaxLength
|
||||
*/
|
||||
#define RFLR_PAYLOADMAXLENGTH 0xFF // Default
|
||||
|
||||
/*!
|
||||
* RegHopPeriod
|
||||
*/
|
||||
#define RFLR_HOPPERIOD_FREQFOPPINGPERIOD 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegFifoRxByteAddr (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegModemConfig3
|
||||
*/
|
||||
#define RFLR_MODEMCONFIG3_LOWDATARATEOPTIMIZE_MASK 0xF7
|
||||
#define RFLR_MODEMCONFIG3_LOWDATARATEOPTIMIZE_ON 0x08
|
||||
#define RFLR_MODEMCONFIG3_LOWDATARATEOPTIMIZE_OFF 0x00 // Default
|
||||
|
||||
#define RFLR_MODEMCONFIG3_AGCAUTO_MASK 0xFB
|
||||
#define RFLR_MODEMCONFIG3_AGCAUTO_ON 0x04 // Default
|
||||
#define RFLR_MODEMCONFIG3_AGCAUTO_OFF 0x00
|
||||
|
||||
/*!
|
||||
* RegFeiMsb (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegFeiMid (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegFeiLsb (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegRssiWideband (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegDetectOptimize
|
||||
*/
|
||||
#define RFLR_DETECTIONOPTIMIZE_MASK 0xF8
|
||||
#define RFLR_DETECTIONOPTIMIZE_SF7_TO_SF12 0x03 // Default
|
||||
#define RFLR_DETECTIONOPTIMIZE_SF6 0x05
|
||||
|
||||
/*!
|
||||
* RegInvertIQ
|
||||
*/
|
||||
#define RFLR_INVERTIQ_RX_MASK 0xBF
|
||||
#define RFLR_INVERTIQ_RX_OFF 0x00
|
||||
#define RFLR_INVERTIQ_RX_ON 0x40
|
||||
#define RFLR_INVERTIQ_TX_MASK 0xFE
|
||||
#define RFLR_INVERTIQ_TX_OFF 0x01
|
||||
#define RFLR_INVERTIQ_TX_ON 0x00
|
||||
|
||||
/*!
|
||||
* RegDetectionThreshold
|
||||
*/
|
||||
#define RFLR_DETECTIONTHRESH_SF7_TO_SF12 0x0A // Default
|
||||
#define RFLR_DETECTIONTHRESH_SF6 0x0C
|
||||
|
||||
/*!
|
||||
* RegInvertIQ2
|
||||
*/
|
||||
#define RFLR_INVERTIQ2_ON 0x19
|
||||
#define RFLR_INVERTIQ2_OFF 0x1D
|
||||
|
||||
/*!
|
||||
* RegDioMapping1
|
||||
*/
|
||||
#define RFLR_DIOMAPPING1_DIO0_MASK 0x3F
|
||||
#define RFLR_DIOMAPPING1_DIO0_00 0x00 // Default
|
||||
#define RFLR_DIOMAPPING1_DIO0_01 0x40
|
||||
#define RFLR_DIOMAPPING1_DIO0_10 0x80
|
||||
#define RFLR_DIOMAPPING1_DIO0_11 0xC0
|
||||
|
||||
#define RFLR_DIOMAPPING1_DIO1_MASK 0xCF
|
||||
#define RFLR_DIOMAPPING1_DIO1_00 0x00 // Default
|
||||
#define RFLR_DIOMAPPING1_DIO1_01 0x10
|
||||
#define RFLR_DIOMAPPING1_DIO1_10 0x20
|
||||
#define RFLR_DIOMAPPING1_DIO1_11 0x30
|
||||
|
||||
#define RFLR_DIOMAPPING1_DIO2_MASK 0xF3
|
||||
#define RFLR_DIOMAPPING1_DIO2_00 0x00 // Default
|
||||
#define RFLR_DIOMAPPING1_DIO2_01 0x04
|
||||
#define RFLR_DIOMAPPING1_DIO2_10 0x08
|
||||
#define RFLR_DIOMAPPING1_DIO2_11 0x0C
|
||||
|
||||
#define RFLR_DIOMAPPING1_DIO3_MASK 0xFC
|
||||
#define RFLR_DIOMAPPING1_DIO3_00 0x00 // Default
|
||||
#define RFLR_DIOMAPPING1_DIO3_01 0x01
|
||||
#define RFLR_DIOMAPPING1_DIO3_10 0x02
|
||||
#define RFLR_DIOMAPPING1_DIO3_11 0x03
|
||||
|
||||
/*!
|
||||
* RegDioMapping2
|
||||
*/
|
||||
#define RFLR_DIOMAPPING2_DIO4_MASK 0x3F
|
||||
#define RFLR_DIOMAPPING2_DIO4_00 0x00 // Default
|
||||
#define RFLR_DIOMAPPING2_DIO4_01 0x40
|
||||
#define RFLR_DIOMAPPING2_DIO4_10 0x80
|
||||
#define RFLR_DIOMAPPING2_DIO4_11 0xC0
|
||||
|
||||
#define RFLR_DIOMAPPING2_DIO5_MASK 0xCF
|
||||
#define RFLR_DIOMAPPING2_DIO5_00 0x00 // Default
|
||||
#define RFLR_DIOMAPPING2_DIO5_01 0x10
|
||||
#define RFLR_DIOMAPPING2_DIO5_10 0x20
|
||||
#define RFLR_DIOMAPPING2_DIO5_11 0x30
|
||||
|
||||
#define RFLR_DIOMAPPING2_MAP_MASK 0xFE
|
||||
#define RFLR_DIOMAPPING2_MAP_PREAMBLEDETECT 0x01
|
||||
#define RFLR_DIOMAPPING2_MAP_RSSI 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegVersion (Read Only)
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegPllHop
|
||||
*/
|
||||
#define RFLR_PLLHOP_FASTHOP_MASK 0x7F
|
||||
#define RFLR_PLLHOP_FASTHOP_ON 0x80
|
||||
#define RFLR_PLLHOP_FASTHOP_OFF 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegTcxo
|
||||
*/
|
||||
#define RFLR_TCXO_TCXOINPUT_MASK 0xEF
|
||||
#define RFLR_TCXO_TCXOINPUT_ON 0x10
|
||||
#define RFLR_TCXO_TCXOINPUT_OFF 0x00 // Default
|
||||
|
||||
/*!
|
||||
* RegPaDac
|
||||
*/
|
||||
#define RFLR_PADAC_20DBM_MASK 0xF8
|
||||
#define RFLR_PADAC_20DBM_ON 0x07
|
||||
#define RFLR_PADAC_20DBM_OFF 0x04 // Default
|
||||
|
||||
/*!
|
||||
* RegFormerTemp
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegBitrateFrac
|
||||
*/
|
||||
#define RF_BITRATEFRAC_MASK 0xF0
|
||||
|
||||
/*!
|
||||
* RegAgcRef
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegAgcThresh1
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegAgcThresh2
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegAgcThresh3
|
||||
*/
|
||||
|
||||
/*!
|
||||
* RegPll
|
||||
*/
|
||||
#define RF_PLL_BANDWIDTH_MASK 0x3F
|
||||
#define RF_PLL_BANDWIDTH_75 0x00
|
||||
#define RF_PLL_BANDWIDTH_150 0x40
|
||||
#define RF_PLL_BANDWIDTH_225 0x80
|
||||
#define RF_PLL_BANDWIDTH_300 0xC0 // Default
|
||||
|
||||
#endif // __SX1276_REGS_LORA_H__
|
|
@ -0,0 +1,3 @@
|
|||
SRC_DIR := lora-module
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,41 @@
|
|||
from building import *
|
||||
|
||||
src = []
|
||||
cwd = GetCurrentDir()
|
||||
include_path = [cwd]
|
||||
include_path += [cwd+'/lora-module/inc']
|
||||
|
||||
# add lora radio driver.
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_MODULE_LSD4RF_2F717N30'):
|
||||
src += Split('''
|
||||
lora-module/stm32_adapter/lora-spi-board.c
|
||||
lora-module/stm32_adapter/SX1278_LSD4RF-2F717N30/sx1278-board.c
|
||||
''')
|
||||
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_MODULE_LSD4RF_2R822N30'):
|
||||
src += Split('''
|
||||
lora-module/stm32_adapter/lora-spi-board.c
|
||||
lora-module/stm32_adapter/SX1262_LSD4RF-2R822N30/sx1262-board.c
|
||||
''')
|
||||
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_MODULE_LSD4RF_2R717N40'):
|
||||
src += Split('''
|
||||
lora-module/stm32_adapter/lora-spi-board.c
|
||||
lora-module/stm32_adapter/SX1268_LSD4RF-2R717N40/sx1268-board.c
|
||||
''')
|
||||
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_MODULE_RA_01'):
|
||||
src += Split('''
|
||||
lora-module/stm32_adapter/lora-spi-board.c
|
||||
lora-module/stm32_adapter/SX1278_Ra-01/sx1278-board.c
|
||||
''')
|
||||
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_MODULE_ASR6500S'):
|
||||
src += Split('''
|
||||
lora-module/stm32_adapter/lora-spi-board.c
|
||||
lora-module/stm32_adapter/SX1262_ASR6500S/sx126x-board.c
|
||||
''')
|
||||
|
||||
group = DefineGroup('lora-radio-driver/board', src, depend = ['PKG_USING_LORA_RADIO_DRIVER'], CPPPATH = include_path)
|
||||
|
||||
Return('group')
|
|
@ -0,0 +1,5 @@
|
|||
ifeq ($(CONFIG_LORA_RADIO_DRIVER_USING_RTOS_XIUOS),y)
|
||||
SRC_DIR := hc32_adapter
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,18 @@
|
|||
choice
|
||||
prompt "choose lora device module"
|
||||
default LORA_RADIO_DRIVER_USING_SX1268_E22400M30S
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_SX1268_E22400M30S
|
||||
bool "lora device module select E22-400M30S(SX1268)"
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_SX1278_RA01
|
||||
bool "lora device module select RA01(SX1278)"
|
||||
endchoice
|
||||
|
||||
if LORA_RADIO_DRIVER_USING_SX1268_E22400M30S
|
||||
source "$APP_DIR/lib/lorawan/lora_radio_driver/ports/lora-module/hc32_adapter/SX1268_E22-400M30S/Kconfig"
|
||||
endif
|
||||
|
||||
if LORA_RADIO_DRIVER_USING_SX1278_RA01
|
||||
source "$APP_DIR/lib/lorawan/lora_radio_driver/ports/lora-module/hc32_adapter/SX1278_Ra-01/Kconfig"
|
||||
endif
|
|
@ -0,0 +1,11 @@
|
|||
ifeq ($(CONFIG_LORA_RADIO_DRIVER_USING_SX1268_E22400M30S),y)
|
||||
SRC_DIR := SX1268_E22-400M30S
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_LORA_RADIO_DRIVER_USING_SX1278_RA01),y)
|
||||
SRC_DIR := SX1278_Ra-01
|
||||
endif
|
||||
|
||||
SRC_FILES := lora-spi-board.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,45 @@
|
|||
choice
|
||||
prompt "choose board for lora radio driver"
|
||||
default LORA_RADIO_DRIVER_USING_XISHUTONG_ARM32
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
bool "board select edu-arm32 bsp"
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_XISHUTONG_ARM32
|
||||
bool "board select xishutong-arm32 bsp"
|
||||
endchoice
|
||||
|
||||
if LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
config LORA_SPI_DEV_NAME
|
||||
string "lora device pin driver path"
|
||||
default "/dev/spi1_dev0"
|
||||
|
||||
config LORA_RADIO_RESET_PIN
|
||||
int "hc32 board lora chip reset pin[PI02]"
|
||||
default "133"
|
||||
|
||||
config LORA_RADIO_BUSY_PIN
|
||||
int "hc32 board lora chip busy pin[PE03]"
|
||||
default "2"
|
||||
endif
|
||||
|
||||
if LORA_RADIO_DRIVER_USING_XISHUTONG_ARM32
|
||||
config LORA_SPI_DEV_NAME
|
||||
string "lora device pin driver path"
|
||||
default "/dev/spi2_dev0"
|
||||
|
||||
config LORA_RADIO_RESET_PIN
|
||||
int "xishutong-arm32 board lora chip reset pin[PD02]"
|
||||
default "144"
|
||||
endif
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_LORA_CHIP_SX126X
|
||||
bool "hc32 board using lora chip sx126x"
|
||||
default y
|
||||
|
||||
if LORA_RADIO_DRIVER_USING_LORA_CHIP_SX126X
|
||||
config LORA_RADIO_DRIVER_USING_LORA_CHIP_SX1268
|
||||
bool "hc32 board using lora chip sx1268"
|
||||
default y
|
||||
endif
|
||||
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := sx1268-board.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,394 @@
|
|||
/*!
|
||||
* \file sx1268-board.c
|
||||
*
|
||||
* \brief Target board SX126x shield driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sx126x-board.c
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-06-06
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: sx126x-board.c
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-06-06
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include <lora-radio.h>
|
||||
#include <sx126x-board.h>
|
||||
|
||||
#define LOG_TAG "LoRa.Board.E22-400M30S(SX1268)" // E22-400M30S
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include <lora-radio-debug.h>
|
||||
|
||||
/*!
|
||||
* Debug GPIO pins objects
|
||||
*/
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
Gpio_t DbgPinTx;
|
||||
Gpio_t DbgPinRx;
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40004 )
|
||||
int stm32_pin_get(char *pin_name)
|
||||
{
|
||||
/* eg: pin_name : "PA.4" ( GPIOA, GPIO_PIN_4 )--> drv_gpio.c pin */
|
||||
char pin_index = strtol(&pin_name[3],0,10);
|
||||
|
||||
if(pin_name[1] < 'A' || pin_name[1] > 'Z')
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return (16 * (pin_name[1]-'A') + pin_index);
|
||||
}
|
||||
#endif
|
||||
#endif /* LORA_RADIO_GPIO_SETUP_BY_PIN_NAME */
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
void SX126xIoInit( void )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_NSS_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_BUSY_PIN, PIN_MODE_INPUT);
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#if defined( LORA_RADIO_DIO2_PIN )
|
||||
rt_pin_mode(LORA_RADIO_DIO2_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#endif
|
||||
#if defined( LORA_RADIO_RFSW1_PIN ) && defined ( LORA_RADIO_RFSW2_PIN )
|
||||
rt_pin_mode(LORA_RADIO_RFSW1_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_RFSW2_PIN, PIN_MODE_OUTPUT);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void SX126xIoIrqInit( DioIrqHandler dioIrq )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING, dioIrq,(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
}
|
||||
|
||||
void SX126xIoDeInit( void )
|
||||
{
|
||||
//// GpioInit( &SX126x.Spi.Nss, RADIO_NSS, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_PULL_UP, 1 );
|
||||
//// GpioInit( &SX126x.BUSY, RADIO_BUSY, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
//// GpioInit( &SX126x.DIO1, RADIO_DIO_1, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
SX126xAntSwOff();
|
||||
}
|
||||
|
||||
void SX126xIoDbgInit( void )
|
||||
{
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
GpioInit( &DbgPinTx, RADIO_DBG_PIN_TX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
GpioInit( &DbgPinRx, RADIO_DBG_PIN_RX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xIoTcxoInit( void )
|
||||
{
|
||||
// Initialize TCXO control
|
||||
CalibrationParams_t calibParam;
|
||||
|
||||
// +clear OSC_START_ERR for reboot or cold-start from sleep
|
||||
SX126xClearDeviceErrors();
|
||||
|
||||
// TCXO_CTRL_1_7V -> TCXO_CTRL_2_7V 64*15.0625US
|
||||
SX126xSetDio3AsTcxoCtrl( TCXO_CTRL_2_7V, 320);//SX126xGetBoardTcxoWakeupTime( ) << 6 ); // convert from ms to SX126x time base
|
||||
|
||||
calibParam.Value = 0x7F;
|
||||
SX126xCalibrate( calibParam );
|
||||
}
|
||||
|
||||
uint32_t SX126xGetBoardTcxoWakeupTime( void )
|
||||
{
|
||||
return BOARD_TCXO_WAKEUP_TIME;
|
||||
}
|
||||
|
||||
void SX126xReset( void )
|
||||
{
|
||||
SX126X_DELAY_MS( 10 );
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_write(LORA_RADIO_RESET_PIN, PIN_LOW);
|
||||
SX126X_DELAY_MS( 20 );
|
||||
// internal pull-up
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_INPUT);
|
||||
SX126X_DELAY_MS( 10 );
|
||||
}
|
||||
|
||||
void SX126xWaitOnBusy( void )
|
||||
{
|
||||
while( rt_pin_read( LORA_RADIO_BUSY_PIN ) == PIN_HIGH );
|
||||
}
|
||||
|
||||
void SX126xAntSwOn( void )
|
||||
{
|
||||
// No need
|
||||
}
|
||||
|
||||
void SX126xAntSwOff( void )
|
||||
{
|
||||
////GpioInit( &AntPow, RADIO_ANT_SWITCH_POWER, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
|
||||
#if defined( LORA_RADIO_RFSW1_PIN ) && defined ( LORA_RADIO_RFSW2_PIN )
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xSetAntSw( RadioOperatingModes_t mode )
|
||||
{
|
||||
if( mode == MODE_TX )
|
||||
{ // Transmit
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_HIGH);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
}
|
||||
else
|
||||
{
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_HIGH);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
static int pin_fd = -1;
|
||||
void SX126xIoInit( void )
|
||||
{
|
||||
if (pin_fd < 0) {
|
||||
pin_fd = PrivOpen("/dev/pin_dev", O_RDWR);
|
||||
if (pin_fd < 0) {
|
||||
printf("open %s error\n", "/dev/pin_dev");
|
||||
return;
|
||||
}
|
||||
}
|
||||
#ifdef LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
struct PinParam pin_param;
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_OUTPUT;
|
||||
pin_param.pin = LORA_RADIO_RFSW1_PIN;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
struct PinStat pin_stat;
|
||||
pin_stat.pin = LORA_RADIO_RFSW1_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_OUTPUT;
|
||||
pin_param.pin = LORA_RADIO_RFSW2_PIN;
|
||||
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
pin_stat.pin = LORA_RADIO_RFSW2_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_INPUT;
|
||||
pin_param.pin = LORA_RADIO_BUSY_PIN;
|
||||
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
pin_stat.pin = LORA_RADIO_BUSY_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xIoIrqInit( DioIrqHandler dioIrq )
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void SX126xIoDeInit( void )
|
||||
{
|
||||
SX126xAntSwOff();
|
||||
}
|
||||
|
||||
void SX126xIoDbgInit( void )
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void SX126xIoTcxoInit( void )
|
||||
{
|
||||
// Initialize TCXO control
|
||||
CalibrationParams_t calibParam;
|
||||
|
||||
// +clear OSC_START_ERR for reboot or cold-start from sleep
|
||||
SX126xClearDeviceErrors();
|
||||
|
||||
// TCXO_CTRL_1_7V -> TCXO_CTRL_2_7V 64*15.0625US
|
||||
SX126xSetDio3AsTcxoCtrl( TCXO_CTRL_2_7V, 320);//SX126xGetBoardTcxoWakeupTime( ) << 6 ); // convert from ms to SX126x time base
|
||||
|
||||
calibParam.Value = 0x7F;
|
||||
SX126xCalibrate( calibParam );
|
||||
}
|
||||
|
||||
uint32_t SX126xGetBoardTcxoWakeupTime( void )
|
||||
{
|
||||
return BOARD_TCXO_WAKEUP_TIME;
|
||||
}
|
||||
|
||||
void SX126xReset( void )
|
||||
{
|
||||
SX126X_DELAY_MS( 10 );
|
||||
|
||||
if (pin_fd < 0) {
|
||||
pin_fd = PrivOpen("/dev/pin_dev", O_RDWR);
|
||||
if (pin_fd < 0) {
|
||||
printf("open %s error\n", "/dev/pin_dev");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
struct PinParam pin_param;
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_OUTPUT;
|
||||
pin_param.pin = LORA_RADIO_RESET_PIN;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
struct PinStat pin_stat;
|
||||
pin_stat.pin = LORA_RADIO_RESET_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
// Wait 20 ms
|
||||
SX126X_DELAY_MS( 20 );
|
||||
|
||||
// Configure RESET as input
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_INPUT;
|
||||
pin_param.pin = LORA_RADIO_RESET_PIN;
|
||||
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
// Wait 10 ms
|
||||
SX126X_DELAY_MS( 10 );
|
||||
}
|
||||
|
||||
void SX126xWaitOnBusy( void )
|
||||
{
|
||||
if (pin_fd < 0) {
|
||||
pin_fd = PrivOpen("/dev/pin_dev", O_RDWR);
|
||||
if (pin_fd < 0) {
|
||||
printf("open %s error\n", "/dev/pin_dev");
|
||||
return;
|
||||
}
|
||||
}
|
||||
#ifdef LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
struct PinStat pin_stat;
|
||||
pin_stat.pin = LORA_RADIO_BUSY_PIN;
|
||||
PrivRead(pin_fd, &pin_stat, 1);
|
||||
|
||||
while (GPIO_HIGH == pin_stat.val) {
|
||||
PrivRead(pin_fd, &pin_stat, 1);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xAntSwOn( void )
|
||||
{
|
||||
// No need
|
||||
}
|
||||
|
||||
void SX126xAntSwOff( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
struct PinStat pin_stat;
|
||||
pin_stat.pin = LORA_RADIO_RFSW1_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_stat.pin = LORA_RADIO_RFSW2_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xSetAntSw( RadioOperatingModes_t mode )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
struct PinStat pin_stat;
|
||||
if( mode == MODE_TX ) { // Transmit
|
||||
pin_stat.pin = LORA_RADIO_RFSW1_PIN;
|
||||
pin_stat.val = GPIO_HIGH;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_stat.pin = LORA_RADIO_RFSW2_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
} else {
|
||||
pin_stat.pin = LORA_RADIO_RFSW1_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
pin_stat.pin = LORA_RADIO_RFSW2_PIN;
|
||||
pin_stat.val = GPIO_HIGH;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
bool SX126xCheckRfFrequency( uint32_t frequency )
|
||||
{
|
||||
// Implement check. Currently all frequencies are supported
|
||||
return true;
|
||||
}
|
||||
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
void SX126xDbgPinTxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinTx, state );
|
||||
}
|
||||
|
||||
void SX126xDbgPinRxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinRx, state );
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,18 @@
|
|||
config LORA_SPI_DEV_NAME
|
||||
string "lora device pin driver path"
|
||||
default "/dev/spi1_dev0"
|
||||
|
||||
config LORA_RADIO_RESET_PIN
|
||||
int "hc32 board lora chip reset pin[PI02]"
|
||||
default "133"
|
||||
|
||||
config LORA_RADIO_DRIVER_USING_LORA_CHIP_SX127X
|
||||
bool "hc32 board using lora chip sx127x"
|
||||
default y
|
||||
|
||||
if LORA_RADIO_DRIVER_USING_LORA_CHIP_SX127X
|
||||
config LORA_RADIO_DRIVER_USING_LORA_CHIP_SX1278
|
||||
bool "hc32 board using lora chip sx1278"
|
||||
default y
|
||||
endif
|
||||
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := sx1278-board.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,283 @@
|
|||
/*!
|
||||
* \file sx1278-board.c
|
||||
*
|
||||
* \brief Target board SX127x driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sx127x-board.c
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: sx127x-board.c
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include <lora-radio.h>
|
||||
#include <sx127x.h>
|
||||
#include <sx127x-board.h>
|
||||
|
||||
#define LOG_TAG "LoRa.Board.Ra-01(SX1278)"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include <lora-radio-debug.h>
|
||||
/*!
|
||||
* Flag used to set the RF switch control pins in low power mode when the radio is not active.
|
||||
*/
|
||||
static bool RadioIsActive = false;
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
static int pin_fd = -1;
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
/*!
|
||||
* \brief DIO 0 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio0IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 1 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio1IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 2 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio2IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 3 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio3IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 4 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio4IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 5 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio5IrqEvent( void *args );
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* Debug GPIO pins objects
|
||||
*/
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
Gpio_t DbgPinTx;
|
||||
Gpio_t DbgPinRx;
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40004 )
|
||||
int stm32_pin_get(char *pin_name)
|
||||
{
|
||||
/* eg: pin_name : "PA.4" ( GPIOA, GPIO_PIN_4 )--> drv_gpio.c pin */
|
||||
char pin_index = strtol(&pin_name[3],0,10);
|
||||
|
||||
if(pin_name[1] < 'A' || pin_name[1] > 'Z')
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return (16 * (pin_name[1]-'A') + pin_index);
|
||||
}
|
||||
#endif
|
||||
#endif /* LORA_RADIO_GPIO_SETUP_BY_PIN_NAME */
|
||||
|
||||
void SX127xIoInit( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
// RT-Thread
|
||||
rt_pin_mode(LORA_RADIO_NSS_PIN, PIN_MODE_OUTPUT);
|
||||
|
||||
rt_pin_mode(LORA_RADIO_DIO0_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#ifdef LORA_RADIO_DIO1_PIN
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO2_PIN
|
||||
rt_pin_mode(LORA_RADIO_DIO2_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#endif
|
||||
|
||||
#else
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX127xIoIrqInit( DioIrqHandler **irqHandlers )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
#ifdef LORA_RADIO_DIO0_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO0_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio0IrqEvent,(void*)"rf-dio0");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO0_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO1_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio1IrqEvent,(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO2_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO2_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio2IrqEvent,(void*)"rf-dio2");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO2_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX127xIoDeInit( void )
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void SX127xIoDbgInit( void )
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
void SX127xReset( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
// Set RESET pin to 0
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_write(LORA_RADIO_RESET_PIN, PIN_LOW);
|
||||
|
||||
// Wait 1 ms
|
||||
SX127X_DELAY_MS( 1 );
|
||||
|
||||
// Configure RESET as input
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_INPUT);
|
||||
|
||||
// Wait 6 ms
|
||||
SX127X_DELAY_MS( 6 );
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
if (pin_fd < 0) {
|
||||
pin_fd = PrivOpen("/dev/pin_dev", O_RDWR);
|
||||
if (pin_fd < 0) {
|
||||
printf("open %s error\n", "/dev/pin_dev");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
struct PinParam pin_param;
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_OUTPUT;
|
||||
pin_param.pin = LORA_RADIO_RESET_PIN;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
struct PinStat pin_stat;
|
||||
pin_stat.pin = LORA_RADIO_RESET_PIN;
|
||||
pin_stat.val = GPIO_LOW;
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
// Wait 1 ms
|
||||
SX127X_DELAY_MS( 1 );
|
||||
|
||||
// Configure RESET as input
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_INPUT;
|
||||
pin_param.pin = LORA_RADIO_RESET_PIN;
|
||||
|
||||
ioctl_cfg.ioctl_driver_type = PIN_TYPE;
|
||||
ioctl_cfg.args = &pin_param;
|
||||
PrivIoctl(pin_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
// Wait 6 ms
|
||||
SX127X_DELAY_MS( 6 );
|
||||
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void SX127xSetAntSwLowPower( bool status )
|
||||
{
|
||||
if( RadioIsActive != status )
|
||||
{
|
||||
RadioIsActive = status;
|
||||
|
||||
if( status == false )
|
||||
{
|
||||
SX127xAntSwInit( );
|
||||
}
|
||||
else
|
||||
{
|
||||
SX127xAntSwDeInit( );
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SX127xAntSwInit( void )
|
||||
{
|
||||
}
|
||||
|
||||
void SX127xAntSwDeInit( void )
|
||||
{
|
||||
}
|
||||
|
||||
/* TX and RX ANT switch */
|
||||
|
||||
void SX127xSetAntSw( uint8_t opMode )
|
||||
{
|
||||
}
|
||||
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
void SX127xDbgPinTxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinTx, state );
|
||||
}
|
||||
|
||||
void SX127xDbgPinRxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinRx, state );
|
||||
}
|
||||
#endif
|
||||
|
||||
uint8_t SX127xGetPaSelect( int8_t power )
|
||||
{
|
||||
return RF_PACONFIG_PASELECT_PABOOST;
|
||||
}
|
||||
|
||||
bool SX127xCheckRfFrequency( uint32_t frequency )
|
||||
{
|
||||
// Implement check. Currently all frequencies are supported,todo depend on board
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,158 @@
|
|||
/*!
|
||||
* \file lora-spi-board.c
|
||||
*
|
||||
* \brief spi peripheral initlize,it depend on mcu platform.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file lora-spi-board.c
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lora-spi-board.c
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#ifdef LORA_RADIO_DRIVER_USING_LORA_CHIP_SX126X
|
||||
#include <sx126x-board.h>
|
||||
#elif defined LORA_RADIO_DRIVER_USING_LORA_CHIP_SX127X
|
||||
#include <sx127x-board.h>
|
||||
#endif
|
||||
|
||||
#define LOG_TAG "LoRa.HC32.SPI"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include <lora-radio-debug.h>
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
/* for get GPIO fort,eg GPIOA */
|
||||
#ifndef GET_GPIO_PORT
|
||||
#define GET_GPIO_PORT(pin) (GPIO_TypeDef *)( GPIOA_BASE + (uint32_t) ( pin >> 4 ) * 0x0400UL )
|
||||
#endif
|
||||
#ifndef GET_GPIO_PIN
|
||||
#define GET_GPIO_PIN(pin) (rt_uint16_t)( 1 << ( pin & 0x0F ) ) // for get GPIO_PIN, eg: GPIO_PIN_6
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40002 )
|
||||
extern int stm32_pin_get(char *pin_name);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
struct rt_spi_device *lora_radio_spi_init(const char *bus_name, const char *lora_device_name, rt_uint8_t param)
|
||||
{
|
||||
rt_err_t res;
|
||||
struct rt_spi_device *lora_radio_spi_device;
|
||||
|
||||
RT_ASSERT(bus_name);
|
||||
|
||||
{
|
||||
res = rt_hw_spi_device_attach( bus_name, lora_device_name, LORA_RADIO_NSS_PIN);
|
||||
|
||||
if (res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_bus_attach_device failed!\r\n");
|
||||
return RT_NULL;
|
||||
}
|
||||
|
||||
lora_radio_spi_device = (struct rt_spi_device *)rt_device_find(lora_device_name);
|
||||
if (!lora_radio_spi_device)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"spi sample run failed! cant't find %s device!\n", lora_device_name);
|
||||
return RT_NULL;
|
||||
}
|
||||
}
|
||||
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"find %s device!\n", lora_device_name);
|
||||
|
||||
/* config spi */
|
||||
{
|
||||
struct rt_spi_configuration cfg;
|
||||
cfg.data_width = 8;
|
||||
cfg.mode = RT_SPI_MASTER | RT_SPI_MODE_0 | RT_SPI_MSB; /* SPI Compatible: Mode 0. */
|
||||
cfg.max_hz = 8 * 1000000; /* max 10M */
|
||||
|
||||
res = rt_spi_configure(lora_radio_spi_device, &cfg);
|
||||
|
||||
if (res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_configure failed!\r\n");
|
||||
}
|
||||
res = rt_spi_take_bus(lora_radio_spi_device);
|
||||
if (res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_take_bus failed!\r\n");
|
||||
}
|
||||
|
||||
res = rt_spi_release_bus(lora_radio_spi_device);
|
||||
|
||||
if(res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_release_bus failed!\r\n");
|
||||
}
|
||||
}
|
||||
|
||||
return lora_radio_spi_device;
|
||||
}
|
||||
|
||||
/**
|
||||
* This function releases memory
|
||||
*
|
||||
* @param dev the pointer of device driver structure
|
||||
*/
|
||||
void lora_radio_spi_deinit(struct rt_spi_device *dev)
|
||||
{
|
||||
RT_ASSERT(dev);
|
||||
rt_spi_release_bus(dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
int lora_radio_spi_init(void)
|
||||
{
|
||||
int spi_fd;
|
||||
spi_fd = PrivOpen(LORA_SPI_DEV_NAME, O_RDWR);
|
||||
if (spi_fd < 0) {
|
||||
printf("open %s error\n", LORA_SPI_DEV_NAME);
|
||||
return -1;
|
||||
}
|
||||
|
||||
struct SpiMasterParam spi_master_param;
|
||||
spi_master_param.spi_data_bit_width = 8;
|
||||
spi_master_param.spi_work_mode = SPI_MODE_0 | SPI_MSB;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SPI_TYPE;
|
||||
ioctl_cfg.args = &spi_master_param;
|
||||
PrivIoctl(spi_fd, OPE_CFG, &ioctl_cfg);
|
||||
|
||||
ioctl_cfg.args = NULL;
|
||||
PrivIoctl(spi_fd, OPE_INT, &ioctl_cfg);
|
||||
|
||||
PrivClose(spi_fd);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void lora_radio_spi_deinit(int spi_fd)
|
||||
{
|
||||
PrivClose(spi_fd);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,256 @@
|
|||
/*!
|
||||
* \file sx126x-board.h
|
||||
*
|
||||
* \brief Target board SX126x driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sx126x-board.h
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: sx126x-board.h
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#ifndef __SX126x_BOARD_H__
|
||||
#define __SX126x_BOARD_H__
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <sx126x.h>
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40002 )
|
||||
#define LORA_RADIO_NSS_PIN stm32_pin_get(LORA_RADIO_NSS_PIN_NAME)
|
||||
#define LORA_RADIO_BUSY_PIN stm32_pin_get(LORA_RADIO_BUSY_PIN_NAME)
|
||||
#define LORA_RADIO_DIO1_PIN stm32_pin_get(LORA_RADIO_DIO1_PIN_NAME)
|
||||
#define LORA_RADIO_RESET_PIN stm32_pin_get(LORA_RADIO_RESET_PIN_NAME)
|
||||
#if defined( LORA_RADIO_DIO2_PIN_NAME )
|
||||
#define LORA_RADIO_DIO2_PIN stm32_pin_get(LORA_RADIO_DIO2_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_RFSW1_PIN_NAME ) && defined ( LORA_RADIO_RFSW2_PIN_NAME )
|
||||
#define LORA_RADIO_RFSW1_PIN stm32_pin_get(LORA_RADIO_RFSW1_PIN_NAME)
|
||||
#define LORA_RADIO_RFSW2_PIN stm32_pin_get(LORA_RADIO_RFSW2_PIN_NAME)
|
||||
#endif
|
||||
#else
|
||||
#define LORA_RADIO_NSS_PIN rt_pin_get(LORA_RADIO_NSS_PIN_NAME)
|
||||
#define LORA_RADIO_BUSY_PIN rt_pin_get(LORA_RADIO_BUSY_PIN_NAME)
|
||||
#define LORA_RADIO_DIO1_PIN rt_pin_get(LORA_RADIO_DIO1_PIN_NAME)
|
||||
#define LORA_RADIO_RESET_PIN rt_pin_get(LORA_RADIO_RESET_PIN_NAME)
|
||||
#if defined( LORA_RADIO_DIO2_PIN_NAME )
|
||||
#define LORA_RADIO_DIO2_PIN rt_pin_get(LORA_RADIO_DIO2_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_RFSW1_PIN_NAME ) && defined ( LORA_RADIO_RFSW2_PIN_NAME )
|
||||
#define LORA_RADIO_RFSW1_PIN rt_pin_get(LORA_RADIO_RFSW1_PIN_NAME)
|
||||
#define LORA_RADIO_RFSW2_PIN rt_pin_get(LORA_RADIO_RFSW2_PIN_NAME)
|
||||
#endif
|
||||
#endif/* ( RT_VER_NUM <= 0x40002) */
|
||||
|
||||
#else
|
||||
/* if not use env\menuconfig,define Radio GPIO directly.*/
|
||||
#ifndef LORA_RADIO_NSS_PIN
|
||||
#define LORA_RADIO_NSS_PIN GET_PIN(A,15)
|
||||
#endif
|
||||
#ifndef LORA_RADIO_RESET_PIN
|
||||
#define LORA_RADIO_RESET_PIN GET_PIN(A,7)
|
||||
#endif
|
||||
#ifndef LORA_RADIO_DIO1_PIN
|
||||
#define LORA_RADIO_DIO1_PIN GET_PIN(B,1)
|
||||
#endif
|
||||
#ifndef LORA_RADIO_BUSY_PIN
|
||||
#define LORA_RADIO_BUSY_PIN GET_PIN(B,2)
|
||||
#endif
|
||||
#ifndef LORA_RADIO_RFSW1_PIN
|
||||
#define LORA_RADIO_RFSW1_PIN GET_PIN(B,0)
|
||||
#endif
|
||||
#ifndef LORA_RADIO_RFSW2_PIN
|
||||
#define LORA_RADIO_RFSW2_PIN GET_PIN(C,5)
|
||||
#endif
|
||||
#endif // end of LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
#ifdef LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
#ifndef LORA_RADIO_RESET_PIN
|
||||
#define LORA_RADIO_RESET_PIN 133//PI02 on HC32F4A0_I
|
||||
#endif
|
||||
|
||||
#ifndef LORA_RADIO_BUSY_PIN
|
||||
#define LORA_RADIO_BUSY_PIN 2//PE03 on HC32F4A0_I
|
||||
#endif
|
||||
|
||||
#ifndef LORA_RADIO_RFSW1_PIN
|
||||
#define LORA_RADIO_RFSW1_PIN 140//PC11 on HC32F4A0_I TX_EN
|
||||
#endif
|
||||
|
||||
#ifndef LORA_RADIO_RFSW2_PIN
|
||||
#define LORA_RADIO_RFSW2_PIN 143//PD01 on HC32F4A0_I RX_EN
|
||||
#endif
|
||||
|
||||
#ifndef LORA_SPI_DEV_NAME
|
||||
#define LORA_SPI_DEV_NAME "/dev/spi1_dev0"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_XISHUTONG_ARM32
|
||||
#ifndef LORA_RADIO_RESET_PIN
|
||||
#define LORA_RADIO_RESET_PIN 144//PD02 on xishutong-arm32
|
||||
#endif
|
||||
|
||||
#ifndef LORA_SPI_DEV_NAME
|
||||
#define LORA_SPI_DEV_NAME "/dev/spi2_dev0"
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/** @addtogroup LORA_RADIO_BOARD
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup LORA_RADIO_BOARD_SX126X
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*!
|
||||
* Defines the time required for the TCXO to wakeup [ms].
|
||||
*/
|
||||
#define BOARD_TCXO_WAKEUP_TIME 2
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#define SX126X_DELAY_MS( ms ) rt_thread_mdelay(ms)
|
||||
#define SX126X_BLOCK_DELAY_1MS() rt_hw_us_delay(999)
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
#define SX126X_DELAY_MS( ms ) PrivTaskDelay(ms)
|
||||
#define SX126X_BLOCK_DELAY_1MS() PrivTaskDelay(1)
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* \brief Initializes the radio I/Os pins interface
|
||||
*/
|
||||
void SX126xIoInit( void );
|
||||
|
||||
/*!
|
||||
* \brief Initializes DIO IRQ handlers
|
||||
*
|
||||
* \param [IN] irqHandlers Array containing the IRQ callback functions
|
||||
*/
|
||||
void SX126xIoIrqInit( DioIrqHandler dioIrq );
|
||||
|
||||
/*!
|
||||
* \brief De-initializes the radio I/Os pins interface.
|
||||
*
|
||||
* \remark Useful when going in MCU low power modes
|
||||
*/
|
||||
void SX126xIoDeInit( void );
|
||||
|
||||
/*!
|
||||
* \brief Initializes the TCXO power pin.
|
||||
*/
|
||||
void SX126xIoTcxoInit( void );
|
||||
|
||||
/*!
|
||||
* \brief Initializes the radio debug pins.
|
||||
*/
|
||||
void SX126xIoDbgInit( void );
|
||||
|
||||
/*!
|
||||
* \brief HW Reset of the radio
|
||||
*/
|
||||
void SX126xReset( void );
|
||||
|
||||
/*!
|
||||
* \brief Blocking loop to wait while the Busy pin in high
|
||||
*/
|
||||
void SX126xWaitOnBusy( void );
|
||||
|
||||
/*!
|
||||
* \brief Initializes the RF Switch I/Os pins interface
|
||||
*/
|
||||
void SX126xAntSwOn( void );
|
||||
|
||||
/*!
|
||||
* \brief De-initializes the RF Switch I/Os pins interface
|
||||
*
|
||||
* \remark Needed to decrease the power consumption in MCU low power modes
|
||||
*/
|
||||
void SX126xAntSwOff( void );
|
||||
|
||||
/*!
|
||||
* \brief Set the RF Switch I/Os pins interface
|
||||
*/
|
||||
void SX126xSetAntSw( RadioOperatingModes_t mode );
|
||||
|
||||
/*!
|
||||
* \brief Checks if the given RF frequency is supported by the hardware
|
||||
*
|
||||
* \param [IN] frequency RF frequency to be checked
|
||||
* \retval isSupported [true: supported, false: unsupported]
|
||||
*/
|
||||
bool SX126xCheckRfFrequency( uint32_t frequency );
|
||||
|
||||
/*!
|
||||
* \brief Gets the Defines the time required for the TCXO to wakeup [ms].
|
||||
*
|
||||
* \retval time Board TCXO wakeup time in ms.
|
||||
*/
|
||||
uint32_t SX126xGetBoardTcxoWakeupTime( void );
|
||||
|
||||
/*!
|
||||
* \brief Writes new Tx debug pin state
|
||||
*
|
||||
* \param [IN] state Debug pin state
|
||||
*/
|
||||
void SX126xDbgPinTxWrite( uint8_t state );
|
||||
|
||||
/*!
|
||||
* \brief Writes new Rx debug pin state
|
||||
*
|
||||
* \param [IN] state Debug pin state
|
||||
*/
|
||||
void SX126xDbgPinRxWrite( uint8_t state );
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif // __SX126x_BOARD_H__
|
|
@ -0,0 +1,261 @@
|
|||
/*!
|
||||
* \file sx127x-board.h
|
||||
*
|
||||
* \brief Target board SX127x driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*
|
||||
* \author AIIT XUOS Lab
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sx127x-board.h
|
||||
* @brief support lora-radio-driver for XiUOS
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-03-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: sx127x-board.h
|
||||
Description: support lora-radio-driver for XiUOS
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-03-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、add LORA_RADIO_DRIVER_USING_RTOS_XIUOS to support XiUOS.
|
||||
*************************************************/
|
||||
|
||||
#ifndef __SX127x_BOARD_H__
|
||||
#define __SX127x_BOARD_H__
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <sx127x.h>
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40002 )
|
||||
#define LORA_RADIO_NSS_PIN stm32_pin_get(LORA_RADIO_NSS_PIN_NAME)
|
||||
#define LORA_RADIO_RESET_PIN stm32_pin_get(LORA_RADIO_RESET_PIN_NAME)
|
||||
#define LORA_RADIO_DIO0_PIN stm32_pin_get(LORA_RADIO_DIO0_PIN_NAME)
|
||||
#if defined( LORA_RADIO_DIO1_PIN_NAME )
|
||||
#define LORA_RADIO_DIO1_PIN stm32_pin_get(LORA_RADIO_DIO1_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO2_PIN_NAME )
|
||||
#define LORA_RADIO_DIO2_PIN stm32_pin_get(LORA_RADIO_DIO2_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO3_PIN_NAME )
|
||||
#define LORA_RADIO_DIO1_PIN stm32_pin_get(LORA_RADIO_DIO3_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO4_PIN_NAME )
|
||||
#define LORA_RADIO_DIO2_PIN stm32_pin_get(LORA_RADIO_DIO4_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO5_PIN_NAME )
|
||||
#define LORA_RADIO_DIO1_PIN stm32_pin_get(LORA_RADIO_DIO5_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_RFSW1_PIN_NAME ) && defined ( LORA_RADIO_RFSW2_PIN_NAME )
|
||||
#define LORA_RADIO_RFSW1_PIN stm32_pin_get(LORA_RADIO_RFSW1_PIN_NAME)
|
||||
#define LORA_RADIO_RFSW2_PIN stm32_pin_get(LORA_RADIO_RFSW2_PIN_NAME)
|
||||
#endif
|
||||
#else
|
||||
#define LORA_RADIO_NSS_PIN rt_pin_get(LORA_RADIO_NSS_PIN_NAME)
|
||||
#define LORA_RADIO_RESET_PIN rt_pin_get(LORA_RADIO_RESET_PIN_NAME)
|
||||
#define LORA_RADIO_DIO0_PIN rt_pin_get(LORA_RADIO_DIO0_PIN_NAME)
|
||||
#if defined( LORA_RADIO_DIO1_PIN_NAME )
|
||||
#define LORA_RADIO_DIO1_PIN rt_pin_get(LORA_RADIO_DIO1_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO2_PIN_NAME )
|
||||
#define LORA_RADIO_DIO2_PIN rt_pin_get(LORA_RADIO_DIO2_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO3_PIN_NAME )
|
||||
#define LORA_RADIO_DIO1_PIN rt_pin_get(LORA_RADIO_DIO3_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO4_PIN_NAME )
|
||||
#define LORA_RADIO_DIO2_PIN rt_pin_get(LORA_RADIO_DIO4_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_DIO5_PIN_NAME )
|
||||
#define LORA_RADIO_DIO1_PIN rt_pin_get(LORA_RADIO_DIO5_PIN_NAME)
|
||||
#endif
|
||||
#if defined( LORA_RADIO_RFSW1_PIN_NAME ) && defined ( LORA_RADIO_RFSW2_PIN_NAME )
|
||||
#define LORA_RADIO_RFSW1_PIN rt_pin_get(LORA_RADIO_RFSW1_PIN_NAME)
|
||||
#define LORA_RADIO_RFSW2_PIN rt_pin_get(LORA_RADIO_RFSW2_PIN_NAME)
|
||||
#endif
|
||||
#endif /* ( RT_VER_NUM <= 0x40002) */
|
||||
|
||||
#else
|
||||
/* if not use env\menuconfig,define Radio GPIO directly.*/
|
||||
#ifndef LORA_RADIO_NSS_PIN
|
||||
#define LORA_RADIO_NSS_PIN GET_PIN(A,15)
|
||||
#endif
|
||||
#ifndef LORA_RADIO_RESET_PIN
|
||||
#define LORA_RADIO_RESET_PIN GET_PIN(A,7)
|
||||
#endif
|
||||
#ifndef LORA_RADIO_DIO0_PIN
|
||||
#define LORA_RADIO_DIO0_PIN GET_PIN(B,1)
|
||||
#endif
|
||||
|
||||
|
||||
#endif // end of LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
#ifdef LORA_RADIO_DRIVER_USING_EDU_ARM32
|
||||
#ifndef LORA_RADIO_RESET_PIN
|
||||
#define LORA_RADIO_RESET_PIN 133//PI02 on HC32F4A0
|
||||
#endif
|
||||
|
||||
#ifndef LORA_SPI_DEV_NAME
|
||||
#define LORA_SPI_DEV_NAME "/dev/spi1_dev0"
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/** @addtogroup LORA_RADIO_BOARD_SX127X
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_RT_THREAD
|
||||
/*!
|
||||
* \brief delayms for radio access
|
||||
*/
|
||||
#define SX127X_DELAY_MS(ms) rt_thread_mdelay(ms)
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_RTOS_XIUOS
|
||||
#define SX127X_DELAY_MS(ms) PrivTaskDelay(ms)
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* \brief Initializes the radio I/Os pins interface
|
||||
*/
|
||||
void SX127xIoInit( void );
|
||||
|
||||
/*!
|
||||
* \brief De-initializes the radio I/Os pins interface.
|
||||
*
|
||||
* \remark Useful when going in MCU low power modes
|
||||
*/
|
||||
void SX127xIoDeInit( void );
|
||||
|
||||
/*!
|
||||
* \brief Initializes the TCXO power pin.
|
||||
*/
|
||||
void SX127xIoTcxoInit( void );
|
||||
|
||||
/*!
|
||||
* \brief Initializes the radio debug pins.
|
||||
*/
|
||||
void SX127xIoDbgInit( void );
|
||||
|
||||
/*!
|
||||
* \brief Resets the radio
|
||||
*/
|
||||
void SX127xReset( void );
|
||||
|
||||
/*!
|
||||
* \brief Gets the board PA selection configuration
|
||||
*
|
||||
* \param [IN] power Selects the right PA according to the wanted power.
|
||||
* \retval PaSelect RegPaConfig PaSelect value
|
||||
*/
|
||||
uint8_t SX127xGetPaSelect( int8_t power );
|
||||
|
||||
/*!
|
||||
* \brief Set the RF Switch I/Os pins in low power mode
|
||||
*
|
||||
* \param [IN] status enable or disable
|
||||
*/
|
||||
void SX127xSetAntSwLowPower( bool status );
|
||||
|
||||
/*!
|
||||
* \brief Initializes the RF Switch I/Os pins interface
|
||||
*/
|
||||
void SX127xAntSwInit( void );
|
||||
|
||||
/*!
|
||||
* \brief De-initializes the RF Switch I/Os pins interface
|
||||
*
|
||||
* \remark Needed to decrease the power consumption in MCU low power modes
|
||||
*/
|
||||
void SX127xAntSwDeInit( void );
|
||||
|
||||
/*!
|
||||
* \brief Controls the antenna switch if necessary.
|
||||
*
|
||||
* \remark see errata note
|
||||
*
|
||||
* \param [IN] opMode Current radio operating mode
|
||||
*/
|
||||
void SX127xSetAntSw( uint8_t opMode );
|
||||
|
||||
/*!
|
||||
* \brief Checks if the given RF frequency is supported by the hardware
|
||||
*
|
||||
* \param [IN] frequency RF frequency to be checked
|
||||
* \retval isSupported [true: supported, false: unsupported]
|
||||
*/
|
||||
bool SX127xCheckRfFrequency( uint32_t frequency );
|
||||
|
||||
/*!
|
||||
* \brief Enables/disables the TCXO if available on board design.
|
||||
*
|
||||
* \param [IN] state TCXO enabled when true and disabled when false.
|
||||
*/
|
||||
void SX127xSetBoardTcxo( uint8_t state );
|
||||
|
||||
/*!
|
||||
* \brief Gets the Defines the time required for the TCXO to wakeup [ms].
|
||||
*
|
||||
* \retval time Board TCXO wakeup time in ms.
|
||||
*/
|
||||
uint32_t SX127xGetBoardTcxoWakeupTime( void );
|
||||
|
||||
/*!
|
||||
* \brief Writes new Tx debug pin state
|
||||
*
|
||||
* \param [IN] state Debug pin state
|
||||
*/
|
||||
void SX127xDbgPinTxWrite( uint8_t state );
|
||||
|
||||
/*!
|
||||
* \brief Writes new Rx debug pin state
|
||||
*
|
||||
* \param [IN] state Debug pin state
|
||||
*/
|
||||
void SX127xDbgPinRxWrite( uint8_t state );
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
// todo PR to drv_gpio.c
|
||||
int stm32_pin_get(char *pin_name);
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* Radio hardware and global parameters
|
||||
*/
|
||||
extern SX127x_t SX127x;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif // __SX127x_BOARD_H__
|
|
@ -0,0 +1,79 @@
|
|||
/*
|
||||
* author Rick Zhang
|
||||
* date 2020.07.20
|
||||
*/
|
||||
#include "lora-radio-rtos-config.h"
|
||||
#include "lora-radio.h"
|
||||
#include "sx126x-board.h"
|
||||
|
||||
#define DRV_DEBUG
|
||||
#define LOG_TAG "LoRa.Board.ASR6500S(SX1262)" // ASR6500S
|
||||
#include <drv_log.h>
|
||||
|
||||
extern void RadioOnDioIrq( void* context );
|
||||
|
||||
void SX126xIoInit( void )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_NSS_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_BUSY_PIN, PIN_MODE_INPUT);
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT);
|
||||
}
|
||||
|
||||
void SX126xIoIrqInit( DioIrqHandler dioIrq )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT);
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING, RadioOnDioIrq,(void*)"callback args");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
}
|
||||
|
||||
void SX126xIoDeInit( void )
|
||||
{
|
||||
}
|
||||
|
||||
void SX126xIoDbgInit( void )
|
||||
{
|
||||
}
|
||||
|
||||
void SX126xIoTcxoInit( void )
|
||||
{
|
||||
CalibrationParams_t calibParam;
|
||||
SX126xSetDio3AsTcxoCtrl( TCXO_CTRL_1_8V, SX126xGetBoardTcxoWakeupTime( ) << 6 ); // convert from ms to SX126x time base
|
||||
calibParam.Value = 0x7F;
|
||||
SX126xCalibrate( calibParam );
|
||||
}
|
||||
|
||||
uint32_t SX126xGetBoardTcxoWakeupTime( void )
|
||||
{
|
||||
return BOARD_TCXO_WAKEUP_TIME;
|
||||
}
|
||||
|
||||
void SX126xReset( void )
|
||||
{
|
||||
SX126X_DELAY_MS( 20 );
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_write(LORA_RADIO_RESET_PIN, PIN_LOW);
|
||||
SX126X_DELAY_MS( 40 );
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_INPUT);
|
||||
SX126X_DELAY_MS( 20 );
|
||||
}
|
||||
|
||||
void SX126xWaitOnBusy( void )
|
||||
{
|
||||
while( rt_pin_read( LORA_RADIO_BUSY_PIN ) == PIN_HIGH );
|
||||
}
|
||||
|
||||
void SX126xAntSwOn( void )
|
||||
{
|
||||
}
|
||||
|
||||
void SX126xAntSwOff( void )
|
||||
{
|
||||
}
|
||||
|
||||
bool SX126xCheckRfFrequency( uint32_t frequency )
|
||||
{
|
||||
return true;
|
||||
}
|
||||
void SX126xSetAntSw( RadioOperatingModes_t mode )
|
||||
{
|
||||
}
|
|
@ -0,0 +1,174 @@
|
|||
/*!
|
||||
* \file sx1262-board.c
|
||||
*
|
||||
* \brief Target board SX126x shield driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#include "lora-radio-rtos-config.h"
|
||||
#include "lora-radio.h"
|
||||
#include "sx126x-board.h"
|
||||
|
||||
#define LOG_TAG "LoRa.Board.LSD4RF-2R822N30(SX1262)"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include "lora-radio-debug.h"
|
||||
|
||||
/*!
|
||||
* Debug GPIO pins objects
|
||||
*/
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
Gpio_t DbgPinTx;
|
||||
Gpio_t DbgPinRx;
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40004 )
|
||||
int stm32_pin_get(char *pin_name)
|
||||
{
|
||||
/* eg: pin_name : "PA.4" ( GPIOA, GPIO_PIN_4 )--> drv_gpio.c pin */
|
||||
char pin_index = strtol(&pin_name[3],0,10);
|
||||
|
||||
if(pin_name[1] < 'A' || pin_name[1] > 'Z')
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return (16 * (pin_name[1]-'A') + pin_index);
|
||||
}
|
||||
#endif
|
||||
#endif /* LORA_RADIO_GPIO_SETUP_BY_PIN_NAME */
|
||||
|
||||
void SX126xIoInit( void )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_NSS_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_BUSY_PIN, PIN_MODE_INPUT);
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#if defined( LORA_RADIO_DIO2_PIN )
|
||||
rt_pin_mode(LORA_RADIO_DIO2_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#endif
|
||||
#if defined( LORA_RADIO_RFSW1_PIN ) && defined ( LORA_RADIO_RFSW2_PIN )
|
||||
rt_pin_mode(LORA_RADIO_RFSW1_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_RFSW2_PIN, PIN_MODE_OUTPUT);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void SX126xIoIrqInit( DioIrqHandler dioIrq )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING, dioIrq,(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
}
|
||||
|
||||
void SX126xIoDeInit( void )
|
||||
{
|
||||
SX126xAntSwOff();
|
||||
}
|
||||
|
||||
void SX126xIoDbgInit( void )
|
||||
{
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
GpioInit( &DbgPinTx, RADIO_DBG_PIN_TX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
GpioInit( &DbgPinRx, RADIO_DBG_PIN_RX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xIoTcxoInit( void )
|
||||
{
|
||||
// Initialize TCXO control
|
||||
CalibrationParams_t calibParam;
|
||||
|
||||
// +clear OSC_START_ERR for reboot or cold-start from sleep
|
||||
SX126xClearDeviceErrors();
|
||||
|
||||
// TCXO_CTRL_2_7V 64*15.0625US
|
||||
SX126xSetDio3AsTcxoCtrl( TCXO_CTRL_2_7V, 320);//SX126xGetBoardTcxoWakeupTime( ) << 6 ); // convert from ms to SX126x time base
|
||||
|
||||
calibParam.Value = 0x7F;
|
||||
SX126xCalibrate( calibParam );
|
||||
}
|
||||
|
||||
uint32_t SX126xGetBoardTcxoWakeupTime( void )
|
||||
{
|
||||
return BOARD_TCXO_WAKEUP_TIME;
|
||||
}
|
||||
|
||||
void SX126xReset( void )
|
||||
{
|
||||
SX126X_DELAY_MS( 10 );
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_write(LORA_RADIO_RESET_PIN, PIN_LOW);
|
||||
SX126X_DELAY_MS( 20 );
|
||||
// internal pull-up
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_INPUT);
|
||||
SX126X_DELAY_MS( 10 );
|
||||
}
|
||||
|
||||
void SX126xWaitOnBusy( void )
|
||||
{
|
||||
while( rt_pin_read( LORA_RADIO_BUSY_PIN ) == PIN_HIGH );
|
||||
}
|
||||
|
||||
void SX126xAntSwOn( void )
|
||||
{
|
||||
// No need
|
||||
}
|
||||
|
||||
void SX126xAntSwOff( void )
|
||||
{
|
||||
////GpioInit( &AntPow, RADIO_ANT_SWITCH_POWER, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
|
||||
#if defined( LORA_RADIO_RFSW1_PIN ) && defined ( LORA_RADIO_RFSW2_PIN )
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xSetAntSw( RadioOperatingModes_t mode )
|
||||
{
|
||||
if( mode == MODE_TX )
|
||||
{ // Transmit
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_HIGH);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
}
|
||||
else
|
||||
{
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_HIGH);
|
||||
}
|
||||
}
|
||||
|
||||
bool SX126xCheckRfFrequency( uint32_t frequency )
|
||||
{
|
||||
// Implement check. Currently all frequencies are supported
|
||||
return true;
|
||||
}
|
||||
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
void SX126xDbgPinTxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinTx, state );
|
||||
}
|
||||
|
||||
void SX126xDbgPinRxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinRx, state );
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,177 @@
|
|||
/*!
|
||||
* \file sx1268-board.c
|
||||
*
|
||||
* \brief Target board SX126x shield driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#include "lora-radio-rtos-config.h"
|
||||
#include "lora-radio.h"
|
||||
#include "sx126x-board.h"
|
||||
|
||||
#define LOG_TAG "LoRa.Board.LSD4RF-2R717N40(SX1268)" // LSD4RF-2R717N40
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include "lora-radio-debug.h"
|
||||
|
||||
/*!
|
||||
* Debug GPIO pins objects
|
||||
*/
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
Gpio_t DbgPinTx;
|
||||
Gpio_t DbgPinRx;
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40004 )
|
||||
int stm32_pin_get(char *pin_name)
|
||||
{
|
||||
/* eg: pin_name : "PA.4" ( GPIOA, GPIO_PIN_4 )--> drv_gpio.c pin */
|
||||
char pin_index = strtol(&pin_name[3],0,10);
|
||||
|
||||
if(pin_name[1] < 'A' || pin_name[1] > 'Z')
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return (16 * (pin_name[1]-'A') + pin_index);
|
||||
}
|
||||
#endif
|
||||
#endif /* LORA_RADIO_GPIO_SETUP_BY_PIN_NAME */
|
||||
|
||||
void SX126xIoInit( void )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_NSS_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_BUSY_PIN, PIN_MODE_INPUT);
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#if defined( LORA_RADIO_DIO2_PIN )
|
||||
rt_pin_mode(LORA_RADIO_DIO2_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#endif
|
||||
#if defined( LORA_RADIO_RFSW1_PIN ) && defined ( LORA_RADIO_RFSW2_PIN )
|
||||
rt_pin_mode(LORA_RADIO_RFSW1_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_RFSW2_PIN, PIN_MODE_OUTPUT);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void SX126xIoIrqInit( DioIrqHandler dioIrq )
|
||||
{
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING, dioIrq,(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
}
|
||||
|
||||
void SX126xIoDeInit( void )
|
||||
{
|
||||
//// GpioInit( &SX126x.Spi.Nss, RADIO_NSS, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_PULL_UP, 1 );
|
||||
//// GpioInit( &SX126x.BUSY, RADIO_BUSY, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
//// GpioInit( &SX126x.DIO1, RADIO_DIO_1, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
SX126xAntSwOff();
|
||||
}
|
||||
|
||||
void SX126xIoDbgInit( void )
|
||||
{
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
GpioInit( &DbgPinTx, RADIO_DBG_PIN_TX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
GpioInit( &DbgPinRx, RADIO_DBG_PIN_RX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xIoTcxoInit( void )
|
||||
{
|
||||
// Initialize TCXO control
|
||||
CalibrationParams_t calibParam;
|
||||
|
||||
// +clear OSC_START_ERR for reboot or cold-start from sleep
|
||||
SX126xClearDeviceErrors();
|
||||
|
||||
// TCXO_CTRL_1_7V -> TCXO_CTRL_2_7V 64*15.0625US
|
||||
SX126xSetDio3AsTcxoCtrl( TCXO_CTRL_2_7V, 320);//SX126xGetBoardTcxoWakeupTime( ) << 6 ); // convert from ms to SX126x time base
|
||||
|
||||
calibParam.Value = 0x7F;
|
||||
SX126xCalibrate( calibParam );
|
||||
}
|
||||
|
||||
uint32_t SX126xGetBoardTcxoWakeupTime( void )
|
||||
{
|
||||
return BOARD_TCXO_WAKEUP_TIME;
|
||||
}
|
||||
|
||||
void SX126xReset( void )
|
||||
{
|
||||
SX126X_DELAY_MS( 10 );
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_write(LORA_RADIO_RESET_PIN, PIN_LOW);
|
||||
SX126X_DELAY_MS( 20 );
|
||||
// internal pull-up
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_INPUT);
|
||||
SX126X_DELAY_MS( 10 );
|
||||
}
|
||||
|
||||
void SX126xWaitOnBusy( void )
|
||||
{
|
||||
while( rt_pin_read( LORA_RADIO_BUSY_PIN ) == PIN_HIGH );
|
||||
}
|
||||
|
||||
void SX126xAntSwOn( void )
|
||||
{
|
||||
// No need
|
||||
}
|
||||
|
||||
void SX126xAntSwOff( void )
|
||||
{
|
||||
////GpioInit( &AntPow, RADIO_ANT_SWITCH_POWER, PIN_ANALOGIC, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
|
||||
#if defined( LORA_RADIO_RFSW1_PIN ) && defined ( LORA_RADIO_RFSW2_PIN )
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX126xSetAntSw( RadioOperatingModes_t mode )
|
||||
{
|
||||
if( mode == MODE_TX )
|
||||
{ // Transmit
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_HIGH);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
}
|
||||
else
|
||||
{
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_HIGH);
|
||||
}
|
||||
}
|
||||
|
||||
bool SX126xCheckRfFrequency( uint32_t frequency )
|
||||
{
|
||||
// Implement check. Currently all frequencies are supported
|
||||
return true;
|
||||
}
|
||||
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
void SX126xDbgPinTxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinTx, state );
|
||||
}
|
||||
|
||||
void SX126xDbgPinRxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinRx, state );
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,292 @@
|
|||
/*!
|
||||
* \file sx1278-board.c
|
||||
*
|
||||
* \brief Target board SX127x driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#include "lora-radio-rtos-config.h"
|
||||
#include "lora-radio.h"
|
||||
#include "sx127x\sx127x.h"
|
||||
#include "sx127x-board.h"
|
||||
|
||||
#define LOG_TAG "LoRa.Board.LSD4RF-2F717N30(SX1278)"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include "lora-radio-debug.h"
|
||||
|
||||
/*!
|
||||
* Flag used to set the RF switch control pins in low power mode when the radio is not active.
|
||||
*/
|
||||
static bool RadioIsActive = false;
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
/*!
|
||||
* \brief DIO 0 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio0IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 1 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio1IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 2 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio2IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 3 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio3IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 4 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio4IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 5 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio5IrqEvent( void *args );
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* Debug GPIO pins objects
|
||||
*/
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
Gpio_t DbgPinTx;
|
||||
Gpio_t DbgPinRx;
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40004 )
|
||||
int stm32_pin_get(char *pin_name)
|
||||
{
|
||||
/* eg: pin_name : "PA.4" ( GPIOA, GPIO_PIN_4 )--> drv_gpio.c pin */
|
||||
char pin_index = strtol(&pin_name[3],0,10);
|
||||
|
||||
if(pin_name[1] < 'A' || pin_name[1] > 'Z')
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return (16 * (pin_name[1]-'A') + pin_index);
|
||||
}
|
||||
#endif
|
||||
#endif /* LORA_RADIO_GPIO_SETUP_BY_PIN_NAME */
|
||||
|
||||
void SX127xIoInit( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
rt_pin_mode(LORA_RADIO_NSS_PIN, PIN_MODE_OUTPUT);
|
||||
|
||||
rt_pin_mode(LORA_RADIO_DIO0_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
rt_pin_mode(LORA_RADIO_DIO2_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#else
|
||||
// GpioInit( &SX127x.Spi.Nss, RADIO_NSS, PIN_OUTPUT, PIN_PUSH_PULL, PIN_PULL_UP, 1 );
|
||||
|
||||
// GpioInit( &SX127x.DIO0, RADIO_DIO_0, PIN_INPUT, PIN_PUSH_PULL, PIN_PULL_UP, 0 );
|
||||
// GpioInit( &SX127x.DIO1, RADIO_DIO_1, PIN_INPUT, PIN_PUSH_PULL, PIN_PULL_UP, 0 );
|
||||
// GpioInit( &SX127x.DIO2, RADIO_DIO_2, PIN_INPUT, PIN_PUSH_PULL, PIN_PULL_UP, 0 );
|
||||
// GpioInit( &SX127x.DIO3, RADIO_DIO_3, PIN_INPUT, PIN_PUSH_PULL, PIN_PULL_UP, 0 );
|
||||
// GpioInit( &SX127x.DIO4, RADIO_DIO_4, PIN_INPUT, PIN_PUSH_PULL, PIN_PULL_UP, 0 );
|
||||
// GpioInit( &SX127x.DIO5, RADIO_DIO_5, PIN_INPUT, PIN_PUSH_PULL, PIN_PULL_UP, 0 );
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX127xIoIrqInit( DioIrqHandler **irqHandlers )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
|
||||
#ifdef LORA_RADIO_DIO0_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO0_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio0IrqEvent,(void*)"rf-dio0");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO0_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DIO1_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio1IrqEvent,(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DIO2_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO2_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio2IrqEvent,(void*)"rf-dio2");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO2_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
|
||||
#else
|
||||
|
||||
#ifdef LORA_RADIO_DIO0_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO0_PIN, PIN_IRQ_MODE_RISING,irqHandlers[0],(void*)"rf-dio0");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO0_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DIO1_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING,irqHandlers[1],(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_DIO2_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO2_PIN, PIN_IRQ_MODE_RISING,irqHandlers[2],(void*)"rf-dio2");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO2_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
// GpioSetInterrupt( &SX127x.DIO0, IRQ_RISING_EDGE, IRQ_HIGH_PRIORITY, irqHandlers[0] );
|
||||
// GpioSetInterrupt( &SX127x.DIO1, IRQ_RISING_EDGE, IRQ_HIGH_PRIORITY, irqHandlers[1] );
|
||||
// GpioSetInterrupt( &SX127x.DIO2, IRQ_RISING_EDGE, IRQ_HIGH_PRIORITY, irqHandlers[2] );
|
||||
// GpioSetInterrupt( &SX127x.DIO3, IRQ_RISING_EDGE, IRQ_HIGH_PRIORITY, irqHandlers[3] );
|
||||
// GpioSetInterrupt( &SX127x.DIO4, IRQ_RISING_EDGE, IRQ_HIGH_PRIORITY, irqHandlers[4] );
|
||||
// GpioSetInterrupt( &SX127x.DIO5, IRQ_RISING_EDGE, IRQ_HIGH_PRIORITY, irqHandlers[5] );
|
||||
#endif /*end of USING_LORA_RADIO_DRIVER_RTOS_SUPPORT */
|
||||
}
|
||||
|
||||
void SX127xIoDeInit( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
// rt_pin_mode(LORA_RADIO_DIO0_PIN, PIN_MODE_INPUT);
|
||||
// rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT);
|
||||
// rt_pin_mode(LORA_RADIO_DIO2_PIN, PIN_MODE_INPUT);
|
||||
#else
|
||||
// GpioInit( &SX127x.Spi.Nss, RADIO_NSS, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 1 );
|
||||
|
||||
// GpioInit( &SX127x.DIO0, RADIO_DIO_0, PIN_INPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
// GpioInit( &SX127x.DIO1, RADIO_DIO_1, PIN_INPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
// GpioInit( &SX127x.DIO2, RADIO_DIO_2, PIN_INPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
// GpioInit( &SX127x.DIO3, RADIO_DIO_3, PIN_INPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
// GpioInit( &SX127x.DIO4, RADIO_DIO_4, PIN_INPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
// GpioInit( &SX127x.DIO5, RADIO_DIO_5, PIN_INPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
#endif /*end of USING_LORA_RADIO_DRIVER_RTOS_SUPPORT */
|
||||
SX127xAntSwDeInit();
|
||||
}
|
||||
|
||||
void SX127xIoDbgInit( void )
|
||||
{
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
GpioInit( &DbgPinTx, RADIO_DBG_PIN_TX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
GpioInit( &DbgPinRx, RADIO_DBG_PIN_RX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX127xReset( void )
|
||||
{
|
||||
// Set RESET pin to 0
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_write(LORA_RADIO_RESET_PIN, PIN_LOW);
|
||||
|
||||
// Wait 1 ms
|
||||
SX127X_DELAY_MS( 1 );
|
||||
|
||||
// Configure RESET as input
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_INPUT);
|
||||
|
||||
// Wait 6 ms
|
||||
SX127X_DELAY_MS( 6 );
|
||||
}
|
||||
|
||||
void SX127xSetAntSwLowPower( bool status )
|
||||
{
|
||||
if( RadioIsActive != status )
|
||||
{
|
||||
RadioIsActive = status;
|
||||
|
||||
if( status == false )
|
||||
{
|
||||
SX127xAntSwInit( );
|
||||
}
|
||||
else
|
||||
{
|
||||
SX127xAntSwDeInit( );
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SX127xAntSwInit( void )
|
||||
{
|
||||
//// GpioInit( &AntSwitchRx, RADIO_ANT_SWITCH_RX, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
//// GpioInit( &AntSwitchTxBoost, RADIO_ANT_SWITCH_TX_BOOST, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
//// GpioInit( &AntSwitchTxRfo, RADIO_ANT_SWITCH_TX_RFO, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 );
|
||||
|
||||
rt_pin_mode(LORA_RADIO_RFSW1_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_mode(LORA_RADIO_RFSW2_PIN, PIN_MODE_OUTPUT);
|
||||
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
}
|
||||
|
||||
void SX127xAntSwDeInit( void )
|
||||
{
|
||||
//// GpioInit( &AntSwitchRx, RADIO_ANT_SWITCH_RX, PIN_ANALOGIC, PIN_OPEN_DRAIN, PIN_NO_PULL, 0 );
|
||||
//// GpioInit( &AntSwitchTxBoost, RADIO_ANT_SWITCH_TX_BOOST, PIN_ANALOGIC, PIN_OPEN_DRAIN, PIN_NO_PULL, 0 );
|
||||
//// GpioInit( &AntSwitchTxRfo, RADIO_ANT_SWITCH_TX_RFO, PIN_ANALOGIC, PIN_OPEN_DRAIN, PIN_NO_PULL, 0 );
|
||||
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
}
|
||||
|
||||
/* TX/RX ANT Swich */
|
||||
void SX127xSetAntSw( uint8_t opMode )
|
||||
{
|
||||
uint8_t paConfig = SX127xRead( REG_PACONFIG );
|
||||
switch( opMode )
|
||||
{
|
||||
case RFLR_OPMODE_TRANSMITTER:
|
||||
if( ( paConfig & RF_PACONFIG_PASELECT_PABOOST ) == RF_PACONFIG_PASELECT_PABOOST )
|
||||
{
|
||||
///GpioWrite( &AntSwitchTxBoost, 1 );
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_HIGH);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_LOW);
|
||||
}
|
||||
break;
|
||||
case RFLR_OPMODE_RECEIVER:
|
||||
case RFLR_OPMODE_RECEIVER_SINGLE:
|
||||
case RFLR_OPMODE_CAD:
|
||||
default:
|
||||
////GpioWrite( &AntSwitchRx, 1 );
|
||||
rt_pin_write(LORA_RADIO_RFSW1_PIN, PIN_LOW);
|
||||
rt_pin_write(LORA_RADIO_RFSW2_PIN, PIN_HIGH);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
void SX127xDbgPinTxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinTx, state );
|
||||
}
|
||||
|
||||
void SX127xDbgPinRxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinRx, state );
|
||||
}
|
||||
#endif
|
||||
|
||||
uint8_t SX127xGetPaSelect( int8_t power )
|
||||
{
|
||||
return RF_PACONFIG_PASELECT_PABOOST;
|
||||
}
|
||||
|
||||
bool SX127xCheckRfFrequency( uint32_t frequency )
|
||||
{
|
||||
// Implement check. Currently all frequencies are supported,todo depend on board
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,225 @@
|
|||
/*!
|
||||
* \file sx1278-board.c
|
||||
*
|
||||
* \brief Target board SX127x driver implementation
|
||||
*
|
||||
* \copyright Revised BSD License, see section \ref LICENSE.
|
||||
*
|
||||
* \code
|
||||
* ______ _
|
||||
* / _____) _ | |
|
||||
* ( (____ _____ ____ _| |_ _____ ____| |__
|
||||
* \____ \| ___ | (_ _) ___ |/ ___) _ \
|
||||
* _____) ) ____| | | || |_| ____( (___| | | |
|
||||
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
|
||||
* (C)2013-2017 Semtech
|
||||
*
|
||||
* \endcode
|
||||
*
|
||||
* \author Miguel Luis ( Semtech )
|
||||
*
|
||||
* \author Gregory Cristian ( Semtech )
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#include "lora-radio-rtos-config.h"
|
||||
#include "lora-radio.h"
|
||||
#include "sx127x.h"
|
||||
#include "sx127x-board.h"
|
||||
|
||||
#define LOG_TAG "LoRa.Board.Ra-01(SX1278)"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include "lora-radio-debug.h"
|
||||
/*!
|
||||
* Flag used to set the RF switch control pins in low power mode when the radio is not active.
|
||||
*/
|
||||
static bool RadioIsActive = false;
|
||||
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
/*!
|
||||
* \brief DIO 0 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio0IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 1 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio1IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 2 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio2IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 3 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio3IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 4 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio4IrqEvent( void *args );
|
||||
|
||||
/*!
|
||||
* \brief DIO 5 IRQ callback
|
||||
*/
|
||||
void SX127xOnDio5IrqEvent( void *args );
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* Debug GPIO pins objects
|
||||
*/
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
Gpio_t DbgPinTx;
|
||||
Gpio_t DbgPinRx;
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40004 )
|
||||
int stm32_pin_get(char *pin_name)
|
||||
{
|
||||
/* eg: pin_name : "PA.4" ( GPIOA, GPIO_PIN_4 )--> drv_gpio.c pin */
|
||||
char pin_index = strtol(&pin_name[3],0,10);
|
||||
|
||||
if(pin_name[1] < 'A' || pin_name[1] > 'Z')
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return (16 * (pin_name[1]-'A') + pin_index);
|
||||
}
|
||||
#endif
|
||||
#endif /* LORA_RADIO_GPIO_SETUP_BY_PIN_NAME */
|
||||
|
||||
void SX127xIoInit( void )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
// RT-Thread
|
||||
rt_pin_mode(LORA_RADIO_NSS_PIN, PIN_MODE_OUTPUT);
|
||||
|
||||
rt_pin_mode(LORA_RADIO_DIO0_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#ifdef LORA_RADIO_DIO1_PIN
|
||||
rt_pin_mode(LORA_RADIO_DIO1_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO2_PIN
|
||||
rt_pin_mode(LORA_RADIO_DIO2_PIN, PIN_MODE_INPUT_PULLDOWN);
|
||||
#endif
|
||||
#else
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX127xIoIrqInit( DioIrqHandler **irqHandlers )
|
||||
{
|
||||
#ifdef LORA_RADIO_DRIVER_USING_ON_RTOS_RT_THREAD
|
||||
#ifdef LORA_RADIO_DIO0_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO0_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio0IrqEvent,(void*)"rf-dio0");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO0_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO1_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio1IrqEvent,(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO2_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO2_PIN, PIN_IRQ_MODE_RISING,SX127xOnDio2IrqEvent,(void*)"rf-dio2");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO2_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#else
|
||||
#ifdef LORA_RADIO_DIO0_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO0_PIN, PIN_IRQ_MODE_RISING,irqHandlers[0],(void*)"rf-dio0");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO0_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO1_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO1_PIN, PIN_IRQ_MODE_RISING,irqHandlers[1],(void*)"rf-dio1");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO1_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#ifdef LORA_RADIO_DIO2_PIN
|
||||
rt_pin_attach_irq(LORA_RADIO_DIO2_PIN, PIN_IRQ_MODE_RISING,irqHandlers[2],(void*)"rf-dio2");
|
||||
rt_pin_irq_enable(LORA_RADIO_DIO2_PIN, PIN_IRQ_ENABLE);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
void SX127xIoDeInit( void )
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void SX127xIoDbgInit( void )
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
void SX127xReset( void )
|
||||
{
|
||||
// Set RESET pin to 0
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_OUTPUT);
|
||||
rt_pin_write(LORA_RADIO_RESET_PIN, PIN_LOW);
|
||||
|
||||
// Wait 1 ms
|
||||
SX127X_DELAY_MS( 1 );
|
||||
|
||||
// Configure RESET as input
|
||||
rt_pin_mode(LORA_RADIO_RESET_PIN, PIN_MODE_INPUT);
|
||||
|
||||
// Wait 6 ms
|
||||
SX127X_DELAY_MS( 6 );
|
||||
}
|
||||
|
||||
void SX127xSetAntSwLowPower( bool status )
|
||||
{
|
||||
if( RadioIsActive != status )
|
||||
{
|
||||
RadioIsActive = status;
|
||||
|
||||
if( status == false )
|
||||
{
|
||||
SX127xAntSwInit( );
|
||||
}
|
||||
else
|
||||
{
|
||||
SX127xAntSwDeInit( );
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SX127xAntSwInit( void )
|
||||
{
|
||||
}
|
||||
|
||||
void SX127xAntSwDeInit( void )
|
||||
{
|
||||
}
|
||||
|
||||
/* TX and RX ANT switch */
|
||||
|
||||
void SX127xSetAntSw( uint8_t opMode )
|
||||
{
|
||||
}
|
||||
|
||||
#if defined( USE_RADIO_DEBUG )
|
||||
void SX127xDbgPinTxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinTx, state );
|
||||
}
|
||||
|
||||
void SX127xDbgPinRxWrite( uint8_t state )
|
||||
{
|
||||
GpioWrite( &DbgPinRx, state );
|
||||
}
|
||||
#endif
|
||||
|
||||
uint8_t SX127xGetPaSelect( int8_t power )
|
||||
{
|
||||
return RF_PACONFIG_PASELECT_PABOOST;
|
||||
}
|
||||
|
||||
bool SX127xCheckRfFrequency( uint32_t frequency )
|
||||
{
|
||||
// Implement check. Currently all frequencies are supported,todo depend on board
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,100 @@
|
|||
/*!
|
||||
* \file lora-spi-board.c
|
||||
*
|
||||
* \brief spi peripheral initlize,it depend on mcu platform.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
#include "lora-radio-rtos-config.h"
|
||||
#ifdef LORA_RADIO_DRIVER_USING_LORA_CHIP_SX126X
|
||||
#include "sx126x-board.h"
|
||||
#elif defined LORA_RADIO_DRIVER_USING_LORA_CHIP_SX127X
|
||||
#include "sx127x-board.h"
|
||||
#endif
|
||||
|
||||
#define LOG_TAG "LoRa.STM32.SPI"
|
||||
#define LOG_LEVEL LOG_LVL_DBG
|
||||
#include "lora-radio-debug.h"
|
||||
|
||||
/* for get GPIO fort,eg GPIOA */
|
||||
#ifndef GET_GPIO_PORT
|
||||
#define GET_GPIO_PORT(pin) (GPIO_TypeDef *)( GPIOA_BASE + (uint32_t) ( pin >> 4 ) * 0x0400UL )
|
||||
#endif
|
||||
#ifndef GET_GPIO_PIN
|
||||
#define GET_GPIO_PIN(pin) (rt_uint16_t)( 1 << ( pin & 0x0F ) ) // for get GPIO_PIN, eg: GPIO_PIN_6
|
||||
#endif
|
||||
|
||||
#ifdef LORA_RADIO_GPIO_SETUP_BY_PIN_NAME
|
||||
#if ( RT_VER_NUM <= 0x40002 )
|
||||
extern int stm32_pin_get(char *pin_name);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
struct rt_spi_device *lora_radio_spi_init(const char *bus_name, const char *lora_device_name, rt_uint8_t param)
|
||||
{
|
||||
rt_err_t res;
|
||||
struct rt_spi_device *lora_radio_spi_device;
|
||||
|
||||
RT_ASSERT(bus_name);
|
||||
|
||||
{
|
||||
res = rt_hw_spi_device_attach( bus_name, lora_device_name, LORA_RADIO_NSS_PIN);
|
||||
|
||||
if (res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_bus_attach_device failed!\r\n");
|
||||
return RT_NULL;
|
||||
}
|
||||
|
||||
lora_radio_spi_device = (struct rt_spi_device *)rt_device_find(lora_device_name);
|
||||
if (!lora_radio_spi_device)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"spi sample run failed! cant't find %s device!\n", lora_device_name);
|
||||
return RT_NULL;
|
||||
}
|
||||
}
|
||||
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"find %s device!\n", lora_device_name);
|
||||
|
||||
/* config spi */
|
||||
{
|
||||
struct rt_spi_configuration cfg;
|
||||
cfg.data_width = 8;
|
||||
cfg.mode = RT_SPI_MASTER | RT_SPI_MODE_0 | RT_SPI_MSB; /* SPI Compatible: Mode 0. */
|
||||
cfg.max_hz = 8 * 1000000; /* max 10M */
|
||||
|
||||
res = rt_spi_configure(lora_radio_spi_device, &cfg);
|
||||
|
||||
if (res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_configure failed!\r\n");
|
||||
}
|
||||
res = rt_spi_take_bus(lora_radio_spi_device);
|
||||
if (res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_take_bus failed!\r\n");
|
||||
}
|
||||
|
||||
res = rt_spi_release_bus(lora_radio_spi_device);
|
||||
|
||||
if(res != RT_EOK)
|
||||
{
|
||||
LORA_RADIO_DEBUG_LOG(LR_DBG_SPI, LOG_LEVEL,"rt_spi_release_bus failed!\r\n");
|
||||
}
|
||||
}
|
||||
|
||||
return lora_radio_spi_device;
|
||||
}
|
||||
|
||||
/**
|
||||
* This function releases memory
|
||||
*
|
||||
* @param dev the pointer of device driver structure
|
||||
*/
|
||||
void lora_radio_spi_deinit(struct rt_spi_device *dev)
|
||||
{
|
||||
RT_ASSERT(dev);
|
||||
rt_spi_release_bus(dev);
|
||||
}
|
|
@ -0,0 +1,3 @@
|
|||
SRC_DIR := lora-radio-tester
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,14 @@
|
|||
from building import *
|
||||
|
||||
src = []
|
||||
cwd = GetCurrentDir()
|
||||
include_path = [cwd]
|
||||
|
||||
|
||||
if GetDepend('LORA_RADIO_DRIVER_USING_LORA_RADIO_TESTER'):
|
||||
src += Glob('lora-radio-tester/lora-radio-tester.c')
|
||||
|
||||
|
||||
group = DefineGroup('lora-radio-driver/sample', src, depend = ['PKG_USING_LORA_RADIO_DRIVER'], CPPPATH = include_path)
|
||||
|
||||
Return('group')
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := lora-radio-tester.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,158 @@
|
|||
/*!
|
||||
* \file lora-radio-tester.h
|
||||
*
|
||||
* \brief lora radio test implementation
|
||||
*
|
||||
* \copyright SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* \author Forest-Rain
|
||||
*/
|
||||
|
||||
#ifndef __LORA_RADIO_TESTER_H__
|
||||
#define __LORA_RADIO_TESTER_H__
|
||||
|
||||
#include <lora-radio-rtos-config.h>
|
||||
|
||||
/* application debug */
|
||||
#ifndef LR_DBG_SHELL
|
||||
#define LR_DBG_SHELL 1
|
||||
#endif
|
||||
|
||||
#define PHY_REGION_EU433
|
||||
|
||||
#if defined( PHY_REGION_AS923 )
|
||||
|
||||
#define RF_FREQUENCY 923000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_AU915 )
|
||||
|
||||
#define RF_FREQUENCY 915000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_CN470 ) || defined ( PHY_REGION_CN470S )
|
||||
|
||||
#define RF_FREQUENCY 470300000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_CN779 )
|
||||
|
||||
#define RF_FREQUENCY 779000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_EU433 )
|
||||
|
||||
#define RF_FREQUENCY 433000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_EU868 )
|
||||
|
||||
#define RF_FREQUENCY 868000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_KR920 )
|
||||
|
||||
#define RF_FREQUENCY 920000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_IN865 )
|
||||
|
||||
#define RF_FREQUENCY 865000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_US915 )
|
||||
|
||||
#define RF_FREQUENCY 915000000 // Hz
|
||||
|
||||
#elif defined( PHY_REGION_RU864 )
|
||||
|
||||
#define RF_FREQUENCY 864000000 // Hz
|
||||
|
||||
#else
|
||||
#error "Please define a frequency band in the compiler options."
|
||||
#endif
|
||||
|
||||
#define TX_RX_FREQUENCE_OFFSET 0 // 0 TX = RX
|
||||
// 1800000 RX = TX+1.8M
|
||||
#define TX_OUTPUT_POWER 20//14 // dBm
|
||||
|
||||
#define LORA_BANDWIDTH 2 // [0: 125 kHz,
|
||||
// 1: 250 kHz,
|
||||
// 2: 500 kHz,
|
||||
// 3: Reserved]
|
||||
#define LORA_SPREADING_FACTOR 12 // [SF7..SF12]
|
||||
#define LORA_CODINGRATE 2 // [1: 4/5,
|
||||
// 2: 4/6,
|
||||
// 3: 4/7,
|
||||
// 4: 4/8]
|
||||
#define LORA_PREAMBLE_LENGTH 8 // Same for Tx and Rx
|
||||
#define LORA_SYMBOL_TIMEOUT 0 // Symbols
|
||||
#define LORA_FIX_LENGTH_PAYLOAD_ON_DISABLE false
|
||||
#define LORA_IQ_INVERSION_ON_DISABLE false
|
||||
|
||||
|
||||
#define FSK_FDEV 25000 // Hz
|
||||
#define FSK_DATARATE 50000 // bps
|
||||
|
||||
#if defined( LORA_RADIO_DRIVER_USING_LORA_CHIP_SX127X )
|
||||
|
||||
#define FSK_BANDWIDTH 50000 // Hz >> SSB in sx127x
|
||||
#define FSK_AFC_BANDWIDTH 83333 // Hz
|
||||
|
||||
#elif defined( LORA_RADIO_DRIVER_USING_LORA_CHIP_SX126X) || defined( LORA_RADIO_DRIVER_USING_LORA_CHIP_LLCC68 )
|
||||
|
||||
#define FSK_BANDWIDTH 100000 // Hz >> DSB in sx126x
|
||||
#define FSK_AFC_BANDWIDTH 166666 // Hz >> Unused in sx126x
|
||||
|
||||
#elif defined( LORA_RADIO_DRIVER_USING_LORA_SOC_STM32WL )
|
||||
|
||||
#define FSK_BANDWIDTH 100000 // Hz >> DSB in sx126x
|
||||
#define FSK_AFC_BANDWIDTH 166666 // Hz >> Unused in sx126x
|
||||
#elif defined( LORA_RADIO_DRIVER_USING_LORA_CHIP_SX128X )
|
||||
|
||||
#define FSK_BANDWIDTH 100000 // Hz >> DSB in sx126x
|
||||
#define FSK_AFC_BANDWIDTH 166666 // Hz >> Unused in sx126x
|
||||
#else
|
||||
#error "Please define a lora-shield in the compiler options."
|
||||
#endif
|
||||
|
||||
#define FSK_PREAMBLE_LENGTH 5 // Same for Tx and Rx
|
||||
#define FSK_FIX_LENGTH_PAYLOAD_ON false
|
||||
|
||||
#define TX_TIMEOUT_VALUE 1000
|
||||
#define RX_TIMEOUT_VALUE 1000
|
||||
#define BUFFER_SIZE 256 // Define the payload size here
|
||||
#define MIN_TETS_APP_DATA_SIZE 17 // for PING protocol
|
||||
|
||||
#define LORA_MASTER_DEVADDR 0x11223344
|
||||
#define LORA_SLAVER_DEVADDR 0x01020304
|
||||
#define MAC_HEADER_OVERHEAD 13
|
||||
|
||||
// Ping pong event
|
||||
#define EV_RADIO_INIT 0x0001
|
||||
#define EV_RADIO_TX_START 0x0002
|
||||
#define EV_RADIO_TX_DONE 0x0004
|
||||
#define EV_RADIO_TX_TIMEOUT 0x0008
|
||||
#define EV_RADIO_RX_DONE 0x0010
|
||||
#define EV_RADIO_RX_TIMEOUT 0x0020
|
||||
#define EV_RADIO_RX_ERROR 0x0040
|
||||
#define EV_RADIO_ALL (EV_RADIO_INIT | EV_RADIO_TX_START | EV_RADIO_TX_DONE | EV_RADIO_TX_TIMEOUT | EV_RADIO_RX_DONE | EV_RADIO_RX_TIMEOUT | EV_RADIO_RX_ERROR)
|
||||
|
||||
typedef struct
|
||||
{
|
||||
RadioModems_t modem; // LoRa Modem \ FSK modem
|
||||
uint32_t tx_frequency;
|
||||
uint32_t rx_frequency;
|
||||
int32_t trx_frequency_offset;
|
||||
int8_t txpower;
|
||||
|
||||
// LoRa
|
||||
uint8_t sf; // spreadfactor
|
||||
uint8_t bw; // bandwidth
|
||||
uint8_t cr; // coderate
|
||||
uint8_t iq_inversion;
|
||||
bool public_network;
|
||||
|
||||
// FSK
|
||||
uint32_t fdev;
|
||||
uint32_t datarate;
|
||||
uint32_t fsk_bandwidth;
|
||||
uint32_t fsk_afc_bandwidth;
|
||||
uint16_t preamble_len;
|
||||
|
||||
}lora_radio_test_t;
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,33 @@
|
|||
/*
|
||||
* 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 lorawan_gateway_update.c
|
||||
* @brief support lorawan-gateway update function
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023-11-29
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: lorawan_gateway_update.c
|
||||
Description: support lorawan-gateway update function
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-11-29
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、first version.
|
||||
*************************************************/
|
||||
|
||||
|
||||
|
|
@ -18,12 +18,16 @@ Modification:
|
|||
*************************************************/
|
||||
#include "ch32v30x_it.h"
|
||||
#include "board.h"
|
||||
#include "ch32v30x_exti.h"
|
||||
#include "ch32v30x_tim.h"
|
||||
#include "eth_driver.h"
|
||||
#include <xs_isr.h>
|
||||
|
||||
|
||||
|
||||
void NMI_Handler(void) __attribute__((interrupt("WCH-Interrupt-fast")));
|
||||
void HardFault_Handler(void) __attribute__((interrupt("WCH-Interrupt-fast")));
|
||||
void NMI_Handler(void) __attribute__((interrupt()));
|
||||
void HardFault_Handler(void) __attribute__((interrupt()));
|
||||
void ETH_IRQHandler(void) __attribute__((interrupt()));
|
||||
void TIM2_IRQHandler(void) __attribute__((interrupt()));
|
||||
void EXTI9_5_IRQHandler(void) __attribute__((interrupt()));
|
||||
|
||||
/*********************************************************************
|
||||
* @fn NMI_Handler
|
||||
|
@ -53,9 +57,51 @@ void HardFault_Handler(void)
|
|||
GET_INT_SP();
|
||||
isrManager.done->incCounter();
|
||||
KPrintf("HardFault_Handler.\n");
|
||||
|
||||
KPrintf("mepc :%08x\r\n", __get_MEPC());
|
||||
KPrintf("mcause:%08x\r\n", __get_MCAUSE());
|
||||
KPrintf("mtval :%08x\r\n", __get_MTVAL());
|
||||
while (1)
|
||||
;
|
||||
|
||||
isrManager.done->decCounter();
|
||||
FREE_INT_SP();
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn ETH_IRQHandler
|
||||
*
|
||||
* @brief This function handles ETH exception.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void ETH_IRQHandler(void)
|
||||
{
|
||||
WCHNET_ETHIsr();
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn TIM2_IRQHandler
|
||||
*
|
||||
* @brief This function handles TIM2 exception.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void TIM2_IRQHandler(void)
|
||||
{
|
||||
WCHNET_TimeIsr(WCHNETTIMERPERIOD);
|
||||
TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn EXTI9_5_IRQHandler
|
||||
*
|
||||
* @brief This function handles GPIO exception.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void EXTI9_5_IRQHandler(void)
|
||||
{
|
||||
ETH_PHYLink();
|
||||
EXTI_ClearITPendingBit(EXTI_Line7); /* Clear Flag */
|
||||
}
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
extern void KTaskOsAssignAfterIrq(void *);
|
||||
|
||||
void SysTick_Handler(void) __attribute__((interrupt("WCH-Interrupt-fast")));
|
||||
void SysTick_Handler(void) __attribute__((interrupt()));
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
GET_INT_SP();
|
||||
|
|
|
@ -27,15 +27,15 @@
|
|||
* @author AIIT XUOS Lab
|
||||
* @date 2022-08-08
|
||||
*/
|
||||
#include <board.h>
|
||||
#include <xizi.h>
|
||||
#include <stdint.h>
|
||||
#include <device.h>
|
||||
#include "connect_uart.h"
|
||||
#include "xsconfig.h"
|
||||
#include "ch32v30x.h"
|
||||
#include "connect_ether.h"
|
||||
#include "connect_uart.h"
|
||||
#include "core_riscv.h"
|
||||
// #include <system_ch32v30x.h>
|
||||
#include "xsconfig.h"
|
||||
#include <board.h>
|
||||
#include <device.h>
|
||||
#include <stdint.h>
|
||||
#include <xizi.h>
|
||||
|
||||
// core clock.
|
||||
extern uint32_t SystemCoreClock;
|
||||
|
@ -67,6 +67,10 @@ void InitBoardHardware()
|
|||
InitHwUart();
|
||||
InstallConsole("uart1", "uart1_drv", "uart1_dev1");
|
||||
|
||||
#ifdef BSP_USING_ETH
|
||||
InitHwEth();
|
||||
#endif
|
||||
|
||||
KPrintf("consle init completed.\n");
|
||||
KPrintf("board initialization......\n");
|
||||
// KPrintf("memory address range: [0x%08x - 0x%08x], size: %d\n", (x_ubase) MEMORY_START_ADDRESS, (x_ubase) MEMORY_END_ADDRESS, gd32vf103_SRAM_SIZE);
|
||||
|
@ -75,4 +79,3 @@ void InitBoardHardware()
|
|||
KPrintf("board init done.\n");
|
||||
KPrintf("start okernel...\n");
|
||||
}
|
||||
|
||||
|
|
|
@ -15,6 +15,8 @@ export CROSS_COMPILE ?=/opt/riscv-embedded-gcc/bin/riscv-none-embed-
|
|||
|
||||
export DEFINES := -DHAVE_CCONFIG_H -DHAVE_SIGINFO
|
||||
|
||||
export LINK_WCH_NET := $(KERNEL_ROOT)/board/ch32v307vct6/third_party_driver/ethernet/libwchnet.a
|
||||
|
||||
export ARCH = risc-v
|
||||
export MCU = GH32V307
|
||||
|
||||
|
|
|
@ -15,4 +15,8 @@ menuconfig BSP_USING_GPIO
|
|||
source "$BSP_DIR/third_party_driver/gpio/Kconfig"
|
||||
endif
|
||||
|
||||
menuconfig BSP_USING_ETH
|
||||
bool "Using Ethernet"
|
||||
default y
|
||||
|
||||
|
|
@ -9,4 +9,8 @@ ifeq ($(CONFIG_BSP_USING_GPIO),y)
|
|||
SRC_DIR += gpio
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_BSP_USING_ETH),y)
|
||||
SRC_DIR += ethernet
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -319,6 +319,9 @@ typedef struct
|
|||
/* PHY basic register */
|
||||
#define PHY_BCR 0x0 /*PHY transceiver Basic Control Register */
|
||||
#define PHY_BSR 0x01 /*PHY transceiver Basic Status Register */
|
||||
#define PHY_ANAR 0x04 /* Auto-Negotiation Advertisement Register */
|
||||
#define PHY_ANLPAR 0x05 /* Auto-Negotiation Link Partner Base Page Ability Register*/
|
||||
#define PHY_ANER 0x06 /* Auto-Negotiation Expansion Register */
|
||||
#define PHY_BMCR PHY_BCR
|
||||
#define PHY_BMSR PHY_BSR
|
||||
#define PHY_STATUS 0x10
|
||||
|
|
|
@ -0,0 +1,4 @@
|
|||
SRC_FILES := eth_driver.c connect_ether.c
|
||||
SRC_DIR := test
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,268 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : main.c
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2022/05/31
|
||||
* Description : Main program body.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
/*
|
||||
*@Note
|
||||
TCP Client example, demonstrating that TCP Client connects
|
||||
to the server and receives data and then sends it back.
|
||||
For details on the selection of engineering chips,
|
||||
please refer to the "CH32V30x Evaluation Board Manual" under the CH32V307EVT\EVT\PUB folder.
|
||||
*/
|
||||
|
||||
#include "connect_ether.h"
|
||||
#include "ch32v30x_rcc.h"
|
||||
#include "ch32v30x_tim.h"
|
||||
#include "core_riscv.h"
|
||||
#include "eth_driver.h"
|
||||
#include "string.h"
|
||||
#include "xs_base.h"
|
||||
|
||||
extern uint32_t SystemCoreClock;
|
||||
#define KEEPALIVE_ENABLE 1 // Enable keep alive function
|
||||
|
||||
uint8_t MACAddr[6]; // MAC address
|
||||
uint8_t IPAddr[4] = { 192, 168, 1, 10 }; // IP address
|
||||
uint8_t GWIPAddr[4] = { 192, 168, 1, 1 }; // Gateway IP address
|
||||
uint8_t IPMask[4] = { 255, 255, 255, 0 }; // subnet mask
|
||||
|
||||
uint8_t MyBuf[RECE_BUF_LEN];
|
||||
uint8_t socket[WCHNET_MAX_SOCKET_NUM]; // Save the currently connected socket
|
||||
uint8_t SocketRecvBuf[WCHNET_MAX_SOCKET_NUM][RECE_BUF_LEN]; // socket receive buffer
|
||||
|
||||
/*********************************************************************
|
||||
* @fn mStopIfError
|
||||
*
|
||||
* @brief check if error.
|
||||
*
|
||||
* @param iError - error constants.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void mStopIfError(uint8_t iError)
|
||||
{
|
||||
if (iError == WCHNET_ERR_SUCCESS)
|
||||
return;
|
||||
KPrintf("Error: %02X\r\n", (uint16_t)iError);
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn TIM2_Init
|
||||
*
|
||||
* @brief Initializes TIM2.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void TIM2_Init(void)
|
||||
{
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0 };
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
|
||||
|
||||
TIM_TimeBaseStructure.TIM_Period = SystemCoreClock / 1000000;
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = WCHNETTIMERPERIOD * 1000 - 1;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
|
||||
TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
|
||||
|
||||
TIM_Cmd(TIM2, ENABLE);
|
||||
TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
|
||||
NVIC_EnableIRQ(TIM2_IRQn);
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn WCHNET_CreateTcpSocket
|
||||
*
|
||||
* @brief Create TCP Socket
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void WCHNET_CreateTcpSocket(uint8_t* DESIP, uint16_t srcport, uint16_t desport, uint8_t* SocketId)
|
||||
{
|
||||
uint8_t i;
|
||||
SOCK_INF TmpSocketInf;
|
||||
|
||||
memset((void*)&TmpSocketInf, 0, sizeof(SOCK_INF));
|
||||
memcpy((void*)TmpSocketInf.IPAddr, DESIP, 4);
|
||||
TmpSocketInf.DesPort = desport;
|
||||
TmpSocketInf.SourPort = srcport++;
|
||||
TmpSocketInf.ProtoType = PROTO_TYPE_TCP;
|
||||
TmpSocketInf.RecvBufLen = RECE_BUF_LEN;
|
||||
i = WCHNET_SocketCreat(SocketId, &TmpSocketInf);
|
||||
KPrintf("SocketId %d\r\n", *SocketId);
|
||||
mStopIfError(i);
|
||||
i = WCHNET_SocketConnect(*SocketId); // make a TCP connection
|
||||
mStopIfError(i);
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn WCHNET_DataLoopback
|
||||
*
|
||||
* @brief Data loopback function.
|
||||
*
|
||||
* @param id - socket id.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void WCHNET_DataLoopback(uint8_t id)
|
||||
{
|
||||
u32 len, totallen;
|
||||
uint8_t *p = MyBuf, TransCnt = 255;
|
||||
|
||||
len = WCHNET_SocketRecvLen(id, NULL); // query length
|
||||
KPrintf("Receive Len = %d\r\n", len);
|
||||
totallen = len;
|
||||
WCHNET_SocketRecv(id, MyBuf, &len); // Read the data of the receive buffer into MyBuf
|
||||
while (1) {
|
||||
len = totallen;
|
||||
WCHNET_SocketSend(id, p, &len); // Send the data
|
||||
totallen -= len; // Subtract the sent length from the total length
|
||||
p += len; // offset buffer pointer
|
||||
if (!--TransCnt)
|
||||
break; // Timeout exit
|
||||
if (totallen)
|
||||
continue; // If the data is not sent, continue to send
|
||||
break; // After sending, exit
|
||||
}
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn WCHNET_HandleSockInt
|
||||
*
|
||||
* @brief Socket Interrupt Handle
|
||||
*
|
||||
* @param socketid - socket id.
|
||||
* intstat - interrupt status
|
||||
*
|
||||
* @return 0 or TIME_OUT
|
||||
*/
|
||||
int WCHNET_HandleSockInt(uint8_t socketid, uint8_t intstat)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
if (intstat & SINT_STAT_RECV) // receive data
|
||||
{
|
||||
WCHNET_DataLoopback(socketid); // Data loopback
|
||||
}
|
||||
if (intstat & SINT_STAT_CONNECT) // connect successfully
|
||||
{
|
||||
#if KEEPALIVE_ENABLE
|
||||
WCHNET_SocketSetKeepLive(socketid, ENABLE);
|
||||
#endif
|
||||
WCHNET_ModifyRecvBuf(socketid, (u32)SocketRecvBuf[socketid], RECE_BUF_LEN);
|
||||
for (i = 0; i < WCHNET_MAX_SOCKET_NUM; i++) {
|
||||
if (socket[i] == 0xff) { // save connected socket id
|
||||
socket[i] = socketid;
|
||||
break;
|
||||
}
|
||||
}
|
||||
KPrintf("TCP Connect Success\r\n");
|
||||
KPrintf("socket id: %d\r\n", socket[i]);
|
||||
}
|
||||
if (intstat & SINT_STAT_DISCONNECT) // disconnect
|
||||
{
|
||||
for (i = 0; i < WCHNET_MAX_SOCKET_NUM; i++) { // delete disconnected socket id
|
||||
if (socket[i] == socketid) {
|
||||
socket[i] = 0xff;
|
||||
break;
|
||||
}
|
||||
}
|
||||
KPrintf("TCP Disconnect\r\n");
|
||||
}
|
||||
if (intstat & SINT_STAT_TIM_OUT) // timeout disconnect
|
||||
{
|
||||
for (i = 0; i < WCHNET_MAX_SOCKET_NUM; i++) { // delete disconnected socket id
|
||||
if (socket[i] == socketid) {
|
||||
socket[i] = 0xff;
|
||||
break;
|
||||
}
|
||||
}
|
||||
KPrintf("TCP Timeout\r\n");
|
||||
return TIME_OUT;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn WCHNET_HandleGlobalInt
|
||||
*
|
||||
* @brief Global Interrupt Handle
|
||||
*
|
||||
* @return 0 or SockInt
|
||||
*/
|
||||
int WCHNET_HandleGlobalInt(void)
|
||||
{
|
||||
uint8_t intstat;
|
||||
uint16_t i;
|
||||
uint8_t socketint;
|
||||
|
||||
intstat = WCHNET_GetGlobalInt(); // get global interrupt flag
|
||||
if (intstat & GINT_STAT_UNREACH) // Unreachable interrupt
|
||||
{
|
||||
KPrintf("GINT_STAT_UNREACH\r\n");
|
||||
}
|
||||
if (intstat & GINT_STAT_IP_CONFLI) // IP conflict
|
||||
{
|
||||
KPrintf("GINT_STAT_IP_CONFLI\r\n");
|
||||
}
|
||||
if (intstat & GINT_STAT_PHY_CHANGE) // PHY status change
|
||||
{
|
||||
i = WCHNET_GetPHYStatus();
|
||||
if (i & PHY_Linked_Status)
|
||||
KPrintf("PHY Link Success\r\n");
|
||||
}
|
||||
if (intstat & GINT_STAT_SOCKET) { // socket related interrupt
|
||||
for (i = 0; i < WCHNET_MAX_SOCKET_NUM; i++) {
|
||||
socketint = WCHNET_GetSocketInt(i);
|
||||
if (socketint) {
|
||||
return WCHNET_HandleSockInt(i, socketint);
|
||||
}
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t InitHwEth()
|
||||
{
|
||||
uint8_t i = 0;
|
||||
|
||||
KPrintf("net version:%x\n", WCHNET_GetVer());
|
||||
if (WCHNET_LIB_VER != WCHNET_GetVer()) {
|
||||
KPrintf("version error.\n");
|
||||
}
|
||||
|
||||
WCHNET_GetMacAddr(MACAddr); // get the chip MAC address
|
||||
KPrintf("mac addr:");
|
||||
for (i = 0; i < 6; i++)
|
||||
KPrintf("%x ", MACAddr[i]);
|
||||
KPrintf("\n");
|
||||
|
||||
TIM2_Init();
|
||||
|
||||
i = ETH_LibInit(IPAddr, GWIPAddr, IPMask, MACAddr); // Ethernet library initialize
|
||||
mStopIfError(i);
|
||||
if (i == WCHNET_ERR_SUCCESS)
|
||||
KPrintf("WCHNET_LibInit Success\r\n");
|
||||
#if KEEPALIVE_ENABLE // Configure keep alive parameters
|
||||
{
|
||||
struct _KEEP_CFG cfg;
|
||||
|
||||
cfg.KLIdle = 20000;
|
||||
cfg.KLIntvl = 15000;
|
||||
cfg.KLCount = 9;
|
||||
WCHNET_ConfigKeepLive(&cfg);
|
||||
}
|
||||
#endif
|
||||
|
||||
memset(socket, 0xff, WCHNET_MAX_SOCKET_NUM);
|
||||
|
||||
return i;
|
||||
}
|
File diff suppressed because it is too large
Load Diff
Binary file not shown.
|
@ -0,0 +1,4 @@
|
|||
SRC_FILES := wch_tcp_test.c
|
||||
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,47 @@
|
|||
#include "connect_ether.h"
|
||||
#include "eth_driver.h"
|
||||
#include "shell.h"
|
||||
#include "wchnet.h"
|
||||
#include "xs_base.h"
|
||||
|
||||
uint8_t DESIP[4] = { 192, 168, 1, 100 }; // destination IP address
|
||||
uint16_t desport = 1000; // destination port
|
||||
uint16_t srcport = 1000; // source port
|
||||
|
||||
uint8_t SocketId;
|
||||
|
||||
/*********************************************************************
|
||||
* @fn TCP client
|
||||
*
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
int Tcp_Client(void)
|
||||
{
|
||||
uint8_t i;
|
||||
for (i = 0; i < WCHNET_MAX_SOCKET_NUM; i++)
|
||||
WCHNET_CreateTcpSocket(DESIP, srcport, desport, &SocketId); // Create TCP Socket
|
||||
|
||||
while (1) {
|
||||
/*Ethernet library main task function,
|
||||
* which needs to be called cyclically*/
|
||||
WCHNET_MainTask();
|
||||
/*Query the Ethernet global interrupt,
|
||||
* if there is an interrupt, call the global interrupt handler*/
|
||||
if (WCHNET_QueryGlobalInt()) {
|
||||
if (WCHNET_HandleGlobalInt() == TIME_OUT) {
|
||||
WCHNET_CreateTcpSocket(DESIP, srcport, desport, &SocketId);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int test_tcp_client(int argc, char* argv[])
|
||||
{
|
||||
KPrintf("TCPClient Test\r\n");
|
||||
Tcp_Client();
|
||||
return 0;
|
||||
}
|
||||
|
||||
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0) | SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN),
|
||||
test_tcp_client, test_tcp_client, test tcp client);
|
|
@ -0,0 +1,42 @@
|
|||
/*
|
||||
* 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 connect_ethernet.h
|
||||
* @brief define rvstar uart function
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2022-08-01
|
||||
*/
|
||||
|
||||
#ifndef CONNECT_ETH_H
|
||||
#define CONNECT_ETH_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
uint8_t InitHwEth();
|
||||
void WCHNET_CreateTcpSocket(uint8_t* DESIP, uint16_t srcport, uint16_t desport, uint8_t* SocketId);
|
||||
void WCHNET_CreateTcpSocketListen(uint16_t srcport, uint8_t* SocketId);
|
||||
|
||||
int WCHNET_HandleGlobalInt(void);
|
||||
|
||||
#define TIME_OUT -1
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,181 @@
|
|||
/********************************** (C) COPYRIGHT ************* ******************
|
||||
* File Name : eth_driver.h
|
||||
* Author : WCH
|
||||
* Version : V1.3.0
|
||||
* Date : 2022/06/02
|
||||
* Description : This file contains the headers of the ETH Driver.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __ETH_DRIVER__
|
||||
#define __ETH_DRIVER__
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include "ch32v30x_eth.h"
|
||||
#include "debug.h"
|
||||
#include "wchnet.h"
|
||||
|
||||
/* Internal 10M PHY */
|
||||
#define USE_10M_BASE 1
|
||||
/* The chips supported by the MII/RMII driver are: CH182/RTL8201F, etc. */
|
||||
#define USE_MAC_MII 2
|
||||
#define USE_MAC_RMII 3
|
||||
#define USE_MAC_RGMII 4
|
||||
|
||||
#ifndef PHY_MODE
|
||||
#define PHY_MODE USE_10M_BASE
|
||||
#endif
|
||||
|
||||
/* 1: interrupt 0: polling in RMII or RGMII mode */
|
||||
#define LINK_STAT_ACQUISITION_METHOD 1
|
||||
|
||||
#define PHY_ADDRESS 1
|
||||
|
||||
#define ETH_DMARxDesc_FrameLengthShift 16
|
||||
|
||||
#define ROM_CFG_USERADR_ID 0x1FFFF7E8
|
||||
|
||||
#define PHY_LINK_TASK_PERIOD 50
|
||||
|
||||
#define PHY_ANLPAR_SELECTOR_FIELD 0x1F
|
||||
#define PHY_ANLPAR_SELECTOR_VALUE 0x01 /* 5B'00001 */
|
||||
|
||||
#define PHY_LINK_INIT 0x00
|
||||
#define PHY_LINK_SUC_P (1 << 0)
|
||||
#define PHY_LINK_SUC_N (1 << 1)
|
||||
#define PHY_LINK_WAIT_SUC (1 << 7)
|
||||
|
||||
#define PHY_PN_SWITCH_P (0 << 2)
|
||||
#define PHY_PN_SWITCH_N (1 << 2)
|
||||
#define PHY_PN_SWITCH_AUTO (2 << 2)
|
||||
|
||||
#ifndef WCHNETTIMERPERIOD
|
||||
#define WCHNETTIMERPERIOD 10 /* Timer period, in Ms. */
|
||||
#endif
|
||||
|
||||
#define GPIO_Output(a, b) \
|
||||
GPIO_InitStructure.GPIO_Pin = b; \
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; \
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; \
|
||||
GPIO_Init(a, &GPIO_InitStructure)
|
||||
|
||||
#define GPIO_Input(a, b) \
|
||||
GPIO_InitStructure.GPIO_Pin = b; \
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; \
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; \
|
||||
GPIO_Init(a, &GPIO_InitStructure)
|
||||
|
||||
#define QUERY_STAT_FLAG ((LastQueryPhyTime == (LocalTime / 1000)) ? 0 : 1)
|
||||
|
||||
#define ENABLE_POLLING_TO_QUERY_PHY_LINK_STAT ((PHY_MODE == USE_MAC_MII) || (((PHY_MODE == USE_MAC_RMII) || (PHY_MODE == USE_MAC_RGMII)) && !LINK_STAT_ACQUISITION_METHOD))
|
||||
|
||||
#define ACCELERATE_LINK_PROCESS() \
|
||||
do { \
|
||||
if ((TRDetectStep < 2) && (ETH_ReadPHYRegister(gPHYAddress, PHY_ANLPAR) & PHY_ANLPAR_SELECTOR_FIELD)) \
|
||||
LinkTaskPeriod = 0; \
|
||||
} while (0)
|
||||
|
||||
#define UPDATE_LINKTASKPERIOD() \
|
||||
do { \
|
||||
if (TRDetectStep == 1) { \
|
||||
RandVal = RandVal * 214017 + 2531017; \
|
||||
LinkTaskPeriod = RandVal % 100 + 50; \
|
||||
} else { \
|
||||
LinkTaskPeriod = 50; \
|
||||
} \
|
||||
} while (0)
|
||||
|
||||
#define PHY_RESTART_AUTONEGOTIATION() \
|
||||
do { \
|
||||
RegVal = ETH_ReadPHYRegister(gPHYAddress, PHY_BCR); \
|
||||
RegVal &= ~0x01; \
|
||||
RegVal |= PHY_Restart_AutoNegotiation; \
|
||||
ETH_WritePHYRegister(gPHYAddress, PHY_BCR, RegVal); \
|
||||
RegVal = ETH_ReadPHYRegister(gPHYAddress, PHY_BCR); \
|
||||
RegVal |= 0x03 | PHY_Restart_AutoNegotiation; \
|
||||
ETH_WritePHYRegister(gPHYAddress, PHY_BCR, RegVal); \
|
||||
} while (0)
|
||||
|
||||
#define PHY_TR_SWITCH() \
|
||||
do { \
|
||||
phy_mdix = ETH_ReadPHYRegister(gPHYAddress, PHY_MDIX); \
|
||||
if (phy_mdix & 0x01) { \
|
||||
phy_mdix &= ~0x03; \
|
||||
phy_mdix |= 1 << 1; \
|
||||
} else { \
|
||||
phy_mdix &= ~0x03; \
|
||||
phy_mdix |= 1 << 0; \
|
||||
} \
|
||||
ETH_WritePHYRegister(gPHYAddress, PHY_MDIX, phy_mdix); \
|
||||
PHY_RESTART_AUTONEGOTIATION(); \
|
||||
} while (0)
|
||||
|
||||
#define PHY_TR_REVERSE() \
|
||||
do { \
|
||||
RegVal = ETH_ReadPHYRegister(gPHYAddress, PHY_MDIX); \
|
||||
if (RegVal & 0x01) { \
|
||||
RegVal &= ~0x03; \
|
||||
RegVal |= 1 << 1; \
|
||||
} else { \
|
||||
RegVal &= ~0x03; \
|
||||
RegVal |= 1 << 0; \
|
||||
} \
|
||||
ETH_WritePHYRegister(gPHYAddress, PHY_MDIX, RegVal); \
|
||||
} while (0)
|
||||
|
||||
#define PHY_PN_SWITCH(PNMode) \
|
||||
do { \
|
||||
if (PNMode == PHY_PN_SWITCH_AUTO) { \
|
||||
phyPN = PHY_PN_SWITCH_AUTO; \
|
||||
} else { \
|
||||
phyPN = (ETH_ReadPHYRegister(gPHYAddress, PHY_MDIX) & (~(0x03 << 2))) | PNMode; \
|
||||
} \
|
||||
ETH_WritePHYRegister(gPHYAddress, PHY_MDIX, phyPN); \
|
||||
phyPN = PNMode; \
|
||||
PHY_RESTART_AUTONEGOTIATION(); \
|
||||
} while (0)
|
||||
|
||||
#define PHY_NEGOTIATION_PARAM_INIT() \
|
||||
do { \
|
||||
phyStatus = 0; \
|
||||
phySucCnt = 0; \
|
||||
phyLinkCnt = 0; \
|
||||
TRDetectStep = 0; \
|
||||
PhyPolarityDetect = 0; \
|
||||
phyLinkStatus = PHY_LINK_INIT; \
|
||||
phyPN = PHY_PN_SWITCH_AUTO; \
|
||||
ETH_WritePHYRegister(gPHYAddress, PHY_MDIX, phyPN); \
|
||||
} while (0)
|
||||
|
||||
#define PHY_LINK_RESET() \
|
||||
do { \
|
||||
ETH_WritePHYRegister(gPHYAddress, PHY_BCR, PHY_Reset); \
|
||||
PHY_NEGOTIATION_PARAM_INIT(); \
|
||||
} while (0)
|
||||
|
||||
extern ETH_DMADESCTypeDef* DMATxDescToSet;
|
||||
extern ETH_DMADESCTypeDef* DMARxDescToGet;
|
||||
extern SOCK_INF SocketInf[];
|
||||
|
||||
void ETH_PHYLink(void);
|
||||
void WCHNET_ETHIsr(void);
|
||||
void WCHNET_MainTask(void);
|
||||
void ETH_LedConfiguration(void);
|
||||
void ETH_Init(uint8_t* macAddr);
|
||||
void ETH_LedLinkSet(uint8_t mode);
|
||||
void ETH_LedDataSet(uint8_t mode);
|
||||
void WCHNET_TimeIsr(uint16_t timperiod);
|
||||
void ETH_Configuration(uint8_t* macAddr);
|
||||
uint8_t ETH_LibInit(uint8_t* ip, uint8_t* gwip, uint8_t* mask, uint8_t* macaddr);
|
||||
void WCHNET_MainTask(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,160 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : net_config.h
|
||||
* Author : WCH
|
||||
* Version : V1.30
|
||||
* Date : 2022/06/02
|
||||
* Description : This file contains the configurations of
|
||||
* Ethernet protocol stack library
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __NET_CONFIG_H__
|
||||
#define __NET_CONFIG_H__
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/*********************************************************************
|
||||
* socket configuration, IPRAW + UDP + TCP + TCP_LISTEN = number of sockets
|
||||
*/
|
||||
#define WCHNET_NUM_IPRAW 0 /* Number of IPRAW connections */
|
||||
|
||||
#define WCHNET_NUM_UDP 0 /* The number of UDP connections */
|
||||
|
||||
#define WCHNET_NUM_TCP 1 /* Number of TCP connections */
|
||||
|
||||
#define WCHNET_NUM_TCP_LISTEN 0 /* Number of TCP listening */
|
||||
|
||||
/* The number of sockets, the maximum is 31 */
|
||||
#define WCHNET_MAX_SOCKET_NUM (WCHNET_NUM_IPRAW + WCHNET_NUM_UDP + WCHNET_NUM_TCP + WCHNET_NUM_TCP_LISTEN)
|
||||
|
||||
#define WCHNET_TCP_MSS 1460 /* Size of TCP MSS*/
|
||||
|
||||
#define WCHNET_NUM_POOL_BUF (WCHNET_NUM_TCP * 2 + 2) /* The number of POOL BUFs, the number of receive queues */
|
||||
|
||||
/*********************************************************************
|
||||
* MAC queue configuration
|
||||
*/
|
||||
#define ETH_TXBUFNB 2 /* The number of descriptors sent by the MAC */
|
||||
|
||||
#define ETH_RXBUFNB 4 /* Number of MAC received descriptors */
|
||||
|
||||
#ifndef ETH_MAX_PACKET_SIZE
|
||||
#define ETH_RX_BUF_SZE 1520 /* MAC receive buffer length, an integer multiple of 4 */
|
||||
#define ETH_TX_BUF_SZE 1520 /* MAC send buffer length, an integer multiple of 4 */
|
||||
#else
|
||||
#define ETH_RX_BUF_SZE ETH_MAX_PACKET_SIZE
|
||||
#define ETH_TX_BUF_SZE ETH_MAX_PACKET_SIZE
|
||||
#endif
|
||||
|
||||
/*********************************************************************
|
||||
* Functional configuration
|
||||
*/
|
||||
#define WCHNET_PING_ENABLE 1 /* PING is enabled, PING is enabled by default */
|
||||
|
||||
#define TCP_RETRY_COUNT 20 /* The number of TCP retransmissions, the default value is 20 */
|
||||
|
||||
#define TCP_RETRY_PERIOD 10 /* TCP retransmission period, the default value is 10, the unit is 50ms */
|
||||
|
||||
#define SOCKET_SEND_RETRY 0 /* Send failed retry configuration, 1: enable, 0: disable */
|
||||
|
||||
#define HARDWARE_CHECKSUM_CONFIG 0 /* Hardware checksum checking and insertion configuration, 1: enable, 0: disable */
|
||||
|
||||
#define FINE_DHCP_PERIOD 8 /* Fine DHCP period, the default value is 8, the unit is 250ms */
|
||||
|
||||
#define CFG0_TCP_SEND_COPY 1 /* TCP send buffer copy, 1: copy, 0: not copy */
|
||||
|
||||
#define CFG0_TCP_RECV_COPY 1 /* TCP receive replication optimization, internal debugging use */
|
||||
|
||||
#define CFG0_TCP_OLD_DELETE 0 /* Delete oldest TCP connection, 1: enable, 0: disable */
|
||||
|
||||
#define CFG0_IP_REASS_PBUFS 0 /* Number of reassembled IP PBUFs */
|
||||
|
||||
#define CFG0_TCP_DEALY_ACK_DISABLE 1 /* 1: disable TCP delay ACK 0: enable TCP delay ACK */
|
||||
|
||||
/*********************************************************************
|
||||
* Memory related configuration
|
||||
*/
|
||||
/* If you want to achieve a higher transmission speed,
|
||||
* try to increase RECE_BUF_LEN to (WCHNET_TCP_MSS*4)
|
||||
* and increase WCHNET_NUM_TCP_SEG to (WCHNET_NUM_TCP*4)*/
|
||||
#define RECE_BUF_LEN (WCHNET_TCP_MSS * 2) /* socket receive buffer size */
|
||||
|
||||
#define WCHNET_NUM_PBUF WCHNET_NUM_POOL_BUF /* Number of PBUF structures */
|
||||
|
||||
#define WCHNET_NUM_TCP_SEG (WCHNET_NUM_TCP * 2) /* The number of TCP segments used to send */
|
||||
|
||||
#define WCHNET_MEM_HEAP_SIZE (((WCHNET_TCP_MSS + 0x10 + 54 + 8) * WCHNET_NUM_TCP_SEG) + ETH_TX_BUF_SZE + 64 + 2 * 0x18) /* memory heap size */
|
||||
|
||||
#define WCHNET_NUM_ARP_TABLE 50 /* Number of ARP lists */
|
||||
|
||||
#define WCHNET_MEM_ALIGNMENT 4 /* 4 byte alignment */
|
||||
|
||||
#if CFG0_IP_REASS_PBUFS
|
||||
#define WCHNET_NUM_IP_REASSDATA 2 /* Number of reassembled IP structures */
|
||||
/*1: When using the fragmentation function,
|
||||
* ensure that the size of WCHNET_SIZE_POOL_BUF is large enough to store a single fragmented packet*/
|
||||
#define WCHNET_SIZE_POOL_BUF (((1500 + 14 + 4) + 3) & ~3) /* Buffer size for receiving a single packet */
|
||||
/*2: When creating a socket that can receive fragmented packets,
|
||||
* ensure that "RecvBufLen" member of the "struct _SOCK_INF" structure
|
||||
* (the parameter initialized when calling WCHNET_SocketCreat) is sufficient
|
||||
* to receive a complete fragmented packet */
|
||||
#else
|
||||
#define WCHNET_NUM_IP_REASSDATA 0 /* Number of reassembled IP structures */
|
||||
#define WCHNET_SIZE_POOL_BUF (((WCHNET_TCP_MSS + 40 + 14 + 4) + 3) & ~3) /* Buffer size for receiving a single packet */
|
||||
#endif
|
||||
|
||||
/* Check receive buffer */
|
||||
#if (WCHNET_NUM_POOL_BUF * WCHNET_SIZE_POOL_BUF < ETH_RX_BUF_SZE)
|
||||
#error "WCHNET_NUM_POOL_BUF or WCHNET_TCP_MSS Error"
|
||||
#error "Please Increase WCHNET_NUM_POOL_BUF or WCHNET_TCP_MSS to make sure the receive buffer is sufficient"
|
||||
#endif
|
||||
/* Check the configuration of the SOCKET quantity */
|
||||
#if (WCHNET_NUM_TCP_LISTEN && !WCHNET_NUM_TCP)
|
||||
#error "WCHNET_NUM_TCP Error,Please Configure WCHNET_NUM_TCP >= 1"
|
||||
#endif
|
||||
/* Check byte alignment must be a multiple of 4 */
|
||||
#if ((WCHNET_MEM_ALIGNMENT % 4) || (WCHNET_MEM_ALIGNMENT == 0))
|
||||
#error "WCHNET_MEM_ALIGNMENT Error,Please Configure WCHNET_MEM_ALIGNMENT = 4 * N, N >=1"
|
||||
#endif
|
||||
/* TCP maximum segment length */
|
||||
#if ((WCHNET_TCP_MSS > 1460) || (WCHNET_TCP_MSS < 60))
|
||||
#error "WCHNET_TCP_MSS Error,Please Configure WCHNET_TCP_MSS >= 60 && WCHNET_TCP_MSS <= 1460"
|
||||
#endif
|
||||
/* Number of ARP cache tables */
|
||||
#if ((WCHNET_NUM_ARP_TABLE > 0X7F) || (WCHNET_NUM_ARP_TABLE < 1))
|
||||
#error "WCHNET_NUM_ARP_TABLE Error,Please Configure WCHNET_NUM_ARP_TABLE >= 1 && WCHNET_NUM_ARP_TABLE <= 0X7F"
|
||||
#endif
|
||||
/* Check POOL BUF configuration */
|
||||
#if (WCHNET_NUM_POOL_BUF < 1)
|
||||
#error "WCHNET_NUM_POOL_BUF Error,Please Configure WCHNET_NUM_POOL_BUF >= 1"
|
||||
#endif
|
||||
/* Check PBUF structure configuration */
|
||||
#if (WCHNET_NUM_PBUF < 1)
|
||||
#error "WCHNET_NUM_PBUF Error,Please Configure WCHNET_NUM_PBUF >= 1"
|
||||
#endif
|
||||
/* Check IP Assignment Configuration */
|
||||
#if (CFG0_IP_REASS_PBUFS && ((WCHNET_NUM_IP_REASSDATA > 10) || (WCHNET_NUM_IP_REASSDATA < 1)))
|
||||
#error "WCHNET_NUM_IP_REASSDATA Error,Please Configure WCHNET_NUM_IP_REASSDATA < 10 && WCHNET_NUM_IP_REASSDATA >= 1 "
|
||||
#endif
|
||||
/* Check the number of reassembled IP PBUFs */
|
||||
#if (CFG0_IP_REASS_PBUFS > WCHNET_NUM_POOL_BUF)
|
||||
#error "WCHNET_NUM_POOL_BUF Error,Please Configure CFG0_IP_REASS_PBUFS < WCHNET_NUM_POOL_BUF"
|
||||
#endif
|
||||
/* Check Timer period, in Ms. */
|
||||
#if (WCHNETTIMERPERIOD > 50)
|
||||
#error "WCHNETTIMERPERIOD Error,Please Configure WCHNETTIMERPERIOD < 50"
|
||||
#endif
|
||||
|
||||
/* Configuration value 0 */
|
||||
#define WCHNET_MISC_CONFIG0 (((CFG0_TCP_SEND_COPY) << 0) | ((CFG0_TCP_RECV_COPY) << 1) | ((CFG0_TCP_OLD_DELETE) << 2) | ((CFG0_IP_REASS_PBUFS) << 3) | ((CFG0_TCP_DEALY_ACK_DISABLE) << 8))
|
||||
/* Configuration value 1 */
|
||||
#define WCHNET_MISC_CONFIG1 (((WCHNET_MAX_SOCKET_NUM) << 0) | ((WCHNET_PING_ENABLE) << 13) | ((TCP_RETRY_COUNT) << 14) | ((TCP_RETRY_PERIOD) << 19) | ((SOCKET_SEND_RETRY) << 25) | ((HARDWARE_CHECKSUM_CONFIG) << 26) | ((FINE_DHCP_PERIOD) << 27))
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif
|
|
@ -0,0 +1,591 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : wchnet.h
|
||||
* Author : WCH
|
||||
* Version : V1.80
|
||||
* Date : 2023/05/12
|
||||
* Description : This file contains the headers of
|
||||
* the Ethernet protocol stack library.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __WCHNET_H__
|
||||
#define __WCHNET_H__
|
||||
|
||||
#include "stdint.h"
|
||||
#ifndef NET_LIB
|
||||
#include "net_config.h"
|
||||
#endif
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define WCHNET_LIB_VER 0x18 // the library version number
|
||||
#define WCHNET_CFG_VALID 0x12345678 // Configuration value valid flag
|
||||
|
||||
/* LED state @LED_STAT */
|
||||
#define LED_ON 0
|
||||
#define LED_OFF 1
|
||||
|
||||
/* PHY state @PHY_STAT */
|
||||
#define PHY_LINK_SUCCESS (1 << 2) // PHY connection success
|
||||
#define PHY_AUTO_SUCCESS (1 << 5) // PHY auto negotiation completed
|
||||
|
||||
/* Library initialization state @CFG_INIT_STAT */
|
||||
#define INIT_OK 0x00
|
||||
#define INIT_ERR_RX_BUF_SIZE 0x01
|
||||
#define INIT_ERR_TCP_MSS 0x02
|
||||
#define INIT_ERR_HEAP_SIZE 0x03
|
||||
#define INIT_ERR_ARP_TABLE_NEM 0x04
|
||||
#define INIT_ERR_MISC_CONFIG0 0x05
|
||||
#define INIT_ERR_MISC_CONFIG1 0x06
|
||||
#define INIT_ERR_FUNC_SEND 0x09
|
||||
#define INIT_ERR_CHECK_VALID 0xFF
|
||||
|
||||
/* Socket protocol type */
|
||||
#define PROTO_TYPE_IP_RAW 0 // IP layer raw data
|
||||
#define PROTO_TYPE_UDP 2 // UDP protocol
|
||||
#define PROTO_TYPE_TCP 3 // TCP protocol
|
||||
|
||||
/* interrupt status */
|
||||
/* The following are the states
|
||||
* that GLOB_INT will generate */
|
||||
#define GINT_STAT_UNREACH (1 << 0) // unreachable interrupt
|
||||
#define GINT_STAT_IP_CONFLI (1 << 1) // IP conflict interrupt
|
||||
#define GINT_STAT_PHY_CHANGE (1 << 2) // PHY state change interrupt
|
||||
#define GINT_STAT_SOCKET (1 << 4) // socket related interrupt
|
||||
|
||||
/* The following are the states
|
||||
* that Sn_INT will generate*/
|
||||
#define SINT_STAT_RECV (1 << 2) // the socket receives data or the receive buffer is not empty
|
||||
#define SINT_STAT_CONNECT (1 << 3) // connect successfully,generated in TCP mode
|
||||
#define SINT_STAT_DISCONNECT (1 << 4) // disconnect,generated in TCP mode
|
||||
#define SINT_STAT_TIM_OUT (1 << 6) // timeout disconnect,generated in TCP mode
|
||||
|
||||
/* Definitions for error constants. @ERR_T */
|
||||
#define ERR_T
|
||||
#define WCHNET_ERR_SUCCESS 0x00 // No error, everything OK
|
||||
#define WCHNET_ERR_BUSY 0x10 // busy
|
||||
#define WCHNET_ERR_MEM 0x11 // Out of memory error
|
||||
#define WCHNET_ERR_BUF 0x12 // Buffer error
|
||||
#define WCHNET_ERR_TIMEOUT 0x13 // Timeout
|
||||
#define WCHNET_ERR_RTE 0x14 // Routing problem
|
||||
#define WCHNET_ERR_ABRT 0x15 // Connection aborted
|
||||
#define WCHNET_ERR_RST 0x16 // Connection reset
|
||||
#define WCHNET_ERR_CLSD 0x17 // Connection closed
|
||||
#define WCHNET_ERR_CONN 0x18 // Not connected
|
||||
#define WCHNET_ERR_VAL 0x19 // Illegal value
|
||||
#define WCHNET_ERR_ARG 0x1a // Illegal argument
|
||||
#define WCHNET_ERR_USE 0x1b // Address in use
|
||||
#define WCHNET_ERR_IF 0x1c // Low-level netif error
|
||||
#define WCHNET_ERR_ISCONN 0x1d // Already connected
|
||||
#define WCHNET_ERR_INPROGRESS 0x1e // Operation in progress
|
||||
#define WCHNET_ERR_SOCKET_MEM 0X20 // Socket information error
|
||||
#define WCHNET_ERR_UNSUPPORT_PROTO 0X21 // unsupported protocol type
|
||||
#define WCHNET_RET_ABORT 0x5F // command process fail
|
||||
#define WCHNET_ERR_UNKNOW 0xFA // unknow
|
||||
|
||||
/* unreachable condition related codes */
|
||||
#define UNREACH_CODE_HOST 0 // host unreachable
|
||||
#define UNREACH_CODE_NET 1 // network unreachable
|
||||
#define UNREACH_CODE_PROTOCOL 2 // protocol unreachable
|
||||
#define UNREACH_CODE_PROT 3 // port unreachable
|
||||
/*For other values, please refer to the RFC792 document*/
|
||||
|
||||
/* TCP disconnect related codes */
|
||||
#define TCP_CLOSE_NORMAL 0 // normal disconnect,a four-way handshake
|
||||
#define TCP_CLOSE_RST 1 // reset the connection and close
|
||||
#define TCP_CLOSE_ABANDON 2 // drop connection, and no termination message is sent
|
||||
|
||||
/* socket state code */
|
||||
#define SOCK_STAT_CLOSED 0X00 // socket close
|
||||
#define SOCK_STAT_OPEN 0X05 // socket open
|
||||
|
||||
/* TCP state code */
|
||||
#define TCP_CLOSED 0 // TCP close
|
||||
#define TCP_LISTEN 1 // TCP listening
|
||||
#define TCP_SYN_SENT 2 // SYN send, connect request
|
||||
#define TCP_SYN_RCVD 3 // SYN received, connection request received
|
||||
#define TCP_ESTABLISHED 4 // TCP connection establishment
|
||||
#define TCP_FIN_WAIT_1 5 // WAIT_1 state
|
||||
#define TCP_FIN_WAIT_2 6 // WAIT_2 state
|
||||
#define TCP_CLOSE_WAIT 7 // wait to close
|
||||
#define TCP_CLOSING 8 // closing
|
||||
#define TCP_LAST_ACK 9 // LAST_ACK
|
||||
#define TCP_TIME_WAIT 10 // 2MSL wait
|
||||
|
||||
/* The following values are fixed and cannot be changed */
|
||||
#define WCHNET_MEM_ALIGN_SIZE(size) (((size) + WCHNET_MEM_ALIGNMENT - 1) & ~(WCHNET_MEM_ALIGNMENT - 1))
|
||||
#define WCHNET_SIZE_IPRAW_PCB 0x1C // IPRAW PCB size
|
||||
#define WCHNET_SIZE_UDP_PCB 0x20 // UDP PCB size
|
||||
#define WCHNET_SIZE_TCP_PCB 0xB4 // TCP PCB size
|
||||
#define WCHNET_SIZE_TCP_PCB_LISTEN 0x24 // TCP LISTEN PCB size
|
||||
#define WCHNET_SIZE_IP_REASSDATA 0x20 // IP reassembled Management
|
||||
#define WCHNET_SIZE_PBUF 0x10 // Packet Buf
|
||||
#define WCHNET_SIZE_TCP_SEG 0x14 // TCP SEG structure
|
||||
#define WCHNET_SIZE_MEM 0x08 // sizeof(struct mem)
|
||||
#define WCHNET_SIZE_ARP_TABLE 0x18 // sizeof ARP table
|
||||
|
||||
#define WCHNET_MEMP_SIZE ((WCHNET_MEM_ALIGNMENT - 1) + (WCHNET_NUM_IPRAW * WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_IPRAW_PCB)) + (WCHNET_NUM_UDP * WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_UDP_PCB)) + (WCHNET_NUM_TCP * WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_TCP_PCB)) + (WCHNET_NUM_TCP_LISTEN * WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_TCP_PCB_LISTEN)) + (WCHNET_NUM_TCP_SEG * WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_TCP_SEG)) + (WCHNET_NUM_IP_REASSDATA * WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_IP_REASSDATA)) + (WCHNET_NUM_PBUF * WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_PBUF)) + (WCHNET_NUM_POOL_BUF * (WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_PBUF) + WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_POOL_BUF))))
|
||||
|
||||
#define HEAP_MEM_ALIGN_SIZE (WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_MEM))
|
||||
#define WCHNET_RAM_HEAP_SIZE (WCHNET_MEM_ALIGN_SIZE(WCHNET_MEM_HEAP_SIZE) + HEAP_MEM_ALIGN_SIZE)
|
||||
#define WCHNET_RAM_ARP_TABLE_SIZE (WCHNET_MEM_ALIGN_SIZE(WCHNET_SIZE_ARP_TABLE) * WCHNET_NUM_ARP_TABLE)
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t length;
|
||||
uint32_t buffer;
|
||||
} ETHFrameType;
|
||||
|
||||
/* LED callback type */
|
||||
typedef void (*led_callback)(uint8_t setbit);
|
||||
|
||||
/* net send callback type */
|
||||
typedef uint32_t (*eth_tx_set)(uint16_t len, uint32_t* pBuff);
|
||||
|
||||
/* net receive callback type */
|
||||
typedef uint32_t (*eth_rx_set)(ETHFrameType* pkt);
|
||||
|
||||
/* DNS callback type */
|
||||
typedef void (*dns_callback)(const char* name, uint8_t* ipaddr, void* callback_arg);
|
||||
|
||||
/* DHCP callback type */
|
||||
typedef uint8_t (*dhcp_callback)(uint8_t status, void*);
|
||||
|
||||
/* socket receive callback type */
|
||||
struct _SOCK_INF;
|
||||
typedef void (*pSockRecv)(struct _SOCK_INF*, uint32_t, uint16_t, uint8_t*, uint32_t);
|
||||
|
||||
/* Socket information struct */
|
||||
typedef struct _SOCK_INF {
|
||||
uint32_t IntStatus; // interrupt state
|
||||
uint32_t SockIndex; // Socket index value
|
||||
uint32_t RecvStartPoint; // Start pointer of the receive buffer
|
||||
uint32_t RecvBufLen; // Receive buffer length
|
||||
uint32_t RecvCurPoint; // current pointer to receive buffer
|
||||
uint32_t RecvReadPoint; // The read pointer of the receive buffer
|
||||
uint32_t RecvRemLen; // The length of the remaining data in the receive buffer
|
||||
uint32_t ProtoType; // protocol type
|
||||
uint32_t SockStatus; // Low byte Socket state, the next low byte is TCP state, only meaningful in TCP mode
|
||||
uint32_t DesPort; // destination port
|
||||
uint32_t SourPort; // Source port, protocol type in IPRAW mode
|
||||
uint8_t IPAddr[4]; // Socket destination IP address
|
||||
void* Resv1; // Reserved, for internal use, for saving individual PCBs
|
||||
void* Resv2; // Reserved, used internally, used by TCP Server
|
||||
pSockRecv AppCallBack; // receive callback function
|
||||
} SOCK_INF;
|
||||
|
||||
struct _WCH_CFG {
|
||||
uint32_t TxBufSize; // MAC send buffer size, reserved for use
|
||||
uint32_t TCPMss; // TCP MSS size
|
||||
uint32_t HeapSize; // heap memory size
|
||||
uint32_t ARPTableNum; // Number of ARP lists
|
||||
uint32_t MiscConfig0; // Miscellaneous Configuration 0
|
||||
/* Bit 0 TCP send buffer copy 1: copy, 0: not copy */
|
||||
/* Bit 1 TCP receive replication optimization, used for internal debugging */
|
||||
/* bit 2 delete oldest TCP connection 1: enable, 0: disable */
|
||||
/* Bits 3-7 Number of PBUFs of IP segments */
|
||||
/* Bit 8 TCP Delay ACK disable */
|
||||
uint32_t MiscConfig1; // Miscellaneous Configuration 1
|
||||
/* Bits 0-7 Number of Sockets*/
|
||||
/* Bits 8-12 Reserved */
|
||||
/* Bit 13 PING enable, 1: On 0: Off */
|
||||
/* Bits 14-18 TCP retransmission times */
|
||||
/* Bits 19-23 TCP retransmission period, in 50 milliseconds */
|
||||
/* bit 25 send failed retry, 1: enable, 0: disable */
|
||||
/* bit 26 Select whether to perform IPv4 checksum check on
|
||||
* the TCP/UDP/ICMP header of the received frame payload by hardware,
|
||||
* and calculate and insert the checksum of the IP header and payload of the sent frame by hardware.*/
|
||||
/* Bits 27-31 period (in 250 milliseconds) of Fine DHCP periodic process */
|
||||
led_callback led_link; // PHY Link Status Indicator
|
||||
led_callback led_data; // Ethernet communication indicator
|
||||
eth_tx_set net_send; // Ethernet send
|
||||
eth_rx_set net_recv; // Ethernet receive
|
||||
uint32_t CheckValid; // Configuration value valid flag, fixed value @WCHNET_CFG_VALID
|
||||
};
|
||||
|
||||
struct _NET_SYS {
|
||||
uint8_t IPAddr[4]; // IP address
|
||||
uint8_t GWIPAddr[4]; // Gateway IP address
|
||||
uint8_t MASKAddr[4]; // subnet mask
|
||||
uint8_t MacAddr[8]; // MAC address
|
||||
uint8_t UnreachIPAddr[4]; // Unreachable IP address
|
||||
uint32_t RetranCount; // number of retries,default is 10 times
|
||||
uint32_t RetranPeriod; // Retry period, unit MS, default 500MS
|
||||
uint32_t PHYStat; // PHY state code
|
||||
uint32_t NetStat; // The status of the Ethernet, including whether it is open, etc.
|
||||
uint32_t MackFilt; // MAC filtering, the default is to receive broadcasts, receive local MAC
|
||||
uint32_t GlobIntStatus; // global interrupt
|
||||
uint32_t UnreachCode; // unreachable code
|
||||
uint32_t UnreachProto; // unreachable protocol
|
||||
uint32_t UnreachPort; // unreachable port
|
||||
uint32_t SendFlag;
|
||||
uint32_t Flags;
|
||||
};
|
||||
|
||||
/* KEEP LIVE configuration structure */
|
||||
struct _KEEP_CFG {
|
||||
uint32_t KLIdle; // KEEPLIVE idle time, in ms
|
||||
uint32_t KLIntvl; // KEEPLIVE period, in ms
|
||||
uint32_t KLCount; // KEEPLIVE times
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Library initialization .
|
||||
*
|
||||
* @param ip - IP address pointer
|
||||
* @param gwip - Gateway address pointer
|
||||
* @param mask - Subnet mask pointer
|
||||
* @param macaddr - MAC address pointer
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_Init(const uint8_t* ip, const uint8_t* gwip, const uint8_t* mask, const uint8_t* macaddr);
|
||||
|
||||
/**
|
||||
* @brief get library version
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return library version
|
||||
*/
|
||||
uint8_t WCHNET_GetVer(void);
|
||||
|
||||
/**
|
||||
* @brief Get MAC address.
|
||||
*
|
||||
* @param(in) macaddr - MAC address
|
||||
*
|
||||
* @param(out) MAC address
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_GetMacAddr(uint8_t* macaddr);
|
||||
|
||||
/**
|
||||
* @brief Library parameter configuration.
|
||||
*
|
||||
* @param cfg - Configuration parameter @_WCH_CFG
|
||||
*
|
||||
* @return Library configuration initialization state @CFG_INIT_STAT
|
||||
*/
|
||||
uint8_t WCHNET_ConfigLIB(struct _WCH_CFG* cfg);
|
||||
|
||||
/**
|
||||
* @brief Handle periodic tasks in the protocol stack
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_PeriodicHandle(void);
|
||||
|
||||
/**
|
||||
* @brief Ethernet data input. Always called in the main program,
|
||||
* or called after the reception interrupt is detected.
|
||||
*
|
||||
* @param
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_NetInput(void);
|
||||
|
||||
/**
|
||||
* @brief Ethernet interrupt service function. Called after
|
||||
* Ethernet interrupt is generated.
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_ETHIsr(void);
|
||||
|
||||
/**
|
||||
* @brief Get PHY status
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return PHY status @PHY_STAT
|
||||
*/
|
||||
uint8_t WCHNET_GetPHYStatus(void);
|
||||
|
||||
/**
|
||||
* @brief Query global interrupt status.
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return GLOB_INT
|
||||
*/
|
||||
uint8_t WCHNET_QueryGlobalInt(void);
|
||||
|
||||
/**
|
||||
* @brief Read global interrupt and clear it.
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return GLOB_INT
|
||||
*/
|
||||
uint8_t WCHNET_GetGlobalInt(void);
|
||||
|
||||
/**
|
||||
* @brief create socket
|
||||
*
|
||||
* @param(in) *socketid - socket variable pointer
|
||||
* @param socinf - Configuration parameters for creating sockets @SOCK_INF
|
||||
*
|
||||
* @param(out) *socketid - socket value
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketCreat(uint8_t* socketid, SOCK_INF* socinf);
|
||||
|
||||
/**
|
||||
* @brief Socket sends data.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param *buf - the first address of send buffer
|
||||
* @param(in) *len - pointer to the length of the data expected to be sent
|
||||
*
|
||||
* @param(out) *len - pointer to the length of the data sent actually
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketSend(uint8_t socketid, uint8_t* buf, uint32_t* len);
|
||||
|
||||
/**
|
||||
* @brief Socket receives data.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param *buf - the first address of receive buffer
|
||||
* @param(in) *len - pointer to the length of the data expected to be read
|
||||
*
|
||||
* @param(out) *buf - the first address of data buffer
|
||||
* @param(out) *len - pointer to the length of the data read actually
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketRecv(uint8_t socketid, uint8_t* buf, uint32_t* len);
|
||||
|
||||
/**
|
||||
* @brief Get socket interrupt, and clear socket interrupt.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
*
|
||||
* @return Sn_INT
|
||||
*/
|
||||
uint8_t WCHNET_GetSocketInt(uint8_t socketid);
|
||||
|
||||
/**
|
||||
* @brief Get the length of the data received by socket.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param(in) *bufaddr - the first address of receive buffer
|
||||
*
|
||||
* @param(out) *bufaddr - the first address of data buffer
|
||||
*
|
||||
* @return the length of the data
|
||||
*/
|
||||
uint32_t WCHNET_SocketRecvLen(uint8_t socketid, uint32_t* bufaddr);
|
||||
|
||||
/**
|
||||
* @brief TCP connect. Used in TCP Client mode.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketConnect(uint8_t socketid);
|
||||
|
||||
/**
|
||||
* @brief TCP listen. Used in TCP SERVER mode.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketListen(uint8_t socketid);
|
||||
|
||||
/**
|
||||
* @brief Close socket.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param mode - the way of disconnection.Used in TCP connection.
|
||||
* @TCP disconnect related codes
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketClose(uint8_t socketid, uint8_t mode);
|
||||
|
||||
/**
|
||||
* @brief Modify socket receive buffer.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param bufaddr - Address of the receive buffer
|
||||
* @param bufsize - Size of the receive buffer
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_ModifyRecvBuf(uint8_t socketid, uint32_t bufaddr, uint32_t bufsize);
|
||||
|
||||
/**
|
||||
* @brief UDP send, specify the target IP and target port
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param *buf - Address of the sent data
|
||||
* @param(in) *slen - Address of the sent length
|
||||
* @param *sip - destination IP address
|
||||
* @param port - destination port
|
||||
*
|
||||
* @param(out) *slen - actual length sent
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketUdpSendTo(uint8_t socketid, uint8_t* buf, uint32_t* slen, uint8_t* sip, uint16_t port);
|
||||
|
||||
/**
|
||||
* @brief Convert ASCII address to network address.
|
||||
*
|
||||
* @param *cp - ASCII address to be converted, such as "192.168.1.2"
|
||||
* @param(in) *addr - First address of the memory stored in the converted network address
|
||||
* @param(out) *addr - Converted network address, such as 0xC0A80102
|
||||
* @return 0 - Success. Others - Failure.
|
||||
*/
|
||||
uint8_t WCHNET_Aton(const char* cp, uint8_t* addr);
|
||||
|
||||
/**
|
||||
* @brief Convert network address to ASCII address.
|
||||
*
|
||||
* @param *ipaddr - socket id value
|
||||
*
|
||||
* @return Converted ASCII address
|
||||
*/
|
||||
uint8_t* WCHNET_Ntoa(uint8_t* ipaddr);
|
||||
|
||||
/**
|
||||
* @brief Set socket TTL.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param ttl - TTL value
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SetSocketTTL(uint8_t socketid, uint8_t ttl);
|
||||
|
||||
/**
|
||||
* @brief Start TCP retry sending immediately.
|
||||
*
|
||||
* @param socketid - TTL value
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_RetrySendUnack(uint8_t socketid);
|
||||
|
||||
/**
|
||||
* @brief Query the packets that are not sent successfully.
|
||||
*
|
||||
* @param socketid - TTL value
|
||||
* @param(in) *addrlist - pointer to the address of the address list
|
||||
* @param lislen - Length of the list
|
||||
*
|
||||
* @param(out) *addrlist - Address list of the data packets that are not sent successfully
|
||||
*
|
||||
* @return Number of unsent and unacknowledged segments
|
||||
*/
|
||||
uint8_t WCHNET_QueryUnack(uint8_t socketid, uint32_t* addrlist, uint16_t lislen);
|
||||
|
||||
/**
|
||||
* @brief Start DHCP.
|
||||
*
|
||||
* @param dhcp - Application layer callback function
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_DHCPStart(dhcp_callback dhcp);
|
||||
|
||||
/**
|
||||
* @brief Stop DHCP.
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_DHCPStop(void);
|
||||
|
||||
/**
|
||||
* @brief Configure DHCP host name.
|
||||
*
|
||||
* @param *name - First address of DHCP host name
|
||||
*
|
||||
* @return 0 - Success. Others - Failure.
|
||||
*/
|
||||
uint8_t WCHNET_DHCPSetHostname(char* name);
|
||||
|
||||
/**
|
||||
* @brief Initialize the resolver: set up the UDP pcb and configure the default server
|
||||
*
|
||||
* @param *dnsip - the IP address of dns server
|
||||
* @param port - the port number of dns server
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_InitDNS(uint8_t* dnsip, uint16_t port);
|
||||
|
||||
/**
|
||||
* @brief Stop DNS.
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_DNSStop(void);
|
||||
|
||||
/**
|
||||
* Resolve a hostname (string) into an IP address.
|
||||
*
|
||||
* @param hostname - the hostname that is to be queried
|
||||
* @param addr - pointer to a struct ip_addr where to store the address if it is already
|
||||
* cached in the dns_table (only valid if ERR_OK is returned!)
|
||||
* @param found - a callback function to be called on success, failure or timeout (only if
|
||||
* ERR_INPROGRESS is returned!)
|
||||
* @param arg - argument to pass to the callback function
|
||||
*
|
||||
* @return @ERR_T
|
||||
* WCHNET_ERR_SUCCESS if hostname is a valid IP address string or the host name is already in the local names table.
|
||||
* ERR_INPROGRESS enqueue a request to be sent to the DNS server for resolution if no errors are present.
|
||||
*/
|
||||
uint8_t WCHNET_HostNameGetIp(const char* hostname, uint8_t* addr, dns_callback found, void* arg);
|
||||
|
||||
/**
|
||||
* @brief Configure KEEP LIVE parameter.
|
||||
*
|
||||
* @param *cfg - KEEPLIVE configuration parameter
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_ConfigKeepLive(struct _KEEP_CFG* cfg);
|
||||
|
||||
/**
|
||||
* @brief Configure socket KEEP LIVE enable.
|
||||
*
|
||||
* @param socketid - socket id value
|
||||
* @param enable - 1: Enabled. 0: Disabled.
|
||||
*
|
||||
* @return @ERR_T
|
||||
*/
|
||||
uint8_t WCHNET_SocketSetKeepLive(uint8_t socketid, uint8_t enable);
|
||||
|
||||
/**
|
||||
* @brief Configure PHY state
|
||||
*
|
||||
* @param phy_stat - PHY state
|
||||
*
|
||||
* @return None
|
||||
*/
|
||||
void WCHNET_PhyStatus(uint32_t phy_stat);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif
|
|
@ -18,11 +18,11 @@
|
|||
* @date 2022-08-01
|
||||
*/
|
||||
|
||||
#include <xizi.h>
|
||||
#include "ch32v30x.h"
|
||||
#include "xsconfig.h"
|
||||
#include "connect_uart.h"
|
||||
#include "ch32v30x.h"
|
||||
#include "ch32v30x_usart.h"
|
||||
#include "xsconfig.h"
|
||||
#include <xizi.h>
|
||||
|
||||
/* uart driver */
|
||||
|
||||
|
@ -68,8 +68,7 @@ static void UartIsr(struct SerialDriver *serial_drv, struct SerialHardwareDevice
|
|||
{
|
||||
struct SerialCfgParam* serial_cfg = (struct SerialCfgParam*)serial_drv->private_data;
|
||||
|
||||
if (RESET != USART_GetITStatus((USART_TypeDef *)serial_cfg->hw_cfg.serial_register_base, USART_IT_RXNE))
|
||||
{
|
||||
if (RESET != USART_GetITStatus((USART_TypeDef*)serial_cfg->hw_cfg.serial_register_base, USART_IT_RXNE)) {
|
||||
SerialSetIsr(serial_dev, SERIAL_EVENT_RX_IND);
|
||||
USART_ClearITPendingBit((USART_TypeDef*)serial_cfg->hw_cfg.serial_register_base, USART_IT_RXNE);
|
||||
}
|
||||
|
@ -109,8 +108,7 @@ static uint32 SerialInit(struct SerialDriver *serial_drv, struct BusConfigureInf
|
|||
USART_InitTypeDef USART_InitStructure;
|
||||
USART_InitStructure.USART_BaudRate = serial_cfg->data_cfg.serial_baud_rate;
|
||||
|
||||
switch (serial_cfg->data_cfg.serial_data_bits)
|
||||
{
|
||||
switch (serial_cfg->data_cfg.serial_data_bits) {
|
||||
case DATA_BITS_8:
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
break;
|
||||
|
@ -123,8 +121,7 @@ static uint32 SerialInit(struct SerialDriver *serial_drv, struct BusConfigureInf
|
|||
break;
|
||||
}
|
||||
|
||||
switch (serial_cfg->data_cfg.serial_stop_bits)
|
||||
{
|
||||
switch (serial_cfg->data_cfg.serial_stop_bits) {
|
||||
case STOP_BITS_1:
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
break;
|
||||
|
@ -136,8 +133,7 @@ static uint32 SerialInit(struct SerialDriver *serial_drv, struct BusConfigureInf
|
|||
break;
|
||||
}
|
||||
|
||||
switch (serial_cfg->data_cfg.serial_parity_mode)
|
||||
{
|
||||
switch (serial_cfg->data_cfg.serial_parity_mode) {
|
||||
case PARITY_NONE:
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
break;
|
||||
|
@ -160,7 +156,6 @@ static uint32 SerialInit(struct SerialDriver *serial_drv, struct BusConfigureInf
|
|||
// usart_hardware_flow_rts_config(serial_cfg->hw_cfg.serial_register_base, USART_RTS_DISABLE);
|
||||
// usart_hardware_flow_cts_config(serial_cfg->hw_cfg.serial_register_base, USART_CTS_DISABLE);
|
||||
|
||||
|
||||
return EOK;
|
||||
}
|
||||
|
||||
|
@ -170,8 +165,7 @@ static uint32 SerialConfigure(struct SerialDriver *serial_drv, int serial_operat
|
|||
|
||||
struct SerialCfgParam* serial_cfg = (struct SerialCfgParam*)serial_drv->private_data;
|
||||
|
||||
switch (serial_operation_cmd)
|
||||
{
|
||||
switch (serial_operation_cmd) {
|
||||
case OPER_CLR_INT:
|
||||
NVIC_DisableIRQ(serial_cfg->hw_cfg.serial_irq_interrupt);
|
||||
USART_ITConfig((USART_TypeDef*)serial_cfg->hw_cfg.serial_register_base, USART_IT_RXNE, DISABLE);
|
||||
|
@ -195,8 +189,7 @@ static uint32 SerialDrvConfigure(void *drv, struct BusConfigureInfo *configure_i
|
|||
int serial_operation_cmd;
|
||||
struct SerialDriver* serial_drv = (struct SerialDriver*)drv;
|
||||
|
||||
switch (configure_info->configure_cmd)
|
||||
{
|
||||
switch (configure_info->configure_cmd) {
|
||||
case OPE_INT:
|
||||
ret = SerialInit(serial_drv, configure_info);
|
||||
break;
|
||||
|
@ -215,7 +208,8 @@ static int SerialPutChar(struct SerialHardwareDevice *serial_dev, char c)
|
|||
{
|
||||
struct SerialCfgParam* serial_cfg = (struct SerialCfgParam*)serial_dev->private_data;
|
||||
|
||||
while (USART_GetFlagStatus((USART_TypeDef *)serial_cfg->hw_cfg.serial_register_base, USART_FLAG_TXE) == RESET);
|
||||
while (USART_GetFlagStatus((USART_TypeDef*)serial_cfg->hw_cfg.serial_register_base, USART_FLAG_TXE) == RESET)
|
||||
;
|
||||
USART_SendData((USART_TypeDef*)serial_cfg->hw_cfg.serial_register_base, (uint8_t)c);
|
||||
return 0;
|
||||
}
|
||||
|
@ -225,16 +219,14 @@ static int SerialGetChar(struct SerialHardwareDevice *serial_dev)
|
|||
int ch = -1;
|
||||
struct SerialCfgParam* serial_cfg = (struct SerialCfgParam*)serial_dev->private_data;
|
||||
|
||||
if (RESET != USART_GetFlagStatus((USART_TypeDef *)serial_cfg->hw_cfg.serial_register_base, USART_FLAG_RXNE))
|
||||
{
|
||||
if (RESET != USART_GetFlagStatus((USART_TypeDef*)serial_cfg->hw_cfg.serial_register_base, USART_FLAG_RXNE)) {
|
||||
ch = USART_ReceiveData((USART_TypeDef*)serial_cfg->hw_cfg.serial_register_base) & 0xff;
|
||||
}
|
||||
|
||||
return ch;
|
||||
}
|
||||
|
||||
static const struct SerialDataCfg data_cfg_init =
|
||||
{
|
||||
static const struct SerialDataCfg data_cfg_init = {
|
||||
.serial_baud_rate = BAUD_RATE_115200,
|
||||
.serial_data_bits = DATA_BITS_8,
|
||||
.serial_stop_bits = STOP_BITS_1,
|
||||
|
@ -246,15 +238,13 @@ static const struct SerialDataCfg data_cfg_init =
|
|||
};
|
||||
|
||||
/*manage the serial device operations*/
|
||||
static const struct SerialDrvDone drv_done =
|
||||
{
|
||||
static const struct SerialDrvDone drv_done = {
|
||||
.init = SerialInit,
|
||||
.configure = SerialConfigure,
|
||||
};
|
||||
|
||||
/*manage the serial device hal operations*/
|
||||
static struct SerialHwDevDone hwdev_done =
|
||||
{
|
||||
static struct SerialHwDevDone hwdev_done = {
|
||||
.put_char = SerialPutChar,
|
||||
.get_char = SerialGetChar,
|
||||
};
|
||||
|
@ -311,7 +301,7 @@ static int BoardSerialDevBend(struct SerialHardwareDevice *serial_device, void *
|
|||
struct SerialDriver serial_driver_1;
|
||||
struct SerialHardwareDevice serial_device_1;
|
||||
|
||||
void USART1_IRQHandler(void) __attribute__((interrupt("WCH-Interrupt-fast")));
|
||||
void USART1_IRQHandler(void) __attribute__((interrupt()));
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
GET_INT_SP();
|
||||
|
|
|
@ -20,13 +20,12 @@
|
|||
|
||||
#include <connect_hwtimer.h>
|
||||
|
||||
#define TMR0_CMP_VAL 1000
|
||||
#define TMR0_CMP_VAL (100000000U / 1024U / 2 - 1U)
|
||||
#define TMR0x ((CM_TMR0_TypeDef *)CM_TMR0_1_BASE)
|
||||
#define TMR0_CH_x (TMR0_CH_A)
|
||||
#define INTSEL_REG ((uint32_t)(&CM_INTC->SEL0))
|
||||
#define TIMER0_IRQn (18)
|
||||
|
||||
|
||||
void (*callback_function)(void *) ;
|
||||
|
||||
static void Timer0Callback(int vector, void *param)
|
||||
|
@ -47,7 +46,7 @@ static uint32 HwtimerOpen(void *dev)
|
|||
|
||||
/* TIMER0 basetimer function initialize */
|
||||
(void)TMR0_StructInit(&stcTmr0Init);
|
||||
stcTmr0Init.u32ClockDiv = TMR0_CLK_DIV128; /* Config clock division */
|
||||
stcTmr0Init.u32ClockDiv = TMR0_CLK_DIV1024; /* Config clock division */
|
||||
stcTmr0Init.u32ClockSrc = TMR0_CLK_SRC_INTERN_CLK; /* Chose clock source */
|
||||
stcTmr0Init.u32Func = TMR0_FUNC_CMP; /* Timer0 compare mode */
|
||||
stcTmr0Init.u16CompareValue = TMR0_CMP_VAL; /* Set compare register data */
|
||||
|
@ -98,7 +97,8 @@ static uint32 HwtimerDrvConfigure(void *drv, struct BusConfigureInfo *configure_
|
|||
break;
|
||||
case OPE_CFG:
|
||||
TMR0_ClearStatus(TMR0x, TMR0_FLAG_CMP_A);
|
||||
TMR0_SetCompareValue(TMR0x, TMR0_CH_x, *((int *)configure_info->private_data) );
|
||||
uint32_t cmp_value = *((uint32_t *)configure_info->private_data) * 100;//1ms 100, max 655ms 65535
|
||||
TMR0_SetCompareValue(TMR0x, TMR0_CH_x, (uint16_t)cmp_value);
|
||||
/* Timer0 interrupt function Enable */
|
||||
TMR0_SetCountValue(TMR0x, TMR0_CH_x, 0x0000);
|
||||
TMR0_Start(TMR0x, TMR0_CH_x);
|
||||
|
|
|
@ -82,6 +82,10 @@ Modification:
|
|||
#include <connect_ethernet.h>
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_EXTSDRAM
|
||||
#include <connect_sdram.h>
|
||||
#endif
|
||||
|
||||
extern void entry(void);
|
||||
extern int HwUsartInit();
|
||||
|
||||
|
@ -180,6 +184,9 @@ struct InitSequenceDesc _board_init[] = {
|
|||
#ifdef BSP_USING_GPIO
|
||||
{ "hw_pin", HwGpioInit },
|
||||
#endif
|
||||
#ifdef BSP_USING_EXTSDRAM
|
||||
{ "ext_sdram", ExtSdramInit},
|
||||
#endif
|
||||
#ifdef BSP_USING_SDIO
|
||||
{ "sdio", HwSdioInit },
|
||||
#endif
|
||||
|
|
|
@ -49,6 +49,8 @@ MEMORY
|
|||
OTP_LOCK (rx): ORIGIN = __OTP_LOCK_START, LENGTH = __OTP_LOCK_SIZE
|
||||
RAM (rwx): ORIGIN = 0x1FFE0000, LENGTH = 512K
|
||||
RAMB (rwx): ORIGIN = 0x200F0000, LENGTH = 4K
|
||||
|
||||
SDRAM (rwx): ORIGIN = 0x80000000, LENGTH = 8M
|
||||
}
|
||||
|
||||
ENTRY(Reset_Handler)
|
||||
|
|
|
@ -25,6 +25,7 @@ menuconfig BSP_USING_ETHERNET
|
|||
menuconfig BSP_USING_W5500
|
||||
bool "Using W5500 ethernet device"
|
||||
default n
|
||||
select BSP_USING_ETHERNET
|
||||
select BSP_USING_LWIP
|
||||
select BSP_USING_SPI
|
||||
select BSP_USING_SPI1
|
||||
|
@ -52,3 +53,10 @@ menuconfig BSP_USING_SPI
|
|||
if BSP_USING_SPI
|
||||
source "$BSP_DIR/third_party_driver/spi/Kconfig"
|
||||
endif
|
||||
|
||||
menuconfig BSP_USING_SDRAM
|
||||
bool "Using SDRAM IS42S16400J"
|
||||
default n
|
||||
if BSP_USING_SDRAM
|
||||
source "$BSP_DIR/third_party_driver/sdram/Kconfig"
|
||||
endif
|
||||
|
|
|
@ -24,4 +24,8 @@ ifeq ($(CONFIG_BSP_USING_SPI),y)
|
|||
SRC_DIR += spi
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_BSP_USING_EXTSDRAM),y)
|
||||
SRC_DIR += sdram
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
|
|
@ -48,4 +48,8 @@ ifeq ($(CONFIG_BSP_USING_CAN),y)
|
|||
SRC_FILES += hc32_ll_can.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_BSP_USING_EXTSDRAM),y)
|
||||
SRC_FILES += hc32_ll_dmc.c
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue