Compare commits
181 Commits
fit_5g
...
prepare_fo
| Author | SHA1 | Date | |
|---|---|---|---|
| 7c47e3ff69 | |||
| e472c801ce | |||
| 2d2d266b01 | |||
|
|
0e0f5e9ba7 | ||
|
|
bc3352dcf8 | ||
|
|
10bad777c8 | ||
|
|
6502bdd61c | ||
|
|
58aa7a2d2e | ||
|
|
25255ce4df | ||
|
|
c12434f7bd | ||
|
|
6b63f02625 | ||
|
|
183e0d4da0 | ||
|
|
04249a986e | ||
|
|
e67eca9a8b | ||
|
|
c776bb1fd6 | ||
| d0d6546d7a | |||
| 93bd7dc45a | |||
| e25927698b | |||
| 1b505c5d78 | |||
| 4ffff0c693 | |||
|
|
caa3fc3bb5 | ||
|
|
0da14e6546 | ||
|
|
b175f77b10 | ||
|
|
d512b49a6a | ||
|
|
18264a638c | ||
|
|
fe3733ac17 | ||
|
|
7f899a3446 | ||
|
|
e214c1bdee | ||
|
|
e36db3f932 | ||
|
|
9f18ae042a | ||
|
|
60f3679e60 | ||
|
|
6e83d451eb | ||
|
|
f6ead02730 | ||
|
|
0f8bad3bb2 | ||
|
|
d8b4719781 | ||
|
|
94b49ffea4 | ||
|
|
0da346d568 | ||
|
|
8b8e334160 | ||
|
|
32b253d3c3 | ||
|
|
d68fb81399 | ||
|
|
9fe9331ea2 | ||
|
|
871671b8bf | ||
|
|
b9c34ae93e | ||
|
|
d562b6479a | ||
|
|
d5afd37e1d | ||
|
|
4e61d6b409 | ||
|
|
a621543f24 | ||
|
|
fb1cf06b6e | ||
|
|
c5aa020398 | ||
|
|
84e4f2c3a1 | ||
|
|
fc82573bbe | ||
|
|
4eb5f245cb | ||
|
|
2c647495af | ||
|
|
1703db93cb | ||
|
|
a20a2d5327 | ||
|
|
77ef32cbb9 | ||
|
|
33523335e2 | ||
|
|
cd121f49f9 | ||
|
|
a3771bed07 | ||
|
|
07126e6bd1 | ||
|
|
f68de5128c | ||
|
|
4ed3c6037d | ||
|
|
7a785b041e | ||
|
|
aca8486498 | ||
|
|
5e331e4c7c | ||
|
|
0fa8ff5368 | ||
|
|
fd1e44de35 | ||
|
|
2305563306 | ||
|
|
beeac96f2d | ||
|
|
221e21139d | ||
|
|
7d53245d00 | ||
|
|
928085215b | ||
|
|
9383a1e465 | ||
|
|
6c81808ac5 | ||
|
|
e82955c7d4 | ||
|
|
6f474ea500 | ||
|
|
2586ab6800 | ||
|
|
935b990667 | ||
|
|
6c704a3638 | ||
|
|
4cb90f3e93 | ||
|
|
ed87416859 | ||
|
|
15b3faeee6 | ||
|
|
f77245be7b | ||
|
|
7f2d1150b1 | ||
|
|
ec9bcaefb5 | ||
|
|
b3aae320fe | ||
|
|
3e70ccddce | ||
|
|
c5bd15ab91 | ||
|
|
15a3ac1130 | ||
|
|
25bfec1560 | ||
|
|
1559013f2b | ||
|
|
a6ed30fd5e | ||
|
|
ca35c72d02 | ||
|
|
0d05dab7b3 | ||
|
|
32977dd301 | ||
|
|
861795f8bd | ||
|
|
7c2b3d10b5 | ||
|
|
e98cffed83 | ||
|
|
e0fb6dc926 | ||
|
|
619b32ad49 | ||
|
|
6176717125 | ||
|
|
f872eaea25 | ||
|
|
994145bd63 | ||
|
|
b03330f0f8 | ||
|
|
675da41f02 | ||
|
|
eb5f73251c | ||
|
|
b8c77c5758 | ||
|
|
5190dadd12 | ||
|
|
1631e60baa | ||
|
|
ee49e0d71c | ||
|
|
301073476f | ||
|
|
dca3e93959 | ||
|
|
788988e105 | ||
|
|
47c091dfbc | ||
|
|
3b133b4fe7 | ||
|
|
42b17738ee | ||
|
|
fd95d9a7de | ||
|
|
9e9f00dbf7 | ||
|
|
3ef1f5570c | ||
|
|
5f47b92255 | ||
|
|
157c622d1f | ||
|
|
726500bd77 | ||
|
|
ed934b5bae | ||
|
|
ad6a6d7cc6 | ||
|
|
b6340dee69 | ||
|
|
beef098836 | ||
|
|
3154da5ec6 | ||
|
|
a39ab68b4c | ||
|
|
e20ff7483c | ||
|
|
6b636dfde0 | ||
|
|
74da96e1f1 | ||
|
|
8752a17203 | ||
|
|
d68abecdba | ||
|
|
e0ff453726 | ||
|
|
af1ceec308 | ||
|
|
21104f0f31 | ||
|
|
ab531f720a | ||
|
|
21304531a5 | ||
|
|
7639937678 | ||
|
|
9fbb5be499 | ||
|
|
7e94dc5cb2 | ||
|
|
197957f202 | ||
|
|
a2ed0ee073 | ||
|
|
9a6857843b | ||
|
|
8f0c6bbd5c | ||
|
|
64ba03adef | ||
|
|
2087cb7d33 | ||
|
|
06bb9c4e9b | ||
|
|
ffd2262300 | ||
|
|
8b08816b60 | ||
|
|
fe26bb4e5a | ||
|
|
72e3175707 | ||
|
|
3f08641909 | ||
|
|
254651bcd0 | ||
|
|
ce1c689379 | ||
|
|
d7c99b7f01 | ||
|
|
a268135205 | ||
|
|
a9f8fba6dd | ||
|
|
87c5f1549f | ||
|
|
8795b4138e | ||
|
|
1eedb9d24e | ||
|
|
6df7ccb7f6 | ||
|
|
18e5483d57 | ||
|
|
de438ed9a5 | ||
|
|
c97fa52c5f | ||
|
|
bac1ec5b71 | ||
|
|
7897a91a8a | ||
|
|
49b20dfa6a | ||
|
|
0fdf4f2ace | ||
|
|
1c0edba5bd | ||
|
|
d0e822c757 | ||
|
|
22b980cc08 | ||
|
|
64b2117012 | ||
|
|
16a31c6739 | ||
|
|
d664e2298e | ||
|
|
02c82025c8 | ||
|
|
dbaffab140 | ||
|
|
1e59fd2a8d | ||
|
|
2e11a31da3 | ||
|
|
446c3746a6 | ||
|
|
293fd9fea9 |
11
.clang-format
Normal file
11
.clang-format
Normal file
@@ -0,0 +1,11 @@
|
||||
BasedOnStyle: LLVM
|
||||
IndentWidth: 4
|
||||
IndentAccessModifiers: false
|
||||
AccessModifierOffset: -4
|
||||
DerivePointerAlignment: false
|
||||
PointerAlignment: Left
|
||||
SortIncludes: CaseSensitive
|
||||
IndentPPDirectives: BeforeHash
|
||||
AlignAfterOpenBracket: BlockIndent
|
||||
BinPackArguments: false
|
||||
BinPackParameters: false
|
||||
6
.gitignore
vendored
6
.gitignore
vendored
@@ -2,4 +2,8 @@
|
||||
*.o
|
||||
*libmusl.a
|
||||
*liblwip.a
|
||||
.DS_Store
|
||||
.DS_Store
|
||||
|
||||
.cache/
|
||||
compile_commands.json
|
||||
.clangd
|
||||
|
||||
@@ -1,3 +1,15 @@
|
||||
SRC_FILES := 4g_app.c
|
||||
SRC_FILES := 4g_app.c
|
||||
|
||||
ifeq ($(CONFIG_DEVICE_ADL400),y)
|
||||
SRC_FILES += ch32v208_adl400.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_DEVICE_DTZ178),y)
|
||||
SRC_FILES += ch32v208_dtz178.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_DEVICE_DTSD342),y)
|
||||
SRC_FILES += ch32v208_dtsd342.c
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
@@ -0,0 +1,673 @@
|
||||
/**
|
||||
* @file ch32v208_adl400.c
|
||||
* @brief ch32v208 board gets data from Acrel-ADL400 electricity meter with rs485 bus,
|
||||
* and then sends it to the server with 4G.
|
||||
* @author Huo Yujia (huoyujia081@126.com)
|
||||
* @version 1.0
|
||||
* @date 2024-07-10
|
||||
*/
|
||||
|
||||
#include <ModuleConfig.h>
|
||||
#include <adapter.h>
|
||||
#include <transform.h>
|
||||
#define MAX_FRAME_SIZE 256 // 最大帧大小
|
||||
#define MAX_BUFFER_SIZE 1024 * 2 // 最大缓冲区大小
|
||||
#define RECEIVE_DATA_INTERVAL_MS 1000 * 60 * 2 // ADL400数据采集间隔时间,单位为毫秒
|
||||
#define RESEND_COUNT 3 // 最大帧重发次数
|
||||
#define RECONNECT_COUNT 5 // 最大连接次数
|
||||
#define WATING_RESPONSE_MS 5000 // 等待响应时间,单位为毫秒
|
||||
|
||||
/**
|
||||
* @brief 生成Modbus RTU请求帧中的CRC循环冗余码
|
||||
* @param CRC_Ptr
|
||||
* @param LEN 需要生成CRC冗余码的数据长度
|
||||
* @return uint16_t 以小端顺序返回CRC循环冗余码
|
||||
*/
|
||||
static uint16_t generateCRC(uint8_t *CRC_Ptr, uint8_t LEN) {
|
||||
uint16_t CRC_Value = 0;
|
||||
uint8_t i = 0;
|
||||
uint8_t j = 0;
|
||||
|
||||
CRC_Value = 0xffff;
|
||||
for (i = 0; i < LEN; i++) // LEN为数组长度
|
||||
{
|
||||
CRC_Value ^= *(CRC_Ptr + i);
|
||||
for (j = 0; j < 8; j++) {
|
||||
if (CRC_Value & 0x00001)
|
||||
CRC_Value = (CRC_Value >> 1) ^ 0xA001;
|
||||
else
|
||||
CRC_Value = (CRC_Value >> 1);
|
||||
}
|
||||
}
|
||||
CRC_Value = ((CRC_Value >> 8) + (CRC_Value << 8)); // 交换高低字节
|
||||
|
||||
return CRC_Value;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 生成Modbus RTU请求帧,用于获取指定寄存器的值
|
||||
* @param address 请求的Modbus地址
|
||||
* @param functionCode 功能码
|
||||
* @param startAddress 数据起始地址
|
||||
* @param quantity 数据读取个数
|
||||
* @param modbusRtuRequestFrame 生成的ModBus RTU请求帧数组
|
||||
* @param requestFrameArrLength 生成的ModBus RTU请求帧数组长度,固定为8
|
||||
* @return int 0表示生成成功,其他结果表示生成失败
|
||||
* @note Modbus
|
||||
* RTU请求帧格式:地址(1字节)+功能码(1字节)+数据起始地址(2字节)+数据读取个数(2字节)+校验码(2字节)
|
||||
*/
|
||||
static int generateRequestFrame(unsigned char address, unsigned char functionCode, unsigned short startAddress, unsigned short quantity,
|
||||
unsigned char modbusRtuRequestFrame[], int requestFrameArrLength) {
|
||||
if (requestFrameArrLength != 8) {
|
||||
printf("the length of request frame array is not 8\n");
|
||||
return -1;
|
||||
}
|
||||
modbusRtuRequestFrame[0] = address;
|
||||
modbusRtuRequestFrame[1] = functionCode;
|
||||
modbusRtuRequestFrame[2] = (startAddress >> 8) & 0xff;
|
||||
modbusRtuRequestFrame[3] = startAddress & 0xff;
|
||||
modbusRtuRequestFrame[4] = (quantity >> 8) & 0xff;
|
||||
modbusRtuRequestFrame[5] = quantity & 0xff;
|
||||
modbusRtuRequestFrame[6] = (generateCRC(modbusRtuRequestFrame, 6) >> 8) & 0xff;
|
||||
modbusRtuRequestFrame[7] = generateCRC(modbusRtuRequestFrame, 6) & 0xff;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 将要上传服务器的数据帧
|
||||
*/
|
||||
struct DataFrame {
|
||||
unsigned char id[13]; // 用响应的时间戳作为数据帧的id
|
||||
unsigned char data[MAX_FRAME_SIZE]; // 上传服务器的数据帧字符串,前12字节表示数据帧id。字符串格式:数据帧id,数据1,数据2,数据3...
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Modbus RTU响应数据帧的缓存,使用循环队列作为数据结构
|
||||
*/
|
||||
struct QueueBuffer {
|
||||
struct DataFrame *buffer[MAX_BUFFER_SIZE / sizeof(struct DataFrame)]; // 循环队列存储空间,使用数组存储
|
||||
int front; // 循环队列队头
|
||||
int rear; // 循环队列队尾
|
||||
pthread_mutex_t mutex; // 互斥访问循环队列信号量
|
||||
sem_t full; // 循环队列中有效成员个数的信号量
|
||||
};
|
||||
|
||||
#define BUFFER_ELEM_COUNT (MAX_BUFFER_SIZE / sizeof(struct DataFrame)) // 循环队列中可以容纳的最大成员个数
|
||||
|
||||
/**
|
||||
* @brief 初始化循环队列
|
||||
* @param pQueueBuffer 循环队列指针
|
||||
* @return * int 0表示初始化成功,其他表示初始化失败
|
||||
*/
|
||||
static int initBuffer(struct QueueBuffer *pQueueBuffer) {
|
||||
pQueueBuffer->front = 0;
|
||||
pQueueBuffer->rear = 0;
|
||||
if (PrivMutexCreate(&pQueueBuffer->mutex, 0) < 0) {
|
||||
printf("buffer mutex create failed.\n");
|
||||
return -1;
|
||||
}
|
||||
if (PrivSemaphoreCreate(&pQueueBuffer->full, 0, 0) < 0) {
|
||||
printf("buffer full semaphore create failed.\n");
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 循环队列入队,如果循环队列已满,则将最旧的成员出队后,新成员再入队
|
||||
* @param pQueueBuffer 循环队列指针
|
||||
* @param pDataFrame ADL400响应数据帧
|
||||
* @return int 0表示入队成功,其他表示入队失败
|
||||
*/
|
||||
static int offerBuffer(struct QueueBuffer *pQueueBuffer, struct DataFrame *pDataFrame) {
|
||||
/* 循环队列已满,将最旧的成员出队 */
|
||||
if ((pQueueBuffer->rear + 1) % BUFFER_ELEM_COUNT == pQueueBuffer->front) {
|
||||
struct DataFrame *frontDataFrame = pQueueBuffer->buffer[pQueueBuffer->front];
|
||||
PrivFree(frontDataFrame);
|
||||
pQueueBuffer->front = (pQueueBuffer->front + 1) % BUFFER_ELEM_COUNT;
|
||||
}
|
||||
/* 新成员入队 */
|
||||
pQueueBuffer->buffer[pQueueBuffer->rear] = pDataFrame;
|
||||
pQueueBuffer->rear = (pQueueBuffer->rear + 1) % BUFFER_ELEM_COUNT;
|
||||
printf("front: %d\n", pQueueBuffer->front);
|
||||
printf("rear: %d\n", pQueueBuffer->rear);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 循环队列出队,如果队列为空则返回NULL
|
||||
* @param pQueueBuffer 循环队列指针
|
||||
* @return struct DataFrame* 出队成员,如果队列为空则返回NULL
|
||||
*/
|
||||
static struct DataFrame *pollBuffer(struct QueueBuffer *pQueueBuffer) {
|
||||
/* 队列为空,返回NULL */
|
||||
if (pQueueBuffer->front == pQueueBuffer->rear) {
|
||||
return NULL;
|
||||
}
|
||||
/* 最旧的成员出队 */
|
||||
struct DataFrame *pFrontDataFrame = pQueueBuffer->buffer[pQueueBuffer->front];
|
||||
pQueueBuffer->buffer[pQueueBuffer->front] = NULL;
|
||||
pQueueBuffer->front = (pQueueBuffer->front + 1) % BUFFER_ELEM_COUNT;
|
||||
printf("front: %d\n", pQueueBuffer->front);
|
||||
printf("rear: %d\n", pQueueBuffer->rear);
|
||||
return pFrontDataFrame;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 查看队头元素,如果队列为空则返回NULL
|
||||
* @param pQueueBuffer 循环队列指针
|
||||
* @return struct DataFrame* 队头元素,如果队列为空则返回NULL
|
||||
*/
|
||||
static struct DataFrame *peekBuffer(struct QueueBuffer *pQueueBuffer) {
|
||||
/* 如果队列为空,返回NULL */
|
||||
if (pQueueBuffer->front == pQueueBuffer->rear) {
|
||||
return NULL;
|
||||
}
|
||||
/* 返回队头元素,但不出队 */
|
||||
return pQueueBuffer->buffer[pQueueBuffer->front];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 改写PrivRead函数,原有函数只会读取接收缓冲区的当前已有字节,新函数会读取指定字节数再返回
|
||||
* @param fd 文件描述符
|
||||
* @param buf 数据读取到的位置
|
||||
* @param len 读取的指定字节数
|
||||
* @return int 如果读取到指定字节数返回0;如果到达WATING_RESPONSE_MS仍未读取到指定字节数,或者读数据错误,返回-1
|
||||
*/
|
||||
static int privReadEnoughData(int fd, void *buf, size_t len) {
|
||||
char *buffer = (char *)buf; // 将接收的存储空间指针强制转型
|
||||
int gottenBytes = 0; // 已经读取到的字节数
|
||||
int remainTime = WATING_RESPONSE_MS; // 剩余的时间
|
||||
|
||||
/* 只有接收的字节数不够,并且还有剩余时间,才可以继续读取 */
|
||||
while (gottenBytes < len && remainTime > 0) {
|
||||
int bytes = PrivRead(fd, buffer + gottenBytes, len - gottenBytes); // 从设备读取
|
||||
if (bytes > 0) {
|
||||
gottenBytes += bytes; // 读取到字节
|
||||
} else if (bytes < 0) {
|
||||
printf("Error reading from serial port\n");
|
||||
return -1; // 读取错误
|
||||
}
|
||||
PrivTaskDelay(100); // 每100ms读取一次
|
||||
remainTime -= 100; // 剩余时间减去100ms
|
||||
}
|
||||
/* 若没有剩余时间,表示还没有读取到指定的字节数,返回-1;若有剩余时间,表示已经读取了指定的字节数,返回0 */
|
||||
return remainTime < 0 ? -1 : 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 解析ADL400响应的Modbus RTU数据帧
|
||||
* @param modbusRtuResponseFrame0 请求数据后ADL400的响应帧
|
||||
* @param modbusRtuResponseFrame1 请求时间戳后ADL400的响应帧
|
||||
* @param modbusRtuResponseFrame2 请求电流电压比后ADL400的响应帧
|
||||
* @param pDataFrame 将要上传给服务器的数据帧,包括id和数据
|
||||
*/
|
||||
static void parseModBusRtuResponseFrame(unsigned char *modbusRtuResponseFrame0, unsigned char *modbusRtuResponseFrame1,
|
||||
unsigned char *modbusRtuResponseFrame2, struct DataFrame *pDataFrame) {
|
||||
/* 从frame2中获取电压变比pt和电流变比ct */
|
||||
unsigned char *p = modbusRtuResponseFrame2;
|
||||
int pt = (unsigned short)modbusRtuResponseFrame2[3] << 8 | (unsigned short)modbusRtuResponseFrame2[4];
|
||||
int ct = (unsigned short)modbusRtuResponseFrame2[5] << 8 | (unsigned short)modbusRtuResponseFrame2[6];
|
||||
|
||||
/* 从frame1中获取时间戳,即数据帧的id */
|
||||
for (int i = 8; i >= 3; i--) {
|
||||
sprintf(pDataFrame->id, "%s%02x", pDataFrame->id, modbusRtuResponseFrame1[i]);
|
||||
sprintf(pDataFrame->data, "%s%02x", pDataFrame->data, modbusRtuResponseFrame1[i]);
|
||||
}
|
||||
|
||||
/* 从frame0中获取要上传到服务器的ADL400的数据 */
|
||||
for (int i = 3; i < modbusRtuResponseFrame0[2] + 3; i += 4) {
|
||||
int originalData = (unsigned int)modbusRtuResponseFrame0[i] << 24 | (unsigned int)modbusRtuResponseFrame0[i + 1] << 16 |
|
||||
(unsigned int)modbusRtuResponseFrame0[i + 2] << 8 | (unsigned int)modbusRtuResponseFrame0[i + 3];
|
||||
sprintf(pDataFrame->data, "%s,%d", pDataFrame->data, originalData); // 将数据拼接到字符串
|
||||
}
|
||||
|
||||
strcat(pDataFrame->data, "\n"); // 字符串末尾添加换行符,表示数据帧结束
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 从ADL400接收数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *receiveDataFromADL400Task(void *arg) {
|
||||
struct QueueBuffer *pQueueBuffer = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
int fd = PrivOpen("/dev/rs485_dev1", O_RDWR); // 打开设备文件
|
||||
if (fd < 0) { // 打开设备文件失败,打印错误信息
|
||||
printf("open rs485 fd error: %d\n", fd);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
struct SerialDataCfg rs485Configuration;
|
||||
memset(&rs485Configuration, 0, sizeof(struct SerialDataCfg));
|
||||
/* 读取RS485配置信息 */
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待
|
||||
int baudRatesOption = CFG->baudRate_Rs485;
|
||||
int dataBitsOption = CFG->dataBits_Rs485;
|
||||
int stopBitsOption = CFG->stopBits_Rs485;
|
||||
int parityOption = CFG->parity_Rs485;
|
||||
PrivMutexAbandon(&romConfigurationMutex); // 释放互斥锁
|
||||
switch (baudRatesOption) {
|
||||
case 1:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_2400;
|
||||
break;
|
||||
case 2:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_4800;
|
||||
break;
|
||||
case 3:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_9600;
|
||||
break;
|
||||
case 4:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_19200;
|
||||
break;
|
||||
case 5:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_38400;
|
||||
break;
|
||||
case 6:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_57600;
|
||||
break;
|
||||
case 7:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_115200;
|
||||
break;
|
||||
case 8:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_230400;
|
||||
break;
|
||||
default:
|
||||
rs485Configuration.serial_baud_rate = BAUD_RATE_9600;
|
||||
break;
|
||||
}
|
||||
switch (dataBitsOption) {
|
||||
case 1:
|
||||
rs485Configuration.serial_data_bits = DATA_BITS_8;
|
||||
break;
|
||||
case 2:
|
||||
rs485Configuration.serial_data_bits = DATA_BITS_9;
|
||||
break;
|
||||
default:
|
||||
rs485Configuration.serial_data_bits = DATA_BITS_8;
|
||||
break;
|
||||
}
|
||||
switch (stopBitsOption) {
|
||||
case 1:
|
||||
rs485Configuration.serial_stop_bits = STOP_BITS_1;
|
||||
break;
|
||||
case 2:
|
||||
rs485Configuration.serial_stop_bits = STOP_BITS_2;
|
||||
break;
|
||||
default:
|
||||
rs485Configuration.serial_stop_bits = STOP_BITS_1;
|
||||
break;
|
||||
}
|
||||
switch (parityOption) {
|
||||
case 1:
|
||||
rs485Configuration.serial_parity_mode = PARITY_NONE;
|
||||
break;
|
||||
case 2:
|
||||
rs485Configuration.serial_parity_mode = PARITY_ODD;
|
||||
break;
|
||||
case 3:
|
||||
rs485Configuration.serial_parity_mode = PARITY_EVEN;
|
||||
break;
|
||||
}
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = (void *)&rs485Configuration;
|
||||
if (0 != PrivIoctl(fd, OPE_INT, &ioctl_cfg)) {
|
||||
printf("ioctl uart fd error %d\n", fd);
|
||||
PrivClose(fd);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
unsigned char modbusRtuRequestFrame[8]; // 定义Modbus RTU请求帧
|
||||
unsigned char modBusRtuResponseFrame0[256]; // 定义Modbus RTU响应帧0
|
||||
unsigned char modBusRtuResponseFrame1[256]; // 定义Modbus RTU响应帧1
|
||||
unsigned char modBusRtuResponseFrame2[32]; // 定义Modbus RTU响应帧2
|
||||
while (1) {
|
||||
/* 生成Modbus RTU请求帧0,用于请求ADL400数据 */
|
||||
if (generateRequestFrame(0x93, 0x03, 0x0000, 0x003C, modbusRtuRequestFrame, sizeof(modbusRtuRequestFrame)) < 0) {
|
||||
break; // 生成请求帧失败,退出循环
|
||||
}
|
||||
PrivWrite(fd, modbusRtuRequestFrame, sizeof(modbusRtuRequestFrame)); // 发送Modbus RTU请求帧
|
||||
/* 读取Modbus RTU响应帧0数据 */
|
||||
if (privReadEnoughData(fd, modBusRtuResponseFrame0, 5 + (0x003C << 1)) < 0) {
|
||||
printf("read data from adl400 time out\n"); // 读取超时,打印错误信息
|
||||
break; // 读取失败,退出循环
|
||||
}
|
||||
|
||||
/* 生成Modbus RTU请求帧1,用于请求时间戳 */
|
||||
if (generateRequestFrame(0x93, 0x03, 0x003C, 0x0003, modbusRtuRequestFrame, sizeof(modbusRtuRequestFrame)) < 0) {
|
||||
break; // 生成请求帧失败,退出循环
|
||||
}
|
||||
PrivWrite(fd, modbusRtuRequestFrame, sizeof(modbusRtuRequestFrame)); // 发送Modbus RTU请求帧
|
||||
/* 读取Modbus RTU响应帧1数据 */
|
||||
if (privReadEnoughData(fd, modBusRtuResponseFrame1, 5 + (0x0003 << 1)) < 0) {
|
||||
printf("read data from adl400 time out\n"); // 读取超时,打印错误信息
|
||||
break; // 读取失败,退出循环
|
||||
}
|
||||
|
||||
/* 生成Modbus RTU请求帧2,用于请求电压电流变比 */
|
||||
if (generateRequestFrame(0x93, 0x03, 0x008D, 0x0002, modbusRtuRequestFrame, sizeof(modbusRtuRequestFrame)) < 0) {
|
||||
break; // 生成请求帧失败,退出循环
|
||||
}
|
||||
PrivWrite(fd, modbusRtuRequestFrame, sizeof(modbusRtuRequestFrame)); // 发送Modbus RTU请求帧
|
||||
/* 读取Modbus RTU响应帧2 */
|
||||
if (privReadEnoughData(fd, modBusRtuResponseFrame2, 5 + (0x0002 << 1)) < 0) {
|
||||
printf("read data from adl400 time out\n"); // 读取超时,打印错误信息
|
||||
break; // 读取失败,退出循环
|
||||
}
|
||||
|
||||
/* 解析Modbus RTU响应帧 */
|
||||
struct DataFrame *pDataFrame = (struct DataFrame *)PrivMalloc(sizeof(struct DataFrame));
|
||||
memset(pDataFrame, 0, sizeof(struct DataFrame));
|
||||
parseModBusRtuResponseFrame(modBusRtuResponseFrame0, modBusRtuResponseFrame1, modBusRtuResponseFrame2, pDataFrame);
|
||||
|
||||
/* 将解析后的数据帧放入循环队列 */
|
||||
PrivMutexObtain(&pQueueBuffer->mutex); // 获取互斥锁
|
||||
offerBuffer(pQueueBuffer, pDataFrame); // 将数据帧放入队列
|
||||
printf("receive data from ADL400, id: %s\n", pDataFrame->id); // 打印接收到的数据帧ID
|
||||
PrivMutexAbandon(&pQueueBuffer->mutex); // 释放互斥锁
|
||||
PrivSemaphoreAbandon(&pQueueBuffer->full); // 释放信号量,即告知发送数据线程,队列中有新的数据帧
|
||||
|
||||
PrivTaskDelay(RECEIVE_DATA_INTERVAL_MS); // 延迟一段时间再读取下一帧数据
|
||||
}
|
||||
|
||||
PrivClose(fd); // 关闭设备文件
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 通过4G向服务器发送数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *sendDataToServerTask_4G(void *arg) {
|
||||
uint8_t serverIpAddress[16] = {}; // 目的IP地址
|
||||
uint8_t serverPort[6] = {}; // 目的端口号
|
||||
struct QueueBuffer *pQueueBuffer = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
unsigned char receiveBuffer[256]; // 从服务器接收每帧响应的存储空间
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_4G_NAME); // 查找4G模块适配器
|
||||
|
||||
AdapterDeviceOpen(adapter); // 打开适配器对应的设备(实际打开串口中断)
|
||||
int baud_rate = BAUD_RATE_115200; // 波特率,用于设置4G模块串口
|
||||
AdapterDeviceControl(adapter, OPE_INT, &baud_rate); // 对适配器对应设备进行配置(实际配置波特率)
|
||||
|
||||
struct DataFrame *pDataFrame = NULL; // 数据帧定义
|
||||
while (1) {
|
||||
PrivSemaphoreObtainWait(&pQueueBuffer->full, NULL); // 尝试获取循环队列队头元素,如果获取信号量失败,则等待信号量
|
||||
#ifdef BSP_BLE_CONFIG // 如果启用了BLE配置功能
|
||||
/* 获取互斥锁 */
|
||||
PrivMutexObtain(&adapter->lock); // 若其他线程正在使用adapter,则阻塞等待
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待
|
||||
|
||||
/* 尝试连接服务器 */
|
||||
sprintf(serverIpAddress, "%u.%u.%u.%u", CFG->destinationIpAddress_4G[0], CFG->destinationIpAddress_4G[1],
|
||||
CFG->destinationIpAddress_4G[2], CFG->destinationIpAddress_4G[3]);
|
||||
sprintf(serverPort, "%u", (unsigned short)CFG->destinationPort_4G[0] | CFG->destinationPort_4G[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_4G*-*-*-*\n");
|
||||
printf("serverIpAddress:\t%s\n", serverIpAddress);
|
||||
printf("serverPort:\t\t%s\n", serverPort);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
if (CFG->mqttSwitch_4G == 1) { // 如果使能MQTT
|
||||
AdapterDeviceMqttConnect(adapter, serverIpAddress, serverPort, CFG->mqttClientId_4G, CFG->mqttUsername_4G,
|
||||
CFG->mqttPassword_4G);
|
||||
} else { // 如果禁用MQTT
|
||||
AdapterDeviceConnect(adapter, CLIENT, serverIpAddress, serverPort, IPV4);
|
||||
}
|
||||
|
||||
AdapterDeviceNetstat(adapter); // 读取网络连接状态
|
||||
/* 若连接失败,则等待10s再次尝试连接 */
|
||||
if (CFG->mqttSwitch_4G == 0 && !adapter->network_info.is_connected ||
|
||||
CFG->mqttSwitch_4G == 1 && !adapter->network_info.mqttIsConnected) {
|
||||
PrivSemaphoreAbandon(&pQueueBuffer->full); // 释放信号量
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
printf("4G connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#else // 如果没有启用BLE配置功能
|
||||
/* 尝试连接到服务器 */
|
||||
sprintf(serverIpAddress, "%u.%u.%u.%u", CFG->destinationIpAddress_4G[0], CFG->destinationIpAddress_4G[1],
|
||||
CFG->destinationIpAddress_4G[2], CFG->destinationIpAddress_4G[3]);
|
||||
sprintf(serverPort, "%u", (unsigned short)CFG->destinationPort_4G[0] | CFG->destinationPort_4G[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_4G*-*-*-*\n");
|
||||
printf("serverIpAddress:\t%s\n", serverIpAddress);
|
||||
printf("serverPort:\t\t%s\n", serverPort);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int reconnectCount = RECONNECT_COUNT; // 尝试重新连接服务器最多RECONNECT_COUNT次
|
||||
while (reconnectCount > 0) {
|
||||
int res;
|
||||
if (CFG->mqttSwitch_4G == 1) {
|
||||
res = AdapterDeviceMqttConnect(adapter, mqttServerIp, mqttServerPort, CFG->mqttClientId_4G, CFG->mqttUsername_4G,
|
||||
CFG->mqttPassword_4G);
|
||||
} else {
|
||||
res = AdapterDeviceConnect(adapter, CLIENT, serverIpAddress, serverPort, IPV4);
|
||||
}
|
||||
if (res == 0) {
|
||||
break;
|
||||
}
|
||||
reconnectCount--;
|
||||
}
|
||||
if (reconnectCount <= 0) { // 若RECONNECT_COUNT次都连接失败,则等待10s再次尝试连接
|
||||
PrivSemaphoreAbandon(&pQueueBuffer->full); // 释放信号量
|
||||
printf("4G connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
PrivMutexObtain(&pQueueBuffer->mutex); // 获取互斥锁
|
||||
pDataFrame = pollBuffer(pQueueBuffer); // 从队列中获取数据帧
|
||||
PrivMutexAbandon(&pQueueBuffer->mutex); // 释放互斥锁
|
||||
|
||||
int resendCount = RESEND_COUNT; // 定义数据帧重发次数
|
||||
while (pDataFrame != NULL && resendCount > 0) { // 只有数据帧非空并且还有剩余重发次数,才进行发送
|
||||
/* 向服务器发送数据 */
|
||||
printf("pDataFrame->data: %s", pDataFrame->data);
|
||||
printf("send data to server, id: %s\n", pDataFrame->id);
|
||||
if (CFG->mqttSwitch_4G == 1) { // MQTT模式下,无需服务器响应数据
|
||||
AdapterDeviceMqttSend(adapter, CFG->mqttTopic_4G, pDataFrame->data,
|
||||
strlen(pDataFrame->data)); // 发送数据,注意当前最多发送256字节
|
||||
break;
|
||||
} else {
|
||||
AdapterDeviceSend(adapter, pDataFrame->data,
|
||||
strlen(pDataFrame->data)); // 发送数据,注意当前最多发送256字节
|
||||
|
||||
/* 从服务器接收响应,约定服务器接收完数据帧后,返回数据帧中的前12个字节,即数据帧id */
|
||||
/* 多读取2字节,是为了防止前面还有命令模式返回的剩余的\r\n影响判断 */
|
||||
memset(receiveBuffer, 0, sizeof(receiveBuffer));
|
||||
int receiveLength = AdapterDeviceRecv(adapter, receiveBuffer, strlen(pDataFrame->id) + 2);
|
||||
if (receiveLength == strlen(pDataFrame->id) + 2 || receiveLength == strlen(pDataFrame->id)) {
|
||||
/* 打印服务器响应 */
|
||||
printf("receiveLength: %d\n", receiveLength);
|
||||
printf("receiveBuffer: ");
|
||||
for (int i = 0; i < receiveLength; i++) {
|
||||
printf("%c", receiveBuffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
/* 比较服务器响应的内容与发送的数据帧id是否一致 */
|
||||
if (strstr(receiveBuffer, pDataFrame->id) != NULL) {
|
||||
break; // 接收成功,退出循环
|
||||
}
|
||||
} else {
|
||||
printf("receiveLength: %d\n", receiveLength);
|
||||
printf("receiveBuffer: ");
|
||||
for (int i = 0; i < receiveLength; i++) {
|
||||
printf("%d ", receiveBuffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
}
|
||||
resendCount--;
|
||||
}
|
||||
if (pDataFrame != NULL) {
|
||||
PrivFree(pDataFrame); // 释放数据帧内存
|
||||
pDataFrame = NULL; // 避免野指针
|
||||
}
|
||||
// AdapterDeviceDisconnect(adapter, NULL); // 关闭适配器对应的设备
|
||||
#ifdef BSP_BLE_CONFIG
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
#endif
|
||||
if (resendCount <= 0) { // 如果数据帧重发次数超过上限,表示发送失败,丢弃该帧
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 通过以太网向服务器发送数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *sendDataToServerTask_Ethernet(void *arg) {
|
||||
uint8_t serverIpAddress[16] = {}; // 目的IP地址
|
||||
uint8_t serverPort[6] = {}; // 目的端口号
|
||||
struct QueueBuffer *pQueueBuffer = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
unsigned char receiveBuffer[256]; // 从服务器接收每帧响应的存储空间
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_ETHERNET_NAME); // 查找以太网模块适配器
|
||||
|
||||
#ifndef BSP_BLE_CONFIG // 如果没有使能蓝牙配置功能
|
||||
AdapterDeviceSetUp(adapter); // 启动以太网主任务线程
|
||||
AdapterDeviceSetDhcp(adapter, CFG->dhcpSwitch_Ethernet); // 启用或禁用DHCP
|
||||
#endif
|
||||
|
||||
struct DataFrame *pDataFrame = NULL; // 数据帧定义
|
||||
while (1) {
|
||||
PrivSemaphoreObtainWait(&pQueueBuffer->full, NULL); // 尝试获取循环队列队头元素,如果获取信号量失败,则等待信号量
|
||||
#ifdef BSP_BLE_CONFIG // 使能蓝牙配置功能
|
||||
/* 获取互斥锁 */
|
||||
PrivMutexObtain(&adapter->lock); // 若其他线程正在使用adapter,则阻塞等待
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待;
|
||||
|
||||
/* 尝试连接服务器 */
|
||||
sprintf(serverIpAddress, "%u.%u.%u.%u", CFG->destinationIpAddress_Ethernet[0], CFG->destinationIpAddress_Ethernet[1],
|
||||
CFG->destinationIpAddress_Ethernet[2], CFG->destinationIpAddress_Ethernet[3]);
|
||||
sprintf(serverPort, "%u", (unsigned short)CFG->destinationPort_Ethernet[0] | CFG->destinationPort_Ethernet[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_Ethernet*-*-*-*\n");
|
||||
printf("serverIpAddress:\t%s\n", serverIpAddress);
|
||||
printf("serverPort:\t\t%s\n", serverPort);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int res = AdapterDeviceConnect(adapter, CLIENT, serverIpAddress, serverPort, IPV4);
|
||||
|
||||
/* 连接失败,则等待10s再次尝试连接 */
|
||||
if (res != 0 && res != 0x1D) {
|
||||
PrivSemaphoreAbandon(&pQueueBuffer->full); // 释放信号量
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
printf("Ethernet connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#else
|
||||
/* 尝试连接到服务器 */
|
||||
sprintf(serverIpAddress, "%u.%u.%u.%u", CFG->destinationIpAddress_Ethernet[0], CFG->destinationIpAddress_Ethernet[1],
|
||||
CFG->destinationIpAddress_Ethernet[2], CFG->destinationIpAddress_Ethernet[3]);
|
||||
sprintf(serverPort, "%u", (unsigned short)CFG->destinationPort_Ethernet[0] | CFG->destinationPort_Ethernet[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_Ethernet*-*-*-*\n");
|
||||
printf("serverIpAddress:\t%s\n", serverIpAddress);
|
||||
printf("serverPort:\t\t%s\n", serverPort);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int reconnectCount = RECONNECT_COUNT; // 尝试重新连接服务器最多RECONNECT_COUNT次
|
||||
while (reconnectCount > 0) {
|
||||
int res = AdapterDeviceConnect(adapter, CLIENT, serverIpAddress, serverPort, IPV4); // 尝试连接服务器
|
||||
if (res == 0 || res == 0x1D) {
|
||||
break;
|
||||
}
|
||||
reconnectCount--;
|
||||
}
|
||||
if (reconnectCount <= 0) { // 若RECONNECT_COUNT次都连接失败,则等待10s再次尝试连接
|
||||
PrivSemaphoreAbandon(&pQueueBuffer->full); // 释放信号量
|
||||
printf("Ethernet connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
PrivMutexObtain(&pQueueBuffer->mutex); // 获取互斥锁
|
||||
pDataFrame = pollBuffer(pQueueBuffer); // 从队列中获取数据帧
|
||||
PrivMutexAbandon(&pQueueBuffer->mutex); // 释放互斥锁
|
||||
|
||||
int resendCount = RESEND_COUNT; // 定义数据帧重发次数
|
||||
|
||||
/* 只有数据帧非空并且还有剩余重发次数,才进行发送 */
|
||||
while (pDataFrame != NULL && resendCount > 0) {
|
||||
/* 向服务器发送数据 */
|
||||
printf("send data to server, id: %s\n", pDataFrame->id);
|
||||
printf("pDataFrame->data: %s", pDataFrame->data);
|
||||
AdapterDeviceSend(adapter, pDataFrame->data,
|
||||
strlen(pDataFrame->data)); // 发送数据,注意当前最多发送256字节
|
||||
|
||||
/* 从服务器接收响应,约定服务器接收完数据帧后,返回数据帧中的前12个字节,即数据帧id */
|
||||
memset(receiveBuffer, 0, sizeof(receiveBuffer));
|
||||
PrivTaskDelay(6000);
|
||||
if (AdapterDeviceRecv(adapter, receiveBuffer, strlen(pDataFrame->id)) == strlen(pDataFrame->id)) {
|
||||
/* 打印服务器响应 */
|
||||
printf("receiveBuffer: ");
|
||||
for (int i = 0; i < strlen(receiveBuffer); i++) {
|
||||
printf("%c", receiveBuffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
/* 比较服务器响应的内容与发送的数据帧id是否一致 */
|
||||
if (strstr(pDataFrame->id, receiveBuffer) != NULL) {
|
||||
break; // 接收成功,退出循环
|
||||
}
|
||||
}
|
||||
resendCount--;
|
||||
}
|
||||
if (pDataFrame != NULL) {
|
||||
PrivFree(pDataFrame); // 释放数据帧内存
|
||||
pDataFrame = NULL; // 避免野指针
|
||||
}
|
||||
AdapterDeviceDisconnect(adapter, NULL);
|
||||
#ifdef BSP_BLE_CONFIG
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
#endif
|
||||
if (resendCount <= 0) { // 如果数据帧重发次数超过上限,表示发送失败,丢弃该帧
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 开启从ADL400接收数据的线程以及上传数据到服务器的线程,此方法在main方法中被调用,开机或复位启动
|
||||
*/
|
||||
void startUpTransformDataTask(void) {
|
||||
/* 分配循环队列空间 */
|
||||
struct QueueBuffer *pQueueBuffer = (struct QueueBuffer *)PrivCalloc(1, sizeof(struct QueueBuffer));
|
||||
if (initBuffer(pQueueBuffer) < 0) {
|
||||
PrivFree(pQueueBuffer);
|
||||
return;
|
||||
}
|
||||
|
||||
/* 启动从ADL400接收数据的线程 */
|
||||
pthread_attr_t receiveDataFromADL400TaskAttr;
|
||||
pthread_args_t receiveDataFromADL400TaskArgs;
|
||||
receiveDataFromADL400TaskAttr.schedparam.sched_priority = 16; // 线程优先级
|
||||
receiveDataFromADL400TaskAttr.stacksize = 2048; // 线程栈大小
|
||||
receiveDataFromADL400TaskArgs.pthread_name = "receiveDataFromADL400Task"; // 线程名字
|
||||
receiveDataFromADL400TaskArgs.arg = pQueueBuffer; // 线程参数
|
||||
pthread_t receiveDataThread; // 线程ID
|
||||
PrivTaskCreate(&receiveDataThread, &receiveDataFromADL400TaskAttr, receiveDataFromADL400Task, &receiveDataFromADL400TaskArgs);
|
||||
PrivTaskStartup(&receiveDataThread);
|
||||
|
||||
/* 启动上传数据到服务器的线程 */
|
||||
pthread_attr_t sendDataToServerTaskAttr;
|
||||
pthread_args_t sendDataToServerTaskArgs;
|
||||
sendDataToServerTaskAttr.schedparam.sched_priority = 16; // 线程优先级
|
||||
sendDataToServerTaskAttr.stacksize = 2200; // 线程栈大小
|
||||
sendDataToServerTaskArgs.pthread_name = "sendDataToServerTask"; // 线程名字
|
||||
sendDataToServerTaskArgs.arg = pQueueBuffer; // 线程参数
|
||||
pthread_t sendDataThread; // 线程ID
|
||||
void *(*start_routine)(void *) = sendDataToServerTask_4G; // 通过4G模块上传到服务器
|
||||
// void *(*start_routine)(void *) = sendDataToServerTask_Ethernet; // 通过以太网模块上传到服务器
|
||||
PrivTaskCreate(&sendDataThread, &sendDataToServerTaskAttr, start_routine, &sendDataToServerTaskArgs); // 通过4G模块上传到服务器
|
||||
PrivTaskStartup(&sendDataThread);
|
||||
}
|
||||
@@ -0,0 +1,807 @@
|
||||
/*
|
||||
* Copyright (c) 2022 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 .c
|
||||
* @brief Support reading data from WASION DTSD342 using the Modbus-RTU protocol
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2025.4.21
|
||||
*/
|
||||
|
||||
#include <ModuleConfig.h>
|
||||
#include <adapter.h>
|
||||
#include <transform.h>
|
||||
#include <math.h>
|
||||
#include <cJSON.h>
|
||||
|
||||
#define MAX_FRAME_SIZE 256 // 最大帧大小
|
||||
#define MAX_DATA_SIZE 1024 // 最大数据大小
|
||||
#define MAX_BUFFER_SIZE 1024 * 2 // 最大缓冲区大小
|
||||
#define RECEIVE_DATA_INTERVAL_MS 1000 * 60 * 2 // DTSD342数据采集间隔时间,单位为毫秒
|
||||
#define SAMPLE_DATA_INTERVAL_MS 350 // 稳定连续采集的间隔时间,单位为毫秒
|
||||
#define SEND_FRAME_LEN 8 // 发送帧长度
|
||||
#define RECEIVE_FRAME_LEN 5 // 返回帧长度(不包含各项数据长度)
|
||||
#define RESEND_COUNT 3 // 最大帧重发次数
|
||||
#define RECONNECT_COUNT 5 // 最大连接次数
|
||||
#define WATING_RESPONSE_MS 5000 // 等待响应时间,单位为毫秒
|
||||
#define DATA_COUNT (sizeof(data_start_address_map) / sizeof(data_start_address_map[0])) // 数据项数量
|
||||
#define READ_COMMAND 0x03 /* 读取数据 */
|
||||
#define ADDRESS 0x01
|
||||
#define FRAME_ID "DTSD342"
|
||||
|
||||
#ifndef DATA_ITEMS_DEF_H
|
||||
#define DATA_ITEMS_DEF_H
|
||||
|
||||
#define DATA_ITEMS_XMACRO \
|
||||
X(FORWARD_ACTIVE_ENERGY, 0x2006, 4, 1) /* 正向有功电能,4字节,1位小数,单位Wh */ \
|
||||
X(FORWARD_REACTIVE_ENERGY, 0x200E, 4, 1) /* 正向无功电能,4字节,1位小数,单位varh */ \
|
||||
X(REVERSE_ACTIVE_ENERGY, 0x2106, 4, 1) /* 反向有功电能,4字节,1位小数,单位Wh */ \
|
||||
X(REVERSE_REACTIVE_ENERGY, 0x210E, 4, 1) /* 反向无功电能,4字节,1位小数,单位varh */ \
|
||||
X(VOLTAGE_A, 0x1800, 4, 3) /* A相电压,4字节,3位小数,单位V */ \
|
||||
X(VOLTAGE_B, 0x1802, 4, 3) /* B相电压,4字节,3位小数,单位V */ \
|
||||
X(VOLTAGE_C, 0x1804, 4, 3) /* C相电压,4字节,3位小数,单位V */ \
|
||||
X(CURRENT_A, 0x1810, 4, 4) /* A相电流,4字节,4位小数,单位A */ \
|
||||
X(CURRENT_B, 0x1812, 4, 4) /* B相电流,4字节,4位小数,单位A */ \
|
||||
X(CURRENT_C, 0x1814, 4, 4) /* C相电流,4字节,4位小数,单位A */ \
|
||||
X(ACTIVE_POWER_A, 0x181A, 4, 1) /* A有功功率,4字节,1位小数,单位W */ \
|
||||
X(ACTIVE_POWER_B, 0x181C, 4, 1) /* B有功功率,4字节,1位小数,单位W */ \
|
||||
X(ACTIVE_POWER_C, 0x181E, 4, 1) /* C有功功率,4字节,1位小数,单位W */ \
|
||||
X(ACTIVE_POWER_TOTAL, 0x1820, 4, 1) /* 总有功功率,4字节,1位小数,单位W */ \
|
||||
X(REACTIVE_POWER_A, 0x1822, 4, 1) /* A无功功率,4字节,1位小数,单位var */ \
|
||||
X(REACTIVE_POWER_B, 0x1824, 4, 1) /* B无功功率,4字节,1位小数,单位var */ \
|
||||
X(REACTIVE_POWER_C, 0x1826, 4, 1) /* C无功功率,4字节,1位小数,单位var */ \
|
||||
X(REACTIVE_POWER_TOTAL, 0x1828, 4, 1) /* 总无功功率,4字节,1位小数,单位var */ \
|
||||
X(APPARENT_POWER_A, 0x182A, 4, 1) /* A视在功率,4字节,1位小数,单位VA */ \
|
||||
X(APPARENT_POWER_B, 0x182C, 4, 1) /* B视在功率,4字节,1位小数,单位VA */ \
|
||||
X(APPARENT_POWER_C, 0x182E, 4, 1) /* C视在功率,4字节,1位小数,单位VA */ \
|
||||
X(APPARENT_POWER_TOTAL, 0x1830, 4, 1) /* 总视在功率,4字节,1位小数,单位VA */ \
|
||||
X(POWER_FACTOR_A, 0x1019, 2, 3) /* A功率因数,2字节,3位小数,单位无 */ \
|
||||
X(POWER_FACTOR_B, 0x101A, 2, 3) /* B功率因数,2字节,3位小数,单位无 */ \
|
||||
X(POWER_FACTOR_C, 0x101B, 2, 3) /* C功率因数,2字节,3位小数,单位无 */ \
|
||||
X(POWER_FACTOR_TOTAL, 0x101C, 2, 3) /* 总功率因数,2字节,3位小数,单位无 */ \
|
||||
X(FREQUENCY, 0x101D, 2, 2) /* 电网频率,2字节,2位小数,单位Hz */ \
|
||||
X(INTERNAL_TEMPERATURE, 0x0135, 2, 0) /* 内部温度,2字节,0位小数,单位℃ */
|
||||
|
||||
#endif // DATA_ITEMS_DEF_H
|
||||
|
||||
#ifndef DATA_ITEMS_H
|
||||
#define DATA_ITEMS_H
|
||||
|
||||
typedef enum {
|
||||
#define X(name, start_address, size, dec) name,
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
} DataIdIndex;
|
||||
|
||||
typedef struct {
|
||||
uint8_t byte_size;
|
||||
uint8_t decimal_places;
|
||||
} DataInfo;
|
||||
|
||||
static const uint16_t data_start_address_map[] = {
|
||||
#define X(name, start_address, size, dec) start_address,
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
};
|
||||
|
||||
static const DataInfo data_info_map[] = {
|
||||
#define X(name, start_address, size, dec) {size, dec},
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
};
|
||||
|
||||
static const char *data_id_names[] = {
|
||||
#define X(name, start_address, size, dec) #name,
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
};
|
||||
|
||||
#endif // DATA_ITEMS_H
|
||||
|
||||
/**
|
||||
* @brief 生成Modbus RTU请求帧中的CRC循环冗余码
|
||||
* @param data 需要生成CRC冗余码的数据指针
|
||||
* @param len 需要生成CRC冗余码的数据长度
|
||||
* @return uint16_t
|
||||
*/
|
||||
static uint16_t GenerateCRC(uint8_t *data, uint8_t len) {
|
||||
uint16_t crc = 0xFFFF;
|
||||
|
||||
for (uint8_t i = 0; i < len; i++) {
|
||||
crc ^= data[i];
|
||||
for (uint8_t j = 0; j < 8; j++) {
|
||||
if (crc & 0x0001)
|
||||
crc = (crc >> 1) ^ 0xA001;
|
||||
else
|
||||
crc >>= 1;
|
||||
}
|
||||
}
|
||||
|
||||
return crc; // 返回原始值,高字节在高位
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 生成Modbus RTU请求帧,用于获取指定寄存器的值
|
||||
* @param address 请求的Modbus地址
|
||||
* @param function_code 功能码
|
||||
* @param start_address 数据起始地址
|
||||
* @param quantity 数据读取个数
|
||||
* @param request_frame 生成的ModBus RTU请求帧数组
|
||||
* @return int 0表示生成成功,其他结果表示生成失败
|
||||
* @note Modbus
|
||||
* RTU请求帧格式:地址(1字节)+功能码(1字节)+数据起始地址(2字节)+数据读取个数(2字节)+校验码(2字节)
|
||||
*/
|
||||
static int GenerateRequestFrame(unsigned char address, unsigned char function_code, unsigned short start_address, unsigned short quantity, unsigned char request_frame[]) {
|
||||
request_frame[0] = address;
|
||||
request_frame[1] = function_code;
|
||||
request_frame[2] = (start_address >> 8) & 0xff;
|
||||
request_frame[3] = start_address & 0xff;
|
||||
request_frame[4] = (quantity >> 8) & 0xff;
|
||||
request_frame[5] = quantity & 0xff;
|
||||
|
||||
uint16_t crc = GenerateCRC(request_frame, 6);
|
||||
|
||||
request_frame[6] = crc & 0xff;
|
||||
request_frame[7] = (crc >> 8) & 0xff;
|
||||
|
||||
// printf("GenerateRequestFrame: ");
|
||||
// for (int i = 0; i < 8; i++)
|
||||
// printf("%02X ", request_frame[i]);
|
||||
// printf("\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 将要上传服务器的数据帧
|
||||
*/
|
||||
struct DataFrame {
|
||||
unsigned char id[8]; // 电表型号标识
|
||||
unsigned char data[MAX_DATA_SIZE]; // 上传服务器的数据帧字符串,用JSON封装
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Modbus RTU响应数据帧的缓存,使用循环队列作为数据结构
|
||||
*/
|
||||
struct QueueBuffer {
|
||||
struct DataFrame *buffer[MAX_BUFFER_SIZE / sizeof(struct DataFrame)]; // 循环队列存储空间,使用数组存储
|
||||
int front; // 循环队列队头
|
||||
int rear; // 循环队列队尾
|
||||
pthread_mutex_t mutex; // 互斥访问循环队列信号量
|
||||
sem_t full; // 循环队列中有效成员个数的信号量
|
||||
};
|
||||
|
||||
#define BUFFER_ELEM_COUNT (MAX_BUFFER_SIZE / sizeof(struct DataFrame)) // 循环队列中可以容纳的最大成员个数
|
||||
|
||||
/**
|
||||
* @brief 初始化循环队列
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @return * int 0表示初始化成功,其他表示初始化失败
|
||||
*/
|
||||
static int InitBuffer(struct QueueBuffer *queue_buffer_ptr) {
|
||||
queue_buffer_ptr->front = 0;
|
||||
queue_buffer_ptr->rear = 0;
|
||||
if (PrivMutexCreate(&queue_buffer_ptr->mutex, 0) < 0) {
|
||||
printf("buffer mutex create failed.\n");
|
||||
return -1;
|
||||
}
|
||||
if (PrivSemaphoreCreate(&queue_buffer_ptr->full, 0, 0) < 0) {
|
||||
printf("buffer full semaphore create failed.\n");
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 循环队列入队,如果循环队列已满,则将最旧的成员出队后,新成员再入队
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @param data_frame_ptr DTSD342响应数据帧
|
||||
* @return int 0表示入队成功,其他表示入队失败
|
||||
*/
|
||||
static int OfferBuffer(struct QueueBuffer *queue_buffer_ptr, struct DataFrame *data_frame_ptr) {
|
||||
/* 循环队列已满,将最旧的成员出队 */
|
||||
if ((queue_buffer_ptr->rear + 1) % BUFFER_ELEM_COUNT == queue_buffer_ptr->front) {
|
||||
struct DataFrame *front_data_frame_ptr = queue_buffer_ptr->buffer[queue_buffer_ptr->front];
|
||||
PrivFree(front_data_frame_ptr);
|
||||
queue_buffer_ptr->front = (queue_buffer_ptr->front + 1) % BUFFER_ELEM_COUNT;
|
||||
}
|
||||
/* 新成员入队 */
|
||||
queue_buffer_ptr->buffer[queue_buffer_ptr->rear] = data_frame_ptr;
|
||||
queue_buffer_ptr->rear = (queue_buffer_ptr->rear + 1) % BUFFER_ELEM_COUNT;
|
||||
printf("front: %d\n", queue_buffer_ptr->front);
|
||||
printf("rear: %d\n", queue_buffer_ptr->rear);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 循环队列出队,如果队列为空则返回NULL
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @return struct DataFrame* 出队成员,如果队列为空则返回NULL
|
||||
*/
|
||||
static struct DataFrame *PollBuffer(struct QueueBuffer *queue_buffer_ptr) {
|
||||
/* 队列为空,返回NULL */
|
||||
if (queue_buffer_ptr->front == queue_buffer_ptr->rear) {
|
||||
return NULL;
|
||||
}
|
||||
/* 最旧的成员出队 */
|
||||
struct DataFrame *front_data_frame_ptr = queue_buffer_ptr->buffer[queue_buffer_ptr->front];
|
||||
queue_buffer_ptr->buffer[queue_buffer_ptr->front] = NULL;
|
||||
queue_buffer_ptr->front = (queue_buffer_ptr->front + 1) % BUFFER_ELEM_COUNT;
|
||||
printf("front: %d\n", queue_buffer_ptr->front);
|
||||
printf("rear: %d\n", queue_buffer_ptr->rear);
|
||||
return front_data_frame_ptr;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 查看队头元素,如果队列为空则返回NULL
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @return struct DataFrame* 队头元素,如果队列为空则返回NULL
|
||||
*/
|
||||
static struct DataFrame *PeekBuffer(struct QueueBuffer *queue_buffer_ptr) {
|
||||
/* 如果队列为空,返回NULL */
|
||||
if (queue_buffer_ptr->front == queue_buffer_ptr->rear) {
|
||||
return NULL;
|
||||
}
|
||||
/* 返回队头元素,但不出队 */
|
||||
return queue_buffer_ptr->buffer[queue_buffer_ptr->front];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 改写PrivRead函数,原有函数只会读取接收缓冲区的当前已有字节,新函数会读取指定字节数再返回
|
||||
* @param fd 文件描述符
|
||||
* @param buf 数据读取到的位置
|
||||
* @param len 读取的指定字节数
|
||||
* @return int 如果读取到指定字节数返回0;如果到达WATING_RESPONSE_MS仍未读取到指定字节数,或者读数据错误,返回-1
|
||||
*/
|
||||
static int PrivReadEnoughData(int fd, void *buf, size_t len) {
|
||||
char *buffer = (char *)buf; // 将接收的存储空间指针强制转型
|
||||
int gotten_bytes = 0; // 已经读取到的字节数
|
||||
int remain_time = WATING_RESPONSE_MS; // 剩余的时间
|
||||
|
||||
/* 只有接收的字节数不够,并且还有剩余时间,才可以继续读取 */
|
||||
while (gotten_bytes < len && remain_time > 0) {
|
||||
int bytes = PrivRead(fd, buffer + gotten_bytes, len - gotten_bytes); // 从设备读取
|
||||
// printf("gotten_bytes: %d\n", bytes);
|
||||
gotten_bytes += bytes;
|
||||
PrivTaskDelay(100); // 每100ms读取一次
|
||||
remain_time -= 100; // 剩余时间减去100ms
|
||||
}
|
||||
/* 若没有剩余时间,表示还没有读取到指定的字节数,返回-1;若有剩余时间,表示已经读取了指定的字节数,返回0 */
|
||||
return remain_time < 0 ? -1 : 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 解析DTSD342响应的Modbus RTU数据帧
|
||||
* @param response_frame 返回的数据帧
|
||||
* @param data_info_ptr 数据项的字节数和小数位数信息
|
||||
* @param item_id 数据项ID
|
||||
* @param root 根节点
|
||||
*/
|
||||
static void ParseResponseFrame(unsigned char *response_frame, const DataInfo *data_info_ptr, int item_id, cJSON *root) {
|
||||
if (!response_frame || !data_info_ptr || !root) {
|
||||
printf("Invalid input to ParseResponseFrame\n");
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t data_len = response_frame[2]; // 数据域长度
|
||||
if (data_len != data_info_ptr->byte_size) {
|
||||
printf("Invalid data length in frame\n");
|
||||
return;
|
||||
}
|
||||
|
||||
const uint8_t *data_value = &response_frame[3]; // 数据内容起始位置
|
||||
|
||||
// for (int i = 0; i < data_info_ptr->byte_size; i++)
|
||||
// printf("%02x ", data_value[i]);
|
||||
|
||||
uint32_t raw_value = 0;
|
||||
for (int i = 0; i < data_len; i++) {
|
||||
raw_value = (raw_value << 8) | data_value[i]; // 高字节在前
|
||||
}
|
||||
|
||||
double scaled_value = raw_value / pow(10, data_info_ptr->decimal_places);
|
||||
// printf("Parsed value: %.*f\n", data_info_ptr->decimal_places, scaled_value);
|
||||
|
||||
char format[10];
|
||||
snprintf(format, sizeof(format), "%%.%df", data_info_ptr->decimal_places);
|
||||
|
||||
char scaled_value_str[20];
|
||||
snprintf(scaled_value_str, sizeof(scaled_value_str), format, scaled_value);
|
||||
|
||||
cJSON_AddStringToObject(root, data_id_names[item_id], scaled_value_str);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 从DTSD342接收数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *ReceiveDataFromDTSD342Task(void *arg) {
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
int fd = PrivOpen("/dev/rs485_dev1", O_RDWR); // 打开设备文件
|
||||
if (fd < 0) { // 打开设备文件失败,打印错误信息
|
||||
printf("open rs485 fd error: %d\n", fd);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
struct SerialDataCfg rs485_configuration;
|
||||
memset(&rs485_configuration, 0, sizeof(struct SerialDataCfg));
|
||||
/* 读取RS485配置信息 */
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待
|
||||
int baud_rates_option = CFG->baudRate_Rs485;
|
||||
int data_bits_option = CFG->dataBits_Rs485;
|
||||
int stop_bits_option = CFG->stopBits_Rs485;
|
||||
int parity_option = CFG->parity_Rs485;
|
||||
PrivMutexAbandon(&romConfigurationMutex); // 释放互斥锁
|
||||
switch (baud_rates_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_2400;
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_4800;
|
||||
break;
|
||||
case 3:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_9600; // 默认波特率9600
|
||||
break;
|
||||
case 4:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_19200;
|
||||
break;
|
||||
case 5:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_38400;
|
||||
break;
|
||||
case 6:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_57600;
|
||||
break;
|
||||
case 7:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_115200;
|
||||
break;
|
||||
case 8:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_230400;
|
||||
break;
|
||||
default:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_9600;
|
||||
break;
|
||||
}
|
||||
switch (data_bits_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_data_bits = DATA_BITS_8;
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_data_bits = DATA_BITS_9;
|
||||
break;
|
||||
default:
|
||||
rs485_configuration.serial_data_bits = DATA_BITS_8;
|
||||
break;
|
||||
}
|
||||
switch (stop_bits_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_stop_bits = STOP_BITS_1;
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_stop_bits = STOP_BITS_2;
|
||||
break;
|
||||
default:
|
||||
rs485_configuration.serial_stop_bits = STOP_BITS_1;
|
||||
break;
|
||||
}
|
||||
switch (parity_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_parity_mode = PARITY_NONE; // 默认无奇偶校验
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_parity_mode = PARITY_ODD;
|
||||
break;
|
||||
case 3:
|
||||
rs485_configuration.serial_parity_mode = PARITY_EVEN;
|
||||
break;
|
||||
}
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = (void *)&rs485_configuration;
|
||||
if (0 != PrivIoctl(fd, OPE_INT, &ioctl_cfg)) {
|
||||
printf("ioctl uart fd error %d\n", fd);
|
||||
PrivClose(fd);
|
||||
return NULL;
|
||||
}
|
||||
printf("open rs485 fd success %d\n", fd);
|
||||
|
||||
unsigned char request_frame[MAX_FRAME_SIZE]; // 定义请求帧
|
||||
unsigned char response_frame[MAX_FRAME_SIZE]; // 定义回复帧
|
||||
while (1) {
|
||||
printf("enter cycle\n");
|
||||
struct DataFrame *data_frame_ptr = (struct DataFrame *)PrivMalloc(sizeof(struct DataFrame));
|
||||
memset(data_frame_ptr, 0, sizeof(struct DataFrame));
|
||||
|
||||
// 创建一个空的JSON对象
|
||||
cJSON *root = cJSON_CreateObject();
|
||||
int is_success = 1;
|
||||
|
||||
for (int i = 0; i < DATA_COUNT; i++) {
|
||||
const uint16_t start_address = data_start_address_map[i];
|
||||
const DataInfo *data_info = &data_info_map[i];
|
||||
|
||||
memset(request_frame, 0, sizeof(request_frame));
|
||||
if (GenerateRequestFrame(ADDRESS, READ_COMMAND, start_address, data_info->byte_size / 2, request_frame) < 0) {
|
||||
printf("Generate frame failed for index %d\n", i);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
PrivWrite(fd, request_frame, SEND_FRAME_LEN); // 发送Modbus RTU请求帧
|
||||
|
||||
/* 读取响应帧数据 */
|
||||
memset(response_frame, 0, sizeof(response_frame));
|
||||
if (PrivReadEnoughData(fd, response_frame, RECEIVE_FRAME_LEN + data_info->byte_size) < 0) {
|
||||
printf("Timeout reading response for index %d\n", i);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
// printf("Response frame for index %d: ", i);
|
||||
// for (int j = 0; j < RECEIVE_FRAME_LEN + data_info->byte_size; j++)
|
||||
// printf("%02X ", response_frame[j]);
|
||||
// printf("\n");
|
||||
|
||||
// 校验帧头、帧尾
|
||||
if (response_frame[0] != ADDRESS || response_frame[1] != READ_COMMAND) {
|
||||
printf("Invalid frame format for index %d\n", i);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
// 校验和
|
||||
uint16_t calc_crc16 = GenerateCRC(response_frame, RECEIVE_FRAME_LEN + data_info->byte_size - 2);
|
||||
uint16_t recv_crc16 = (response_frame[RECEIVE_FRAME_LEN + data_info->byte_size - 1] << 8) | response_frame[RECEIVE_FRAME_LEN + data_info->byte_size - 2];
|
||||
if (calc_crc16 != recv_crc16) {
|
||||
printf("Modbus CRC16 error at index %d: calc %04X, recv %04X\n", i, calc_crc16, recv_crc16);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
ParseResponseFrame(response_frame, data_info, i, root);
|
||||
|
||||
PrivTaskDelay(SAMPLE_DATA_INTERVAL_MS);
|
||||
}
|
||||
|
||||
if (!is_success) {
|
||||
printf("read all data failed\n");
|
||||
PrivFree(data_frame_ptr);
|
||||
cJSON_Delete(root);
|
||||
continue;
|
||||
}
|
||||
|
||||
memcpy(data_frame_ptr->id, FRAME_ID, strlen(FRAME_ID));
|
||||
printf("data_frame_ptr->id: %s\n", data_frame_ptr->id);
|
||||
|
||||
char *json_str = cJSON_Print(root);
|
||||
strncpy((char *)data_frame_ptr->data, json_str, MAX_DATA_SIZE - 1);
|
||||
data_frame_ptr->data[MAX_DATA_SIZE - 1] = '\0'; // 确保结尾是 \0
|
||||
printf("data_frame_ptr->data: %s\n", data_frame_ptr->data);
|
||||
|
||||
// 删除字符串空间
|
||||
free(json_str);
|
||||
// 删除 cJSON 对象
|
||||
cJSON_Delete(root);
|
||||
|
||||
/* 将解析后的数据帧放入循环队列 */
|
||||
PrivMutexObtain(&queue_buffer_ptr->mutex); // 获取互斥锁
|
||||
OfferBuffer(queue_buffer_ptr, data_frame_ptr); // 将数据帧放入队列
|
||||
printf("receive data from DTSD342, id: %s\n", data_frame_ptr->id); // 打印接收到的数据帧ID
|
||||
PrivMutexAbandon(&queue_buffer_ptr->mutex); // 释放互斥锁
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量,即告知发送数据线程,队列中有新的数据帧
|
||||
|
||||
PrivTaskDelay(RECEIVE_DATA_INTERVAL_MS); // 延迟一段时间再读取下一帧数据
|
||||
|
||||
printf("end cycle\n");
|
||||
}
|
||||
|
||||
PrivClose(fd); // 关闭设备文件
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 通过4G向服务器发送数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *SendDataToServerTask_4G(void *arg) {
|
||||
uint8_t server_ip_address[16] = {}; // 目的IP地址
|
||||
uint8_t server_port[6] = {}; // 目的端口号
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
unsigned char receive_buffer[256]; // 从服务器接收每帧响应的存储空间
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_4G_NAME); // 查找4G模块适配器
|
||||
|
||||
AdapterDeviceOpen(adapter); // 打开适配器对应的设备(实际打开串口中断)
|
||||
int baud_rate = BAUD_RATE_115200; // 波特率,用于设置4G模块串口
|
||||
AdapterDeviceControl(adapter, OPE_INT, &baud_rate); // 对适配器对应设备进行配置(实际配置波特率)
|
||||
|
||||
struct DataFrame *data_frame_ptr = NULL; // 数据帧定义
|
||||
while (1) {
|
||||
PrivSemaphoreObtainWait(&queue_buffer_ptr->full, NULL); // 尝试获取循环队列队头元素,如果获取信号量失败,则等待信号量
|
||||
#ifdef BSP_BLE_CONFIG // 如果启用了BLE配置功能
|
||||
/* 获取互斥锁 */
|
||||
PrivMutexObtain(&adapter->lock); // 若其他线程正在使用adapter,则阻塞等待
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待
|
||||
|
||||
/* 尝试连接服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_4G[0], CFG->destinationIpAddress_4G[1],
|
||||
CFG->destinationIpAddress_4G[2], CFG->destinationIpAddress_4G[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_4G[0] | CFG->destinationPort_4G[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_4G*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
if (CFG->mqttSwitch_4G == 1) { // 如果使能MQTT
|
||||
AdapterDeviceMqttConnect(adapter, server_ip_address, server_port, CFG->mqttClientId_4G, CFG->mqttUsername_4G,
|
||||
CFG->mqttPassword_4G);
|
||||
} else { // 如果禁用MQTT
|
||||
AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4);
|
||||
}
|
||||
|
||||
AdapterDeviceNetstat(adapter); // 读取网络连接状态
|
||||
/* 若连接失败,则等待10s再次尝试连接 */
|
||||
if (CFG->mqttSwitch_4G == 0 && !adapter->network_info.is_connected ||
|
||||
CFG->mqttSwitch_4G == 1 && !adapter->network_info.mqttIsConnected) {
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
printf("4G connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#else // 如果没有启用BLE配置功能
|
||||
/* 尝试连接到服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_4G[0], CFG->destinationIpAddress_4G[1],
|
||||
CFG->destinationIpAddress_4G[2], CFG->destinationIpAddress_4G[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_4G[0] | CFG->destinationPort_4G[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_4G*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int reconnect_count = RECONNECT_COUNT; // 尝试重新连接服务器最多RECONNECT_COUNT次
|
||||
while (reconnect_count > 0) {
|
||||
int res;
|
||||
if (CFG->mqttSwitch_4G == 1) {
|
||||
res = AdapterDeviceMqttConnect(adapter, mqttServerIp, mqttServerPort, CFG->mqttClientId_4G, CFG->mqttUsername_4G,
|
||||
CFG->mqttPassword_4G);
|
||||
} else {
|
||||
res = AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4);
|
||||
}
|
||||
if (res == 0) {
|
||||
break;
|
||||
}
|
||||
reconnect_count--;
|
||||
}
|
||||
if (reconnect_count <= 0) { // 若RECONNECT_COUNT次都连接失败,则等待10s再次尝试连接
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
printf("4G connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
PrivMutexObtain(&queue_buffer_ptr->mutex); // 获取互斥锁
|
||||
data_frame_ptr = PollBuffer(queue_buffer_ptr); // 从队列中获取数据帧
|
||||
PrivMutexAbandon(&queue_buffer_ptr->mutex); // 释放互斥锁
|
||||
|
||||
int resend_count = RESEND_COUNT; // 定义数据帧重发次数
|
||||
while (data_frame_ptr != NULL && resend_count > 0) { // 只有数据帧非空并且还有剩余重发次数,才进行发送
|
||||
/* 向服务器发送数据 */
|
||||
printf("data_frame_ptr->data: %s", data_frame_ptr->data);
|
||||
printf("send data to server, id: %s\n", data_frame_ptr->id);
|
||||
if (CFG->mqttSwitch_4G == 1) { // MQTT模式下,无需服务器响应数据
|
||||
AdapterDeviceMqttSend(adapter, CFG->mqttTopic_4G, data_frame_ptr->data,
|
||||
strlen(data_frame_ptr->data)); // 发送数据,注意当前最多发送256字节
|
||||
break;
|
||||
} else {
|
||||
AdapterDeviceSend(adapter, data_frame_ptr->data,
|
||||
strlen(data_frame_ptr->data)); // 发送数据,注意当前最多发送256字节
|
||||
|
||||
/* 从服务器接收响应,约定服务器接收完数据帧后,返回数据帧中的前12个字节,即数据帧id */
|
||||
/* 多读取2字节,是为了防止前面还有命令模式返回的剩余的\r\n影响判断 */
|
||||
memset(receive_buffer, 0, sizeof(receive_buffer));
|
||||
int receive_length = AdapterDeviceRecv(adapter, receive_buffer, strlen(data_frame_ptr->id) + 2);
|
||||
if (receive_length == strlen(data_frame_ptr->id) + 2 || receive_length == strlen(data_frame_ptr->id)) {
|
||||
/* 打印服务器响应 */
|
||||
printf("receive_length: %d\n", receive_length);
|
||||
printf("receive_buffer: ");
|
||||
for (int i = 0; i < receive_length; i++) {
|
||||
printf("%c", receive_buffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
/* 比较服务器响应的内容与发送的数据帧id是否一致 */
|
||||
if (strstr(receive_buffer, data_frame_ptr->id) != NULL) {
|
||||
break; // 接收成功,退出循环
|
||||
}
|
||||
} else {
|
||||
printf("receive_length: %d\n", receive_length);
|
||||
printf("receive_buffer: ");
|
||||
for (int i = 0; i < receive_length; i++) {
|
||||
printf("%d ", receive_buffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
}
|
||||
resend_count--;
|
||||
}
|
||||
if (data_frame_ptr != NULL) {
|
||||
PrivFree(data_frame_ptr); // 释放数据帧内存
|
||||
data_frame_ptr = NULL; // 避免野指针
|
||||
}
|
||||
// AdapterDeviceDisconnect(adapter, NULL); // 关闭适配器对应的设备
|
||||
#ifdef BSP_BLE_CONFIG
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
#endif
|
||||
if (resend_count <= 0) { // 如果数据帧重发次数超过上限,表示发送失败,丢弃该帧
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 通过以太网向服务器发送数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *SendDataToServerTask_Ethernet(void *arg) {
|
||||
uint8_t server_ip_address[16] = {}; // 目的IP地址
|
||||
uint8_t server_port[6] = {}; // 目的端口号
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
unsigned char receive_buffer[256]; // 从服务器接收每帧响应的存储空间
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_ETHERNET_NAME); // 查找以太网模块适配器
|
||||
|
||||
#ifndef BSP_BLE_CONFIG // 如果没有使能蓝牙配置功能
|
||||
AdapterDeviceSetUp(adapter); // 启动以太网主任务线程
|
||||
AdapterDeviceSetDhcp(adapter, CFG->dhcpSwitch_Ethernet); // 启用或禁用DHCP
|
||||
#endif
|
||||
|
||||
struct DataFrame *data_frame_ptr = NULL; // 数据帧定义
|
||||
while (1) {
|
||||
PrivSemaphoreObtainWait(&queue_buffer_ptr->full, NULL); // 尝试获取循环队列队头元素,如果获取信号量失败,则等待信号量
|
||||
#ifdef BSP_BLE_CONFIG // 使能蓝牙配置功能
|
||||
/* 获取互斥锁 */
|
||||
PrivMutexObtain(&adapter->lock); // 若其他线程正在使用adapter,则阻塞等待
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待;
|
||||
|
||||
/* 尝试连接服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_Ethernet[0], CFG->destinationIpAddress_Ethernet[1],
|
||||
CFG->destinationIpAddress_Ethernet[2], CFG->destinationIpAddress_Ethernet[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_Ethernet[0] | CFG->destinationPort_Ethernet[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_Ethernet*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int res = AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4);
|
||||
|
||||
/* 连接失败,则等待10s再次尝试连接 */
|
||||
if (res != 0 && res != 0x1D) {
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
printf("Ethernet connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#else
|
||||
/* 尝试连接到服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_Ethernet[0], CFG->destinationIpAddress_Ethernet[1],
|
||||
CFG->destinationIpAddress_Ethernet[2], CFG->destinationIpAddress_Ethernet[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_Ethernet[0] | CFG->destinationPort_Ethernet[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_Ethernet*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int reconnect_count = RECONNECT_COUNT; // 尝试重新连接服务器最多RECONNECT_COUNT次
|
||||
while (reconnect_count > 0) {
|
||||
int res = AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4); // 尝试连接服务器
|
||||
if (res == 0 || res == 0x1D) {
|
||||
break;
|
||||
}
|
||||
reconnect_count--;
|
||||
}
|
||||
if (reconnect_count <= 0) { // 若RECONNECT_COUNT次都连接失败,则等待10s再次尝试连接
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
printf("Ethernet connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
PrivMutexObtain(&queue_buffer_ptr->mutex); // 获取互斥锁
|
||||
data_frame_ptr = PollBuffer(queue_buffer_ptr); // 从队列中获取数据帧
|
||||
PrivMutexAbandon(&queue_buffer_ptr->mutex); // 释放互斥锁
|
||||
|
||||
int resend_count = RESEND_COUNT; // 定义数据帧重发次数
|
||||
|
||||
/* 只有数据帧非空并且还有剩余重发次数,才进行发送 */
|
||||
while (data_frame_ptr != NULL && resend_count > 0) {
|
||||
/* 向服务器发送数据 */
|
||||
printf("send data to server, id: %s\n", data_frame_ptr->id);
|
||||
printf("data_frame_ptr->data: %s", data_frame_ptr->data);
|
||||
AdapterDeviceSend(adapter, data_frame_ptr->data,
|
||||
strlen(data_frame_ptr->data)); // 发送数据,注意当前最多发送256字节
|
||||
|
||||
/* 从服务器接收响应,约定服务器接收完数据帧后,返回数据帧中的前12个字节,即数据帧id */
|
||||
memset(receive_buffer, 0, sizeof(receive_buffer));
|
||||
PrivTaskDelay(6000);
|
||||
if (AdapterDeviceRecv(adapter, receive_buffer, strlen(data_frame_ptr->id)) == strlen(data_frame_ptr->id)) {
|
||||
/* 打印服务器响应 */
|
||||
printf("receive_buffer: ");
|
||||
for (int i = 0; i < strlen(receive_buffer); i++) {
|
||||
printf("%c", receive_buffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
/* 比较服务器响应的内容与发送的数据帧id是否一致 */
|
||||
if (strstr(data_frame_ptr->id, receive_buffer) != NULL) {
|
||||
break; // 接收成功,退出循环
|
||||
}
|
||||
}
|
||||
resend_count--;
|
||||
}
|
||||
if (data_frame_ptr != NULL) {
|
||||
PrivFree(data_frame_ptr); // 释放数据帧内存
|
||||
data_frame_ptr = NULL; // 避免野指针
|
||||
}
|
||||
AdapterDeviceDisconnect(adapter, NULL);
|
||||
#ifdef BSP_BLE_CONFIG
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
#endif
|
||||
if (resend_count <= 0) { // 如果数据帧重发次数超过上限,表示发送失败,丢弃该帧
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 开启从DTSD342接收数据的线程以及上传数据到服务器的线程,此方法在main方法中被调用,开机或复位启动
|
||||
*/
|
||||
void StartUpTransformDataTask(void) {
|
||||
/* 分配循环队列空间 */
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)PrivCalloc(1, sizeof(struct QueueBuffer));
|
||||
if (InitBuffer(queue_buffer_ptr) < 0) {
|
||||
PrivFree(queue_buffer_ptr);
|
||||
return;
|
||||
}
|
||||
|
||||
/* 启动从DTSD342接收数据的线程 */
|
||||
pthread_attr_t receive_data_from_dtsd342_task_attr;
|
||||
pthread_args_t receive_data_from_dtsd342_task_args;
|
||||
receive_data_from_dtsd342_task_attr.schedparam.sched_priority = 16; // 线程优先级
|
||||
receive_data_from_dtsd342_task_attr.stacksize = 2048; // 线程栈大小
|
||||
receive_data_from_dtsd342_task_args.pthread_name = "ReceiveDataFromDTSD342Task"; // 线程名字
|
||||
receive_data_from_dtsd342_task_args.arg = queue_buffer_ptr; // 线程参数
|
||||
pthread_t receive_data_thread; // 线程ID
|
||||
PrivTaskCreate(&receive_data_thread, &receive_data_from_dtsd342_task_attr, ReceiveDataFromDTSD342Task, &receive_data_from_dtsd342_task_args);
|
||||
PrivTaskStartup(&receive_data_thread);
|
||||
|
||||
/* 启动上传数据到服务器的线程 */
|
||||
pthread_attr_t send_data_to_server_task_attr;
|
||||
pthread_args_t send_data_to_server_task_args;
|
||||
send_data_to_server_task_attr.schedparam.sched_priority = 16; // 线程优先级
|
||||
send_data_to_server_task_attr.stacksize = 2200; // 线程栈大小
|
||||
send_data_to_server_task_args.pthread_name = "SendDataToServerTask"; // 线程名字
|
||||
send_data_to_server_task_args.arg = queue_buffer_ptr; // 线程参数
|
||||
pthread_t send_data_thread; // 线程ID
|
||||
void *(*start_routine)(void *) = SendDataToServerTask_4G; // 通过4G模块上传到服务器
|
||||
// void *(*start_routine)(void *) = SendDataToServerTask_Ethernet; // 通过以太网模块上传到服务器
|
||||
PrivTaskCreate(&send_data_thread, &send_data_to_server_task_attr, start_routine, &send_data_to_server_task_args); // 通过4G模块上传到服务器
|
||||
PrivTaskStartup(&send_data_thread);
|
||||
}
|
||||
@@ -0,0 +1,862 @@
|
||||
/*
|
||||
* Copyright (c) 2022 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 .c
|
||||
* @brief Support reading data from WISDOM DTZ178 using the DL/T645-2007 protocol
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2025.4.14
|
||||
*/
|
||||
|
||||
#include <ModuleConfig.h>
|
||||
#include <adapter.h>
|
||||
#include <transform.h>
|
||||
#include <math.h>
|
||||
#include <cJSON.h>
|
||||
|
||||
#define MAX_FRAME_SIZE 256 // 最大帧大小
|
||||
#define MAX_DATA_SIZE 1024 // 最大数据大小
|
||||
#define MAX_BUFFER_SIZE 1024 * 2 // 最大缓冲区大小
|
||||
#define RECEIVE_DATA_INTERVAL_MS 1000 * 60 * 2 // DTZ178数据采集间隔时间,单位为毫秒
|
||||
#define SAMPLE_DATA_INTERVAL_MS 300 // 稳定连续采集的间隔时间,单位为毫秒
|
||||
#define SEND_FRAME_LEN 16 // 发送帧长度
|
||||
#define BASE_RECEIVE_FRAME_LEN 16 // 基础返回帧长度(不包含各项数据长度)
|
||||
#define TOTAL_RECEIVE_FRAME_LEN 20 // 总返回帧长度(不包含各项数据长度),包含4个前置0xFE字节
|
||||
#define RESEND_COUNT 3 // 最大帧重发次数
|
||||
#define RECONNECT_COUNT 5 // 最大连接次数
|
||||
#define WATING_RESPONSE_MS 5000 // 等待响应时间,单位为毫秒
|
||||
#define DATA_COUNT (sizeof(data_id_map) / sizeof(data_id_map[0])) // 数据项数量
|
||||
#define READ_COMMAND 0x11 // 读取数据指令
|
||||
|
||||
static const uint8_t addr_meter[6] = {0x01, 0x22, 0x00, 0x03, 0x61, 0x74};
|
||||
static uint8_t parsed_date[11] = {0};
|
||||
static uint8_t parsed_time[9] = {0};
|
||||
|
||||
#ifndef DATA_ITEMS_DEF_H
|
||||
#define DATA_ITEMS_DEF_H
|
||||
|
||||
#define DATA_ITEMS_XMACRO \
|
||||
X(ENERGY_TOTAL, 0x00, 0x00, 0x00, 0x00, 4, 2) /* 总电能,4字节,2位小数,单位kWh */ \
|
||||
X(ENERGY_ACTIVE, 0x00, 0x01, 0x00, 0x00, 4, 2) /* 有功电能,4字节,2位小数,单位kWh */ \
|
||||
X(ENERGY_REACTIVE, 0x00, 0x02, 0x00, 0x00, 4, 2) /* 无功电能,4字节,2位小数,单位kWh */ \
|
||||
X(VOLTAGE_A, 0x02, 0x01, 0x01, 0x00, 2, 1) /* A相电压,2字节,1位小数,单位V */ \
|
||||
X(VOLTAGE_B, 0x02, 0x01, 0x02, 0x00, 2, 1) /* B相电压,2字节,1位小数,单位V */ \
|
||||
X(VOLTAGE_C, 0x02, 0x01, 0x03, 0x00, 2, 1) /* C相电压,2字节,1位小数,单位V */ \
|
||||
X(CURRENT_A, 0x02, 0x02, 0x01, 0x00, 3, 3) /* A相电流,3字节,3位小数,单位A */ \
|
||||
X(CURRENT_B, 0x02, 0x02, 0x02, 0x00, 3, 3) /* B相电流,3字节,3位小数,单位A */ \
|
||||
X(CURRENT_C, 0x02, 0x02, 0x03, 0x00, 3, 3) /* C相电流,3字节,3位小数,单位A */ \
|
||||
X(ACTIVE_POWER_TOTAL, 0x02, 0x03, 0x00, 0x00, 3, 4) /* 总有功功率,3字节,4位小数,单位kW */ \
|
||||
X(ACTIVE_POWER_A, 0x02, 0x03, 0x01, 0x00, 3, 4) /* A有功功率,3字节,4位小数,单位kW */ \
|
||||
X(ACTIVE_POWER_B, 0x02, 0x03, 0x02, 0x00, 3, 4) /* B有功功率,3字节,4位小数,单位kW */ \
|
||||
X(ACTIVE_POWER_C, 0x02, 0x03, 0x03, 0x00, 3, 4) /* C有功功率,3字节,4位小数,单位kW */ \
|
||||
X(REACTIVE_POWER_TOTAL, 0x02, 0x04, 0x00, 0x00, 3, 4) /* 总无功功率,3字节,4位小数,单位kvar */ \
|
||||
X(REACTIVE_POWER_A, 0x02, 0x04, 0x01, 0x00, 3, 4) /* A无功功率,3字节,4位小数,单位kvar */ \
|
||||
X(REACTIVE_POWER_B, 0x02, 0x04, 0x02, 0x00, 3, 4) /* B无功功率,3字节,4位小数,单位kvar */ \
|
||||
X(REACTIVE_POWER_C, 0x02, 0x04, 0x03, 0x00, 3, 4) /* C无功功率,3字节,4位小数,单位kvar */ \
|
||||
X(APPARENT_POWER_TOTAL, 0x02, 0x05, 0x00, 0x00, 3, 4) /* 总视在功率,3字节,4位小数,单位kVA */ \
|
||||
X(APPARENT_POWER_A, 0x02, 0x05, 0x01, 0x00, 3, 4) /* A视在功率,3字节,4位小数,单位kVA */ \
|
||||
X(APPARENT_POWER_B, 0x02, 0x05, 0x02, 0x00, 3, 4) /* B视在功率,3字节,4位小数,单位kVA */ \
|
||||
X(APPARENT_POWER_C, 0x02, 0x05, 0x03, 0x00, 3, 4) /* C视在功率,3字节,4位小数,单位kVA */ \
|
||||
X(POWER_FACTOR_TOTAL, 0x02, 0x06, 0x00, 0x00, 2, 3) /* 总功率因数,2字节,3位小数,单位无 */ \
|
||||
X(POWER_FACTOR_A, 0x02, 0x06, 0x01, 0x00, 2, 3) /* A功率因数,2字节,3位小数,单位无 */ \
|
||||
X(POWER_FACTOR_B, 0x02, 0x06, 0x02, 0x00, 2, 3) /* B功率因数,2字节,3位小数,单位无 */ \
|
||||
X(POWER_FACTOR_C, 0x02, 0x06, 0x03, 0x00, 2, 3) /* C功率因数,2字节,3位小数,单位无 */ \
|
||||
X(FREQUENCY, 0x02, 0x80, 0x00, 0x02, 2, 2) /* 电网频率,2字节,2位小数,单位Hz */ \
|
||||
X(INTERNAL_TEMPERATURE, 0x02, 0x80, 0x00, 0x07, 2, 1) /* 内部温度,2字节,1位小数,单位℃ */ \
|
||||
X(DATE_YMD, 0x04, 0x00, 0x01, 0x01, 4, 0) /* 年月日星期,4字节,0位小数,单位无*/ \
|
||||
X(TIME_HMS, 0x04, 0x00, 0x01, 0x02, 3, 0) /* 时分秒,3字节,0位小数,单位无 */
|
||||
|
||||
|
||||
#endif // DATA_ITEMS_DEF_H
|
||||
|
||||
#ifndef DATA_ITEMS_H
|
||||
#define DATA_ITEMS_H
|
||||
|
||||
typedef enum {
|
||||
#define X(name, id3, id2, id1, id0, size, dec) name,
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
} DataIdIndex;
|
||||
|
||||
typedef struct {
|
||||
uint8_t byte_size;
|
||||
uint8_t decimal_places;
|
||||
} DataInfo;
|
||||
|
||||
static const uint8_t data_id_map[][4] = {
|
||||
#define X(name, id3, id2, id1, id0, size, dec) {id3, id2, id1, id0},
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
};
|
||||
|
||||
static const DataInfo data_info_map[] = {
|
||||
#define X(name, id3, id2, id1, id0, size, dec) {size, dec},
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
};
|
||||
|
||||
static const char *data_id_names[] = {
|
||||
#define X(name, id3, id2, id1, id0, size, dec) #name,
|
||||
DATA_ITEMS_XMACRO
|
||||
#undef X
|
||||
};
|
||||
|
||||
#endif // DATA_ITEMS_H
|
||||
|
||||
/**
|
||||
* @brief 计算DL/T645-2007数据帧的校验和
|
||||
* @param data 数据帧指针
|
||||
* @param len 校验的长度(从第一个 0x68 开始,到CS前一位)
|
||||
* @return uint8_t 校验和
|
||||
*/
|
||||
static uint8_t CheckSum(const uint8_t *data, uint8_t len)
|
||||
{
|
||||
uint16_t sum = 0;
|
||||
for (int i = 0; i < len; i++) {
|
||||
sum += data[i];
|
||||
}
|
||||
return (uint8_t)(sum & 0xFF); // 返回低8位
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 构造DL/T645-2007协议数据帧
|
||||
* @param addr 6字节地址(低位在前)
|
||||
* @param ctrl_code 控制码,如0x11表示读数据
|
||||
* @param data_id 4字节数据标识(低位在前)
|
||||
* @param data 数据域内容(可为空)
|
||||
* @param data_len 数据域长度(读数据时<=200,写数据时<=50)
|
||||
* @param request_frame 输出构造好的完整帧
|
||||
* @return int 0成功,-1失败
|
||||
*/
|
||||
static int GenerateRequestFrame(const uint8_t addr[6], uint8_t ctrl_code, const uint8_t data_id[4], const uint8_t *data, uint8_t data_len, uint8_t *request_frame)
|
||||
{
|
||||
if (!addr || !data_id || !request_frame)
|
||||
return -1;
|
||||
|
||||
uint8_t idx = 0;
|
||||
request_frame[idx++] = 0x68;
|
||||
|
||||
// 地址 6 字节(低位在前)
|
||||
for (int i = 5; i >= 0; i--)
|
||||
request_frame[idx++] = addr[i];
|
||||
|
||||
request_frame[idx++] = 0x68;
|
||||
request_frame[idx++] = ctrl_code;
|
||||
|
||||
uint8_t total_data_len = 4 + data_len;
|
||||
request_frame[idx++] = total_data_len;
|
||||
|
||||
// 数据标识 + 数据内容,低位在前,+0x33加密
|
||||
for (int i = 3; i >= 0; i--)
|
||||
request_frame[idx++] = data_id[i] + 0x33;
|
||||
|
||||
for (int i = 0; i < data_len; i++)
|
||||
request_frame[idx++] = data[i] + 0x33;
|
||||
|
||||
// 校验和
|
||||
uint8_t cs = CheckSum(request_frame, idx);
|
||||
request_frame[idx++] = cs;
|
||||
|
||||
// 结束码
|
||||
request_frame[idx++] = 0x16;
|
||||
|
||||
// printf("GenerateRequestFrame: ");
|
||||
// for (int i = 0; i < idx; i++) {
|
||||
// printf("%02X ", request_frame[i]);
|
||||
// }
|
||||
// printf("\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 将要上传服务器的数据帧
|
||||
*/
|
||||
struct DataFrame {
|
||||
unsigned char id[20]; // 用响应的时间戳作为数据帧的id
|
||||
unsigned char data[MAX_DATA_SIZE]; // 上传服务器的数据帧字符串,用JSON封装
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Modbus RTU响应数据帧的缓存,使用循环队列作为数据结构
|
||||
*/
|
||||
struct QueueBuffer {
|
||||
struct DataFrame *buffer[MAX_BUFFER_SIZE / sizeof(struct DataFrame)]; // 循环队列存储空间,使用数组存储
|
||||
int front; // 循环队列队头
|
||||
int rear; // 循环队列队尾
|
||||
pthread_mutex_t mutex; // 互斥访问循环队列信号量
|
||||
sem_t full; // 循环队列中有效成员个数的信号量
|
||||
};
|
||||
|
||||
#define BUFFER_ELEM_COUNT (MAX_BUFFER_SIZE / sizeof(struct DataFrame)) // 循环队列中可以容纳的最大成员个数
|
||||
|
||||
/**
|
||||
* @brief 初始化循环队列
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @return * int 0表示初始化成功,其他表示初始化失败
|
||||
*/
|
||||
static int InitBuffer(struct QueueBuffer *queue_buffer_ptr) {
|
||||
queue_buffer_ptr->front = 0;
|
||||
queue_buffer_ptr->rear = 0;
|
||||
if (PrivMutexCreate(&queue_buffer_ptr->mutex, 0) < 0) {
|
||||
printf("buffer mutex create failed.\n");
|
||||
return -1;
|
||||
}
|
||||
if (PrivSemaphoreCreate(&queue_buffer_ptr->full, 0, 0) < 0) {
|
||||
printf("buffer full semaphore create failed.\n");
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 循环队列入队,如果循环队列已满,则将最旧的成员出队后,新成员再入队
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @param data_frame_ptr DTZ178响应数据帧
|
||||
* @return int 0表示入队成功,其他表示入队失败
|
||||
*/
|
||||
static int OfferBuffer(struct QueueBuffer *queue_buffer_ptr, struct DataFrame *data_frame_ptr) {
|
||||
/* 循环队列已满,将最旧的成员出队 */
|
||||
if ((queue_buffer_ptr->rear + 1) % BUFFER_ELEM_COUNT == queue_buffer_ptr->front) {
|
||||
struct DataFrame *front_data_frame_ptr = queue_buffer_ptr->buffer[queue_buffer_ptr->front];
|
||||
PrivFree(front_data_frame_ptr);
|
||||
queue_buffer_ptr->front = (queue_buffer_ptr->front + 1) % BUFFER_ELEM_COUNT;
|
||||
}
|
||||
/* 新成员入队 */
|
||||
queue_buffer_ptr->buffer[queue_buffer_ptr->rear] = data_frame_ptr;
|
||||
queue_buffer_ptr->rear = (queue_buffer_ptr->rear + 1) % BUFFER_ELEM_COUNT;
|
||||
printf("front: %d\n", queue_buffer_ptr->front);
|
||||
printf("rear: %d\n", queue_buffer_ptr->rear);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 循环队列出队,如果队列为空则返回NULL
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @return struct DataFrame* 出队成员,如果队列为空则返回NULL
|
||||
*/
|
||||
static struct DataFrame *PollBuffer(struct QueueBuffer *queue_buffer_ptr) {
|
||||
/* 队列为空,返回NULL */
|
||||
if (queue_buffer_ptr->front == queue_buffer_ptr->rear) {
|
||||
return NULL;
|
||||
}
|
||||
/* 最旧的成员出队 */
|
||||
struct DataFrame *front_data_frame_ptr = queue_buffer_ptr->buffer[queue_buffer_ptr->front];
|
||||
queue_buffer_ptr->buffer[queue_buffer_ptr->front] = NULL;
|
||||
queue_buffer_ptr->front = (queue_buffer_ptr->front + 1) % BUFFER_ELEM_COUNT;
|
||||
printf("front: %d\n", queue_buffer_ptr->front);
|
||||
printf("rear: %d\n", queue_buffer_ptr->rear);
|
||||
return front_data_frame_ptr;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 查看队头元素,如果队列为空则返回NULL
|
||||
* @param queue_buffer_ptr 循环队列指针
|
||||
* @return struct DataFrame* 队头元素,如果队列为空则返回NULL
|
||||
*/
|
||||
static struct DataFrame *PeekBuffer(struct QueueBuffer *queue_buffer_ptr) {
|
||||
/* 如果队列为空,返回NULL */
|
||||
if (queue_buffer_ptr->front == queue_buffer_ptr->rear) {
|
||||
return NULL;
|
||||
}
|
||||
/* 返回队头元素,但不出队 */
|
||||
return queue_buffer_ptr->buffer[queue_buffer_ptr->front];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 改写PrivRead函数,原有函数只会读取接收缓冲区的当前已有字节,新函数会读取指定字节数再返回
|
||||
* @param fd 文件描述符
|
||||
* @param buf 数据读取到的位置
|
||||
* @param len 读取的指定字节数
|
||||
* @return int 如果读取到指定字节数返回0;如果到达WATING_RESPONSE_MS仍未读取到指定字节数,或者读数据错误,返回-1
|
||||
*/
|
||||
static int PrivReadEnoughData(int fd, void *buf, size_t len) {
|
||||
char *buffer = (char *)buf; // 将接收的存储空间指针强制转型
|
||||
int gotten_bytes = 0; // 已经读取到的字节数
|
||||
int remain_time = WATING_RESPONSE_MS; // 剩余的时间
|
||||
|
||||
/* 只有接收的字节数不够,并且还有剩余时间,才可以继续读取 */
|
||||
while (gotten_bytes < len && remain_time > 0) {
|
||||
int bytes = PrivRead(fd, buffer + gotten_bytes, len - gotten_bytes); // 从设备读取
|
||||
gotten_bytes += bytes;
|
||||
PrivTaskDelay(100); // 每100ms读取一次
|
||||
remain_time -= 100; // 剩余时间减去100ms
|
||||
}
|
||||
/* 若没有剩余时间,表示还没有读取到指定的字节数,返回-1;若有剩余时间,表示已经读取了指定的字节数,返回0 */
|
||||
return remain_time < 0 ? -1 : 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 将BCD格式的多字节数值转换为十进制整数
|
||||
* @param bcd BCD格式的原始数值(低字节在低位)
|
||||
* @param bytes BCD所占用的字节数
|
||||
* @return 转换后的十进制整数结果
|
||||
* @note 每个字节的高4位和低4位分别代表1位十进制数字,即每个字节表示两位十进制数。
|
||||
* 最低位字节代表最低的两位十进制数,依此类推。例如 0x12 0x34 表示1234。
|
||||
*/
|
||||
static uint32_t BcdToDecimal(uint32_t bcd, uint8_t bytes)
|
||||
{
|
||||
uint32_t result = 0;
|
||||
for (int i = 0; i < bytes; i++) {
|
||||
uint8_t byte = (bcd >> (i * 8)) & 0xFF;
|
||||
uint8_t high = (byte >> 4) & 0x0F; // 高4位
|
||||
uint8_t low = byte & 0x0F; // 低4位
|
||||
result += (high * 10 + low) * pow(100, i); // 每个字节是2位十进制
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 解析DTZ178响应的Modbus RTU数据帧
|
||||
* @param response_frame 返回的数据帧
|
||||
* @param data_info_ptr 数据项的字节数和小数位数信息
|
||||
* @param item_id 数据项ID
|
||||
* @param root 根节点
|
||||
*/
|
||||
static void ParseResponseFrame(unsigned char *response_frame, const DataInfo *data_info_ptr, int item_id, cJSON *root) {
|
||||
if (!response_frame || !data_info_ptr || !root) {
|
||||
printf("Invalid input to ParseResponseFrame\n");
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t data_len_total = response_frame[13]; // 数据域长度,包括数据标识(4字节) + 数据内容
|
||||
if (data_len_total < 4 || data_len_total - 4 != data_info_ptr->byte_size) {
|
||||
printf("Invalid data length in frame\n");
|
||||
return;
|
||||
}
|
||||
|
||||
const uint8_t *data_field = &response_frame[14]; // 数据域开始位置(含数据标识 + 数据内容)
|
||||
const uint8_t *data_value = &data_field[4]; // 数据内容起始位置
|
||||
|
||||
// for (int i = 0; i < data_info_ptr->byte_size; i++)
|
||||
// printf("%02x ", data_value[i]);
|
||||
|
||||
// 判断是否是日期或时间
|
||||
if (item_id == DATE_YMD) {
|
||||
snprintf(parsed_date, sizeof(parsed_date), "20%02x-%02x-%02x", data_value[3] - 0x33, data_value[2] - 0x33, data_value[1] - 0x33);
|
||||
// printf("Parsed date: %s\n", parsed_date);
|
||||
return;
|
||||
} else if (item_id == TIME_HMS) {
|
||||
snprintf(parsed_time, sizeof(parsed_time), "%02x:%02x:%02x", data_value[2] - 0x33, data_value[1] - 0x33, data_value[0] - 0x33);
|
||||
// printf("Parsed time: %s\n", parsed_time);
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t bcd = 0;
|
||||
|
||||
for (int i = data_info_ptr->byte_size - 1; i >= 0; i--) {
|
||||
// 解密(减去0x33),反向拼接(低位在前 → 高位在前)
|
||||
bcd |= ((uint32_t)(data_value[i] - 0x33)) << (8 * i);
|
||||
}
|
||||
|
||||
uint32_t value = 0;
|
||||
value = BcdToDecimal(bcd, data_info_ptr->byte_size);
|
||||
|
||||
// 除以10的倍数来处理小数点
|
||||
double final_value = value / pow(10, data_info_ptr->decimal_places);
|
||||
|
||||
// printf("Parsed value: %.*f\n", data_info_ptr->decimal_places, final_value);
|
||||
|
||||
char format[10];
|
||||
snprintf(format, sizeof(format), "%%.%df", data_info_ptr->decimal_places);
|
||||
|
||||
char final_value_str[20];
|
||||
snprintf(final_value_str, sizeof(final_value_str), format, final_value);
|
||||
|
||||
cJSON_AddStringToObject(root, data_id_names[item_id], final_value_str);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 从DTZ178接收数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *ReceiveDataFromDTZ178Task(void *arg) {
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
int fd = PrivOpen("/dev/rs485_dev1", O_RDWR); // 打开设备文件
|
||||
if (fd < 0) { // 打开设备文件失败,打印错误信息
|
||||
printf("open rs485 fd error: %d\n", fd);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
struct SerialDataCfg rs485_configuration;
|
||||
memset(&rs485_configuration, 0, sizeof(struct SerialDataCfg));
|
||||
/* 读取RS485配置信息 */
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待
|
||||
int baud_rates_option = CFG->baudRate_Rs485;
|
||||
int data_bits_option = CFG->dataBits_Rs485;
|
||||
int stop_bits_option = CFG->stopBits_Rs485;
|
||||
int parity_option = CFG->parity_Rs485;
|
||||
PrivMutexAbandon(&romConfigurationMutex); // 释放互斥锁
|
||||
switch (baud_rates_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_2400; // 默认波特率为2400
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_4800;
|
||||
break;
|
||||
case 3:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_9600;
|
||||
break;
|
||||
case 4:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_19200;
|
||||
break;
|
||||
case 5:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_38400;
|
||||
break;
|
||||
case 6:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_57600;
|
||||
break;
|
||||
case 7:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_115200;
|
||||
break;
|
||||
case 8:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_230400;
|
||||
break;
|
||||
default:
|
||||
rs485_configuration.serial_baud_rate = BAUD_RATE_9600;
|
||||
break;
|
||||
}
|
||||
switch (data_bits_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_data_bits = DATA_BITS_8;
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_data_bits = DATA_BITS_9;
|
||||
break;
|
||||
default:
|
||||
rs485_configuration.serial_data_bits = DATA_BITS_8;
|
||||
break;
|
||||
}
|
||||
switch (stop_bits_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_stop_bits = STOP_BITS_1;
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_stop_bits = STOP_BITS_2;
|
||||
break;
|
||||
default:
|
||||
rs485_configuration.serial_stop_bits = STOP_BITS_1;
|
||||
break;
|
||||
}
|
||||
switch (parity_option) {
|
||||
case 1:
|
||||
rs485_configuration.serial_parity_mode = PARITY_NONE;
|
||||
break;
|
||||
case 2:
|
||||
rs485_configuration.serial_parity_mode = PARITY_ODD;
|
||||
break;
|
||||
case 3:
|
||||
rs485_configuration.serial_parity_mode = PARITY_EVEN; // 默认校验方式为偶校验
|
||||
break;
|
||||
}
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = (void *)&rs485_configuration;
|
||||
if (0 != PrivIoctl(fd, OPE_INT, &ioctl_cfg)) {
|
||||
printf("ioctl uart fd error %d\n", fd);
|
||||
PrivClose(fd);
|
||||
return NULL;
|
||||
}
|
||||
printf("open rs485 fd success %d\n", fd);
|
||||
|
||||
unsigned char request_frame[MAX_FRAME_SIZE]; // 定义请求帧
|
||||
unsigned char response_frame[MAX_FRAME_SIZE]; // 定义回复帧
|
||||
while (1) {
|
||||
printf("enter cycle\n");
|
||||
struct DataFrame *data_frame_ptr = (struct DataFrame *)PrivMalloc(sizeof(struct DataFrame));
|
||||
memset(data_frame_ptr, 0, sizeof(struct DataFrame));
|
||||
|
||||
// 创建一个空的JSON对象
|
||||
cJSON *root = cJSON_CreateObject();
|
||||
int is_success = 1;
|
||||
|
||||
for (int i = 0; i < DATA_COUNT; i++) {
|
||||
const uint8_t *data_id = data_id_map[i];
|
||||
const DataInfo *data_info = &data_info_map[i];
|
||||
|
||||
memset(request_frame, 0, sizeof(request_frame));
|
||||
if (GenerateRequestFrame(addr_meter, READ_COMMAND, data_id, NULL, 0, request_frame) < 0) {
|
||||
printf("Generate frame failed for index %d\n", i);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
PrivWrite(fd, request_frame, SEND_FRAME_LEN); // 发送Modbus RTU请求帧
|
||||
|
||||
/* 读取响应帧数据 */
|
||||
memset(response_frame, 0, sizeof(response_frame));
|
||||
if (PrivReadEnoughData(fd, response_frame, TOTAL_RECEIVE_FRAME_LEN + data_info->byte_size) < 0) {
|
||||
printf("Timeout reading response for index %d\n", i);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
// printf("Response frame for index %d: ", i);
|
||||
// for (int j = 0; j < TOTAL_RECEIVE_FRAME_LEN + data_info->byte_size; j++)
|
||||
// printf("%02X ", response_frame[j]);
|
||||
// printf("\n");
|
||||
|
||||
// 校验帧头、帧尾
|
||||
if (response_frame[4] != 0x68 || response_frame[11] != 0x68 || response_frame[TOTAL_RECEIVE_FRAME_LEN + data_info->byte_size - 1] != 0x16) {
|
||||
printf("Invalid frame format for index %d\n", i);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
// 校验和
|
||||
uint8_t calc_cs = CheckSum(response_frame + 4, BASE_RECEIVE_FRAME_LEN + data_info->byte_size - 2);
|
||||
uint8_t recv_cs = response_frame[TOTAL_RECEIVE_FRAME_LEN + data_info->byte_size - 2];
|
||||
if (calc_cs != recv_cs) {
|
||||
printf("CheckSum error at index %d: calc %02X, recv %02X\n", i, calc_cs, recv_cs);
|
||||
is_success = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
ParseResponseFrame(response_frame, data_info, i, root);
|
||||
|
||||
PrivTaskDelay(SAMPLE_DATA_INTERVAL_MS);
|
||||
}
|
||||
|
||||
if (!is_success) {
|
||||
printf("read all data failed\n");
|
||||
PrivFree(data_frame_ptr);
|
||||
cJSON_Delete(root);
|
||||
continue;
|
||||
}
|
||||
|
||||
snprintf((char *)data_frame_ptr->id, sizeof(data_frame_ptr->id), "%s %s", parsed_date, parsed_time);
|
||||
printf("data_frame_ptr->id: %s\n", data_frame_ptr->id);
|
||||
|
||||
char *json_str = cJSON_Print(root);
|
||||
strncpy((char *)data_frame_ptr->data, json_str, MAX_DATA_SIZE - 1);
|
||||
data_frame_ptr->data[MAX_DATA_SIZE - 1] = '\0'; // 确保结尾是 \0
|
||||
printf("data_frame_ptr->data: %s\n", data_frame_ptr->data);
|
||||
|
||||
// 删除字符串空间
|
||||
free(json_str);
|
||||
// 删除 cJSON 对象
|
||||
cJSON_Delete(root);
|
||||
|
||||
/* 将解析后的数据帧放入循环队列 */
|
||||
PrivMutexObtain(&queue_buffer_ptr->mutex); // 获取互斥锁
|
||||
OfferBuffer(queue_buffer_ptr, data_frame_ptr); // 将数据帧放入队列
|
||||
printf("receive data from DTZ178, id: %s\n", data_frame_ptr->id); // 打印接收到的数据帧ID
|
||||
PrivMutexAbandon(&queue_buffer_ptr->mutex); // 释放互斥锁
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量,即告知发送数据线程,队列中有新的数据帧
|
||||
|
||||
PrivTaskDelay(RECEIVE_DATA_INTERVAL_MS); // 延迟一段时间再读取下一帧数据
|
||||
|
||||
printf("end cycle\n");
|
||||
}
|
||||
|
||||
PrivClose(fd); // 关闭设备文件
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 通过4G向服务器发送数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *SendDataToServerTask_4G(void *arg) {
|
||||
uint8_t server_ip_address[16] = {}; // 目的IP地址
|
||||
uint8_t server_port[6] = {}; // 目的端口号
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
unsigned char receive_buffer[256]; // 从服务器接收每帧响应的存储空间
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_4G_NAME); // 查找4G模块适配器
|
||||
|
||||
AdapterDeviceOpen(adapter); // 打开适配器对应的设备(实际打开串口中断)
|
||||
int baud_rate = BAUD_RATE_115200; // 波特率,用于设置4G模块串口
|
||||
AdapterDeviceControl(adapter, OPE_INT, &baud_rate); // 对适配器对应设备进行配置(实际配置波特率)
|
||||
|
||||
struct DataFrame *data_frame_ptr = NULL; // 数据帧定义
|
||||
while (1) {
|
||||
PrivSemaphoreObtainWait(&queue_buffer_ptr->full, NULL); // 尝试获取循环队列队头元素,如果获取信号量失败,则等待信号量
|
||||
#ifdef BSP_BLE_CONFIG // 如果启用了BLE配置功能
|
||||
/* 获取互斥锁 */
|
||||
PrivMutexObtain(&adapter->lock); // 若其他线程正在使用adapter,则阻塞等待
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待
|
||||
|
||||
/* 尝试连接服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_4G[0], CFG->destinationIpAddress_4G[1],
|
||||
CFG->destinationIpAddress_4G[2], CFG->destinationIpAddress_4G[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_4G[0] | CFG->destinationPort_4G[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_4G*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
if (CFG->mqttSwitch_4G == 1) { // 如果使能MQTT
|
||||
AdapterDeviceMqttConnect(adapter, server_ip_address, server_port, CFG->mqttClientId_4G, CFG->mqttUsername_4G,
|
||||
CFG->mqttPassword_4G);
|
||||
} else { // 如果禁用MQTT
|
||||
AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4);
|
||||
}
|
||||
|
||||
AdapterDeviceNetstat(adapter); // 读取网络连接状态
|
||||
/* 若连接失败,则等待10s再次尝试连接 */
|
||||
if (CFG->mqttSwitch_4G == 0 && !adapter->network_info.is_connected ||
|
||||
CFG->mqttSwitch_4G == 1 && !adapter->network_info.mqttIsConnected) {
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
printf("4G connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#else // 如果没有启用BLE配置功能
|
||||
/* 尝试连接到服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_4G[0], CFG->destinationIpAddress_4G[1],
|
||||
CFG->destinationIpAddress_4G[2], CFG->destinationIpAddress_4G[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_4G[0] | CFG->destinationPort_4G[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_4G*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int reconnect_count = RECONNECT_COUNT; // 尝试重新连接服务器最多RECONNECT_COUNT次
|
||||
while (reconnect_count > 0) {
|
||||
int res;
|
||||
if (CFG->mqttSwitch_4G == 1) {
|
||||
res = AdapterDeviceMqttConnect(adapter, mqttServerIp, mqttServerPort, CFG->mqttClientId_4G, CFG->mqttUsername_4G,
|
||||
CFG->mqttPassword_4G);
|
||||
} else {
|
||||
res = AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4);
|
||||
}
|
||||
if (res == 0) {
|
||||
break;
|
||||
}
|
||||
reconnect_count--;
|
||||
}
|
||||
if (reconnect_count <= 0) { // 若RECONNECT_COUNT次都连接失败,则等待10s再次尝试连接
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
printf("4G connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
PrivMutexObtain(&queue_buffer_ptr->mutex); // 获取互斥锁
|
||||
data_frame_ptr = PollBuffer(queue_buffer_ptr); // 从队列中获取数据帧
|
||||
PrivMutexAbandon(&queue_buffer_ptr->mutex); // 释放互斥锁
|
||||
|
||||
int resend_count = RESEND_COUNT; // 定义数据帧重发次数
|
||||
while (data_frame_ptr != NULL && resend_count > 0) { // 只有数据帧非空并且还有剩余重发次数,才进行发送
|
||||
/* 向服务器发送数据 */
|
||||
printf("data_frame_ptr->data: %s", data_frame_ptr->data);
|
||||
printf("send data to server, id: %s\n", data_frame_ptr->id);
|
||||
if (CFG->mqttSwitch_4G == 1) { // MQTT模式下,无需服务器响应数据
|
||||
AdapterDeviceMqttSend(adapter, CFG->mqttTopic_4G, data_frame_ptr->data,
|
||||
strlen(data_frame_ptr->data)); // 发送数据,注意当前最多发送256字节
|
||||
break;
|
||||
} else {
|
||||
AdapterDeviceSend(adapter, data_frame_ptr->data,
|
||||
strlen(data_frame_ptr->data)); // 发送数据,注意当前最多发送256字节
|
||||
|
||||
/* 从服务器接收响应,约定服务器接收完数据帧后,返回数据帧中的前12个字节,即数据帧id */
|
||||
/* 多读取2字节,是为了防止前面还有命令模式返回的剩余的\r\n影响判断 */
|
||||
memset(receive_buffer, 0, sizeof(receive_buffer));
|
||||
int receive_length = AdapterDeviceRecv(adapter, receive_buffer, strlen(data_frame_ptr->id) + 2);
|
||||
if (receive_length == strlen(data_frame_ptr->id) + 2 || receive_length == strlen(data_frame_ptr->id)) {
|
||||
/* 打印服务器响应 */
|
||||
printf("receive_length: %d\n", receive_length);
|
||||
printf("receive_buffer: ");
|
||||
for (int i = 0; i < receive_length; i++) {
|
||||
printf("%c", receive_buffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
/* 比较服务器响应的内容与发送的数据帧id是否一致 */
|
||||
if (strstr(receive_buffer, data_frame_ptr->id) != NULL) {
|
||||
break; // 接收成功,退出循环
|
||||
}
|
||||
} else {
|
||||
printf("receive_length: %d\n", receive_length);
|
||||
printf("receive_buffer: ");
|
||||
for (int i = 0; i < receive_length; i++) {
|
||||
printf("%d ", receive_buffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
}
|
||||
resend_count--;
|
||||
}
|
||||
if (data_frame_ptr != NULL) {
|
||||
PrivFree(data_frame_ptr); // 释放数据帧内存
|
||||
data_frame_ptr = NULL; // 避免野指针
|
||||
}
|
||||
// AdapterDeviceDisconnect(adapter, NULL); // 关闭适配器对应的设备
|
||||
#ifdef BSP_BLE_CONFIG
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
#endif
|
||||
if (resend_count <= 0) { // 如果数据帧重发次数超过上限,表示发送失败,丢弃该帧
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 通过以太网向服务器发送数据的线程
|
||||
* @param arg 循环队列指针
|
||||
* @return void* 目前返回值无意义
|
||||
*/
|
||||
static void *SendDataToServerTask_Ethernet(void *arg) {
|
||||
uint8_t server_ip_address[16] = {}; // 目的IP地址
|
||||
uint8_t server_port[6] = {}; // 目的端口号
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)arg; // 循环队列指针
|
||||
unsigned char receive_buffer[256]; // 从服务器接收每帧响应的存储空间
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_ETHERNET_NAME); // 查找以太网模块适配器
|
||||
|
||||
#ifndef BSP_BLE_CONFIG // 如果没有使能蓝牙配置功能
|
||||
AdapterDeviceSetUp(adapter); // 启动以太网主任务线程
|
||||
AdapterDeviceSetDhcp(adapter, CFG->dhcpSwitch_Ethernet); // 启用或禁用DHCP
|
||||
#endif
|
||||
|
||||
struct DataFrame *data_frame_ptr = NULL; // 数据帧定义
|
||||
while (1) {
|
||||
PrivSemaphoreObtainWait(&queue_buffer_ptr->full, NULL); // 尝试获取循环队列队头元素,如果获取信号量失败,则等待信号量
|
||||
#ifdef BSP_BLE_CONFIG // 使能蓝牙配置功能
|
||||
/* 获取互斥锁 */
|
||||
PrivMutexObtain(&adapter->lock); // 若其他线程正在使用adapter,则阻塞等待
|
||||
PrivMutexObtain(&romConfigurationMutex); // 若其他线程正在读取或者写入CFG,则阻塞等待;
|
||||
|
||||
/* 尝试连接服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_Ethernet[0], CFG->destinationIpAddress_Ethernet[1],
|
||||
CFG->destinationIpAddress_Ethernet[2], CFG->destinationIpAddress_Ethernet[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_Ethernet[0] | CFG->destinationPort_Ethernet[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_Ethernet*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int res = AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4);
|
||||
|
||||
/* 连接失败,则等待10s再次尝试连接 */
|
||||
if (res != 0 && res != 0x1D) {
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
printf("Ethernet connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#else
|
||||
/* 尝试连接到服务器 */
|
||||
sprintf(server_ip_address, "%u.%u.%u.%u", CFG->destinationIpAddress_Ethernet[0], CFG->destinationIpAddress_Ethernet[1],
|
||||
CFG->destinationIpAddress_Ethernet[2], CFG->destinationIpAddress_Ethernet[3]);
|
||||
sprintf(server_port, "%u", (unsigned short)CFG->destinationPort_Ethernet[0] | CFG->destinationPort_Ethernet[1] << 8);
|
||||
printf("-*-*-*-*sendDataToServerTask_Ethernet*-*-*-*\n");
|
||||
printf("server_ip_address:\t%s\n", server_ip_address);
|
||||
printf("server_port:\t\t%s\n", server_port);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
int reconnect_count = RECONNECT_COUNT; // 尝试重新连接服务器最多RECONNECT_COUNT次
|
||||
while (reconnect_count > 0) {
|
||||
int res = AdapterDeviceConnect(adapter, CLIENT, server_ip_address, server_port, IPV4); // 尝试连接服务器
|
||||
if (res == 0 || res == 0x1D) {
|
||||
break;
|
||||
}
|
||||
reconnect_count--;
|
||||
}
|
||||
if (reconnect_count <= 0) { // 若RECONNECT_COUNT次都连接失败,则等待10s再次尝试连接
|
||||
PrivSemaphoreAbandon(&queue_buffer_ptr->full); // 释放信号量
|
||||
printf("Ethernet connect to server failed\n"); // 连接失败,打印错误信息
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
PrivMutexObtain(&queue_buffer_ptr->mutex); // 获取互斥锁
|
||||
data_frame_ptr = PollBuffer(queue_buffer_ptr); // 从队列中获取数据帧
|
||||
PrivMutexAbandon(&queue_buffer_ptr->mutex); // 释放互斥锁
|
||||
|
||||
int resend_count = RESEND_COUNT; // 定义数据帧重发次数
|
||||
|
||||
/* 只有数据帧非空并且还有剩余重发次数,才进行发送 */
|
||||
while (data_frame_ptr != NULL && resend_count > 0) {
|
||||
/* 向服务器发送数据 */
|
||||
printf("send data to server, id: %s\n", data_frame_ptr->id);
|
||||
printf("data_frame_ptr->data: %s", data_frame_ptr->data);
|
||||
AdapterDeviceSend(adapter, data_frame_ptr->data,
|
||||
strlen(data_frame_ptr->data)); // 发送数据,注意当前最多发送256字节
|
||||
|
||||
/* 从服务器接收响应,约定服务器接收完数据帧后,返回数据帧中的前12个字节,即数据帧id */
|
||||
memset(receive_buffer, 0, sizeof(receive_buffer));
|
||||
PrivTaskDelay(6000);
|
||||
if (AdapterDeviceRecv(adapter, receive_buffer, strlen(data_frame_ptr->id)) == strlen(data_frame_ptr->id)) {
|
||||
/* 打印服务器响应 */
|
||||
printf("receive_buffer: ");
|
||||
for (int i = 0; i < strlen(receive_buffer); i++) {
|
||||
printf("%c", receive_buffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
/* 比较服务器响应的内容与发送的数据帧id是否一致 */
|
||||
if (strstr(data_frame_ptr->id, receive_buffer) != NULL) {
|
||||
break; // 接收成功,退出循环
|
||||
}
|
||||
}
|
||||
resend_count--;
|
||||
}
|
||||
if (data_frame_ptr != NULL) {
|
||||
PrivFree(data_frame_ptr); // 释放数据帧内存
|
||||
data_frame_ptr = NULL; // 避免野指针
|
||||
}
|
||||
AdapterDeviceDisconnect(adapter, NULL);
|
||||
#ifdef BSP_BLE_CONFIG
|
||||
/* 释放互斥锁 */
|
||||
PrivMutexAbandon(&romConfigurationMutex);
|
||||
PrivMutexAbandon(&adapter->lock);
|
||||
#endif
|
||||
if (resend_count <= 0) { // 如果数据帧重发次数超过上限,表示发送失败,丢弃该帧
|
||||
PrivTaskDelay(1000 * 10); // 延迟10秒,避免网络拥塞
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 开启从DTZ178接收数据的线程以及上传数据到服务器的线程,此方法在main方法中被调用,开机或复位启动
|
||||
*/
|
||||
void StartUpTransformDataTask(void) {
|
||||
/* 分配循环队列空间 */
|
||||
struct QueueBuffer *queue_buffer_ptr = (struct QueueBuffer *)PrivCalloc(1, sizeof(struct QueueBuffer));
|
||||
if (InitBuffer(queue_buffer_ptr) < 0) {
|
||||
PrivFree(queue_buffer_ptr);
|
||||
return;
|
||||
}
|
||||
|
||||
/* 启动从DTZ178接收数据的线程 */
|
||||
pthread_attr_t receive_data_from_dtz178_task_attr;
|
||||
pthread_args_t receive_data_from_dtz178_task_args;
|
||||
receive_data_from_dtz178_task_attr.schedparam.sched_priority = 16; // 线程优先级
|
||||
receive_data_from_dtz178_task_attr.stacksize = 2048; // 线程栈大小
|
||||
receive_data_from_dtz178_task_args.pthread_name = "ReceiveDataFromDTZ178Task"; // 线程名字
|
||||
receive_data_from_dtz178_task_args.arg = queue_buffer_ptr; // 线程参数
|
||||
pthread_t receive_data_thread; // 线程ID
|
||||
PrivTaskCreate(&receive_data_thread, &receive_data_from_dtz178_task_attr, ReceiveDataFromDTZ178Task, &receive_data_from_dtz178_task_args);
|
||||
PrivTaskStartup(&receive_data_thread);
|
||||
|
||||
/* 启动上传数据到服务器的线程 */
|
||||
pthread_attr_t send_data_to_server_task_attr;
|
||||
pthread_args_t send_data_to_server_task_args;
|
||||
send_data_to_server_task_attr.schedparam.sched_priority = 16; // 线程优先级
|
||||
send_data_to_server_task_attr.stacksize = 2200; // 线程栈大小
|
||||
send_data_to_server_task_args.pthread_name = "SendDataToServerTask"; // 线程名字
|
||||
send_data_to_server_task_args.arg = queue_buffer_ptr; // 线程参数
|
||||
pthread_t send_data_thread; // 线程ID
|
||||
void *(*start_routine)(void *) = SendDataToServerTask_4G; // 通过4G模块上传到服务器
|
||||
// void *(*start_routine)(void *) = SendDataToServerTask_Ethernet; // 通过以太网模块上传到服务器
|
||||
PrivTaskCreate(&send_data_thread, &send_data_to_server_task_attr, start_routine, &send_data_to_server_task_args); // 通过4G模块上传到服务器
|
||||
PrivTaskStartup(&send_data_thread);
|
||||
}
|
||||
@@ -8,6 +8,20 @@ menu "connection app"
|
||||
menuconfig SOCKET_DEMO
|
||||
bool "Config test socket demo"
|
||||
default n
|
||||
|
||||
choice
|
||||
prompt "Select Ammeter Device Type"
|
||||
default DEVICE_ADL400
|
||||
|
||||
config DEVICE_ADL400
|
||||
bool "CH32V208_ADL400"
|
||||
|
||||
config DEVICE_DTZ178
|
||||
bool "CH32V208_DTZ178"
|
||||
|
||||
config DEVICE_DTSD342
|
||||
bool "CH32V208_DTSD342"
|
||||
endchoice
|
||||
endif
|
||||
|
||||
endmenu
|
||||
|
||||
@@ -1,3 +1,3 @@
|
||||
SRC_DIR := advantech beckhoff br delta mitsubishi omron schneider siemens ge xinje inovance keyence panasonic fatek ab abb
|
||||
SRC_DIR := advantech beckhoff br delta mitsubishi omron schneider siemens ge xinje inovance keyence panasonic fatek ab abb koyo
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
@@ -1,3 +1,3 @@
|
||||
SRC_FILES := inovance_am401_cpu1608tn_ethernet.c inovance_am401_cpu1608tn_uart.c
|
||||
SRC_FILES := inovance_am401_cpu1608tn_ethernet.c inovance_am401_cpu1608tn_uart.c inovance_H3U_cpu3232MT_ethernet.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,52 @@
|
||||
/*
|
||||
* Copyright (c) 2024 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 inovance_H3U_cpu3232MT_ethernet.c
|
||||
* @brief PLC Inovance H3U-3232MT app
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.08.06
|
||||
*/
|
||||
|
||||
#include <control.h>
|
||||
|
||||
void ControlInovanceH3UCPU3232MTTest(void)
|
||||
{
|
||||
int i, j = 0;
|
||||
int read_data_length = 0;
|
||||
uint8_t read_data[128] = {0};
|
||||
ControlProtocolType modbus_tcp_protocol = ControlProtocolFind();
|
||||
if (NULL == modbus_tcp_protocol) {
|
||||
printf("%s get modbus tcp protocol %p failed\n", __func__, modbus_tcp_protocol);
|
||||
return;
|
||||
}
|
||||
printf("%s get modbus tcp protocol %p successfull\n", __func__, modbus_tcp_protocol);
|
||||
|
||||
if (CONTROL_REGISTERED == modbus_tcp_protocol->protocol_status) {
|
||||
ControlProtocolOpen(modbus_tcp_protocol);
|
||||
for (;;) {
|
||||
read_data_length = ControlProtocolRead(modbus_tcp_protocol, read_data, sizeof(read_data));
|
||||
printf("%s read [%d] modbus tcp data %d using receipe file\n", __func__, i, read_data_length);
|
||||
if (read_data_length) {
|
||||
for (j = 0; j < read_data_length; j++) {
|
||||
printf("j %d data 0x%x\n", j, read_data[j]);
|
||||
}
|
||||
}
|
||||
i++;
|
||||
memset(read_data, 0, sizeof(read_data));
|
||||
PrivTaskDelay(10000);
|
||||
}
|
||||
// ControlProtocolClose(modbus_tcp_protocol);
|
||||
}
|
||||
}
|
||||
PRIV_SHELL_CMD_FUNCTION(ControlInovanceH3UCPU3232MTTest, Inovance PLC N3UCPU3232MT Demo, PRIV_SHELL_CMD_MAIN_ATTR);
|
||||
@@ -0,0 +1,30 @@
|
||||
{
|
||||
"device_id": 1,
|
||||
"device_name": "Ino_H3U3232MT",
|
||||
"communication_type": 0,
|
||||
"socket_config": {
|
||||
"plc_ip": "192.168.250.55",
|
||||
"local_ip": "192.168.250.147",
|
||||
"gateway": "192.168.250.252",
|
||||
"netmask": "255.255.255.0",
|
||||
"port": 502
|
||||
},
|
||||
"protocol_type": 2,
|
||||
"read_period": 300,
|
||||
"read_item_list": [
|
||||
{
|
||||
"value_name": "M8000",
|
||||
"value_type": 1,
|
||||
"function_code": 1,
|
||||
"start_address": 8000,
|
||||
"quantity": 1
|
||||
},
|
||||
{
|
||||
"value_name": "D120",
|
||||
"value_type": 3,
|
||||
"function_code": 3,
|
||||
"start_address": 120,
|
||||
"quantity": 1
|
||||
}
|
||||
]
|
||||
}
|
||||
3
APP_Framework/Applications/control_app/plc_demo/koyo/Makefile
Executable file
3
APP_Framework/Applications/control_app/plc_demo/koyo/Makefile
Executable file
@@ -0,0 +1,3 @@
|
||||
SRC_FILES := koyo_nk1cpu40.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
Binary file not shown.
|
After Width: | Height: | Size: 1.7 MiB |
@@ -0,0 +1,52 @@
|
||||
/*
|
||||
* Copyright (c) 2024 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 koyo_nk1cpu40.c
|
||||
* @brief PLC AB MICRO850 app
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.07.03
|
||||
*/
|
||||
|
||||
#include <control.h>
|
||||
|
||||
void ControlKoyoNK1CPU40Test(void)
|
||||
{
|
||||
int i, j = 0;
|
||||
int read_data_length = 0;
|
||||
uint8_t read_data[128] = {0};
|
||||
ControlProtocolType modbus_tcp_protocol = ControlProtocolFind();
|
||||
if (NULL == modbus_tcp_protocol) {
|
||||
printf("%s get modbus tcp protocol %p failed\n", __func__, modbus_tcp_protocol);
|
||||
return;
|
||||
}
|
||||
printf("%s get modbus tcp protocol %p successfull\n", __func__, modbus_tcp_protocol);
|
||||
|
||||
if (CONTROL_REGISTERED == modbus_tcp_protocol->protocol_status) {
|
||||
ControlProtocolOpen(modbus_tcp_protocol);
|
||||
for (;;) {
|
||||
read_data_length = ControlProtocolRead(modbus_tcp_protocol, read_data, sizeof(read_data));
|
||||
printf("%s read [%d] modbus tcp data %d using receipe file\n", __func__, i, read_data_length);
|
||||
if (read_data_length) {
|
||||
for (j = 0; j < read_data_length; j++) {
|
||||
printf("j %d data 0x%x\n", j, read_data[j]);
|
||||
}
|
||||
}
|
||||
i++;
|
||||
memset(read_data, 0, sizeof(read_data));
|
||||
PrivTaskDelay(10000);
|
||||
}
|
||||
// ControlProtocolClose(modbus_tcp_protocol);
|
||||
}
|
||||
}
|
||||
PRIV_SHELL_CMD_FUNCTION(ControlKoyoNK1CPU40Test, Koyo Plc NK1CPU40 Demo, PRIV_SHELL_CMD_MAIN_ATTR);
|
||||
@@ -1,3 +1,11 @@
|
||||
config ADAPTER_EC801E
|
||||
bool "Using 4G adapter device EC801E"
|
||||
default n
|
||||
|
||||
if ADAPTER_EC801E
|
||||
source "$APP_DIR/Framework/connection/4g/ec801e/Kconfig"
|
||||
endif
|
||||
|
||||
config ADAPTER_EC200T
|
||||
bool "Using 4G adapter device EC200T"
|
||||
default n
|
||||
@@ -13,3 +21,11 @@ config ADAPTER_EC200A
|
||||
if ADAPTER_EC200A
|
||||
source "$APP_DIR/Framework/connection/4g/ec200a/Kconfig"
|
||||
endif
|
||||
|
||||
config ADAPTER_GM800TF
|
||||
bool "Using 4G adapter device GM800TF"
|
||||
default n
|
||||
|
||||
if ADAPTER_GM800TF
|
||||
source "$APP_DIR/Framework/connection/4g/gm800tf/Kconfig"
|
||||
endif
|
||||
|
||||
@@ -9,6 +9,10 @@ endif
|
||||
ifeq ($(CONFIG_ADD_XIZI_FEATURES),y)
|
||||
SRC_FILES := adapter_4g.c
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_EC801E),y)
|
||||
SRC_DIR += ec801e
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_EC200T),y)
|
||||
SRC_DIR += ec200t
|
||||
endif
|
||||
@@ -17,5 +21,9 @@ ifeq ($(CONFIG_ADD_XIZI_FEATURES),y)
|
||||
SRC_DIR += ec200a
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADAPTER_GM800TF),y)
|
||||
SRC_DIR += gm800tf
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
endif
|
||||
@@ -28,6 +28,14 @@ extern AdapterProductInfoType Ec200tAttach(struct Adapter *adapter);
|
||||
extern AdapterProductInfoType Ec200aAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#ifdef ADAPTER_GM800TF
|
||||
extern AdapterProductInfoType Gm800tfAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
#ifdef ADAPTER_EC801E
|
||||
extern AdapterProductInfoType Ec801eAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
static int Adapter4GRegister(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
@@ -66,6 +74,20 @@ int Adapter4GInit(void)
|
||||
return -1;
|
||||
}
|
||||
|
||||
#ifdef ADAPTER_EC801E
|
||||
AdapterProductInfoType product_info = Ec801eAttach(adapter);
|
||||
if (!product_info) {
|
||||
printf("Adapter4GInit ec801e attach error\n");
|
||||
PrivFree(adapter);
|
||||
return -1;
|
||||
}
|
||||
|
||||
adapter->product_info_flag = 1;
|
||||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef ADAPTER_EC200T
|
||||
AdapterProductInfoType product_info = Ec200tAttach(adapter);
|
||||
if (!product_info) {
|
||||
@@ -92,6 +114,20 @@ int Adapter4GInit(void)
|
||||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef ADAPTER_GM800TF
|
||||
AdapterProductInfoType product_info = Gm800tfAttach(adapter);
|
||||
if (!product_info) {
|
||||
printf("Adapter4GInit gm800tf attach error\n");
|
||||
PrivFree(adapter);
|
||||
return -1;
|
||||
}
|
||||
|
||||
adapter->product_info_flag = 1;
|
||||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
@@ -164,6 +200,106 @@ int Adapter4GTest(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef ADAPTER_GM800TF
|
||||
uint8 server_addr[64] = "115.238.53.59";
|
||||
uint8 server_port[64] = "10208";
|
||||
|
||||
adapter->socket.socket_id = 0;
|
||||
AdapterDeviceOpen(adapter);
|
||||
AdapterDeviceControl(adapter, OPE_INT, &baud_rate);
|
||||
AdapterDeviceConnect(adapter, CLIENT, server_addr, server_port, IPV4);
|
||||
// AdapterDeviceDisconnect(adapter, NULL);
|
||||
// AdapterDeviceConnect(adapter, CLIENT, server_addr, server_port, IPV4);
|
||||
AdapterDeviceNetstat(adapter);
|
||||
|
||||
// char sendData[15] = "Hello World!";
|
||||
char sendData = 'a';
|
||||
char receiveData = 0;
|
||||
int failCount = 0;
|
||||
for (int i = 0; i < 1024; i++) { // send 1kB data
|
||||
AdapterDeviceSend(adapter, &sendData, 1);
|
||||
sendData = sendData + 1 > 'z' ? 'a' : sendData + 1;
|
||||
}
|
||||
// AdapterDeviceSend(adapter, sendData, 13);
|
||||
// while (1) {
|
||||
// // if (sendData > 'z') {
|
||||
// // break;
|
||||
// // }
|
||||
// AdapterDeviceSend(adapter, &sendData, 1);
|
||||
// sendData = sendData + 1 > 'z' ? 'a' : sendData + 1;
|
||||
// // int ret = AdapterDeviceRecv(adapter, &receiveData, 1);
|
||||
// // printf("receiveData: %d\n", receiveData);
|
||||
// // if (ret >= 0 && receiveData == sendData) {
|
||||
// // sendData = sendData + 1 > 'z' ? 'a' : sendData + 1;
|
||||
// // failCount = 0;
|
||||
// // } else {
|
||||
// // failCount++;
|
||||
// // if (failCount >= 10) {
|
||||
// // AdapterDeviceConnect(adapter, CLIENT, server_addr, server_port, IPV4);
|
||||
// // failCount = 0;
|
||||
// // }
|
||||
// // }
|
||||
// // printf("4G recv msg %c\n", receiveData);
|
||||
// // receiveData = 0;
|
||||
// }
|
||||
// PrivTaskDelay(10000);
|
||||
AdapterDeviceClose(adapter);
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
PRIV_SHELL_CMD_FUNCTION(Adapter4GTest, a EC200T or EC200A adapter sample, PRIV_SHELL_CMD_FUNC_ATTR);
|
||||
|
||||
#ifdef ADAPTER_GM800TF
|
||||
// unsigned char data[1024 * 40];
|
||||
void *uploadDataTask(void *param) {
|
||||
int baud_rate = BAUD_RATE_115200;
|
||||
struct Adapter* adapter = AdapterDeviceFindByName(ADAPTER_4G_NAME);
|
||||
int reconnectLimit = 3; // try reconnect to server up to 3 times
|
||||
|
||||
uint8 server_addr[64] = "115.238.53.59";
|
||||
uint8 server_port[64] = "10208";
|
||||
|
||||
adapter->socket.socket_id = 0;
|
||||
AdapterDeviceOpen(adapter);
|
||||
AdapterDeviceControl(adapter, OPE_INT, &baud_rate);
|
||||
|
||||
/* try to connect to server */
|
||||
do {
|
||||
AdapterDeviceConnect(adapter, CLIENT, server_addr, server_port, IPV4);
|
||||
AdapterDeviceNetstat(adapter);
|
||||
if (adapter->network_info.is_connected && adapter->network_info.signal_strength < 99) {
|
||||
break;
|
||||
}
|
||||
} while (--reconnectLimit > 0);
|
||||
if (reconnectLimit <= 0) {
|
||||
printf("4G connect to server failed\n");
|
||||
AdapterDeviceClose(adapter);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/* send data to server */
|
||||
char sendData[15] = "Hello World!";
|
||||
AdapterDeviceSend(adapter, &sendData, 13);
|
||||
// char sendData = 'a';
|
||||
// char receiveData = 0;
|
||||
// int failCount = 0;
|
||||
// for (int i = 0; i < 1024; i++) { // send 1kB data
|
||||
// AdapterDeviceSend(adapter, &sendData, 1);
|
||||
// sendData = sendData + 1 > 'z' ? 'a' : sendData + 1;
|
||||
// }
|
||||
|
||||
AdapterDeviceClose(adapter);
|
||||
}
|
||||
|
||||
void startUploadDataTask(void) {
|
||||
pthread_attr_t attr;
|
||||
attr.schedparam.sched_priority = 20;
|
||||
attr.stacksize = 8096;
|
||||
|
||||
// char task_name[] = "upload_data_task";
|
||||
|
||||
pthread_t thread;
|
||||
PrivTaskCreate(&thread, &attr, uploadDataTask, NULL);
|
||||
PrivTaskStartup(&thread);
|
||||
}
|
||||
#endif
|
||||
|
||||
24
APP_Framework/Framework/connection/4g/ec801e/Kconfig
Normal file
24
APP_Framework/Framework/connection/4g/ec801e/Kconfig
Normal file
@@ -0,0 +1,24 @@
|
||||
config ADAPTER_4G_EC801E
|
||||
string "EC801E adapter name"
|
||||
default "ec801e"
|
||||
|
||||
if ADD_XIZI_FEATURES
|
||||
config ADAPTER_EC801E_DRIVER_EXTUART
|
||||
bool "Using extra uart to support 4G"
|
||||
default n
|
||||
|
||||
config ADAPTER_EC801E_DRIVER
|
||||
string "EC801E device uart driver path"
|
||||
default "/dev/usart6_dev6"
|
||||
depends on !ADAPTER_EC801E_DRIVER_EXTUART
|
||||
|
||||
if ADAPTER_EC801E_DRIVER_EXTUART
|
||||
config ADAPTER_EC801E_DRIVER
|
||||
string "EC801E device extra uart driver path"
|
||||
default "/dev/extuart_dev5"
|
||||
|
||||
config ADAPTER_EC801E_DRIVER_EXT_PORT
|
||||
int "if EC801E device using extuart, choose port"
|
||||
default "5"
|
||||
endif
|
||||
endif
|
||||
6
APP_Framework/Framework/connection/4g/ec801e/Make.defs
Normal file
6
APP_Framework/Framework/connection/4g/ec801e/Make.defs
Normal file
@@ -0,0 +1,6 @@
|
||||
############################################################################
|
||||
# APP_Framework/Framework/connection/4g/ec801e/Make.defs
|
||||
############################################################################
|
||||
ifneq ($(CONFIG_ADAPTER_4G_EC801E),)
|
||||
CONFIGURED_APPS += $(APPDIR)/../../../APP_Framework/Framework/connection/4g/ec801e
|
||||
endif
|
||||
14
APP_Framework/Framework/connection/4g/ec801e/Makefile
Normal file
14
APP_Framework/Framework/connection/4g/ec801e/Makefile
Normal file
@@ -0,0 +1,14 @@
|
||||
include $(KERNEL_ROOT)/.config
|
||||
ifeq ($(CONFIG_ADD_NUTTX_FEATURES),y)
|
||||
include $(APPDIR)/Make.defs
|
||||
CSRCS += ec801e.c
|
||||
include $(APPDIR)/Application.mk
|
||||
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADD_XIZI_FEATURES),y)
|
||||
SRC_FILES := ec801e.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
endif
|
||||
10
APP_Framework/Framework/connection/4g/ec801e/SConscript
Normal file
10
APP_Framework/Framework/connection/4g/ec801e/SConscript
Normal file
@@ -0,0 +1,10 @@
|
||||
from building import *
|
||||
import os
|
||||
|
||||
cwd = GetCurrentDir()
|
||||
src = []
|
||||
if GetDepend(['ADAPTER_EC801E']):
|
||||
src += ['ec801e.c']
|
||||
group = DefineGroup('connection 4g ec801e', src, depend = [], CPPPATH = [cwd])
|
||||
|
||||
Return('group')
|
||||
568
APP_Framework/Framework/connection/4g/ec801e/ec801e.c
Normal file
568
APP_Framework/Framework/connection/4g/ec801e/ec801e.c
Normal file
@@ -0,0 +1,568 @@
|
||||
/*
|
||||
* 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 ec801e_cn.c
|
||||
* @brief Implement the connection 4G adapter function, using EC801E-CN device
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.12.25
|
||||
*/
|
||||
|
||||
#include <adapter.h>
|
||||
#include <at_agent.h>
|
||||
|
||||
#define EC801E_AT_MODE_CMD "+++"
|
||||
#define EC801E_ATI_CMD "ATI\r\n"
|
||||
#define EC801E_CIMI_CMD "AT+CIMI\r\n"
|
||||
#define EC801E_GET_QCCID_CMD "AT+QCCID=?\r\n"
|
||||
#define EC801E_GET_CPIN_CMD "AT+CPIN?\r\n"
|
||||
#define EC801E_GET_CREG_CMD "AT+CREG?\r\n"
|
||||
#define EC801E_CFG_TCP_CMD "AT+QICSGP"
|
||||
#define EC801E_ACTIVE_PDP_CMD "AT+QIACT=1\r\n"
|
||||
#define EC801E_DEACTIVE_PDP_CMD "AT+QIDEACT=1\r\n"
|
||||
#define EC801E_OPEN_SOCKET_CMD "AT+QIOPEN=1,%u"
|
||||
#define EC801E_CLOSE_SOCKET_CMD "AT+QICLOSE=%u\r\n"
|
||||
#define EC801E_CLOSE "AT+QPOWD\r\n"
|
||||
#define EC801E_GET_COPS_CMD "AT+COPS?\r\n"
|
||||
#define EC801E_GET_CSQ_CMD "AT+CSQ\r\n"
|
||||
#define EC801E_GET_POP_IP "AT+CGPADDR=1\r\n"
|
||||
|
||||
#define EC801E_OK_REPLY "OK"
|
||||
#define EC801E_READY_REPLY "READY"
|
||||
#define EC801E_CREG_REPLY ",1"
|
||||
#define EC801E_CONNECT_REPLY "CONNECT"
|
||||
|
||||
#define TRY_TIMES 10
|
||||
|
||||
static void Ec801ePowerSet(void)
|
||||
{
|
||||
#ifdef ADAPTER_EC801E_USING_PWRKEY
|
||||
int pin_fd;
|
||||
pin_fd = PrivOpen(ADAPTER_EC801E_PIN_DRIVER, O_RDWR);
|
||||
if (pin_fd < 0) {
|
||||
printf("open %s error\n", ADAPTER_EC801E_PIN_DRIVER);
|
||||
return;
|
||||
}
|
||||
|
||||
struct PinParam pin_param;
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.mode = GPIO_CFG_OUTPUT;
|
||||
pin_param.pin = ADAPTER_EC801E_PWRKEY;
|
||||
|
||||
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 = ADAPTER_EC801E_PWRKEY;
|
||||
pin_stat.val = GPIO_LOW; //put power key at low-level state
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
PrivTaskDelay(2500); //wait at least 2s
|
||||
|
||||
pin_stat.val = GPIO_HIGH; //put power key at high-level state
|
||||
PrivWrite(pin_fd, &pin_stat, 1);
|
||||
|
||||
PrivClose(pin_fd);
|
||||
|
||||
PrivTaskDelay(10000);
|
||||
#endif
|
||||
}
|
||||
|
||||
static int Ec801eOpen(struct Adapter *adapter)
|
||||
{
|
||||
/*step1: open ec801e serial port*/
|
||||
adapter->fd = PrivOpen(ADAPTER_EC801E_DRIVER, O_RDWR);
|
||||
if (adapter->fd < 0) {
|
||||
printf("Ec801eOpen get serial %s fd error\n", ADAPTER_EC801E_DRIVER);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/*step2: init AT agent*/
|
||||
if (!adapter->agent) {
|
||||
char *agent_name = "4G_uart_client";
|
||||
if (0 != InitATAgent(agent_name, adapter->fd, 512)) {
|
||||
printf("at agent init failed !\n");
|
||||
return -1;
|
||||
}
|
||||
ATAgentType at_agent = GetATAgent(agent_name);
|
||||
|
||||
adapter->agent = at_agent;
|
||||
}
|
||||
|
||||
PrivTaskDelay(2500);
|
||||
|
||||
ADAPTER_DEBUG("Ec801e open done\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int Ec801eClose(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
uint8_t ec801e_cmd[64];
|
||||
|
||||
if (!adapter->agent) {
|
||||
printf("Ec801eClose AT agent NULL\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 0x4F, 0x4B); //'O', 'K'
|
||||
|
||||
/*step1: serial write "+++", quit transparent mode*/
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "+++");
|
||||
|
||||
/*step2: serial write "AT+QICLOSE", close socket connect before open socket*/
|
||||
memset(ec801e_cmd, 0, sizeof(ec801e_cmd));
|
||||
sprintf(ec801e_cmd, EC801E_CLOSE_SOCKET_CMD, adapter->socket.socket_id);
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec801e_cmd, EC801E_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step3: serial write "AT+QIDEACT", close TCP net before open socket*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_DEACTIVE_PDP_CMD, EC801E_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
out:
|
||||
/*step4: power down ec801e*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_CLOSE, EC801E_OK_REPLY);
|
||||
PrivTaskDelay(12500); //wait at least 12s
|
||||
|
||||
/*step5: close ec801e serial port*/
|
||||
PrivClose(adapter->fd);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
#ifdef ADD_RTTHREAD_FEATURES
|
||||
static int Ec801eIoctl(struct Adapter *adapter, int cmd, void *args){ return 0;}
|
||||
#else
|
||||
static int Ec801eIoctl(struct Adapter *adapter, int cmd, void *args)
|
||||
{
|
||||
if (OPE_INT != cmd) {
|
||||
printf("Ec801eIoctl only support OPE_INT, do not support %d\n", cmd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint32_t baud_rate = *((uint32_t *)args);
|
||||
|
||||
struct SerialDataCfg serial_cfg;
|
||||
memset(&serial_cfg, 0 ,sizeof(struct SerialDataCfg));
|
||||
serial_cfg.serial_baud_rate = baud_rate;
|
||||
serial_cfg.serial_data_bits = DATA_BITS_8;
|
||||
serial_cfg.serial_stop_bits = STOP_BITS_1;
|
||||
serial_cfg.serial_buffer_size = SERIAL_RB_BUFSZ;
|
||||
serial_cfg.serial_parity_mode = PARITY_NONE;
|
||||
serial_cfg.serial_bit_order = STOP_BITS_1;
|
||||
serial_cfg.serial_invert_mode = NRZ_NORMAL;
|
||||
#ifdef TOOL_USING_OTA
|
||||
serial_cfg.serial_timeout = OTA_RX_TIMEOUT;
|
||||
#else
|
||||
//serial receive timeout 10s
|
||||
serial_cfg.serial_timeout = 100000;
|
||||
#endif
|
||||
serial_cfg.is_ext_uart = 0;
|
||||
#ifdef ADAPTER_EC801E_DRIVER_EXT_PORT
|
||||
serial_cfg.is_ext_uart = 1;
|
||||
serial_cfg.ext_uart_no = ADAPTER_EC801E_DRIVER_EXT_PORT;
|
||||
serial_cfg.port_configure = PORT_CFG_INIT;
|
||||
#endif
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = &serial_cfg;
|
||||
PrivIoctl(adapter->fd, OPE_INT, &ioctl_cfg);
|
||||
|
||||
Ec801ePowerSet();
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
static int Ec801eConnect(struct Adapter *adapter, enum NetRoleType net_role, const char *ip, const char *port, enum IpType ip_type)
|
||||
{
|
||||
int ret = 0;
|
||||
int try = 0;
|
||||
uint8_t ec801e_cmd[64];
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 0x4F, 0x4B);
|
||||
|
||||
/*step1: serial write "+++", quit transparent mode*/
|
||||
PrivTaskDelay(1500); //before +++ command, wait at least 1s
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, EC801E_AT_MODE_CMD);
|
||||
PrivTaskDelay(1500); //after +++ command, wait at least 1s
|
||||
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_ATI_CMD, EC801E_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(300);
|
||||
|
||||
/*step2: serial write "AT+CPIN?", check SIM status*/
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_GET_CPIN_CMD, EC801E_READY_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(300);
|
||||
|
||||
/*step3: serial write "AT+CCID", get SIM ID*/
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_GET_QCCID_CMD, EC801E_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step4: serial write "AT+CREG?", check whether registered to GSM net*/
|
||||
PrivTaskDelay(1000); //before CREG command, wait 1s
|
||||
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_GET_CREG_CMD, EC801E_CREG_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(300);
|
||||
|
||||
/*step5: serial write "AT+QICSGP", connect to China Mobile using ipv4 or ipv6*/
|
||||
memset(ec801e_cmd, 0, sizeof(ec801e_cmd));
|
||||
|
||||
if (IPV4 == ip_type) {
|
||||
strcpy(ec801e_cmd, "AT+QICSGP=1,1,\"CMNET\",\"\",\"\",1\r\n");
|
||||
} else if (IPV6 == ip_type) {
|
||||
strcpy(ec801e_cmd, "AT+QICSGP=1,2,\"CMNET\",\"\",\"\",1\r\n");
|
||||
}
|
||||
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec801e_cmd, EC801E_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(300);
|
||||
|
||||
/*step6: serial write "AT+QICLOSE", close socket connect before open socket*/
|
||||
memset(ec801e_cmd, 0, sizeof(ec801e_cmd));
|
||||
|
||||
sprintf(ec801e_cmd, EC801E_CLOSE_SOCKET_CMD, adapter->socket.socket_id);
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec801e_cmd, EC801E_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(300);
|
||||
|
||||
/*step7: serial write "AT+QIDEACT", close TCP net before open socket*/
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_DEACTIVE_PDP_CMD, EC801E_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(300);
|
||||
|
||||
/*step8: serial write "AT+QIACT", open TCP net*/
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_ACTIVE_PDP_CMD, EC801E_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step9: serial write "AT+QIOPEN", connect socket using TCP*/
|
||||
memset(ec801e_cmd, 0, sizeof(ec801e_cmd));
|
||||
sprintf(ec801e_cmd, EC801E_OPEN_SOCKET_CMD, adapter->socket.socket_id);
|
||||
strcat(ec801e_cmd, ",\"TCP\",\"");
|
||||
strcat(ec801e_cmd, ip);
|
||||
strcat(ec801e_cmd, "\",");
|
||||
strcat(ec801e_cmd, port);
|
||||
strcat(ec801e_cmd, ",0,2\r\n");
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 0x43, 0x54);
|
||||
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec801e_cmd, EC801E_CONNECT_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
ADAPTER_DEBUG("Ec801e connect TCP done\n");
|
||||
|
||||
return 0;
|
||||
|
||||
out:
|
||||
ADAPTER_DEBUG("Ec801e connect TCP failed. Power down\n");
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_CLOSE, EC801E_OK_REPLY);
|
||||
return -1;
|
||||
}
|
||||
|
||||
static int Ec801eSend(struct Adapter *adapter, const void *buf, size_t len)
|
||||
{
|
||||
if (adapter->agent) {
|
||||
EntmSend(adapter->agent, (const char *)buf, len);
|
||||
} else {
|
||||
printf("Ec801eSend can not find agent\n");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int Ec801eRecv(struct Adapter *adapter, void *buf, size_t len)
|
||||
{
|
||||
if (adapter->agent) {
|
||||
return EntmRecv(adapter->agent, (char *)buf, len, 6);
|
||||
} else {
|
||||
printf("Ec801eRecv can not find agent\n");
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
static int Ec801eDisconnect(struct Adapter *adapter)
|
||||
{
|
||||
int ret = 0;
|
||||
uint8_t ec801e_cmd[64];
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 0x4F, 0x4B);
|
||||
|
||||
/*step1: serial write "+++", quit transparent mode*/
|
||||
PrivTaskDelay(1500); //before +++ command, wait at least 1s
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "+++");
|
||||
PrivTaskDelay(1500); //after +++ command, wait at least 1s
|
||||
|
||||
/*step2: serial write "AT+QICLOSE", close socket connect before open socket*/
|
||||
memset(ec801e_cmd, 0, sizeof(ec801e_cmd));
|
||||
sprintf(ec801e_cmd, EC801E_CLOSE_SOCKET_CMD, adapter->socket.socket_id);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, ec801e_cmd, EC801E_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
ADAPTER_DEBUG("Ec801e disconnect TCP done\n");
|
||||
|
||||
return 0;
|
||||
|
||||
out:
|
||||
ADAPTER_DEBUG("Ec801e disconnect TCP failed. Power down\n");
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_CLOSE, EC801E_OK_REPLY);
|
||||
return -1;
|
||||
}
|
||||
|
||||
static void extractCarrierInfo(char *response, struct NetworkInfo *networkInfo)
|
||||
{
|
||||
const char *delimiter = "\"";
|
||||
const char *token;
|
||||
|
||||
token = strtok(response, delimiter);
|
||||
token = strtok(NULL, delimiter);
|
||||
|
||||
if (strcmp(token, "CHINA MOBILE") == 0) {
|
||||
networkInfo->carrier_type = CARRIER_CHINA_MOBILE;
|
||||
} else if (strcmp(token, "CHN-UNICOM") == 0) {
|
||||
networkInfo->carrier_type = CARRIER_CHINA_UNICOM;
|
||||
} else if (strcmp(token, "CHN-CT") == 0) {
|
||||
networkInfo->carrier_type = CARRIER_CHINA_TELECOM;
|
||||
} else {
|
||||
networkInfo->carrier_type = CARRIER_UNKNOWN;
|
||||
}
|
||||
}
|
||||
|
||||
static int Ec801eNetstat(struct Adapter *adapter) {
|
||||
char result[64] = {0};
|
||||
|
||||
struct NetworkInfo info = {
|
||||
.carrier_type = CARRIER_UNKNOWN,
|
||||
.signal_strength = 0,
|
||||
.ip_address = "192.168.1.1"
|
||||
};
|
||||
|
||||
int ret = 0;
|
||||
int try = 0;
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 0x4F, 0x4B);
|
||||
|
||||
/*step1: serial write "+++", quit transparent mode*/
|
||||
PrivTaskDelay(1500); //before +++ command, wait at least 1s
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "+++");
|
||||
PrivTaskDelay(1500); //after +++ command, wait at least 1s
|
||||
|
||||
/*step2: serial write "AT+CPIN?", check SIM status*/
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_GET_CPIN_CMD, EC801E_READY_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step3: serial write "AT+CCID", get SIM ID*/
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_GET_QCCID_CMD, EC801E_OK_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step4: serial write "AT+CREG?", check whether registered to GSM net*/
|
||||
PrivTaskDelay(1000); //before CREG command, wait 1s
|
||||
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_GET_CREG_CMD, EC801E_CREG_REPLY);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step5: serial write "AT+COPS?", get carrier type*/
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, EC801E_GET_COPS_CMD, result);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
extractCarrierInfo(result, &info);
|
||||
adapter->network_info.carrier_type = info.carrier_type;
|
||||
|
||||
/*step6: serial write "AT+CSQ", get carrier type*/
|
||||
memset(result, 0, sizeof(result));
|
||||
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, EC801E_GET_CSQ_CMD, result);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(result, "AT+CSQ\n+CSQ: %d", &info.signal_strength) == 1) {
|
||||
printf("Signal Strength: %d\n", info.signal_strength);
|
||||
adapter->network_info.signal_strength = info.signal_strength;
|
||||
} else {
|
||||
printf("Failed to parse signal strength\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step7: serial write "AT+CSQ", get carrier type*/
|
||||
memset(result, 0, sizeof(result));
|
||||
|
||||
for(try = 0; try < TRY_TIMES; try++){
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, EC801E_GET_POP_IP, result);
|
||||
if (ret == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(result, "AT+CGPADDR=1\n+CGPADDR: 1,\"%15[^\"]\"", info.ip_address) == 1) {
|
||||
printf("IP Address: %s\n", info.ip_address);
|
||||
strcpy(adapter->network_info.ip_address, info.ip_address);
|
||||
} else {
|
||||
printf("Failed to parse IP address\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
out:
|
||||
ADAPTER_DEBUG("Ec801e get netstat failed. Power down\n");
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, EC801E_CLOSE, EC801E_OK_REPLY);
|
||||
return -1;
|
||||
}
|
||||
|
||||
static const struct IpProtocolDone ec801e_done =
|
||||
{
|
||||
.open = Ec801eOpen,
|
||||
.close = Ec801eClose,
|
||||
.ioctl = Ec801eIoctl,
|
||||
.setup = NULL,
|
||||
.setdown = NULL,
|
||||
.setaddr = NULL,
|
||||
.setdns = NULL,
|
||||
.setdhcp = NULL,
|
||||
.ping = NULL,
|
||||
.netstat = Ec801eNetstat,
|
||||
.connect = Ec801eConnect,
|
||||
.send = Ec801eSend,
|
||||
.recv = Ec801eRecv,
|
||||
.disconnect = Ec801eDisconnect,
|
||||
.mqttconnect = NULL,
|
||||
.mqttdisconnect = NULL,
|
||||
.mqttsend = NULL,
|
||||
.mqttrecv = NULL,
|
||||
};
|
||||
|
||||
AdapterProductInfoType Ec801eAttach(struct Adapter *adapter)
|
||||
{
|
||||
struct AdapterProductInfo *product_info = PrivMalloc(sizeof(struct AdapterProductInfo));
|
||||
if (!product_info) {
|
||||
printf("Ec801eAttach malloc product_info error\n");
|
||||
PrivFree(product_info);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
strcpy(product_info->model_name, ADAPTER_4G_EC801E);
|
||||
|
||||
product_info->model_done = (void *)&ec801e_done;
|
||||
|
||||
return product_info;
|
||||
}
|
||||
21
APP_Framework/Framework/connection/4g/gm800tf/Kconfig
Normal file
21
APP_Framework/Framework/connection/4g/gm800tf/Kconfig
Normal file
@@ -0,0 +1,21 @@
|
||||
config ADAPTER_4G_GM800TF
|
||||
string "GM800TF adapter name"
|
||||
default "gm800tf"
|
||||
|
||||
if ADD_XIZI_FEATURES
|
||||
config ADAPTER_GM800TF_DEV
|
||||
string "GM800TF device path"
|
||||
default "/dev/lte_dev1"
|
||||
endif
|
||||
|
||||
if ADD_NUTTX_FEATURES
|
||||
config ADAPTER_GM800TF_DEV
|
||||
string "GM800TF device path"
|
||||
default "/dev/ttyS8"
|
||||
endif
|
||||
|
||||
if ADD_RTTHREAD_FEATURES
|
||||
config ADAPTER_GM800TF_DEV
|
||||
string "GM800TF device path"
|
||||
default "/dev/usart8"
|
||||
endif
|
||||
6
APP_Framework/Framework/connection/4g/gm800tf/Make.defs
Normal file
6
APP_Framework/Framework/connection/4g/gm800tf/Make.defs
Normal file
@@ -0,0 +1,6 @@
|
||||
############################################################################
|
||||
# APP_Framework/Framework/connection/4g/gm800tf/Make.defs
|
||||
############################################################################
|
||||
ifneq ($(CONFIG_ADAPTER_4G_GM800TF),)
|
||||
CONFIGURED_APPS += $(APPDIR)/../../../APP_Framework/Framework/connection/4g/gm800tf
|
||||
endif
|
||||
14
APP_Framework/Framework/connection/4g/gm800tf/Makefile
Normal file
14
APP_Framework/Framework/connection/4g/gm800tf/Makefile
Normal file
@@ -0,0 +1,14 @@
|
||||
include $(KERNEL_ROOT)/.config
|
||||
ifeq ($(CONFIG_ADD_NUTTX_FEATURES),y)
|
||||
include $(APPDIR)/Make.defs
|
||||
CSRCS += gm800tf.c gm800tf_mqtt.c
|
||||
include $(APPDIR)/Application.mk
|
||||
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADD_XIZI_FEATURES),y)
|
||||
SRC_FILES := gm800tf.c gm800tf_mqtt.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
endif
|
||||
10
APP_Framework/Framework/connection/4g/gm800tf/SConscript
Normal file
10
APP_Framework/Framework/connection/4g/gm800tf/SConscript
Normal file
@@ -0,0 +1,10 @@
|
||||
from building import *
|
||||
import os
|
||||
|
||||
cwd = GetCurrentDir()
|
||||
src = []
|
||||
if GetDepend(['ADAPTER_GM800TF']):
|
||||
src += ['gm800tf.c']
|
||||
group = DefineGroup('connection 4g gm800tf', src, depend = [], CPPPATH = [cwd])
|
||||
|
||||
Return('group')
|
||||
639
APP_Framework/Framework/connection/4g/gm800tf/gm800tf.c
Normal file
639
APP_Framework/Framework/connection/4g/gm800tf/gm800tf.c
Normal file
@@ -0,0 +1,639 @@
|
||||
/*
|
||||
* 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 gm800tf.c
|
||||
* @brief Implement the connection 4G adapter function, using GM800TF device
|
||||
* @author Huo Yujia (huoyujia081@126.com)
|
||||
* @version 1.0
|
||||
* @date 2024-07-05
|
||||
*/
|
||||
|
||||
#include <adapter.h>
|
||||
#include <at_agent.h>
|
||||
|
||||
#define GM800TF_AT_MODE_CMD "+++"
|
||||
#define GM800TF_GET_ICCID_CMD "AT+ICCID\r\n"
|
||||
#define GM800TF_SETUP_SOCKET_CMD "AT+SOCK%c=TCP,%s,%s\r\n"
|
||||
#define GM800TF_OPEN_SOCKET_CMD "AT+SOCK%cEN=ON\r\n"
|
||||
#define GM800TF_CLOSE_SOCKET_CMD "AT+SOCK%cEN=OFF\r\n"
|
||||
#define GM800TF_SET_WKMOD_NET_CMD "AT+WKMOD=NET\r\n"
|
||||
#define GM800TF_GET_WKMOD_CMD "AT+WKMOD?\r\n"
|
||||
#define GM800TF_SAVE_CFG_CMD "AT+S\r\n"
|
||||
#define GM800TF_GET_CSQ_CMD "AT+CSQ\r\n"
|
||||
#define GM800TF_ENTM_MODE_CMD "AT+ENTM\r\n"
|
||||
#define GM800TF_GET_SOCKET_PARAM_CMD "AT+SOCK%c?\r\n"
|
||||
#define GM800TF_GET_SOCKET_STATUS_CMD "AT+SOCK%cLK\r\n"
|
||||
#define GM800TF_RESET_CMD "AT+CLEAR\r\n"
|
||||
#define GM800TF_SET_HEART_CMD "AT+HEARTEN=%s\r\n"
|
||||
#define GM800TF_SET_HEART_DATA_CMD "AT+HEARTDT=%s\r\n"
|
||||
#define GM800TF_SET_HEART_TIME_CMD "AT+HEARTTM=%d\r\n"
|
||||
#define GM800TF_GET_MQTT_STATUS_CMD "AT+MQTTSTA?\r\n"
|
||||
#define GM800TF_GET_MQTT_SERVER_CMD "AT+MQTTSVR?\r\n"
|
||||
#define GM800TF_GET_MQTT_CLIENTID_CMD "AT+MQTTCID?\r\n"
|
||||
#define GM800TF_GET_MQTT_USERNAME_CMD "AT+MQTTUSER?\r\n"
|
||||
#define GM800TF_GET_MQTT_PASSWORD_CMD "AT+MQTTPSW?\r\n"
|
||||
|
||||
#define GM800TF_OK_REPLY "OK"
|
||||
#define GM800TF_READY_REPLY "READY"
|
||||
#define GM800TF_CREG_REPLY ",1"
|
||||
#define GM800TF_CONNECT_REPLY "CONNECT"
|
||||
|
||||
#define TRY_TIMES 10
|
||||
|
||||
/**
|
||||
* @brief convert string to corresponding hex string
|
||||
* @param input original string
|
||||
* @param output hex string
|
||||
*/
|
||||
void string_to_hex(const char *input, char *output) {
|
||||
while (*input) {
|
||||
sprintf(output, "%02X", (unsigned char)*input);
|
||||
input++;
|
||||
output += 2;
|
||||
}
|
||||
*output = '\0'; // Null-terminate the output string
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief enter the configuration mode
|
||||
* @param adapter
|
||||
* @return int
|
||||
*/
|
||||
int Gm800tfEnterAtMode(struct Adapter *adapter) {
|
||||
AtSetReplyEndChar(adapter->agent, 'o', 'k');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 1);
|
||||
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "+++");
|
||||
PrivTaskDelay(500);
|
||||
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "a");
|
||||
PrivTaskDelay(100);
|
||||
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "\r\n"); // clear the "+++a", confirm it will not be added to the following command.
|
||||
PrivTaskDelay(500);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief open the GM800TF(aka. init the serial) and init the AT agent
|
||||
* @param adapter
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfOpen(struct Adapter *adapter) {
|
||||
/*step1: open gm800tf serial port*/
|
||||
adapter->fd = PrivOpen(ADAPTER_GM800TF_DEV, O_RDWR);
|
||||
if (adapter->fd < 0) {
|
||||
printf("Gm800tfOpen get serial %s fd error\n", ADAPTER_GM800TF_DEV);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/*step2: init AT agent*/
|
||||
if (!adapter->agent) {
|
||||
char *agent_name = "4G_uart_client";
|
||||
if (0 != InitATAgent(agent_name, adapter->fd, 256)) {
|
||||
printf("at agent init failed !\n");
|
||||
return -1;
|
||||
}
|
||||
ATAgentType at_agent = GetATAgent(agent_name);
|
||||
|
||||
adapter->agent = at_agent;
|
||||
}
|
||||
|
||||
/* step3: reset gm800tf */
|
||||
ADAPTER_DEBUG("Gm800tf reseting configuration\n");
|
||||
Gm800tfEnterAtMode(adapter);
|
||||
AtSetReplyEndChar(adapter->agent, 'O', 'K');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 0);
|
||||
ATOrderSend(adapter->agent, REPLY_TIME_OUT, NULL, "AT+CLEAR\r\n");
|
||||
PrivTaskDelay(15000); // after reset configuration, wait at least 10s for restarting
|
||||
|
||||
/* step4: communication from sockA channel only*/
|
||||
adapter->socket.socket_id = 0;
|
||||
|
||||
ADAPTER_DEBUG("Gm800tf open done\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief close the GM800TF(aka. disable the interrupt) and disconnect the socket
|
||||
* @param adapter
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfClose(struct Adapter *adapter) {
|
||||
int ret = 0;
|
||||
uint8_t gm800tf_cmd[64];
|
||||
|
||||
if (!adapter->agent) {
|
||||
printf("Gm800tfClose AT agent NULL\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 0x4F, 0x4B); //'O', 'K'
|
||||
|
||||
/*step1: serial write "+++", quit transparent mode*/
|
||||
ret = Gm800tfEnterAtMode(adapter);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step2: serial write "AT+SOCKAEN=OFF" or "AT+SOCKBEN=OFF", close socket connect before open socket*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_CLOSE_SOCKET_CMD, 'A' + adapter->socket.socket_id);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step3: serial write "AT+S", save configuration and restart 4G module*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SAVE_CFG_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(15000); // after save configuration, wait at least 10s for restarting
|
||||
|
||||
out:
|
||||
/*step4: close gm800tf serial port and delete ATAgentReceiveProcess*/
|
||||
// DeleteATAgent(adapter->agent);
|
||||
// adapter->agent = NULL;
|
||||
PrivClose(adapter->fd);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief config the serial and enable the interrupt
|
||||
* @param adapter
|
||||
* @param cmd
|
||||
* @param args
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfIoctl(struct Adapter *adapter, int cmd, void *args) {
|
||||
if (OPE_INT != cmd) {
|
||||
printf("Gm800tfIoctl only support OPE_INT, do not support %d\n", cmd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint32_t baud_rate = *((uint32_t *)args);
|
||||
|
||||
struct SerialDataCfg serial_cfg;
|
||||
memset(&serial_cfg, 0, sizeof(struct SerialDataCfg));
|
||||
serial_cfg.serial_baud_rate = baud_rate;
|
||||
serial_cfg.serial_data_bits = DATA_BITS_8;
|
||||
serial_cfg.serial_stop_bits = STOP_BITS_1;
|
||||
serial_cfg.serial_buffer_size = SERIAL_RB_BUFSZ;
|
||||
serial_cfg.serial_parity_mode = PARITY_NONE;
|
||||
serial_cfg.serial_bit_order = STOP_BITS_1;
|
||||
serial_cfg.serial_invert_mode = NRZ_NORMAL;
|
||||
#ifdef TOOL_USING_OTA
|
||||
serial_cfg.serial_timeout = OTA_RX_TIMEOUT;
|
||||
#else
|
||||
// serial receive timeout 10s
|
||||
serial_cfg.serial_timeout = 100000;
|
||||
#endif
|
||||
serial_cfg.is_ext_uart = 0;
|
||||
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = SERIAL_TYPE;
|
||||
ioctl_cfg.args = &serial_cfg;
|
||||
PrivIoctl(adapter->fd, OPE_INT, &ioctl_cfg);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief connect to the server
|
||||
* @param adapter
|
||||
* @param net_role
|
||||
* @param ip
|
||||
* @param port
|
||||
* @param ip_type
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfConnect(struct Adapter *adapter, enum NetRoleType net_role, const char *ip, const char *port, enum IpType ip_type) {
|
||||
int ret = 0;
|
||||
int try = 0;
|
||||
uint8_t gm800tf_cmd[64];
|
||||
|
||||
/*step0: compare ip and port with current configuration, and if they are the same there is no need to connect again*/
|
||||
AdapterDeviceNetstat(adapter);
|
||||
if (adapter->network_info.workMode == 1 && strcmp(adapter->network_info.ip_address, ip) == 0 &&
|
||||
adapter->network_info.port == atoi(port) && adapter->network_info.is_connected && adapter->network_info.signal_strength < 99) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*step1: serial write "+++" and "a", quit transparent mode*/
|
||||
ret = Gm800tfEnterAtMode(adapter);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 'O', 'K');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 0);
|
||||
|
||||
/*step2: serial write "AT+ICCID", get SIM ID*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_GET_ICCID_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step3: serial write "AT+SOCKA=<protocol>,<address>,<port>" or "AT+SOCKB=<protocol>,<address>,<port>", connect
|
||||
* socket using TCP*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SETUP_SOCKET_CMD, 'A' + adapter->socket.socket_id, ip, port);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step4: serial write "AT+SOCKAEN=ON" or "AT+SOCKBEN=ON", connect socket using TCP*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_OPEN_SOCKET_CMD, 'A' + adapter->socket.socket_id);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* step5: set up the heartbeat */
|
||||
// char *heartbeatData = "heartbeat test";
|
||||
// int heartbeatTime = 30;
|
||||
// char heartbeatDataHex[65] = {}; // 最多32个字符
|
||||
// string_to_hex(heartbeatData, heartbeatDataHex);
|
||||
// memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
// sprintf(gm800tf_cmd, GM800TF_SET_HEART_CMD, "ON");
|
||||
// ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
// if (ret < 0) {
|
||||
// goto out;
|
||||
// }
|
||||
// memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
// sprintf(gm800tf_cmd, GM800TF_SET_HEART_DATA_CMD, heartbeatDataHex);
|
||||
// ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
// if (ret < 0) {
|
||||
// goto out;
|
||||
// }
|
||||
// memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
// sprintf(gm800tf_cmd, GM800TF_SET_HEART_TIME_CMD, heartbeatTime);
|
||||
// ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
// if (ret < 0) {
|
||||
// goto out;
|
||||
// }
|
||||
|
||||
/* step5: set down the heartbeat */
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_HEART_CMD, "OFF");
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* step6: serial write "AT+WKMOD=NET", set the working mode to network transparent transmission mode */
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SET_WKMOD_NET_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step7: serial write "AT+S", save configuration and restart 4G module*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SAVE_CFG_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(15000); // after save configuration, wait at least 10s for restarting
|
||||
ADAPTER_DEBUG("Gm800tf connect TCP done\n");
|
||||
|
||||
return 0;
|
||||
|
||||
out:
|
||||
ADAPTER_DEBUG("Gm800tf connect TCP failed.\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief send the data to the server after connect to the server
|
||||
* @param adapter
|
||||
* @param buf
|
||||
* @param len
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfSend(struct Adapter *adapter, const void *buf, size_t len) {
|
||||
/* query for whether socket is connected successfully */
|
||||
AdapterDeviceNetstat(adapter);
|
||||
if (adapter->network_info.is_connected == 0) {
|
||||
printf("[error %s %d]socket has not been connected, please call function AdapterDeviceConnect\n", __func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* send the buf data */
|
||||
if (adapter->agent) {
|
||||
EntmSend(adapter->agent, (const char *)buf, len);
|
||||
} else {
|
||||
printf("Gm800tfSend can not find agent\n");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief receive the data from the server after connect to the server
|
||||
* @param adapter
|
||||
* @param buf
|
||||
* @param len
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfRecv(struct Adapter *adapter, void *buf, size_t len) {
|
||||
if (adapter->agent) {
|
||||
return EntmRecv(adapter->agent, (char *)buf, len, 6);
|
||||
} else {
|
||||
printf("Gm800tfRecv can not find agent\n");
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief disconnect the server
|
||||
* @param adapter
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfDisconnect(struct Adapter *adapter) {
|
||||
int ret = 0;
|
||||
uint8_t gm800tf_cmd[64];
|
||||
|
||||
/* query for whether socket is connected successfully */
|
||||
AdapterDeviceNetstat(adapter);
|
||||
if (adapter->network_info.is_connected == 0) {
|
||||
printf("[error %s %d]socket has not been connected, please call function AdapterDeviceConnect\n", __func__, __LINE__);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*step1: serial write "+++", quit transparent mode*/
|
||||
ret = Gm800tfEnterAtMode(adapter);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 'O', 'K');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 0);
|
||||
|
||||
/*step2: serial write "AT+SOCKAEN=OFF" or "AT+SOCKBEN=OFF", close socket connect before open socket*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_CLOSE_SOCKET_CMD, 'A' + adapter->socket.socket_id);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step3: serial write "AT+S", save configuration and restart 4G module*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SAVE_CFG_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(15000); // after save configuration, wait at least 5s for restarting
|
||||
ADAPTER_DEBUG("Gm800tf disconnect TCP done\n");
|
||||
|
||||
return 0;
|
||||
|
||||
out:
|
||||
ADAPTER_DEBUG("Gm800tf disconnect TCP failed. \n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief query for the network status
|
||||
* @param adapter
|
||||
* @return int
|
||||
*/
|
||||
static int Gm800tfNetstat(struct Adapter *adapter) {
|
||||
char result[96] = {0};
|
||||
uint8_t gm800tf_cmd[64];
|
||||
|
||||
int ret = 0;
|
||||
int try = 0;
|
||||
|
||||
/*step1: serial write "+++", quit transparent mode*/
|
||||
ret = Gm800tfEnterAtMode(adapter);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 'O', 'K');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 0);
|
||||
|
||||
/*step2: serial write "AT+ICCID", get SIM ID*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_GET_ICCID_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
printf("[error %s %d]AT+ICCID failed, please check the SIM card\n", __func__, __LINE__);
|
||||
goto out;
|
||||
}
|
||||
|
||||
printf("-*-*-*-*-*-*-*Gm800tfNetstat*-*-*-*-*-*-*\n");
|
||||
/*step3: serial write "AT+CSQ", get carrier type*/
|
||||
memset(result, 0, sizeof(result));
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, GM800TF_GET_CSQ_CMD, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(strstr(result, "+CSQ:"), "+CSQ: %d", &adapter->network_info.signal_strength) == 1) {
|
||||
printf("signal strength:\t%d\n", adapter->network_info.signal_strength);
|
||||
} else {
|
||||
printf("Failed to parse signal strength\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step4: serial write "AT+WKMOD?", get the current work mode*/
|
||||
memset(result, 0, sizeof(result));
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, GM800TF_GET_WKMOD_CMD, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
char workMode[10] = {};
|
||||
if (sscanf(strstr(result, "+WKMOD:"), "+WKMOD:%s", workMode) == 1) {
|
||||
printf("work mode:\t\t%s\n", workMode);
|
||||
if (strcmp(workMode, "NET") == 0) {
|
||||
adapter->network_info.workMode = 1;
|
||||
} else if (strcmp(workMode, "MQTT,NOR") == 0) {
|
||||
adapter->network_info.workMode = 2;
|
||||
} else {
|
||||
adapter->network_info.workMode = 0;
|
||||
}
|
||||
} else {
|
||||
printf("Failed to parse work mode\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step5: serial write "AT+SOCKA=?", get the current server IP address*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_GET_SOCKET_PARAM_CMD, 'A' + adapter->socket.socket_id);
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, gm800tf_cmd, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(strstr(result, ",") + 1, "%15[^,],%hu", adapter->network_info.ip_address, &adapter->network_info.port) == 2) {
|
||||
printf("server ip address:\t%s\n", adapter->network_info.ip_address);
|
||||
printf("server port:\t\t%hu\n", adapter->network_info.port);
|
||||
} else {
|
||||
printf("server ip address:\t%s\n", adapter->network_info.ip_address);
|
||||
printf("server port:\t\t%d\n", adapter->network_info.port);
|
||||
printf("Failed to parse IP address and port\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step6: serial write "AT+SOCKALK" or "AT+SOCKBLK", get socket status*/
|
||||
memset(result, 0, sizeof(result));
|
||||
sprintf(gm800tf_cmd, GM800TF_GET_SOCKET_STATUS_CMD, 'A' + adapter->socket.socket_id);
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, gm800tf_cmd, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
char socket_status[20] = {};
|
||||
if (sscanf(strstr(result, "LK:"), "LK: %s", socket_status) == 1) {
|
||||
printf("socket status:\t\t%s\n", socket_status);
|
||||
adapter->network_info.is_connected = strcmp(socket_status, "Connected") == 0 ? 1 : 0;
|
||||
} else {
|
||||
printf("Failed to parse socket status\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step7: serial write "AT+MQTTSVR=?", get the current mqtt server IP address and port*/
|
||||
memset(result, 0, sizeof(result));
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, GM800TF_GET_MQTT_SERVER_CMD, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(strstr(result, ":") + 1, "%15[^,],%hu", adapter->network_info.mqttServerIp, &adapter->network_info.mqttServerPort) == 2) {
|
||||
printf("mqtt server ip address:\t%s\n", adapter->network_info.mqttServerIp);
|
||||
printf("mqtt server port:\t%hu\n", adapter->network_info.mqttServerPort);
|
||||
} else {
|
||||
printf("mqtt server ip address:\t%s\n", adapter->network_info.mqttServerIp);
|
||||
printf("mqtt server port:\t%d\n", adapter->network_info.mqttServerPort);
|
||||
printf("Failed to parse IP address and port\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* step8: serial write "AT+MQTTCID=?", get the current mqtt client id*/
|
||||
memset(result, 0, sizeof(result));
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, GM800TF_GET_MQTT_CLIENTID_CMD, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(strstr(result, "MQTTCID:"), "MQTTCID:%s", adapter->network_info.mqttClientId) == 1) {
|
||||
printf("mqtt clientid:\t\t%s\n", adapter->network_info.mqttClientId);
|
||||
} else {
|
||||
printf("Failed to parse mqtt clientid\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* step9: serial write "AT+MQTTUSER=?", get the current mqtt username*/
|
||||
memset(result, 0, sizeof(result));
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, GM800TF_GET_MQTT_USERNAME_CMD, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(strstr(result, "MQTTUSER:"), "MQTTUSER:%s", adapter->network_info.mqttUsername) == 1) {
|
||||
printf("mqtt username:\t\t%s\n", adapter->network_info.mqttUsername);
|
||||
} else {
|
||||
printf("Failed to parse mqtt username\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* step10: serial write "AT+MQTTPSW?", get the current mqtt password */
|
||||
memset(result, 0, sizeof(result));
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, GM800TF_GET_MQTT_PASSWORD_CMD, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
if (sscanf(strstr(result, "MQTTPSW:"), "MQTTPSW:%s", adapter->network_info.mqttPassword) == 1) {
|
||||
printf("mqtt password:\t\t%s\n", adapter->network_info.mqttPassword);
|
||||
} else {
|
||||
printf("Failed to parse mqtt password\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step11: serial write "AT+MQTTSTA", get the status of mqtt connection*/
|
||||
memset(result, 0, sizeof(result));
|
||||
ret = AtGetNetworkInfoReply(adapter->agent, GM800TF_GET_MQTT_STATUS_CMD, result);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
char mqtt_status[20] = {};
|
||||
if (sscanf(strstr(result, "STA:"), "STA: %s", mqtt_status) == 1) {
|
||||
printf("mqtt status:\t\t%s\n", mqtt_status);
|
||||
adapter->network_info.mqttIsConnected = strcmp(mqtt_status, "\"CONNECTION\"") == 0 ? 1 : 0;
|
||||
} else {
|
||||
printf("Failed to parse mqtt status\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* step12: serial write "AT+ENTM", enter entm mode */
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_ENTM_MODE_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-\n");
|
||||
return 0;
|
||||
|
||||
out:
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-\n");
|
||||
ADAPTER_DEBUG("Gm800tf get netstat failed.\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
int Gm800tfMqttConnect(struct Adapter *adapter, const char *ip, const char *port, const char *client_id, const char *username,
|
||||
const char *password);
|
||||
int Gm800tfMqttDisconnect(struct Adapter *adapter);
|
||||
int Gm800tfMqttSend(struct Adapter *adapter, const char *topic, const void *buf, size_t len);
|
||||
int Gm800tfMqttRecv(struct Adapter *adapter, const char *topic, void *buf, size_t len);
|
||||
|
||||
static const struct IpProtocolDone gm800tf_done = {
|
||||
.open = Gm800tfOpen,
|
||||
.close = Gm800tfClose,
|
||||
.ioctl = Gm800tfIoctl,
|
||||
.setup = NULL,
|
||||
.setdown = NULL,
|
||||
.setaddr = NULL,
|
||||
.setdns = NULL,
|
||||
.setdhcp = NULL,
|
||||
.ping = NULL,
|
||||
.netstat = Gm800tfNetstat,
|
||||
.connect = Gm800tfConnect,
|
||||
.send = Gm800tfSend,
|
||||
.recv = Gm800tfRecv,
|
||||
.disconnect = Gm800tfDisconnect,
|
||||
.mqttconnect = Gm800tfMqttConnect,
|
||||
.mqttdisconnect = Gm800tfMqttDisconnect,
|
||||
.mqttsend = Gm800tfMqttSend,
|
||||
.mqttrecv = Gm800tfMqttRecv,
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief expose the behavior of GM800TF to application
|
||||
* @param adapter
|
||||
* @return AdapterProductInfoType
|
||||
*/
|
||||
AdapterProductInfoType Gm800tfAttach(struct Adapter *adapter) {
|
||||
struct AdapterProductInfo *product_info = PrivMalloc(sizeof(struct AdapterProductInfo));
|
||||
if (!product_info) {
|
||||
printf("Gm800tfAttach malloc product_info error\n");
|
||||
PrivFree(product_info);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
strcpy(product_info->model_name, ADAPTER_4G_GM800TF);
|
||||
|
||||
product_info->model_done = (void *)&gm800tf_done;
|
||||
|
||||
return product_info;
|
||||
}
|
||||
316
APP_Framework/Framework/connection/4g/gm800tf/gm800tf_mqtt.c
Normal file
316
APP_Framework/Framework/connection/4g/gm800tf/gm800tf_mqtt.c
Normal file
@@ -0,0 +1,316 @@
|
||||
/*
|
||||
* 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 gm800tf_mqtt.c
|
||||
* @brief Implement the connection 4G adapter function about mqtt, using GM800TF device
|
||||
* @author Huo Yujia (huoyujia081@126.com)
|
||||
* @version 1.0
|
||||
* @date 2024-07-26
|
||||
*/
|
||||
#include <adapter.h>
|
||||
#include <at_agent.h>
|
||||
|
||||
#define GM800TF_GET_ICCID_CMD "AT+ICCID\r\n"
|
||||
#define GM800TF_SET_WKMOD_MQTT_CMD "AT+WKMOD=MQTT,NOR\r\n"
|
||||
#define GM800TF_SET_WKMOD_CMD_CMD "AT+WKMOD=CMD\r\n"
|
||||
#define GM800TF_GET_MQTT_PUBPARAM_CMD "AT+MQTTPUBTP?\r\n"
|
||||
#define GM800TF_SET_MQTT_PUBPARAM_CMD "AT+MQTTPUBTP=%d,%d,%s,%d,%d\r\n"
|
||||
#define GM800TF_SET_MQTT_SUBPARAM_CMD "AT+MQTTSUBTP=%d,%d,%s,%d\r\n"
|
||||
#define GM800TF_SET_MQTT_SERVER_CMD "AT+MQTTSVR=%s,%s\r\n"
|
||||
#define GM800TF_SET_MQTT_USERNAME_CMD "AT+MQTTUSER=%s\r\n"
|
||||
#define GM800TF_SET_MQTT_PASSWORD_CMD "AT+MQTTPSW=%s\r\n"
|
||||
#define GM800TF_SET_MQTT_CLIID_CMD "AT+MQTTCID=%s\r\n"
|
||||
#define GM800TF_SET_MQTT_MODE_CMD "AT+MQTTMOD=%d\r\n"
|
||||
#define GM800TF_SET_HEART_DATA_CMD "AT+HEARTDT=%s\r\n"
|
||||
#define GM800TF_SET_HEART_TIME_CMD "AT+HEARTTM=%d\r\n"
|
||||
#define GM800TF_SAVE_CFG_CMD "AT+S\r\n"
|
||||
#define GM800TF_ENTM_MODE_CMD "AT+ENTM\r\n"
|
||||
|
||||
#define GM800TF_OK_REPLY "OK"
|
||||
#define GM800TF_READY_REPLY "READY"
|
||||
#define GM800TF_CREG_REPLY ",1"
|
||||
#define GM800TF_PUBEX_REPLY ">"
|
||||
|
||||
#define TRY_TIMES 10
|
||||
|
||||
int Gm800tfEnterAtMode(struct Adapter *adapter); // defined in gm800tf.c
|
||||
|
||||
/**
|
||||
* @brief connect to mqtt server
|
||||
* @param adapter
|
||||
* @param ip mqtt server ip address
|
||||
* @param port mqtt server port
|
||||
* @param client_id mqtt client id
|
||||
* @param username mqtt username
|
||||
* @param password mqtt password
|
||||
* @return int 0: success, -1: failed
|
||||
*/
|
||||
int Gm800tfMqttConnect(struct Adapter *adapter, const char *ip, const char *port, const char *client_id, const char *username,
|
||||
const char *password) {
|
||||
int ret = 0;
|
||||
uint8_t gm800tf_cmd[64];
|
||||
|
||||
/*step0: compare ip and port with current configuration, and if they are the same there is no need to connect again*/
|
||||
AdapterDeviceNetstat(adapter);
|
||||
if (adapter->network_info.workMode == 2 && strcmp(adapter->network_info.mqttServerIp, ip) == 0 &&
|
||||
adapter->network_info.mqttServerPort == atoi(port) && strcmp(adapter->network_info.mqttClientId, client_id) == 0 &&
|
||||
strcmp(adapter->network_info.mqttUsername, username) == 0 && strcmp(adapter->network_info.mqttPassword, password) == 0 &&
|
||||
adapter->network_info.mqttIsConnected && adapter->network_info.signal_strength < 99) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*step1: serial write "+++" and "a", quit transparent mode*/
|
||||
ret = Gm800tfEnterAtMode(adapter);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 'O', 'K');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 0);
|
||||
|
||||
/*step2: serial write "AT+ICCID", get SIM ID*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_GET_ICCID_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step3: serial write "AT+MQTTSVR=<server>,<port>", config mqtt ip and port*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_MQTT_SERVER_CMD, ip, port);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step4: serial write "AT+MQTTCID=<clientid>", config mqtt client id*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_MQTT_CLIID_CMD, client_id);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step5: serial write "AT+MQTTUSER=<username>", config mqtt username*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_MQTT_USERNAME_CMD, username);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step6: serial write "AT+MQTTPSW=<password>", config mqtt password*/
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_MQTT_PASSWORD_CMD, password);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step7: serial write "AT+WKMOD=MQTT", set the working mode to mqtt mode*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SET_WKMOD_MQTT_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step8: serial write "AT+MQTTMOD=<mode>, set the mqtt mode*/
|
||||
/* mode-0: Send data to all preset enabled topics */
|
||||
/* mode-1: Send data separately to a specific topic */
|
||||
int mode = 1;
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_MQTT_MODE_CMD, mode);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step9: set the heartbeat parameter*/
|
||||
char *heartbeatData = "heartbeat test";
|
||||
int heartbeatTime = 30;
|
||||
char heartbeatDataHex[65] = {}; // 最多32个字符
|
||||
void string_to_hex(const char *input, char *output);
|
||||
string_to_hex(heartbeatData, heartbeatDataHex);
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_HEART_DATA_CMD, heartbeatDataHex);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_HEART_TIME_CMD, heartbeatTime);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/*step10: serial write "AT+S", save configuration and restart mqtt module*/
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SAVE_CFG_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(20000); // after save configuration, wait at least 10s for restarting
|
||||
ADAPTER_DEBUG("Gm800tf mqtt connect done\n");
|
||||
return 0;
|
||||
|
||||
out:
|
||||
ADAPTER_DEBUG("Gm800tf mqtt connect failed. Power down\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief this function has no use
|
||||
* @param adapter
|
||||
* @return int
|
||||
*/
|
||||
int Gm800tfMqttDisconnect(struct Adapter *adapter) {
|
||||
int ret = 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief send data to mqtt server
|
||||
* @param adapter
|
||||
* @param topic mqtt publish topic
|
||||
* @param buf data buffer to send to mqtt server
|
||||
* @param len data length
|
||||
* @return int 0: success; others: failed
|
||||
*/
|
||||
int Gm800tfMqttSend(struct Adapter *adapter, const char *topic, const void *buf, size_t len) {
|
||||
/* query for whether socket is connected successfully */
|
||||
AdapterDeviceNetstat(adapter);
|
||||
if (adapter->network_info.mqttIsConnected == 0) {
|
||||
printf("[error %s %d]socket has not been connected, please call function AdapterDeviceMqttConnect\n", __func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int ret = 0;
|
||||
char result[256] = {};
|
||||
uint8_t gm800tf_cmd[64];
|
||||
|
||||
static const char *publishTopics[10] = {NULL}; // save the mqtt publish topics temporarily
|
||||
static int topicIndex = 0; // the index next mqtt topic to be saved
|
||||
|
||||
/* step0: check if the topic in the topics array */
|
||||
for (int i = 0; i < 10; i++) {
|
||||
if (publishTopics[i] != NULL && strcmp(publishTopics[i], topic) == 0) {
|
||||
char num[10];
|
||||
sprintf(num, "%d,", i + 1);
|
||||
EntmSend(adapter->agent, num, strlen(num));
|
||||
EntmSend(adapter->agent, (const char *)buf, len);
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
topicIndex = topicIndex >= 10 ? 0 : topicIndex;
|
||||
publishTopics[topicIndex] = topic; // save the topic to the topics array
|
||||
|
||||
/* step1: serial send "+++" and "a", quit transparent mode */
|
||||
ret = Gm800tfEnterAtMode(adapter);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 'O', 'K');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 0);
|
||||
|
||||
/* step2: serial write "AT+MQTTPUBTP=<pubnum>,<puben>,<topic>,<qos>,<retained>", config the publish parameters */
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_MQTT_PUBPARAM_CMD, topicIndex + 1, 1, topic, 2, 0);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* step3: serial write "AT+S", save the configuration and restart the module */
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SAVE_CFG_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(15000); // after save configuration, wait at least 10s for restarting
|
||||
|
||||
/* step4: send the data to mqtt server */
|
||||
char num[10];
|
||||
sprintf(num, "%d,", topicIndex + 1);
|
||||
EntmSend(adapter->agent, num, strlen(num));
|
||||
EntmSend(adapter->agent, buf, len);
|
||||
topicIndex++;
|
||||
|
||||
ADAPTER_DEBUG("Gm800tf mqtt send done\n");
|
||||
return 0;
|
||||
|
||||
out:
|
||||
ADAPTER_DEBUG("Gm800tf mqtt send failed.\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief GM800TF only support transparent mode, so the topic is not used. The Message can't be diffrentiated by
|
||||
* topic in the received data.
|
||||
* @param adapter
|
||||
* @param topic
|
||||
* @param buf
|
||||
* @param len
|
||||
* @return int
|
||||
* @note 该函数暂时未经过测试
|
||||
*/
|
||||
int Gm800tfMqttRecv(struct Adapter *adapter, const char *topic, void *buf, size_t len) {
|
||||
int ret = 0;
|
||||
static const char *subscribeTopics[10] = {NULL};
|
||||
static int topicIndex = 0;
|
||||
uint8_t gm800tf_cmd[64];
|
||||
/* check if the topic in the topics array */
|
||||
for (int i = 0; i < 10; i++) {
|
||||
if (subscribeTopics[i] != NULL && strcmp(subscribeTopics[i], topic) == 0) {
|
||||
if (adapter->agent) {
|
||||
return EntmRecv(adapter->agent, (char *)buf, len, 6);
|
||||
} else {
|
||||
printf("Gm800tfRecv can not find agent\n");
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
topicIndex = topicIndex >= 10 ? 0 : topicIndex;
|
||||
subscribeTopics[topicIndex] = topic;
|
||||
|
||||
ret = Gm800tfEnterAtMode(adapter);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
AtSetReplyEndChar(adapter->agent, 'O', 'K');
|
||||
AtSetReplyCharNum(adapter->agent, 256);
|
||||
AtSetReplyLrEnd(adapter->agent, 0);
|
||||
|
||||
memset(gm800tf_cmd, 0, sizeof(gm800tf_cmd));
|
||||
sprintf(gm800tf_cmd, GM800TF_SET_MQTT_SUBPARAM_CMD, topicIndex + 1, 1, topic, 2);
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, gm800tf_cmd, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
ret = AtCmdConfigAndCheck(adapter->agent, GM800TF_SAVE_CFG_CMD, GM800TF_OK_REPLY);
|
||||
if (ret < 0) {
|
||||
goto out;
|
||||
}
|
||||
PrivTaskDelay(15000); // after save configuration, wait at least 10s for restarting
|
||||
|
||||
if (adapter->agent) {
|
||||
return EntmRecv(adapter->agent, (char *)buf, len, 6);
|
||||
} else {
|
||||
printf("Gm800tfRecv can not find agent\n");
|
||||
}
|
||||
out:
|
||||
ADAPTER_DEBUG("Gm800tf mqtt receive failed.\n");
|
||||
return -1;
|
||||
}
|
||||
@@ -129,6 +129,18 @@ struct NetworkInfo {
|
||||
enum CarrierType carrier_type;
|
||||
int signal_strength;
|
||||
char ip_address[16];
|
||||
#ifdef ADAPTER_GM800TF
|
||||
unsigned char workMode; // 工作模式,1为NET,2为MQTT,NOR
|
||||
unsigned short port; // 目的端口号
|
||||
unsigned char is_connected; // SOCKET连接状态,0为失败,1为成功
|
||||
unsigned char mqttSwitch; // MQTT开关
|
||||
char mqttServerIp[16]; // MQTT目的IP地址
|
||||
unsigned short mqttServerPort; // MQTT目的端口号
|
||||
char mqttClientId[64]; // MQTT客户端ID
|
||||
char mqttUsername[64]; // MQTT用户名
|
||||
char mqttPassword[64]; // MQTT密码
|
||||
unsigned char mqttIsConnected; // MQTT连接状态,0为失败,1为成功
|
||||
#endif
|
||||
};
|
||||
|
||||
struct AdapterData
|
||||
|
||||
@@ -1,14 +1,14 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
* 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 xs_adapterAT_client.c
|
||||
@@ -18,7 +18,6 @@
|
||||
* @date 2021.04.22
|
||||
*/
|
||||
|
||||
|
||||
#include <at_agent.h>
|
||||
#include <adapter.h>
|
||||
#include <stdbool.h>
|
||||
@@ -27,7 +26,7 @@
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
# include <user_api.h>
|
||||
#include <user_api.h>
|
||||
#endif
|
||||
#ifdef ADD_RTTHREAD_FEATURES
|
||||
#include <rtthread.h>
|
||||
@@ -49,9 +48,11 @@ unsigned int IpTint(char *ipstr)
|
||||
|
||||
token = strtok(ipstr, ".");
|
||||
|
||||
while (token != NULL) {
|
||||
while (token != NULL)
|
||||
{
|
||||
cur = atoi(token);
|
||||
if (cur >= 0 && cur <= 255) {
|
||||
if (cur >= 0 && cur <= 255)
|
||||
{
|
||||
total += cur * pow(256, i);
|
||||
}
|
||||
i--;
|
||||
@@ -65,8 +66,10 @@ void SwapStr(char *str, int begin, int end)
|
||||
{
|
||||
int i, j;
|
||||
|
||||
for (i = begin, j = end; i <= j; i++, j--) {
|
||||
if (str[i] != str[j]) {
|
||||
for (i = begin, j = end; i <= j; i++, j--)
|
||||
{
|
||||
if (str[i] != str[j])
|
||||
{
|
||||
str[i] = str[i] ^ str[j];
|
||||
str[j] = str[i] ^ str[j];
|
||||
str[i] = str[i] ^ str[j];
|
||||
@@ -83,7 +86,8 @@ char *IpTstr(unsigned int ipint)
|
||||
char token[4];
|
||||
int bt, ed, len, cur;
|
||||
|
||||
while (ipint) {
|
||||
while (ipint)
|
||||
{
|
||||
cur = ipint % 256;
|
||||
sprintf(token, "%d", cur);
|
||||
strcat(new, token);
|
||||
@@ -95,8 +99,10 @@ char *IpTstr(unsigned int ipint)
|
||||
len = strlen(new);
|
||||
SwapStr(new, 0, len - 1);
|
||||
|
||||
for (bt = ed = 0; ed < len;) {
|
||||
while (ed < len && new[ed] != '.') {
|
||||
for (bt = ed = 0; ed < len;)
|
||||
{
|
||||
while (ed < len && new[ed] != '.')
|
||||
{
|
||||
ed++;
|
||||
}
|
||||
SwapStr(new, bt, ed - 1);
|
||||
@@ -125,14 +131,15 @@ void ATSprintf(int fd, const char *format, va_list params)
|
||||
{
|
||||
last_cmd_len = vsnprintf(send_buf, sizeof(send_buf), format, params);
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
printf("AT send %s len %u\n",send_buf, last_cmd_len);
|
||||
printf("AT send %s len %u\n", send_buf, last_cmd_len);
|
||||
#endif
|
||||
PrivWrite(fd, send_buf, last_cmd_len);
|
||||
PrivWrite(fd, send_buf, last_cmd_len);
|
||||
}
|
||||
|
||||
int ATOrderSend(ATAgentType agent, uint32_t timeout_s, ATReplyType reply, const char *cmd_expr, ...)
|
||||
{
|
||||
if (agent == NULL) {
|
||||
if (agent == NULL)
|
||||
{
|
||||
printf("ATAgent is null");
|
||||
return -1;
|
||||
}
|
||||
@@ -158,19 +165,23 @@ int ATOrderSend(ATAgentType agent, uint32_t timeout_s, ATReplyType reply, const
|
||||
agent->reply = reply;
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
|
||||
if(agent->reply != NULL) {
|
||||
if (agent->reply != NULL)
|
||||
{
|
||||
PrivMutexObtain(&agent->lock);
|
||||
reply->reply_len = 0;
|
||||
va_start(params, cmd_expr);
|
||||
ATSprintf(agent->fd, cmd_expr, params);
|
||||
va_end(params);
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
if (PrivSemaphoreObtainWait(&agent->rsp_sem, &abstime) != 0) {
|
||||
printf("take sem %d timeout\n",agent->rsp_sem);
|
||||
if (PrivSemaphoreObtainWait(&agent->rsp_sem, &abstime) != 0)
|
||||
{
|
||||
printf("take sem %d timeout\n", agent->rsp_sem);
|
||||
result = -2;
|
||||
goto __out;
|
||||
}
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
PrivMutexObtain(&agent->lock);
|
||||
va_start(params, cmd_expr);
|
||||
ATSprintf(agent->fd, cmd_expr, params);
|
||||
@@ -187,35 +198,41 @@ int AtCmdConfigAndCheck(ATAgentType agent, char *cmd, char *check)
|
||||
{
|
||||
int ret = 0;
|
||||
char *result = NULL;
|
||||
if (NULL == agent || NULL == cmd || NULL == check ) {
|
||||
if (NULL == agent || NULL == cmd || NULL == check)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
ATReplyType reply = CreateATReply(256);
|
||||
if (NULL == reply) {
|
||||
printf("%s %d at_create_resp failed!\n",__func__,__LINE__);
|
||||
if (NULL == reply)
|
||||
{
|
||||
printf("%s %d at_create_resp failed!\n", __func__, __LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
ret = ATOrderSend(agent, REPLY_TIME_OUT, reply, cmd);
|
||||
if(ret < 0){
|
||||
printf("%s %d ATOrderSend failed.\n",__func__,__LINE__);
|
||||
printf("%s %d ATOrderSend failed, cmd: %s.\n",__func__,__LINE__,cmd);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
//PrivTaskDelay(3000);
|
||||
// PrivTaskDelay(3000);
|
||||
|
||||
result = GetReplyText(reply);
|
||||
if (!result) {
|
||||
printf("%s %n get reply failed.\n",__func__,__LINE__);
|
||||
if (!result)
|
||||
{
|
||||
printf("%s %n get reply failed.\n", __func__, __LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
printf("[reply result: %s]\n", result);
|
||||
if(!strstr(result, check)) {
|
||||
printf("%s %d check[%s] reply[%s] failed.\n",__func__,__LINE__,check,result);
|
||||
#endif
|
||||
if (!strstr(result, check))
|
||||
{
|
||||
printf("%s %d cmd[%s] check[%s] reply[%s] failed.\n", __func__, __LINE__, cmd, check, result);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
@@ -228,34 +245,40 @@ __exit:
|
||||
int AtGetNetworkInfoReply(ATAgentType agent, char *cmd, char *result)
|
||||
{
|
||||
int ret = 0;
|
||||
if (NULL == agent || NULL == cmd) {
|
||||
if (NULL == agent || NULL == cmd)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
ATReplyType reply = CreateATReply(256);
|
||||
if (NULL == reply) {
|
||||
printf("%s %d at_create_resp failed!\n",__func__,__LINE__);
|
||||
if (NULL == reply)
|
||||
{
|
||||
printf("%s %d at_create_resp failed!\n", __func__, __LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
ret = ATOrderSend(agent, REPLY_TIME_OUT, reply, cmd);
|
||||
if(ret < 0){
|
||||
printf("%s %d ATOrderSend failed.\n",__func__,__LINE__);
|
||||
if (ret < 0)
|
||||
{
|
||||
printf("%s %d ATOrderSend failed.\n", __func__, __LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
const char *replyText = GetReplyText(reply);
|
||||
if (replyText == NULL || replyText[0] == '\0') {
|
||||
printf("%s %n get reply failed.\n",__func__,__LINE__);
|
||||
if (replyText == NULL || replyText[0] == '\0')
|
||||
{
|
||||
printf("%s %n get reply failed.\n", __func__, __LINE__);
|
||||
ret = -1;
|
||||
goto __exit;
|
||||
}
|
||||
|
||||
strncpy(result, replyText, 63);
|
||||
result[63] = '\0';
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
printf("[reply result: %s]\n", result);
|
||||
#endif
|
||||
|
||||
__exit:
|
||||
DeleteATReply(reply);
|
||||
@@ -269,7 +292,8 @@ char *GetReplyText(ATReplyType reply)
|
||||
|
||||
int AtSetReplyLrEnd(ATAgentType agent, char enable)
|
||||
{
|
||||
if (!agent) {
|
||||
if (!agent)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
@@ -280,7 +304,8 @@ int AtSetReplyLrEnd(ATAgentType agent, char enable)
|
||||
|
||||
int AtSetReplyEndChar(ATAgentType agent, char last_ch, char end_ch)
|
||||
{
|
||||
if (!agent) {
|
||||
if (!agent)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
@@ -292,7 +317,8 @@ int AtSetReplyEndChar(ATAgentType agent, char last_ch, char end_ch)
|
||||
|
||||
int AtSetReplyCharNum(ATAgentType agent, unsigned int num)
|
||||
{
|
||||
if (!agent) {
|
||||
if (!agent)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
@@ -303,8 +329,9 @@ int AtSetReplyCharNum(ATAgentType agent, unsigned int num)
|
||||
|
||||
int EntmSend(ATAgentType agent, const char *data, int len)
|
||||
{
|
||||
if(len > 256){
|
||||
printf("send length %d more then max 256 Bytes.\n",len);
|
||||
if (len > 256)
|
||||
{
|
||||
printf("send length %d more then max 256 Bytes.\n", len);
|
||||
return -1;
|
||||
}
|
||||
char *send_buff = (char *)PrivMalloc(256);
|
||||
@@ -333,18 +360,20 @@ int EntmRecv(ATAgentType agent, char *rev_buffer, int buffer_len, int timeout_s)
|
||||
uint32 real_recv_len = 0;
|
||||
|
||||
abstime.tv_sec = timeout_s;
|
||||
if(buffer_len > ENTM_RECV_MAX){
|
||||
printf("read length more then max length[%d] Bytes",ENTM_RECV_MAX);
|
||||
return -1;
|
||||
if (buffer_len > ENTM_RECV_MAX)
|
||||
{
|
||||
printf("read length more then max length[%d] Bytes", ENTM_RECV_MAX);
|
||||
return -1;
|
||||
}
|
||||
PrivMutexObtain(&agent->lock);
|
||||
agent->receive_mode = ENTM_MODE;
|
||||
agent->read_len = buffer_len;
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
//PrivTaskDelay(1000);
|
||||
if (PrivSemaphoreObtainWait(&agent->entm_rx_notice, &abstime)) {
|
||||
// PrivTaskDelay(1000);
|
||||
if (PrivSemaphoreObtainWait(&agent->entm_rx_notice, &abstime))
|
||||
{
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
printf("wait sem[%d] timeout\n",agent->entm_rx_notice);
|
||||
printf("wait sem[%d] timeout\n", agent->entm_rx_notice);
|
||||
#endif
|
||||
agent->entm_recv_len = 0;
|
||||
return -1;
|
||||
@@ -381,74 +410,86 @@ static int GetCompleteATReply(ATAgentType agent)
|
||||
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
|
||||
while (1) {
|
||||
while (1)
|
||||
{
|
||||
res = PrivRead(agent->fd, &ch, 1);
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
if((res == 1) && (ch != 0)) {
|
||||
if ((res == 1) && (ch != 0))
|
||||
{
|
||||
printf(" %c (0x%x)\n", ch, ch);
|
||||
}
|
||||
#endif
|
||||
|
||||
PrivMutexObtain(&agent->lock);
|
||||
if (agent->receive_mode == ENTM_MODE) {
|
||||
if (agent->entm_recv_len < ENTM_RECV_MAX) {
|
||||
if (agent->receive_mode == ENTM_MODE)
|
||||
{
|
||||
if (agent->entm_recv_len < ENTM_RECV_MAX)
|
||||
{
|
||||
#ifdef LIB_USING_MQTT
|
||||
if((res == 1) && (agent->entm_recv_len < agent->read_len))
|
||||
if ((res == 1) && (agent->entm_recv_len < agent->read_len))
|
||||
{
|
||||
agent->entm_recv_buf[agent->entm_recv_len] = ch;
|
||||
agent->entm_recv_len++;
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
#else
|
||||
agent->entm_recv_buf[agent->entm_recv_len] = ch;
|
||||
agent->entm_recv_len++;
|
||||
if(agent->entm_recv_len < agent->read_len)
|
||||
if (agent->entm_recv_len < agent->read_len)
|
||||
{
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
else
|
||||
#endif
|
||||
else
|
||||
{
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
printf("ENTM_MODE recv %d Bytes done.\n",agent->entm_recv_len);
|
||||
printf("ENTM_MODE recv %d Bytes done.\n", agent->entm_recv_len);
|
||||
#endif
|
||||
agent->receive_mode = DEFAULT_MODE;
|
||||
PrivSemaphoreAbandon(&agent->entm_rx_notice);
|
||||
}
|
||||
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("entm_recv_buf is_full ...\n");
|
||||
}
|
||||
}
|
||||
else if (agent->receive_mode == AT_MODE) {
|
||||
if (read_len < agent->maintain_max) {
|
||||
if(ch != 0) { ///< if the char is null then do not save it to the buff
|
||||
else if (agent->receive_mode == AT_MODE)
|
||||
{
|
||||
if (read_len < agent->maintain_max)
|
||||
{
|
||||
if (ch != 0)
|
||||
{ ///< if the char is null then do not save it to the buff
|
||||
agent->maintain_buffer[read_len] = ch;
|
||||
read_len++;
|
||||
agent->maintain_len = read_len;
|
||||
}
|
||||
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("maintain_len is_full %d ...\n", read_len);
|
||||
is_full = true;
|
||||
}
|
||||
|
||||
if (((ch == '\n') && (agent->reply_lr_end)) ||
|
||||
((ch == '\n') && (last_ch == '\r') && (agent->reply_lr_end)) ||
|
||||
((ch == agent->reply_end_char) && (agent->reply_end_char) &&
|
||||
(last_ch == agent->reply_end_last_char) && (agent->reply_end_last_char)) ||
|
||||
((read_len == agent->reply_char_num) && (agent->reply_char_num))) {
|
||||
if (is_full) {
|
||||
((ch == agent->reply_end_char) && (agent->reply_end_char) &&
|
||||
(last_ch == agent->reply_end_last_char) && (agent->reply_end_last_char)) ||
|
||||
((read_len == agent->reply_char_num) && (agent->reply_char_num)))
|
||||
{
|
||||
if (is_full)
|
||||
{
|
||||
printf("read line failed. The line data length is out of buffer size(%d)!", agent->maintain_max);
|
||||
memset(agent->maintain_buffer, 0x00, agent->maintain_max);
|
||||
agent->maintain_len = 0;
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
return -1;
|
||||
}
|
||||
|
||||
#ifdef CONNECTION_FRAMEWORK_DEBUG
|
||||
printf("GetCompleteATReply done\n");
|
||||
#endif
|
||||
agent->receive_mode = DEFAULT_MODE;
|
||||
PrivMutexAbandon(&agent->lock);
|
||||
break;
|
||||
@@ -464,9 +505,11 @@ static int GetCompleteATReply(ATAgentType agent)
|
||||
|
||||
ATAgentType GetATAgent(const char *agent_name)
|
||||
{
|
||||
struct ATAgent* result = NULL;
|
||||
for (int i = 0; i < AT_AGENT_MAX; i++) {
|
||||
if (strcmp(at_agent_table[i].agent_name, agent_name) == 0) {
|
||||
struct ATAgent *result = NULL;
|
||||
for (int i = 0; i < AT_AGENT_MAX; i++)
|
||||
{
|
||||
if (strcmp(at_agent_table[i].agent_name, agent_name) == 0)
|
||||
{
|
||||
result = &at_agent_table[i];
|
||||
}
|
||||
}
|
||||
@@ -474,45 +517,51 @@ ATAgentType GetATAgent(const char *agent_name)
|
||||
return result;
|
||||
}
|
||||
|
||||
|
||||
int DeleteATAgent(ATAgentType agent)
|
||||
{
|
||||
printf("delete agent->at_handler = %d\n",agent->at_handler);
|
||||
if(agent->at_handler > 0){
|
||||
printf("delete agent->at_handler = %d\n", agent->at_handler);
|
||||
if (agent->at_handler > 0)
|
||||
{
|
||||
PrivTaskDelete(agent->at_handler, 0);
|
||||
}
|
||||
|
||||
if (agent->fd > 0) {
|
||||
printf("close agent fd = %d\n",agent->fd);
|
||||
if (agent->fd > 0)
|
||||
{
|
||||
printf("close agent fd = %d\n", agent->fd);
|
||||
PrivClose(agent->fd);
|
||||
}
|
||||
|
||||
#ifdef ADD_NUTTX_FEATURES
|
||||
if (agent->lock.sem.semcount > 0) {
|
||||
printf("delete agent lock = %d\n",agent->lock.sem.semcount);
|
||||
if (agent->lock.sem.semcount > 0)
|
||||
{
|
||||
printf("delete agent lock = %d\n", agent->lock.sem.semcount);
|
||||
PrivMutexDelete(&agent->lock);
|
||||
}
|
||||
#elif defined ADD_RTTHREAD_FEATURES
|
||||
#else
|
||||
if (agent->lock) {
|
||||
printf("delete agent lock = %d\n",agent->lock);
|
||||
if (agent->lock)
|
||||
{
|
||||
printf("delete agent lock = %d\n", agent->lock);
|
||||
PrivMutexDelete(&agent->lock);
|
||||
}
|
||||
#endif
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
if (agent->entm_rx_notice) {
|
||||
printf("delete agent entm_rx_notice = %d\n",agent->entm_rx_notice);
|
||||
if (agent->entm_rx_notice)
|
||||
{
|
||||
printf("delete agent entm_rx_notice = %d\n", agent->entm_rx_notice);
|
||||
PrivSemaphoreDelete(&agent->entm_rx_notice);
|
||||
}
|
||||
#else
|
||||
#endif
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
if (agent->rsp_sem) {
|
||||
printf("delete agent rsp_sem = %d\n",agent->rsp_sem);
|
||||
PrivSemaphoreDelete(&agent->rsp_sem);
|
||||
if (agent->rsp_sem)
|
||||
{
|
||||
printf("delete agent rsp_sem = %d\n", agent->rsp_sem);
|
||||
PrivSemaphoreDelete(&agent->rsp_sem);
|
||||
}
|
||||
#endif
|
||||
if (agent->maintain_buffer) {
|
||||
if (agent->maintain_buffer)
|
||||
{
|
||||
PrivFree(agent->maintain_buffer);
|
||||
}
|
||||
|
||||
@@ -525,18 +574,24 @@ static void *ATAgentReceiveProcess(void *param)
|
||||
ATAgentType agent = (ATAgentType)param;
|
||||
const struct at_urc *urc;
|
||||
|
||||
while (1) {
|
||||
if (GetCompleteATReply(agent) > 0) {
|
||||
while (1)
|
||||
{
|
||||
if (GetCompleteATReply(agent) > 0)
|
||||
{
|
||||
PrivMutexObtain(&agent->lock);
|
||||
if (agent->reply != NULL) {
|
||||
if (agent->reply != NULL)
|
||||
{
|
||||
ATReplyType reply = agent->reply;
|
||||
|
||||
agent->maintain_buffer[agent->maintain_len] = '\0';
|
||||
if (agent->maintain_len <= reply->reply_max_len) {
|
||||
memset(reply->reply_buffer, 0 , reply->reply_max_len);
|
||||
if (agent->maintain_len <= reply->reply_max_len)
|
||||
{
|
||||
memset(reply->reply_buffer, 0, reply->reply_max_len);
|
||||
memcpy(reply->reply_buffer, agent->maintain_buffer, agent->maintain_len);
|
||||
reply->reply_len = agent->maintain_len;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("out of memory (%d)!\n", reply->reply_max_len);
|
||||
}
|
||||
|
||||
@@ -555,7 +610,8 @@ static int ATAgentInit(ATAgentType agent)
|
||||
agent->maintain_len = 0;
|
||||
agent->maintain_buffer = (char *)PrivMalloc(agent->maintain_max);
|
||||
|
||||
if (agent->maintain_buffer == NULL) {
|
||||
if (agent->maintain_buffer == NULL)
|
||||
{
|
||||
printf("ATAgentInit malloc maintain_buffer error\n");
|
||||
goto __out;
|
||||
}
|
||||
@@ -563,18 +619,21 @@ static int ATAgentInit(ATAgentType agent)
|
||||
memset(agent->maintain_buffer, 0, agent->maintain_max);
|
||||
|
||||
result = PrivSemaphoreCreate(&agent->entm_rx_notice, 0, 0);
|
||||
if (result < 0) {
|
||||
if (result < 0)
|
||||
{
|
||||
printf("ATAgentInit create entm sem error\n");
|
||||
goto __out;
|
||||
}
|
||||
|
||||
result = PrivSemaphoreCreate(&agent->rsp_sem, 0, 0);
|
||||
if (result < 0) {
|
||||
if (result < 0)
|
||||
{
|
||||
printf("ATAgentInit create rsp sem error\n");
|
||||
goto __out;
|
||||
}
|
||||
|
||||
if(PrivMutexCreate(&agent->lock, 0) < 0) {
|
||||
if (PrivMutexCreate(&agent->lock, 0) < 0)
|
||||
{
|
||||
printf("AdapterFrameworkInit mutex create failed.\n");
|
||||
goto __out;
|
||||
}
|
||||
@@ -591,6 +650,10 @@ static int ATAgentInit(ATAgentType agent)
|
||||
pthread_attr_t attr;
|
||||
attr.schedparam.sched_priority = 25;
|
||||
attr.stacksize = 4096;
|
||||
#ifdef ADAPTER_GM800TF
|
||||
attr.schedparam.sched_priority = 16;
|
||||
attr.stacksize = 1800;
|
||||
#endif
|
||||
|
||||
char task_name[] = "at_agent";
|
||||
pthread_args_t args;
|
||||
@@ -616,15 +679,18 @@ int InitATAgent(const char *agent_name, int agent_fd, uint32 maintain_max)
|
||||
int open_result = 0;
|
||||
struct ATAgent *agent = NULL;
|
||||
|
||||
if (GetATAgent(agent_name) != NULL) {
|
||||
if (GetATAgent(agent_name) != NULL)
|
||||
{
|
||||
return result;
|
||||
}
|
||||
|
||||
while (i < AT_AGENT_MAX && at_agent_table[i].fd > 0) {
|
||||
while (i < AT_AGENT_MAX && at_agent_table[i].fd > 0)
|
||||
{
|
||||
i++;
|
||||
}
|
||||
|
||||
if (i >= AT_AGENT_MAX) {
|
||||
if (i >= AT_AGENT_MAX)
|
||||
{
|
||||
printf("agent buffer(%d) is full.", AT_AGENT_MAX);
|
||||
result = -1;
|
||||
return result;
|
||||
@@ -639,7 +705,8 @@ int InitATAgent(const char *agent_name, int agent_fd, uint32 maintain_max)
|
||||
agent->maintain_max = maintain_max;
|
||||
|
||||
result = ATAgentInit(agent);
|
||||
if (result == 0) {
|
||||
if (result == 0)
|
||||
{
|
||||
PrivTaskStartup(&agent->at_handler);
|
||||
}
|
||||
|
||||
@@ -651,7 +718,8 @@ ATReplyType CreateATReply(uint32 reply_max_len)
|
||||
ATReplyType reply = NULL;
|
||||
|
||||
reply = (ATReplyType)PrivMalloc(sizeof(struct ATReply));
|
||||
if (reply == NULL) {
|
||||
if (reply == NULL)
|
||||
{
|
||||
printf("no more memory\n");
|
||||
return NULL;
|
||||
}
|
||||
@@ -660,7 +728,8 @@ ATReplyType CreateATReply(uint32 reply_max_len)
|
||||
reply->reply_max_len = reply_max_len;
|
||||
|
||||
reply->reply_buffer = (char *)PrivMalloc(reply_max_len);
|
||||
if (reply->reply_buffer == NULL) {
|
||||
if (reply->reply_buffer == NULL)
|
||||
{
|
||||
printf("no more memory\n");
|
||||
PrivFree(reply);
|
||||
return NULL;
|
||||
@@ -673,14 +742,17 @@ ATReplyType CreateATReply(uint32 reply_max_len)
|
||||
|
||||
void DeleteATReply(ATReplyType reply)
|
||||
{
|
||||
if (reply) {
|
||||
if (reply->reply_buffer) {
|
||||
if (reply)
|
||||
{
|
||||
if (reply->reply_buffer)
|
||||
{
|
||||
PrivFree(reply->reply_buffer);
|
||||
reply->reply_buffer = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
if (reply) {
|
||||
if (reply)
|
||||
{
|
||||
PrivFree(reply);
|
||||
reply = NULL;
|
||||
}
|
||||
|
||||
@@ -58,9 +58,15 @@ struct ATAgent
|
||||
uint32 maintain_len;
|
||||
uint32 maintain_max;
|
||||
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
int lock;
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
|
||||
#if defined(ADAPTER_GM800TF) || defined(ADAPTER_EC801E)
|
||||
pthread_mutex_t lock;
|
||||
#else
|
||||
int lock;
|
||||
#endif
|
||||
|
||||
#else // ADD_XIZI_FEATURES
|
||||
pthread_mutex_t lock;
|
||||
#endif
|
||||
|
||||
@@ -69,7 +75,7 @@ struct ATAgent
|
||||
char reply_end_last_char;
|
||||
char reply_end_char;
|
||||
uint32 reply_char_num;
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
#ifdef ADD_XIZI_FEATURES
|
||||
int rsp_sem;
|
||||
#else
|
||||
sem_t rsp_sem;
|
||||
|
||||
@@ -3,7 +3,13 @@ config ADAPTER_HFA21_ETHERNET
|
||||
Please check HFA21 can only work for adapter_wifi or adapter_ethernet in the meantime!
|
||||
bool "Using ethernet adapter device HFA21"
|
||||
default n
|
||||
config ADAPTER_WCHNET_ETHERNET
|
||||
bool "Using ethernet adapter device WCHNET"
|
||||
default n
|
||||
|
||||
if ADAPTER_HFA21_ETHERNET
|
||||
source "$APP_DIR/Framework/connection/ethernet/hfa21_ethernet/Kconfig"
|
||||
endif
|
||||
if ADAPTER_WCHNET_ETHERNET
|
||||
source "$APP_DIR/Framework/connection/ethernet/wchnet_ethernet/Kconfig"
|
||||
endif
|
||||
|
||||
@@ -3,5 +3,8 @@ SRC_FILES := adapter_ethernet.c
|
||||
ifeq ($(CONFIG_ADAPTER_HFA21_ETHERNET),y)
|
||||
SRC_DIR += hfa21_ethernet
|
||||
endif
|
||||
ifeq ($(CONFIG_ADAPTER_WCHNET_ETHERNET),y)
|
||||
SRC_DIR += wchnet_ethernet
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
@@ -1,14 +1,14 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
* 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 adapter_ethernet.c
|
||||
@@ -23,9 +23,11 @@
|
||||
#ifdef ADAPTER_HFA21_ETHERNET
|
||||
extern AdapterProductInfoType Hfa21EthernetAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
#ifdef ADAPTER_WCHNET_ETHERNET
|
||||
extern AdapterProductInfoType wchnetEthernetAttach(struct Adapter *adapter);
|
||||
#endif
|
||||
|
||||
static int AdapterEthernetRegister(struct Adapter *adapter)
|
||||
{
|
||||
static int AdapterEthernetRegister(struct Adapter *adapter) {
|
||||
int ret = 0;
|
||||
|
||||
strncpy(adapter->name, ADAPTER_ETHERNET_NAME, NAME_NUM_MAX);
|
||||
@@ -42,8 +44,7 @@ static int AdapterEthernetRegister(struct Adapter *adapter)
|
||||
return ret;
|
||||
}
|
||||
|
||||
int AdapterEthernetInit(void)
|
||||
{
|
||||
int AdapterEthernetInit(void) {
|
||||
int ret = 0;
|
||||
|
||||
struct Adapter *adapter = PrivMalloc(sizeof(struct Adapter));
|
||||
@@ -74,17 +75,28 @@ int AdapterEthernetInit(void)
|
||||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
|
||||
#endif
|
||||
#ifdef ADAPTER_WCHNET_ETHERNET
|
||||
AdapterProductInfoType product_info = wchnetEthernetAttach(adapter);
|
||||
if (!product_info) {
|
||||
printf("AdapterEthernetInit wchnet attach error\n");
|
||||
PrivFree(adapter);
|
||||
return -1;
|
||||
}
|
||||
|
||||
adapter->product_info_flag = 1;
|
||||
adapter->info = product_info;
|
||||
adapter->done = product_info->model_done;
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/******************ethernet TEST*********************/
|
||||
int AdapterEthernetTest(void)
|
||||
{
|
||||
int AdapterEthernetTest(void) {
|
||||
int baud_rate = BAUD_RATE_57600;
|
||||
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_ETHERNET_NAME);
|
||||
struct Adapter *adapter = AdapterDeviceFindByName(ADAPTER_ETHERNET_NAME);
|
||||
|
||||
#ifdef ADAPTER_HFA21_ETHERNET
|
||||
|
||||
@@ -96,30 +108,67 @@ int AdapterEthernetTest(void)
|
||||
AdapterDeviceControl(adapter, OPE_INT, &baud_rate);
|
||||
|
||||
AdapterDeviceSetUp(adapter);
|
||||
|
||||
|
||||
const char *ip = "192.168.131.26";
|
||||
const char *port = "9999";
|
||||
enum NetRoleType net_role = CLIENT;//SERVER
|
||||
enum NetRoleType net_role = CLIENT; // SERVER
|
||||
enum IpType ip_type = IPV4;
|
||||
AdapterDeviceConnect(adapter, net_role, ip, port, ip_type);
|
||||
|
||||
printf("ready to test data transfer\n");
|
||||
PrivTaskDelay(2000);
|
||||
len = strlen(ethernet_msg);
|
||||
for (i = 0;i < 10; i ++) {
|
||||
for (i = 0; i < 10; i++) {
|
||||
printf("AdapterEthernetTest send %s\n", ethernet_msg);
|
||||
AdapterDeviceSend(adapter, ethernet_msg, len);
|
||||
PrivTaskDelay(4000);
|
||||
}
|
||||
|
||||
|
||||
while (1) {
|
||||
AdapterDeviceRecv(adapter, ethernet_recv_msg, 128);
|
||||
printf("AdapterEthernetTest recv %s\n", ethernet_recv_msg);
|
||||
memset(ethernet_recv_msg, 0, 128);
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef ADAPTER_WCHNET_ETHERNET
|
||||
AdapterDeviceSetUp(adapter);
|
||||
// AdapterDeviceSetAddr(adapter, "192.168.1.10", "255.255.255.0", "192.168.1.1");
|
||||
// AdapterDeviceSetDhcp(adapter, 1);
|
||||
// AdapterDeviceConnect(adapter, CLIENT, "115.238.53.59", "10208", IPV4);
|
||||
AdapterDeviceConnect(adapter, CLIENT, "192.168.1.100", "1000", IPV4);
|
||||
AdapterDeviceSend(adapter, "Hello World!", sizeof("Hello World!"));
|
||||
// /* 测试DHCP连接路由器后,连接因特网 */
|
||||
// AdapterDeviceSend(adapter,
|
||||
// "GET /v3/weather/weatherInfo?city=%E9%95%BF%E6%B2%99&key=13cb58f5884f9749287abbead9c658f2 "
|
||||
// "HTTP/1.1\r\nHost: restapi.amap.com\r\n\r\n",
|
||||
// sizeof("GET
|
||||
// /v3/weather/weatherInfo?city=%E9%95%BF%E6%B2%99&key=13cb58f5884f9749287abbead9c658f2 "
|
||||
// "HTTP/1.1\r\nHost: restapi.amap.com\r\n\r\n"));
|
||||
char receiveBuffer[128] = {};
|
||||
PrivTaskDelay(20000);
|
||||
ssize_t readLength = AdapterDeviceRecv(adapter, receiveBuffer, sizeof(receiveBuffer));
|
||||
// printf("receiveBuffer:%s\n", receiveBuffer);
|
||||
printf("[socketid-%d]receiveBuffer:", adapter->socket.socket_id);
|
||||
for (int i = 0; i < readLength; i++) {
|
||||
printf("%c", receiveBuffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
AdapterDeviceDisconnect(adapter, NULL);
|
||||
// AdapterDeviceConnect(adapter, CLIENT, "115.238.53.59", "10208", IPV4);
|
||||
AdapterDeviceConnect(adapter, CLIENT, "192.168.1.100", "1000", IPV4);
|
||||
AdapterDeviceSend(adapter, "Hello World!", sizeof("Hello World!"));
|
||||
PrivTaskDelay(20000);
|
||||
readLength = AdapterDeviceRecv(adapter, receiveBuffer, sizeof(receiveBuffer));
|
||||
printf("[socketid-%d]receiveBuffer:", adapter->socket.socket_id);
|
||||
for (int i = 0; i < readLength; i++) {
|
||||
printf("%c", receiveBuffer[i]);
|
||||
}
|
||||
printf("\n");
|
||||
AdapterDeviceSetDown(adapter);
|
||||
AdapterDeviceClose(adapter);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
PRIV_SHELL_CMD_FUNCTION(AdapterEthernetTest, a ethernet test sample, PRIV_SHELL_CMD_MAIN_ATTR);
|
||||
|
||||
@@ -0,0 +1,3 @@
|
||||
config ADAPTER_ETHERNET_WCHNET
|
||||
string "WCHNET ETHERNET adapter name"
|
||||
default "wchnet_ethernet"
|
||||
@@ -0,0 +1,3 @@
|
||||
SRC_FILES := wchnet_ethernet.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,10 @@
|
||||
from building import *
|
||||
import os
|
||||
|
||||
cwd = GetCurrentDir()
|
||||
src = []
|
||||
if GetDepend(['ADAPTER_WCHNET_ETHERNET']):
|
||||
src += ['wchnet_ethernet.c']
|
||||
group = DefineGroup('connection ethernet wchnet', src, depend = [], CPPPATH = [cwd])
|
||||
|
||||
Return('group')
|
||||
@@ -0,0 +1,532 @@
|
||||
/*
|
||||
* 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 wchnet_ethernet.c
|
||||
* @brief Implement the connection ethernet adapter function, using wchnet device
|
||||
* @author Huo Yujia (huoyujia081@126.com)
|
||||
* @version 1.0
|
||||
* @date 2024-07-17
|
||||
*/
|
||||
|
||||
#include <ModuleConfig.h>
|
||||
#include <adapter.h>
|
||||
#include <connect_ether.h>
|
||||
#include <eth_driver.h>
|
||||
|
||||
extern pmodule_cfg CFG; // 从flash中读取的配置信息指针
|
||||
|
||||
/* 记录socket会话参数,由于ch32v208内存限制,目前只支持单个会话通信 */
|
||||
struct WchnetSocketConfiguration wchnetSocketConfiguration;
|
||||
|
||||
/**
|
||||
* @brief wchnet主任务线程,主要用于不断处理以太网中断
|
||||
* @param argv 参数无意义
|
||||
* @return void* 返回值无意义
|
||||
*/
|
||||
static void *wchnetMainTask(void *argv) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration = (struct WchnetSocketConfiguration *)argv;
|
||||
while (1) {
|
||||
PrivTaskDelay(50);
|
||||
WCHNET_MainTask();
|
||||
if (WCHNET_QueryGlobalInt()) {
|
||||
WCHNET_HandleGlobalInt(pWchnetSocketConfiguration);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 以太网发送数据
|
||||
* @param adapter
|
||||
* @param data 所要发送数据的存储区域指针
|
||||
* @param len 所要发送数据的长度
|
||||
* @return int 实际发送的数据长度
|
||||
*/
|
||||
static int wchnetEthernetSend(struct Adapter *adapter, const void *data, size_t len) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration =
|
||||
(struct WchnetSocketConfiguration *)adapter->adapter_param;
|
||||
|
||||
/* 判断是否可以发送数据 */
|
||||
if (pWchnetSocketConfiguration->wchnetMainThread == 0) { // 判断是否已启动wchnet主任务线程
|
||||
printf("[error %s %d]wchnetMainThread has not been started, please call function AdapterDeviceSetUp first\n",
|
||||
__func__, __LINE__);
|
||||
return -1;
|
||||
} else if (pWchnetSocketConfiguration->socketStatus != WCHNET_SOCKET_CONNECT_SUCCESS) { // 判断是否已连接socket
|
||||
printf(
|
||||
"[error %s %d]socket has not been connected, please call function AdapterDeviceConnect "
|
||||
"first\n",
|
||||
__func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* 发送数据 */
|
||||
uint32_t tempLen = (uint32_t)len; // 实际发送数据长度
|
||||
uint8_t res = WCHNET_SocketSend(pWchnetSocketConfiguration->socketId, (uint8_t *)data, &tempLen);
|
||||
if (res == WCHNET_ERR_SUCCESS) {
|
||||
printf("[socketid-%d]send data success, len = %d\n", adapter->socket.socket_id, tempLen);
|
||||
return tempLen;
|
||||
} else {
|
||||
mStopIfError(res);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 以太网接收数据
|
||||
* @param adapter
|
||||
* @param rev_buffer 接收数据首地址
|
||||
* @param buffer_len 期望读取的数据长度
|
||||
* @return int 实际读取的数据长度
|
||||
*/
|
||||
static int wchnetEthernetReceive(struct Adapter *adapter, void *rev_buffer, size_t buffer_len) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration =
|
||||
(struct WchnetSocketConfiguration *)adapter->adapter_param;
|
||||
|
||||
/* 判断是否可以接收数据 */
|
||||
if (pWchnetSocketConfiguration->wchnetMainThread == 0) { // 判断是否已启动wchnet主任务线程
|
||||
printf("[error %s %d]wchnetMainThread has not been started, please call function AdapterDeviceSetUp first\n",
|
||||
__func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* 接收数据 */
|
||||
uint32_t tempLen = (uint32_t)buffer_len; // 实际接收数据长度
|
||||
uint8_t res = WCHNET_SocketRecv(pWchnetSocketConfiguration->socketId, (u8 *)rev_buffer, &tempLen);
|
||||
if (res == WCHNET_ERR_SUCCESS) {
|
||||
printf("[socketid-%d]recv data success, len = %d\n", pWchnetSocketConfiguration->socketId, tempLen);
|
||||
return tempLen;
|
||||
} else {
|
||||
mStopIfError(res);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 启动wchnet主任务线程,监听以太网中断
|
||||
* @param adapter
|
||||
* @return int 0表示线程启动成功,其他表示线程启动失败
|
||||
*/
|
||||
static int wchnetEthernetSetUp(struct Adapter *adapter) {
|
||||
pthread_attr_t wchnetMainTaskAttr;
|
||||
pthread_args_t wchnetMainTaskArgs;
|
||||
wchnetMainTaskAttr.schedparam.sched_priority = 16; // 线程优先级
|
||||
wchnetMainTaskAttr.stacksize = 1100; // 线程栈大小
|
||||
wchnetMainTaskArgs.pthread_name = "wchnetMainTask"; // 线程名字
|
||||
wchnetMainTaskArgs.arg = &wchnetSocketConfiguration; // 线程参数
|
||||
int res = PrivTaskCreate(&wchnetSocketConfiguration.wchnetMainThread, &wchnetMainTaskAttr, wchnetMainTask,
|
||||
&wchnetMainTaskArgs);
|
||||
PrivTaskStartup(&wchnetSocketConfiguration.wchnetMainThread);
|
||||
adapter->adapter_param = &wchnetSocketConfiguration;
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 关闭以太网socket连接
|
||||
* @param adapter
|
||||
* @return int 0表示关闭以太网socket连接成功,其他表示关闭以太网socket连接失败
|
||||
*/
|
||||
static int wchnetEthernetDisconnect(struct Adapter *adapter) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration =
|
||||
(struct WchnetSocketConfiguration *)adapter->adapter_param;
|
||||
|
||||
/* 判断是否可以关闭socket */
|
||||
if (pWchnetSocketConfiguration->wchnetMainThread == 0) { // 判断是否已启动wchnet主任务线程
|
||||
printf("[error %s %d]wchnetMainThread has not been started, please call function AdapterDeviceSetUp first\n",
|
||||
__func__, __LINE__);
|
||||
return -1;
|
||||
} else if (pWchnetSocketConfiguration->socketStatus !=
|
||||
WCHNET_SOCKET_CONNECT_SUCCESS) { // 判断当前是否已有socket连接
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
}
|
||||
|
||||
/* 将目的IP地址和端口号的数组形式转换成字符串形式和unsigned short形式 */
|
||||
char destinationIpAddress[16]; // 目的IP地址
|
||||
uint16_t destinationPort; // 目的端口号
|
||||
sprintf(destinationIpAddress, "%u.%u.%u.%u", pWchnetSocketConfiguration->destinationIpAddress[0],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[1], pWchnetSocketConfiguration->destinationIpAddress[2],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[3]);
|
||||
destinationPort =
|
||||
(pWchnetSocketConfiguration->destinationPort[1] << 8) + pWchnetSocketConfiguration->destinationPort[0];
|
||||
|
||||
/* 关闭socket连接 */
|
||||
uint8_t res = WCHNET_SocketClose(pWchnetSocketConfiguration->socketId, TCP_CLOSE_NORMAL);
|
||||
if (res == WCHNET_ERR_SUCCESS) {
|
||||
while (pWchnetSocketConfiguration->socketStatus == WCHNET_SOCKET_CONNECT_SUCCESS) {
|
||||
PrivTaskDelay(100); // 每100ms检查一次是否socket关闭完成
|
||||
}
|
||||
/* socket关闭完成 */
|
||||
pWchnetSocketConfiguration->socketStatus = WCHNET_SOCKET_UNDEFINED;
|
||||
printf("[socketid-%d]socket with %s:%hu has been disconnected\n", pWchnetSocketConfiguration->socketId,
|
||||
destinationIpAddress, destinationPort);
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
} else {
|
||||
mStopIfError(res);
|
||||
printf("[socketid-%d]socket with %s:%hu disconnect error\n", pWchnetSocketConfiguration->socketId,
|
||||
destinationIpAddress, destinationPort);
|
||||
return res;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 建立以太网socket连接
|
||||
* @param adapter
|
||||
* @param net_role 网络角色,CLIENT或者SERVER
|
||||
* @param ip 目的IP地址字符串
|
||||
* @param port 目的端口号字符串
|
||||
* @param ip_type IP类型,IPV4或者IPV6
|
||||
* @return int 0表示建立以太网socket连接成功,其他表示建立以太网socket连接失败
|
||||
*/
|
||||
static int wchnetEthernetConnect(struct Adapter *adapter, enum NetRoleType net_role, const char *ip, const char *port,
|
||||
enum IpType ip_type) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration =
|
||||
(struct WchnetSocketConfiguration *)adapter->adapter_param;
|
||||
|
||||
/* 由于ch32v208内存限制,当前仅支持IPV4+CLIENT */
|
||||
if (ip_type != IPV4) {
|
||||
printf("[error %s %d]wchnetEthernetConnect only support IPV4, do not support IPV6\n", __func__, __LINE__);
|
||||
return -1;
|
||||
} else if (net_role != CLIENT) {
|
||||
printf("[error %s %d]wchnetEthernetConnect only support CLIENT, do not support SERVER\n", __func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* 将IP地址和端口号的字符串形式转换成数组形式 */
|
||||
uint8_t destinationIpAddress[4];
|
||||
uint8_t destinationPort[2];
|
||||
WCHNET_Aton(ip, destinationIpAddress);
|
||||
destinationPort[0] = atoi(port) % 256;
|
||||
destinationPort[1] = atoi(port) / 256;
|
||||
|
||||
uint8_t res = WCHNET_ERR_SUCCESS;
|
||||
if (pWchnetSocketConfiguration->wchnetMainThread == 0) { // 判断是否已启动wchnet主任务线程
|
||||
printf("[error %s %d]wchnetMainThread has not been started, please call function AdapterDeviceSetUp first\n",
|
||||
__func__, __LINE__);
|
||||
return -1;
|
||||
} else if (pWchnetSocketConfiguration->socketStatus ==
|
||||
WCHNET_SOCKET_CONNECT_SUCCESS) { // 判断当前是否已有socket连接
|
||||
if (memcmp(destinationIpAddress, pWchnetSocketConfiguration->destinationIpAddress, 4) == 0 &&
|
||||
memcmp(destinationPort, pWchnetSocketConfiguration->destinationPort, 2) ==
|
||||
0) { // 当前连接的socket,目的IP地址和端口号完全一致,无需再次连接
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
} else { // 当前连接的socket,目的IP地址和端口号不完全一致,由于ch32v208内存限制,当前仅支持单个socket通信,需断开当前连接
|
||||
res = wchnetEthernetDisconnect(adapter);
|
||||
if (res != WCHNET_ERR_SUCCESS) {
|
||||
mStopIfError(res);
|
||||
printf("[error %s %d]wchnetEthernetDisconnect fail\n", __func__, __LINE__);
|
||||
return res;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* 保存目的IP地址和目的端口号 */
|
||||
memcpy(pWchnetSocketConfiguration->destinationIpAddress, destinationIpAddress, 4);
|
||||
memcpy(pWchnetSocketConfiguration->destinationPort, destinationPort, 2);
|
||||
pWchnetSocketConfiguration->socketStatus = WCHNET_SOCKET_UNDEFINED;
|
||||
|
||||
/* 配置socket会话 */
|
||||
SOCK_INF TmpSocketInf;
|
||||
memset((void *)&TmpSocketInf, 0, sizeof(SOCK_INF));
|
||||
memcpy(TmpSocketInf.IPAddr, destinationIpAddress, 4);
|
||||
TmpSocketInf.SourPort =
|
||||
(pWchnetSocketConfiguration->sourcePort[1] << 8) + pWchnetSocketConfiguration->sourcePort[0]; // 源端口号
|
||||
TmpSocketInf.DesPort = (pWchnetSocketConfiguration->destinationPort[1] << 8) +
|
||||
pWchnetSocketConfiguration->destinationPort[0]; // 目的端口号
|
||||
TmpSocketInf.ProtoType = PROTO_TYPE_TCP; // 协议类型,TCP
|
||||
TmpSocketInf.RecvBufLen = RECE_BUF_LEN; // 接收缓冲区大小
|
||||
|
||||
/* 创建socket */
|
||||
res = WCHNET_SocketCreat(&pWchnetSocketConfiguration->socketId, &TmpSocketInf);
|
||||
if (res == WCHNET_ERR_SUCCESS) {
|
||||
printf("[socketid-%d]create socketId %d\r\n", pWchnetSocketConfiguration->socketId,
|
||||
pWchnetSocketConfiguration->socketId);
|
||||
} else {
|
||||
mStopIfError(res);
|
||||
printf("[error %s %d]WCHNET_SocketCreat fail\n", __func__, __LINE__);
|
||||
return res;
|
||||
}
|
||||
|
||||
/* 连接socket */
|
||||
res = WCHNET_SocketConnect(pWchnetSocketConfiguration->socketId);
|
||||
if (res == WCHNET_ERR_SUCCESS) {
|
||||
printf("[socketid-%d]connecting socketId %d\r\n", pWchnetSocketConfiguration->socketId,
|
||||
pWchnetSocketConfiguration->socketId);
|
||||
} else {
|
||||
mStopIfError(res);
|
||||
printf("[error %s %d]WCHNET_SocketConnect fail\n", __func__, __LINE__);
|
||||
return res;
|
||||
}
|
||||
|
||||
/* 每100ms查询一次,直至连接成功或者超时 */
|
||||
while (pWchnetSocketConfiguration->socketStatus == WCHNET_SOCKET_UNDEFINED) {
|
||||
printf("[socketid-%d]connecting socketId %d\r\n", pWchnetSocketConfiguration->socketId,
|
||||
pWchnetSocketConfiguration->socketId);
|
||||
PrivTaskDelay(1000);
|
||||
}
|
||||
if (pWchnetSocketConfiguration->socketStatus == WCHNET_SOCKET_CONNECT_SUCCESS) {
|
||||
printf("[socketid-%d]socket connect success\n", pWchnetSocketConfiguration->socketId);
|
||||
return res;
|
||||
} else if (pWchnetSocketConfiguration->socketStatus == WCHNET_SOCKET_CONNECT_TIMEOUT) {
|
||||
printf("[socketid-%d]socket connect timeout\n", pWchnetSocketConfiguration->socketId);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 设置以太网源IP地址,网关地址,子网掩码
|
||||
* @param adapter
|
||||
* @param ip 源IP地址
|
||||
* @param gateway 网关地址
|
||||
* @param netmask 子网掩码
|
||||
* @return int 0表示设置成功,其他表示设置失败
|
||||
*/
|
||||
static int wchnetEthernetSetAddr(struct Adapter *adapter, const char *ip, const char *gateway, const char *netmask) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration =
|
||||
(struct WchnetSocketConfiguration *)adapter->adapter_param;
|
||||
|
||||
/* 判断是否已启动wchnet主任务线程 */
|
||||
if (pWchnetSocketConfiguration->wchnetMainThread == 0) {
|
||||
printf("[error %s %d]wchnetMainThread has not been started, please call function AdapterDeviceSetUp first\n",
|
||||
__func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* 将地址的字符串形式转化为数组形式 */
|
||||
uint8_t sourceIpAddress[4], sourceGateway[4], sourceSubnetMask[4];
|
||||
WCHNET_Aton(ip, sourceIpAddress);
|
||||
WCHNET_Aton(gateway, sourceGateway);
|
||||
WCHNET_Aton(netmask, sourceSubnetMask);
|
||||
|
||||
/* 若配置内容和当前配置保持一致,则无需配置 */
|
||||
if (memcmp(sourceIpAddress, pWchnetSocketConfiguration->sourceIpAddress, 4) == 0 &&
|
||||
memcmp(sourceGateway, pWchnetSocketConfiguration->sourceGateway, 4) == 0 &&
|
||||
memcmp(sourceSubnetMask, pWchnetSocketConfiguration->sourceSubnetMask, 4) == 0) {
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
}
|
||||
|
||||
/* 若当前有socket正在连接,则需断开socket,再使用新的配置连接socket */
|
||||
uint8_t socketExists = pWchnetSocketConfiguration->socketStatus == WCHNET_SOCKET_CONNECT_SUCCESS;
|
||||
if (socketExists) {
|
||||
wchnetEthernetDisconnect(adapter);
|
||||
}
|
||||
|
||||
/* 进行配置,并重新初始化wchnet */
|
||||
memcpy(pWchnetSocketConfiguration->sourceIpAddress, sourceIpAddress, 4);
|
||||
memcpy(pWchnetSocketConfiguration->sourceGateway, sourceGateway, 4);
|
||||
memcpy(pWchnetSocketConfiguration->sourceSubnetMask, sourceSubnetMask, 4);
|
||||
uint8_t res = WCHNET_Init(pWchnetSocketConfiguration->sourceIpAddress, pWchnetSocketConfiguration->sourceGateway,
|
||||
pWchnetSocketConfiguration->sourceSubnetMask, pWchnetSocketConfiguration->macAddress);
|
||||
|
||||
if (res == WCHNET_ERR_SUCCESS) { // 初始化wchnet成功
|
||||
pWchnetSocketConfiguration->dhcpSwitch = 0;
|
||||
pWchnetSocketConfiguration->dhcpStatus = WCHNET_DHCP_UNDEFINED;
|
||||
printf("-*-*-*wchnetEthernetSetAddr*-*-*\n");
|
||||
printf("ip:\t%s\ngateway:%s\nnetmask:%s\n", ip, gateway, netmask);
|
||||
printf("-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*\n");
|
||||
if (socketExists) { // 若之前有socket正在连接,则需重新连接
|
||||
char destinationIpAddress[16], destinationPort[6];
|
||||
sprintf(destinationIpAddress, "%u.%u.%u.%u", pWchnetSocketConfiguration->destinationIpAddress[0],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[1],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[2],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[3]);
|
||||
sprintf(
|
||||
destinationPort, "%hu",
|
||||
(pWchnetSocketConfiguration->destinationPort[1] << 8) + pWchnetSocketConfiguration->destinationPort[0]);
|
||||
res = wchnetEthernetConnect(adapter, CLIENT, destinationIpAddress, destinationPort, IPV4);
|
||||
}
|
||||
}
|
||||
mStopIfError(res);
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 删除wchnet主任务线程
|
||||
* @param adapter
|
||||
* @return int 0表示删除wchnet主任务线程成功,其他表示删除wchnet主任务线程失败
|
||||
*/
|
||||
static int wchnetEthernetSetDown(struct Adapter *adapter) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration =
|
||||
(struct WchnetSocketConfiguration *)adapter->adapter_param;
|
||||
|
||||
/* 如果wchnet主任务线程已经处于关闭状态 */
|
||||
if (pWchnetSocketConfiguration->wchnetMainThread == 0) {
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
}
|
||||
|
||||
uint8_t res = WCHNET_ERR_SUCCESS;
|
||||
|
||||
/* 如果仍有socket未关闭,先关闭socket */
|
||||
if (pWchnetSocketConfiguration->socketStatus == WCHNET_SOCKET_CONNECT_SUCCESS) {
|
||||
res = wchnetEthernetDisconnect(adapter);
|
||||
if (res != WCHNET_ERR_SUCCESS) {
|
||||
return res;
|
||||
}
|
||||
}
|
||||
|
||||
/* 删除wchnet主任务线程 */
|
||||
res = PrivTaskDelete(pWchnetSocketConfiguration->wchnetMainThread, 0);
|
||||
if (res != 0) {
|
||||
printf("wchnet ethernet set down fail\n");
|
||||
} else {
|
||||
pWchnetSocketConfiguration->wchnetMainThread = 0;
|
||||
printf("wchnet ethernet set down success\n");
|
||||
}
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 设置DHCP
|
||||
* @param adapter
|
||||
* @param enable 0表示关闭DHCP,1表示打开DHCP
|
||||
* @return int 0表示设置成功,其他表示设置失败
|
||||
* @note 若获得新的动态IP地址,则关闭当前的所有socket连接,并使用新的IP地址建立连接
|
||||
* @note 若获得的动态IP地址和当前的IP地址一致,则不进行任何操作,继续使用旧的IP地址进行通信
|
||||
* @note 若获取动态IP地址失败,则继续使用旧的IP地址进行通信
|
||||
*/
|
||||
static int wchnetEthernetSetDHCP(struct Adapter *adapter, int enable) {
|
||||
struct WchnetSocketConfiguration *pWchnetSocketConfiguration =
|
||||
(struct WchnetSocketConfiguration *)adapter->adapter_param;
|
||||
|
||||
if (pWchnetSocketConfiguration->wchnetMainThread == 0) { // 判断是否已启动wchnet主任务线程
|
||||
printf("[error %s %d]wchnetMainThread has not been started, please call function AdapterDeviceSetUp first\n",
|
||||
__func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint8_t res;
|
||||
switch (enable) {
|
||||
/* 关闭DHCP */
|
||||
case 0:
|
||||
/* 如果原来就没有打开DHCP,无需关闭DHCP */
|
||||
if (pWchnetSocketConfiguration->dhcpSwitch == 0) {
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
}
|
||||
|
||||
/* 重新使用静态IP地址初始化,相当于关闭DHCP */
|
||||
res = WCHNET_Init(pWchnetSocketConfiguration->sourceIpAddress, pWchnetSocketConfiguration->sourceGateway,
|
||||
pWchnetSocketConfiguration->sourceSubnetMask, pWchnetSocketConfiguration->macAddress);
|
||||
if (res != WCHNET_ERR_SUCCESS) { // DHCP关闭失败
|
||||
mStopIfError(res);
|
||||
} else { // DHCP关闭成功
|
||||
pWchnetSocketConfiguration->dhcpSwitch = 0;
|
||||
pWchnetSocketConfiguration->dhcpStatus = WCHNET_DHCP_UNDEFINED;
|
||||
}
|
||||
return res;
|
||||
break;
|
||||
|
||||
/* 打开DHCP */
|
||||
case 1:
|
||||
/* 如果原来已经打开DHCP */
|
||||
if (pWchnetSocketConfiguration->dhcpSwitch == 1 &&
|
||||
(pWchnetSocketConfiguration->dhcpStatus == WCHNET_DHCP_SUCCESS_NEW ||
|
||||
pWchnetSocketConfiguration->dhcpStatus == WCHNET_DHCP_SUCCESS_OLD)) {
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
}
|
||||
|
||||
/* 配置DHCP主机名 */
|
||||
res = WCHNET_DHCPSetHostname("WCHNET");
|
||||
if (res == WCHNET_ERR_SUCCESS) {
|
||||
printf("DHCP hostname set success\n");
|
||||
} else {
|
||||
mStopIfError(res);
|
||||
printf("[error %s %d]WCHNET_DHCPSetHostname fail\n", __func__, __LINE__);
|
||||
}
|
||||
|
||||
/* 开启DHCP */
|
||||
res = WCHNET_DHCPStart(WCHNET_DHCPCallBack);
|
||||
if (res == WCHNET_ERR_SUCCESS) {
|
||||
pWchnetSocketConfiguration->dhcpStatus = WCHNET_DHCP_UNDEFINED;
|
||||
while (pWchnetSocketConfiguration->dhcpStatus == WCHNET_DHCP_UNDEFINED) {
|
||||
PrivTaskDelay(1000); // 每秒查询一次DHCP状态
|
||||
printf("DHCP finding IP\n");
|
||||
}
|
||||
WCHNET_DHCPStop(); // 停止DHCP
|
||||
switch (pWchnetSocketConfiguration->dhcpStatus) {
|
||||
case WCHNET_DHCP_SUCCESS_NEW: // 获取到新的动态IP地址,若之前连接过socket,则重新连接该socket
|
||||
pWchnetSocketConfiguration->dhcpSwitch = 1;
|
||||
printf("DHCP set up successfully, getting new IP configuration\n");
|
||||
if (pWchnetSocketConfiguration->socketStatus == WCHNET_SOCKET_CONNECT_SUCCESS) {
|
||||
char destinationIpAddress[16];
|
||||
char destinationPort[6];
|
||||
sprintf(destinationIpAddress, "%u.%u.%u.%u",
|
||||
pWchnetSocketConfiguration->destinationIpAddress[0],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[1],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[2],
|
||||
pWchnetSocketConfiguration->destinationIpAddress[3]);
|
||||
sprintf(destinationPort, "%hu",
|
||||
(pWchnetSocketConfiguration->destinationPort[1] << 8) +
|
||||
pWchnetSocketConfiguration->destinationPort[0]);
|
||||
if (!wchnetEthernetDisconnect(adapter) &&
|
||||
!wchnetEthernetConnect(adapter, CLIENT, destinationIpAddress, destinationPort, IPV4)) {
|
||||
printf("[socketid-%d]DHCP: socket with %s:%s has been reset\n",
|
||||
pWchnetSocketConfiguration->socketId, destinationIpAddress, destinationPort);
|
||||
} else {
|
||||
printf("[socketid-%d]DHCP: socket with %s:%s reset failed\n",
|
||||
pWchnetSocketConfiguration->socketId, pWchnetSocketConfiguration->socketId,
|
||||
destinationIpAddress, destinationPort);
|
||||
}
|
||||
}
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
break;
|
||||
case WCHNET_DHCP_SUCCESS_OLD: // 获取到旧的动态IP地址
|
||||
pWchnetSocketConfiguration->dhcpSwitch = 1;
|
||||
printf("DHCP set up successfully, getting the same IP configuration\n");
|
||||
return WCHNET_ERR_SUCCESS;
|
||||
break;
|
||||
case WCHNET_DHCP_FAIL: // 获取动态IP地址错误
|
||||
pWchnetSocketConfiguration->dhcpSwitch = 0;
|
||||
printf("[error %s %d]wchnet dhcp fail\n", __func__, __LINE__);
|
||||
return -1;
|
||||
}
|
||||
} else {
|
||||
mStopIfError(res);
|
||||
return res;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static const struct IpProtocolDone wchnet_ethernet_done = {
|
||||
.open = NULL,
|
||||
.close = NULL,
|
||||
.ioctl = NULL,
|
||||
.setup = wchnetEthernetSetUp,
|
||||
.setdown = wchnetEthernetSetDown,
|
||||
.setaddr = wchnetEthernetSetAddr,
|
||||
.setdns = NULL,
|
||||
.setdhcp = wchnetEthernetSetDHCP,
|
||||
.ping = NULL,
|
||||
.netstat = NULL,
|
||||
.connect = wchnetEthernetConnect,
|
||||
.send = wchnetEthernetSend,
|
||||
.recv = wchnetEthernetReceive,
|
||||
.disconnect = wchnetEthernetDisconnect,
|
||||
};
|
||||
|
||||
/**
|
||||
* @description: Register ethernet device wchnet
|
||||
* @return success: product_info, failure: NULL
|
||||
*/
|
||||
AdapterProductInfoType wchnetEthernetAttach(struct Adapter *adapter) {
|
||||
struct AdapterProductInfo *product_info = PrivMalloc(sizeof(struct AdapterProductInfo));
|
||||
if (!product_info) {
|
||||
printf("wchnetEthernetAttach Attach malloc product_info error\n");
|
||||
PrivFree(product_info);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
strcpy(product_info->model_name, ADAPTER_ETHERNET_WCHNET);
|
||||
|
||||
product_info->model_done = (void *)&wchnet_ethernet_done;
|
||||
|
||||
return product_info;
|
||||
}
|
||||
@@ -977,7 +977,7 @@ int AdapterLoraTest(void)
|
||||
char task_name_2[] = "adapter_lora_gateway";
|
||||
args.pthread_name = task_name_2;
|
||||
args.arg = (void *)adapter;
|
||||
PrivTaskCreate(&lora_recv_data_task, &lora_gateway_attr, &LoraReceiveTask, (void *)&args);
|
||||
PrivTaskCreate(&lora_gateway_task, &lora_gateway_attr, &LoraGatewayTask, (void *)&args);
|
||||
#endif
|
||||
|
||||
PrivTaskStartup(&lora_gateway_task);
|
||||
|
||||
@@ -178,7 +178,8 @@ bool MQTT_Connect(void)
|
||||
MQTT_Send(Platform_mqtt.Pack_buff,Platform_mqtt.Fixed_len + Platform_mqtt.Variable_len + Platform_mqtt.Payload_len);
|
||||
MdelayKTask(50);
|
||||
MQTT_Recv(mqtt_rxbuf, 4);
|
||||
if(mqtt_rxbuf[0] == parket_connetAck[0] && mqtt_rxbuf[1] == parket_connetAck[1]) //连接成功
|
||||
if(mqtt_rxbuf[0] == parket_connetAck[0] && mqtt_rxbuf[1] == parket_connetAck[1]
|
||||
&& mqtt_rxbuf[2] == parket_connetAck[2] && mqtt_rxbuf[3] == parket_connetAck[3]) //连接成功
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
@@ -1,18 +0,0 @@
|
||||
#
|
||||
# Automatically generated file; DO NOT EDIT.
|
||||
# XiZi_AIoT Project Configuration
|
||||
#
|
||||
CONFIG_BOARD_IMX6Q_SABRELITE=y
|
||||
CONFIG_ARCH_ARM=y
|
||||
|
||||
#
|
||||
# imx6q sabrelite feature
|
||||
#
|
||||
|
||||
#
|
||||
# Lib
|
||||
#
|
||||
CONFIG_LIB=y
|
||||
CONFIG_LIB_POSIX=y
|
||||
CONFIG_LIB_NEWLIB=y
|
||||
# CONFIG_LIB_MUSLLIB is not set
|
||||
1
Ubiquitous/XiZi_AIoT/.gitignore
vendored
Normal file
1
Ubiquitous/XiZi_AIoT/.gitignore
vendored
Normal file
@@ -0,0 +1 @@
|
||||
build
|
||||
@@ -3,7 +3,7 @@ MAKEFLAGS += --no-print-directory
|
||||
.PHONY:all clean distclean show_info menuconfig
|
||||
.PHONY:COMPILE_APP COMPILE_KERNEL
|
||||
|
||||
riscv_support :=
|
||||
riscv_support := jh7110
|
||||
arm_support += imx6q-sabrelite zynq7000-zc702 3568
|
||||
emulator_support +=
|
||||
support := $(riscv_support) $(arm_support) $(emulator_support)
|
||||
@@ -37,6 +37,9 @@ endif
|
||||
ifneq ($(findstring $(BOARD), 3568), )
|
||||
include $(KERNEL_ROOT)/hardkernel/arch/arm/armv8-a/cortex-a55/preboot_for_$(BOARD)/config.mk
|
||||
endif
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
include $(KERNEL_ROOT)/hardkernel/arch/riscv/rv64gc/preboot_for_$(BOARD)/config.mk
|
||||
endif
|
||||
export BSP_BUILD_DIR := $(KERNEL_ROOT)
|
||||
export HOSTTOOLS_DIR ?= $(KERNEL_ROOT)/services/tools/hosttools
|
||||
export CONFIG2H_EXE ?= $(HOSTTOOLS_DIR)/xsconfig.sh
|
||||
@@ -142,3 +145,12 @@ distclean:
|
||||
@rm -f .config*
|
||||
@rm -f $(KERNEL_ROOT)/lib/musllib/libmusl.a
|
||||
@rm -f $(KERNEL_ROOT)/board/*/.config
|
||||
|
||||
|
||||
# Run qemu with config discribed in README.md.
|
||||
.PHONY: qemu-default
|
||||
qemu-default:
|
||||
qemu-system-arm -M sabrelite -m 1G -smp 4 -cpu cortex-a9 \
|
||||
-display none -serial null -serial stdio \
|
||||
-kernel ./build/XiZi-imx6q-sabrelite.elf
|
||||
|
||||
|
||||
@@ -34,7 +34,7 @@ $(eval LOCALC := $(addprefix $(BUILD_DIR)/,$(COBJ))) \
|
||||
$(eval OBJS += $(LOCALC)) \
|
||||
$(if $(strip $(LOCALC)),$(eval $(LOCALC): $(1)
|
||||
@if [ ! -d $$(@D) ]; then mkdir -p $$(@D); fi
|
||||
@echo cc $$<
|
||||
@echo cc $(subst $(KERNEL_ROOT)/,,$$<)
|
||||
@/bin/echo -n $(dir $(LOCALC)) >>$(KERNEL_ROOT)/build/make.dep
|
||||
@($(CROSS_COMPILE)gcc -MM $$(CFLAGS) -c $$<) >>$(KERNEL_ROOT)/build/make.dep
|
||||
@$(CROSS_COMPILE)gcc $$(CFLAGS) -c $$< -o $$@))
|
||||
|
||||
@@ -1,3 +1,8 @@
|
||||
ifneq ($(findstring $(BOARD), 3568 imx6q-sabrelite zynq7000-zc702), )
|
||||
SRC_DIR := arm
|
||||
endif
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := riscv
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
@@ -76,6 +76,13 @@ Modification:
|
||||
|
||||
#define NR_CPU 4
|
||||
|
||||
static inline uint64_t arch_current_tick()
|
||||
{
|
||||
uint32_t tick = 0;
|
||||
__asm__ __volatile__("MRC p15, 0, %0, c9, c13, 0" : "=r"(tick)); // %0 应该是输出操作数
|
||||
return (uint64_t)tick;
|
||||
}
|
||||
|
||||
__attribute__((always_inline, optimize("O0"))) static inline uint32_t user_mode()
|
||||
{
|
||||
uint32_t val;
|
||||
|
||||
@@ -77,7 +77,7 @@ _boot_start:
|
||||
mul r3, r2, r1
|
||||
sub r0, r0, r3
|
||||
|
||||
msr CPSR_c, #ARM_MODE_SVC | I_BIT | F_BIT
|
||||
msr CPSR_c, #ARM_MODE_SVC | I_BIT
|
||||
mov sp, r0
|
||||
sub r0, r0, r1
|
||||
|
||||
|
||||
@@ -0,0 +1,710 @@
|
||||
/*
|
||||
* Copyright (c) 2012, Freescale Semiconductor, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY FREESCALE "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
|
||||
* SHALL FREESCALE BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
|
||||
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
|
||||
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
|
||||
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
|
||||
* OF SUCH DAMAGE.
|
||||
*/
|
||||
/*
|
||||
* WARNING! DO NOT EDIT THIS FILE DIRECTLY!
|
||||
*
|
||||
* This file was generated automatically and any changes may be lost.
|
||||
*/
|
||||
#ifndef __HW_EPIT_REGISTERS_H__
|
||||
#define __HW_EPIT_REGISTERS_H__
|
||||
|
||||
#include "regs.h"
|
||||
#include "soc_memory_map.h"
|
||||
|
||||
/*
|
||||
* i.MX6SL EPIT
|
||||
*
|
||||
* EPIT
|
||||
*
|
||||
* Registers defined in this header file:
|
||||
* - HW_EPIT_CR - Control register
|
||||
* - HW_EPIT_SR - Status register
|
||||
* - HW_EPIT_LR - Load register
|
||||
* - HW_EPIT_CMPR - Compare register
|
||||
* - HW_EPIT_CNR - Counter register
|
||||
*
|
||||
* - hw_epit_t - Struct containing all module registers.
|
||||
*/
|
||||
|
||||
//! @name Module base addresses
|
||||
//@{
|
||||
#ifndef REGS_EPIT_BASE
|
||||
#define HW_EPIT_INSTANCE_COUNT (2) //!< Number of instances of the EPIT module.
|
||||
#define HW_EPIT1 (1) //!< Instance number for EPIT1.
|
||||
#define HW_EPIT2 (2) //!< Instance number for EPIT2.
|
||||
#define REGS_EPIT1_BASE USERLAND_MMIO_P2V(0x020d0000) //!< Base address for EPIT instance number 1.
|
||||
#define REGS_EPIT2_BASE USERLAND_MMIO_P2V(0x020d4000) //!< Base address for EPIT instance number 2.
|
||||
|
||||
//! @brief Get the base address of EPIT by instance number.
|
||||
//! @param x EPIT instance number, from 1 through 2.
|
||||
#define REGS_EPIT_BASE(x) ((x) == HW_EPIT1 ? REGS_EPIT1_BASE : (x) == HW_EPIT2 ? REGS_EPIT2_BASE \
|
||||
: 0x00d00000)
|
||||
|
||||
//! @brief Get the instance number given a base address.
|
||||
//! @param b Base address for an instance of EPIT.
|
||||
#define REGS_EPIT_INSTANCE(b) ((b) == REGS_EPIT1_BASE ? HW_EPIT1 : (b) == REGS_EPIT2_BASE ? HW_EPIT2 \
|
||||
: 0)
|
||||
#endif
|
||||
//@}
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// HW_EPIT_CR - Control register
|
||||
//-------------------------------------------------------------------------------------------
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
/*!
|
||||
* @brief HW_EPIT_CR - Control register (RW)
|
||||
*
|
||||
* Reset value: 0x00000000
|
||||
*
|
||||
* The EPIT control register (EPIT_CR) is used to configure the operating settings of the EPIT. It
|
||||
* contains the clock division prescaler value and also the interrupt enable bit. Additionally, it
|
||||
* contains other control bits which are described below. Peripheral Bus Write access to EPIT
|
||||
* Control Register (EPIT_CR) results in one cycle of the wait state, while other valid peripheral
|
||||
* bus accesses are with 0 wait state.
|
||||
*/
|
||||
typedef union _hw_epit_cr {
|
||||
reg32_t U;
|
||||
struct _hw_epit_cr_bitfields {
|
||||
unsigned EN : 1; //!< [0] This bit enables the EPIT.
|
||||
unsigned ENMOD : 1; //!< [1] EPIT enable mode.
|
||||
unsigned OCIEN : 1; //!< [2] Output compare interrupt enable.
|
||||
unsigned RLD : 1; //!< [3] Counter reload control.
|
||||
unsigned PRESCALAR : 12; //!< [15:4] Counter clock prescaler value.
|
||||
unsigned SWR : 1; //!< [16] Software reset.
|
||||
unsigned IOVW : 1; //!< [17] EPIT counter overwrite enable.
|
||||
unsigned DBGEN : 1; //!< [18] This bit is used to keep the EPIT functional in debug mode.
|
||||
unsigned WAITEN : 1; //!< [19] This read/write control bit enables the operation of the EPIT during wait mode.
|
||||
unsigned RESERVED0 : 1; //!< [20] Reserved.
|
||||
unsigned STOPEN : 1; //!< [21] EPIT stop mode enable.
|
||||
unsigned OM : 2; //!< [23:22] EPIT output mode.This bit field determines the mode of EPIT output on the output pin.
|
||||
unsigned CLKSRC : 2; //!< [25:24] Select clock source
|
||||
unsigned RESERVED1 : 6; //!< [31:26] Reserved.
|
||||
} B;
|
||||
} hw_epit_cr_t;
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* @name Constants and macros for entire EPIT_CR register
|
||||
*/
|
||||
//@{
|
||||
#define HW_EPIT_CR_ADDR(x) (REGS_EPIT_BASE(x) + 0x0)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
#define HW_EPIT_CR(x) (*(volatile hw_epit_cr_t*)HW_EPIT_CR_ADDR(x))
|
||||
#define HW_EPIT_CR_RD(x) (HW_EPIT_CR(x).U)
|
||||
#define HW_EPIT_CR_WR(x, v) (HW_EPIT_CR(x).U = (v))
|
||||
#define HW_EPIT_CR_SET(x, v) (HW_EPIT_CR_WR(x, HW_EPIT_CR_RD(x) | (v)))
|
||||
#define HW_EPIT_CR_CLR(x, v) (HW_EPIT_CR_WR(x, HW_EPIT_CR_RD(x) & ~(v)))
|
||||
#define HW_EPIT_CR_TOG(x, v) (HW_EPIT_CR_WR(x, HW_EPIT_CR_RD(x) ^ (v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*
|
||||
* constants & macros for individual EPIT_CR bitfields
|
||||
*/
|
||||
|
||||
/*! @name Register EPIT_CR, field EN[0] (RW)
|
||||
*
|
||||
* This bit enables the EPIT. EPIT counter and prescaler value when EPIT is enabled (EN = 1), is
|
||||
* dependent upon ENMOD and RLD bit as described for ENMOD bit. It is recommended that all registers
|
||||
* be properly programmed before setting this bit. This bit is reset by a hardware reset. A software
|
||||
* reset does not affect this bit.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - EPIT is disabled
|
||||
* - 1 - EPIT is enabled
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_EN (0) //!< Bit position for EPIT_CR_EN.
|
||||
#define BM_EPIT_CR_EN (0x00000001) //!< Bit mask for EPIT_CR_EN.
|
||||
|
||||
//! @brief Get value of EPIT_CR_EN from a register value.
|
||||
#define BG_EPIT_CR_EN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_EN) >> BP_EPIT_CR_EN)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_EN.
|
||||
#define BF_EPIT_CR_EN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_EN) & BM_EPIT_CR_EN)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the EN field to a new value.
|
||||
#define BW_EPIT_CR_EN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_EN) | BF_EPIT_CR_EN(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field ENMOD[1] (RW)
|
||||
*
|
||||
* EPIT enable mode. When EPIT is disabled (EN=0), both main counter and prescaler counter freeze
|
||||
* their count at current count values. ENMOD bit is a r/w bit that determines the counter value
|
||||
* when the EPIT is enabled again by setting EN bit. If ENMOD bit is set, then main counter is
|
||||
* loaded with the load value (If RLD=1)/ 0xFFFF_FFFF (If RLD=0) and prescaler counter is reset,
|
||||
* when EPIT is enabled (EN=1). If ENMOD is programmed to 0 then both main counter and prescaler
|
||||
* counter restart counting from their frozen values when EPIT is enabled (EN=1). If EPIT is
|
||||
* programmed to be disabled in a low-power mode (STOP/WAIT/DEBUG), then both the main counter and
|
||||
* the prescaler counter freeze at their current count values when EPIT enters low-power mode. When
|
||||
* EPIT exits the low-power mode, both main counter and prescaler counter start counting from their
|
||||
* frozen values irrespective of the ENMOD bit. This bit is reset by a hardware reset. A software
|
||||
* reset does not affect this bit.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - Counter starts counting from the value it had when it was disabled.
|
||||
* - 1 - Counter starts count from load value (RLD=1) or 0xFFFF_FFFF (If RLD=0)
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_ENMOD (1) //!< Bit position for EPIT_CR_ENMOD.
|
||||
#define BM_EPIT_CR_ENMOD (0x00000002) //!< Bit mask for EPIT_CR_ENMOD.
|
||||
|
||||
//! @brief Get value of EPIT_CR_ENMOD from a register value.
|
||||
#define BG_EPIT_CR_ENMOD(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_ENMOD) >> BP_EPIT_CR_ENMOD)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_ENMOD.
|
||||
#define BF_EPIT_CR_ENMOD(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_ENMOD) & BM_EPIT_CR_ENMOD)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the ENMOD field to a new value.
|
||||
#define BW_EPIT_CR_ENMOD(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_ENMOD) | BF_EPIT_CR_ENMOD(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field OCIEN[2] (RW)
|
||||
*
|
||||
* Output compare interrupt enable. This bit enables the generation of interrupt on occurrence of
|
||||
* compare event.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - Compare interrupt disabled
|
||||
* - 1 - Compare interrupt enabled
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_OCIEN (2) //!< Bit position for EPIT_CR_OCIEN.
|
||||
#define BM_EPIT_CR_OCIEN (0x00000004) //!< Bit mask for EPIT_CR_OCIEN.
|
||||
|
||||
//! @brief Get value of EPIT_CR_OCIEN from a register value.
|
||||
#define BG_EPIT_CR_OCIEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_OCIEN) >> BP_EPIT_CR_OCIEN)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_OCIEN.
|
||||
#define BF_EPIT_CR_OCIEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_OCIEN) & BM_EPIT_CR_OCIEN)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the OCIEN field to a new value.
|
||||
#define BW_EPIT_CR_OCIEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_OCIEN) | BF_EPIT_CR_OCIEN(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field RLD[3] (RW)
|
||||
*
|
||||
* Counter reload control. This bit is cleared by hardware reset. It decides the counter
|
||||
* functionality, whether to run in free-running mode or set-and-forget mode.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - When the counter reaches zero it rolls over to 0xFFFF_FFFF (free-running mode)
|
||||
* - 1 - When the counter reaches zero it reloads from the modulus register (set-and-forget mode)
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_RLD (3) //!< Bit position for EPIT_CR_RLD.
|
||||
#define BM_EPIT_CR_RLD (0x00000008) //!< Bit mask for EPIT_CR_RLD.
|
||||
|
||||
//! @brief Get value of EPIT_CR_RLD from a register value.
|
||||
#define BG_EPIT_CR_RLD(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_RLD) >> BP_EPIT_CR_RLD)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_RLD.
|
||||
#define BF_EPIT_CR_RLD(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_RLD) & BM_EPIT_CR_RLD)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the RLD field to a new value.
|
||||
#define BW_EPIT_CR_RLD(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_RLD) | BF_EPIT_CR_RLD(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field PRESCALAR[15:4] (RW)
|
||||
*
|
||||
* Counter clock prescaler value. This bit field determines the prescaler value by which the clock
|
||||
* is divided before it goes to the counter
|
||||
*
|
||||
* Values:
|
||||
* - 0x000 - Divide by 1
|
||||
* - 0x001 - Divide by 2...
|
||||
* - 0xFFF - Divide by 4096
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_PRESCALAR (4) //!< Bit position for EPIT_CR_PRESCALAR.
|
||||
#define BM_EPIT_CR_PRESCALAR (0x0000fff0) //!< Bit mask for EPIT_CR_PRESCALAR.
|
||||
|
||||
//! @brief Get value of EPIT_CR_PRESCALAR from a register value.
|
||||
#define BG_EPIT_CR_PRESCALAR(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_PRESCALAR) >> BP_EPIT_CR_PRESCALAR)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_PRESCALAR.
|
||||
#define BF_EPIT_CR_PRESCALAR(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_PRESCALAR) & BM_EPIT_CR_PRESCALAR)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the PRESCALAR field to a new value.
|
||||
#define BW_EPIT_CR_PRESCALAR(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_PRESCALAR) | BF_EPIT_CR_PRESCALAR(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field SWR[16] (RW)
|
||||
*
|
||||
* Software reset. The EPIT is reset when this bit is set to 1. It is a self clearing bit. This bit
|
||||
* is set when the block is in reset state and is cleared when the reset procedure is over. Setting
|
||||
* this bit resets all the registers to their reset values, except for the EN, ENMOD, STOPEN, WAITEN
|
||||
* and DBGEN bits in this control register
|
||||
*
|
||||
* Values:
|
||||
* - 0 - EPIT is out of reset
|
||||
* - 1 - EPIT is undergoing reset
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_SWR (16) //!< Bit position for EPIT_CR_SWR.
|
||||
#define BM_EPIT_CR_SWR (0x00010000) //!< Bit mask for EPIT_CR_SWR.
|
||||
|
||||
//! @brief Get value of EPIT_CR_SWR from a register value.
|
||||
#define BG_EPIT_CR_SWR(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_SWR) >> BP_EPIT_CR_SWR)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_SWR.
|
||||
#define BF_EPIT_CR_SWR(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_SWR) & BM_EPIT_CR_SWR)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the SWR field to a new value.
|
||||
#define BW_EPIT_CR_SWR(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_SWR) | BF_EPIT_CR_SWR(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field IOVW[17] (RW)
|
||||
*
|
||||
* EPIT counter overwrite enable. This bit controls the counter data when the modulus register is
|
||||
* written. When this bit is set, all writes to the load register overwrites the counter contents
|
||||
* and the counter starts subsequently counting down from the programmed value.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - Write to load register does not result in counter value being overwritten.
|
||||
* - 1 - Write to load register results in immediate overwriting of counter value.
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_IOVW (17) //!< Bit position for EPIT_CR_IOVW.
|
||||
#define BM_EPIT_CR_IOVW (0x00020000) //!< Bit mask for EPIT_CR_IOVW.
|
||||
|
||||
//! @brief Get value of EPIT_CR_IOVW from a register value.
|
||||
#define BG_EPIT_CR_IOVW(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_IOVW) >> BP_EPIT_CR_IOVW)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_IOVW.
|
||||
#define BF_EPIT_CR_IOVW(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_IOVW) & BM_EPIT_CR_IOVW)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the IOVW field to a new value.
|
||||
#define BW_EPIT_CR_IOVW(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_IOVW) | BF_EPIT_CR_IOVW(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field DBGEN[18] (RW)
|
||||
*
|
||||
* This bit is used to keep the EPIT functional in debug mode. When this bit is cleared, the input
|
||||
* clock is gated off in debug mode.This bit is reset by hardware reset. A software reset does not
|
||||
* affect this bit.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - Inactive in debug mode
|
||||
* - 1 - Active in debug mode
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_DBGEN (18) //!< Bit position for EPIT_CR_DBGEN.
|
||||
#define BM_EPIT_CR_DBGEN (0x00040000) //!< Bit mask for EPIT_CR_DBGEN.
|
||||
|
||||
//! @brief Get value of EPIT_CR_DBGEN from a register value.
|
||||
#define BG_EPIT_CR_DBGEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_DBGEN) >> BP_EPIT_CR_DBGEN)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_DBGEN.
|
||||
#define BF_EPIT_CR_DBGEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_DBGEN) & BM_EPIT_CR_DBGEN)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the DBGEN field to a new value.
|
||||
#define BW_EPIT_CR_DBGEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_DBGEN) | BF_EPIT_CR_DBGEN(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field WAITEN[19] (RW)
|
||||
*
|
||||
* This read/write control bit enables the operation of the EPIT during wait mode. This bit is reset
|
||||
* by a hardware reset. A software reset does not affect this bit.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - EPIT is disabled in wait mode
|
||||
* - 1 - EPIT is enabled in wait mode
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_WAITEN (19) //!< Bit position for EPIT_CR_WAITEN.
|
||||
#define BM_EPIT_CR_WAITEN (0x00080000) //!< Bit mask for EPIT_CR_WAITEN.
|
||||
|
||||
//! @brief Get value of EPIT_CR_WAITEN from a register value.
|
||||
#define BG_EPIT_CR_WAITEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_WAITEN) >> BP_EPIT_CR_WAITEN)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_WAITEN.
|
||||
#define BF_EPIT_CR_WAITEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_WAITEN) & BM_EPIT_CR_WAITEN)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the WAITEN field to a new value.
|
||||
#define BW_EPIT_CR_WAITEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_WAITEN) | BF_EPIT_CR_WAITEN(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field STOPEN[21] (RW)
|
||||
*
|
||||
* EPIT stop mode enable. This read/write control bit enables the operation of the EPIT during stop
|
||||
* mode. This bit is reset by a hardware reset and unaffected by software reset.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - EPIT is disabled in stop mode
|
||||
* - 1 - EPIT is enabled in stop mode
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_STOPEN (21) //!< Bit position for EPIT_CR_STOPEN.
|
||||
#define BM_EPIT_CR_STOPEN (0x00200000) //!< Bit mask for EPIT_CR_STOPEN.
|
||||
|
||||
//! @brief Get value of EPIT_CR_STOPEN from a register value.
|
||||
#define BG_EPIT_CR_STOPEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_STOPEN) >> BP_EPIT_CR_STOPEN)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_STOPEN.
|
||||
#define BF_EPIT_CR_STOPEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_STOPEN) & BM_EPIT_CR_STOPEN)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the STOPEN field to a new value.
|
||||
#define BW_EPIT_CR_STOPEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_STOPEN) | BF_EPIT_CR_STOPEN(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field OM[23:22] (RW)
|
||||
*
|
||||
* EPIT output mode.This bit field determines the mode of EPIT output on the output pin.
|
||||
*
|
||||
* Values:
|
||||
* - 00 - EPIT output is disconnected from pad
|
||||
* - 01 - Toggle output pin
|
||||
* - 10 - Clear output pin
|
||||
* - 11 - Set output pin
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_OM (22) //!< Bit position for EPIT_CR_OM.
|
||||
#define BM_EPIT_CR_OM (0x00c00000) //!< Bit mask for EPIT_CR_OM.
|
||||
|
||||
//! @brief Get value of EPIT_CR_OM from a register value.
|
||||
#define BG_EPIT_CR_OM(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_OM) >> BP_EPIT_CR_OM)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_OM.
|
||||
#define BF_EPIT_CR_OM(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_OM) & BM_EPIT_CR_OM)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the OM field to a new value.
|
||||
#define BW_EPIT_CR_OM(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_OM) | BF_EPIT_CR_OM(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*! @name Register EPIT_CR, field CLKSRC[25:24] (RW)
|
||||
*
|
||||
* Select clock source These bits determine which clock input is to be selected for running the
|
||||
* counter. This field value should only be changed when the EPIT is disabled by clearing the EN bit
|
||||
* in this register. For other programming requirements while changing clock source, refer to .
|
||||
*
|
||||
* Values:
|
||||
* - 00 - Clock is off
|
||||
* - 01 - Peripheral clock
|
||||
* - 10 - High-frequency reference clock
|
||||
* - 11 - Low-frequency reference clock
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CR_CLKSRC (24) //!< Bit position for EPIT_CR_CLKSRC.
|
||||
#define BM_EPIT_CR_CLKSRC (0x03000000) //!< Bit mask for EPIT_CR_CLKSRC.
|
||||
|
||||
//! @brief Get value of EPIT_CR_CLKSRC from a register value.
|
||||
#define BG_EPIT_CR_CLKSRC(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_CLKSRC) >> BP_EPIT_CR_CLKSRC)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CR_CLKSRC.
|
||||
#define BF_EPIT_CR_CLKSRC(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_CLKSRC) & BM_EPIT_CR_CLKSRC)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the CLKSRC field to a new value.
|
||||
#define BW_EPIT_CR_CLKSRC(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_CLKSRC) | BF_EPIT_CR_CLKSRC(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// HW_EPIT_SR - Status register
|
||||
//-------------------------------------------------------------------------------------------
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
/*!
|
||||
* @brief HW_EPIT_SR - Status register (RW)
|
||||
*
|
||||
* Reset value: 0x00000000
|
||||
*
|
||||
* The EPIT status register (EPIT_SR) has a single status bit for the output compare event. The bit
|
||||
* is a write 1 to clear bit.
|
||||
*/
|
||||
typedef union _hw_epit_sr {
|
||||
reg32_t U;
|
||||
struct _hw_epit_sr_bitfields {
|
||||
unsigned OCIF : 1; //!< [0] Output compare interrupt flag.
|
||||
unsigned RESERVED0 : 31; //!< [31:1] Reserved.
|
||||
} B;
|
||||
} hw_epit_sr_t;
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* @name Constants and macros for entire EPIT_SR register
|
||||
*/
|
||||
//@{
|
||||
#define HW_EPIT_SR_ADDR(x) (REGS_EPIT_BASE(x) + 0x4)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
#define HW_EPIT_SR(x) (*(volatile hw_epit_sr_t*)HW_EPIT_SR_ADDR(x))
|
||||
#define HW_EPIT_SR_RD(x) (HW_EPIT_SR(x).U)
|
||||
#define HW_EPIT_SR_WR(x, v) (HW_EPIT_SR(x).U = (v))
|
||||
#define HW_EPIT_SR_SET(x, v) (HW_EPIT_SR_WR(x, HW_EPIT_SR_RD(x) | (v)))
|
||||
#define HW_EPIT_SR_CLR(x, v) (HW_EPIT_SR_WR(x, HW_EPIT_SR_RD(x) & ~(v)))
|
||||
#define HW_EPIT_SR_TOG(x, v) (HW_EPIT_SR_WR(x, HW_EPIT_SR_RD(x) ^ (v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*
|
||||
* constants & macros for individual EPIT_SR bitfields
|
||||
*/
|
||||
|
||||
/*! @name Register EPIT_SR, field OCIF[0] (W1C)
|
||||
*
|
||||
* Output compare interrupt flag. This bit is the interrupt flag that is set when the content of
|
||||
* counter equals the content of the compare register (EPIT_CMPR). The bit is a write 1 to clear
|
||||
* bit.
|
||||
*
|
||||
* Values:
|
||||
* - 0 - Compare event has not occurred
|
||||
* - 1 - Compare event occurred
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_SR_OCIF (0) //!< Bit position for EPIT_SR_OCIF.
|
||||
#define BM_EPIT_SR_OCIF (0x00000001) //!< Bit mask for EPIT_SR_OCIF.
|
||||
|
||||
//! @brief Get value of EPIT_SR_OCIF from a register value.
|
||||
#define BG_EPIT_SR_OCIF(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_SR_OCIF) >> BP_EPIT_SR_OCIF)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_SR_OCIF.
|
||||
#define BF_EPIT_SR_OCIF(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_SR_OCIF) & BM_EPIT_SR_OCIF)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the OCIF field to a new value.
|
||||
#define BW_EPIT_SR_OCIF(x, v) (HW_EPIT_SR_WR(x, (HW_EPIT_SR_RD(x) & ~BM_EPIT_SR_OCIF) | BF_EPIT_SR_OCIF(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// HW_EPIT_LR - Load register
|
||||
//-------------------------------------------------------------------------------------------
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
/*!
|
||||
* @brief HW_EPIT_LR - Load register (RW)
|
||||
*
|
||||
* Reset value: 0xffffffff
|
||||
*
|
||||
* The EPIT load register (EPIT_LR) contains the value that is to be loaded into the counter when
|
||||
* EPIT counter reaches zero if the RLD bit in EPIT_CR is set. If the IOVW bit in the EPIT_CR is set
|
||||
* then a write to this register overwrites the value of the EPIT counter register in addition to
|
||||
* updating this registers value. This overwrite feature is active even if the RLD bit is not set.
|
||||
*/
|
||||
typedef union _hw_epit_lr {
|
||||
reg32_t U;
|
||||
struct _hw_epit_lr_bitfields {
|
||||
unsigned LOAD : 32; //!< [31:0] Load value.
|
||||
} B;
|
||||
} hw_epit_lr_t;
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* @name Constants and macros for entire EPIT_LR register
|
||||
*/
|
||||
//@{
|
||||
#define HW_EPIT_LR_ADDR(x) (REGS_EPIT_BASE(x) + 0x8)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
#define HW_EPIT_LR(x) (*(volatile hw_epit_lr_t*)HW_EPIT_LR_ADDR(x))
|
||||
#define HW_EPIT_LR_RD(x) (HW_EPIT_LR(x).U)
|
||||
#define HW_EPIT_LR_WR(x, v) (HW_EPIT_LR(x).U = (v))
|
||||
#define HW_EPIT_LR_SET(x, v) (HW_EPIT_LR_WR(x, HW_EPIT_LR_RD(x) | (v)))
|
||||
#define HW_EPIT_LR_CLR(x, v) (HW_EPIT_LR_WR(x, HW_EPIT_LR_RD(x) & ~(v)))
|
||||
#define HW_EPIT_LR_TOG(x, v) (HW_EPIT_LR_WR(x, HW_EPIT_LR_RD(x) ^ (v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*
|
||||
* constants & macros for individual EPIT_LR bitfields
|
||||
*/
|
||||
|
||||
/*! @name Register EPIT_LR, field LOAD[31:0] (RW)
|
||||
*
|
||||
* Load value. Value that is loaded into the counter at the start of each count cycle.
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_LR_LOAD (0) //!< Bit position for EPIT_LR_LOAD.
|
||||
#define BM_EPIT_LR_LOAD (0xffffffff) //!< Bit mask for EPIT_LR_LOAD.
|
||||
|
||||
//! @brief Get value of EPIT_LR_LOAD from a register value.
|
||||
#define BG_EPIT_LR_LOAD(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_LR_LOAD) >> BP_EPIT_LR_LOAD)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_LR_LOAD.
|
||||
#define BF_EPIT_LR_LOAD(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_LR_LOAD) & BM_EPIT_LR_LOAD)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the LOAD field to a new value.
|
||||
#define BW_EPIT_LR_LOAD(x, v) (HW_EPIT_LR_WR(x, (HW_EPIT_LR_RD(x) & ~BM_EPIT_LR_LOAD) | BF_EPIT_LR_LOAD(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// HW_EPIT_CMPR - Compare register
|
||||
//-------------------------------------------------------------------------------------------
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
/*!
|
||||
* @brief HW_EPIT_CMPR - Compare register (RW)
|
||||
*
|
||||
* Reset value: 0x00000000
|
||||
*
|
||||
* The EPIT compare register (EPIT_CMPR) holds the value that determines when a compare event is
|
||||
* generated.
|
||||
*/
|
||||
typedef union _hw_epit_cmpr {
|
||||
reg32_t U;
|
||||
struct _hw_epit_cmpr_bitfields {
|
||||
unsigned COMPARE : 32; //!< [31:0] Compare Value.
|
||||
} B;
|
||||
} hw_epit_cmpr_t;
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* @name Constants and macros for entire EPIT_CMPR register
|
||||
*/
|
||||
//@{
|
||||
#define HW_EPIT_CMPR_ADDR(x) (REGS_EPIT_BASE(x) + 0xc)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
#define HW_EPIT_CMPR(x) (*(volatile hw_epit_cmpr_t*)HW_EPIT_CMPR_ADDR(x))
|
||||
#define HW_EPIT_CMPR_RD(x) (HW_EPIT_CMPR(x).U)
|
||||
#define HW_EPIT_CMPR_WR(x, v) (HW_EPIT_CMPR(x).U = (v))
|
||||
#define HW_EPIT_CMPR_SET(x, v) (HW_EPIT_CMPR_WR(x, HW_EPIT_CMPR_RD(x) | (v)))
|
||||
#define HW_EPIT_CMPR_CLR(x, v) (HW_EPIT_CMPR_WR(x, HW_EPIT_CMPR_RD(x) & ~(v)))
|
||||
#define HW_EPIT_CMPR_TOG(x, v) (HW_EPIT_CMPR_WR(x, HW_EPIT_CMPR_RD(x) ^ (v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*
|
||||
* constants & macros for individual EPIT_CMPR bitfields
|
||||
*/
|
||||
|
||||
/*! @name Register EPIT_CMPR, field COMPARE[31:0] (RW)
|
||||
*
|
||||
* Compare Value. When the counter value equals this bit field value a compare event is generated.
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CMPR_COMPARE (0) //!< Bit position for EPIT_CMPR_COMPARE.
|
||||
#define BM_EPIT_CMPR_COMPARE (0xffffffff) //!< Bit mask for EPIT_CMPR_COMPARE.
|
||||
|
||||
//! @brief Get value of EPIT_CMPR_COMPARE from a register value.
|
||||
#define BG_EPIT_CMPR_COMPARE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CMPR_COMPARE) >> BP_EPIT_CMPR_COMPARE)
|
||||
|
||||
//! @brief Format value for bitfield EPIT_CMPR_COMPARE.
|
||||
#define BF_EPIT_CMPR_COMPARE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CMPR_COMPARE) & BM_EPIT_CMPR_COMPARE)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
//! @brief Set the COMPARE field to a new value.
|
||||
#define BW_EPIT_CMPR_COMPARE(x, v) (HW_EPIT_CMPR_WR(x, (HW_EPIT_CMPR_RD(x) & ~BM_EPIT_CMPR_COMPARE) | BF_EPIT_CMPR_COMPARE(v)))
|
||||
#endif
|
||||
//@}
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// HW_EPIT_CNR - Counter register
|
||||
//-------------------------------------------------------------------------------------------
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
/*!
|
||||
* @brief HW_EPIT_CNR - Counter register (RO)
|
||||
*
|
||||
* Reset value: 0xffffffff
|
||||
*
|
||||
* The EPIT counter register (EPIT_CNR) contains the current count value and can be read at any time
|
||||
* without disturbing the counter. This is a read-only register and any attempt to write into it
|
||||
* generates a transfer error. But if the IOVW bit in EPIT_CR is set, the value of this register can
|
||||
* be overwritten with a write to EPIT_LR. This change is reflected when this register is
|
||||
* subsequently read.
|
||||
*/
|
||||
typedef union _hw_epit_cnr {
|
||||
reg32_t U;
|
||||
struct _hw_epit_cnr_bitfields {
|
||||
unsigned COUNT : 32; //!< [31:0] Counter value.
|
||||
} B;
|
||||
} hw_epit_cnr_t;
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* @name Constants and macros for entire EPIT_CNR register
|
||||
*/
|
||||
//@{
|
||||
#define HW_EPIT_CNR_ADDR(x) (REGS_EPIT_BASE(x) + 0x10)
|
||||
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
#define HW_EPIT_CNR(x) (*(volatile hw_epit_cnr_t*)HW_EPIT_CNR_ADDR(x))
|
||||
#define HW_EPIT_CNR_RD(x) (HW_EPIT_CNR(x).U)
|
||||
#endif
|
||||
//@}
|
||||
|
||||
/*
|
||||
* constants & macros for individual EPIT_CNR bitfields
|
||||
*/
|
||||
|
||||
/*! @name Register EPIT_CNR, field COUNT[31:0] (RO)
|
||||
*
|
||||
* Counter value. This contains the current value of the counter.
|
||||
*/
|
||||
//@{
|
||||
#define BP_EPIT_CNR_COUNT (0) //!< Bit position for EPIT_CNR_COUNT.
|
||||
#define BM_EPIT_CNR_COUNT (0xffffffff) //!< Bit mask for EPIT_CNR_COUNT.
|
||||
|
||||
//! @brief Get value of EPIT_CNR_COUNT from a register value.
|
||||
#define BG_EPIT_CNR_COUNT(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CNR_COUNT) >> BP_EPIT_CNR_COUNT)
|
||||
//@}
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// hw_epit_t - module struct
|
||||
//-------------------------------------------------------------------------------------------
|
||||
/*!
|
||||
* @brief All EPIT module registers.
|
||||
*/
|
||||
#ifndef __LANGUAGE_ASM__
|
||||
#pragma pack(1)
|
||||
typedef struct _hw_epit {
|
||||
volatile hw_epit_cr_t CR; //!< Control register
|
||||
volatile hw_epit_sr_t SR; //!< Status register
|
||||
volatile hw_epit_lr_t LR; //!< Load register
|
||||
volatile hw_epit_cmpr_t CMPR; //!< Compare register
|
||||
volatile hw_epit_cnr_t CNR; //!< Counter register
|
||||
} hw_epit_t;
|
||||
#pragma pack()
|
||||
|
||||
//! @brief Macro to access all EPIT registers.
|
||||
//! @param x EPIT instance number.
|
||||
//! @return Reference (not a pointer) to the registers struct. To get a pointer to the struct,
|
||||
//! use the '&' operator, like <code>&HW_EPIT(0)</code>.
|
||||
#define HW_EPIT(x) (*(hw_epit_t*)REGS_EPIT_BASE(x))
|
||||
#endif
|
||||
|
||||
#endif // __HW_EPIT_REGISTERS_H__
|
||||
// v18/121106/1.2.2
|
||||
// EOF
|
||||
@@ -33,7 +33,7 @@ Modification:
|
||||
#define NO_INT 0x80 // disable IRQ.
|
||||
#define DIS_INT 0xc0 // disable both IRQ and FIQ.
|
||||
|
||||
#define MODE_STACK_SIZE 0x1000
|
||||
#define MODE_STACK_SIZE 0x2000
|
||||
|
||||
//! @name SPSR fields
|
||||
//@{
|
||||
@@ -75,6 +75,13 @@ Modification:
|
||||
|
||||
#define NR_CPU 4 // maximum number of CPUs
|
||||
|
||||
static inline uintptr_t arch_curr_tick()
|
||||
{
|
||||
uint64_t x;
|
||||
__asm__ volatile("mrs %0, cntpct_el0" : "=r"(x));
|
||||
return x;
|
||||
}
|
||||
|
||||
__attribute__((always_inline)) static inline uint64_t EL0_mode() // Set ARM mode to EL0
|
||||
{
|
||||
uint64_t val = 0;
|
||||
|
||||
@@ -15,21 +15,10 @@
|
||||
#define SPSR_EL2_VALUE (7 << 6) | (5 << 0)
|
||||
#define SCTLR_EL1_VALUE (0x30D00800)
|
||||
|
||||
/* Macros for MAIR setting. */
|
||||
#define MAIR(attr, mt) ((attr) << ((mt) * 8))
|
||||
#define MT_DEVICE_nGnRnE 0
|
||||
#define MT_DEVICE_nGnRE 1
|
||||
#define MT_DEVICE_GRE 2
|
||||
#define MT_NORMAL_NC 3
|
||||
#define MT_NORMAL 4
|
||||
#define MT_NORMAL_WT 5
|
||||
|
||||
.section ".text", "ax"
|
||||
.global _boot_start
|
||||
.global primary_cpu_init
|
||||
.global el2_setup
|
||||
/* The function for setting memory types and MAIR registers. */
|
||||
.global __cpu_mair_setup
|
||||
|
||||
_boot_start:
|
||||
bl el2_setup
|
||||
@@ -64,7 +53,6 @@ _boot_start:
|
||||
mov x5, x2
|
||||
cmp x5, #0
|
||||
beq primary_cpu_init
|
||||
bl __cpu_mair_setup
|
||||
bl bootmain // for secondary cpus, jump to argument function pointer passed in by ROM
|
||||
|
||||
bl .
|
||||
@@ -80,7 +68,6 @@ primary_cpu_init:
|
||||
stp x3, x3, [x1], #16
|
||||
b.lt 1b
|
||||
|
||||
bl __cpu_mair_setup
|
||||
bl bootmain
|
||||
|
||||
.func el2_setup
|
||||
@@ -130,39 +117,4 @@ el2_setup:
|
||||
eret
|
||||
.endfunc
|
||||
|
||||
.func __cpu_mair_setup
|
||||
__cpu_mair_setup:
|
||||
tlbi vmalle1 // Invalidate local TLB
|
||||
dsb nsh
|
||||
|
||||
// mov x0, #3 << 20
|
||||
// msr cpacr_el1, x0 // Enable FP/ASIMD
|
||||
// mov x0, #1 << 12 // Reset mdscr_el1 and disable
|
||||
// msr mdscr_el1, x0 // access to the DCC from EL0
|
||||
isb // Unmask debug exceptions now,
|
||||
// enable_dbg // since this is per-cpu
|
||||
/*
|
||||
* Memory region attributes for LPAE:
|
||||
*
|
||||
* n = AttrIndx[2:0]
|
||||
* n MAIR
|
||||
* DEVICE_nGnRnE 000 00000000
|
||||
* DEVICE_nGnRE 001 00000100
|
||||
* DEVICE_GRE 010 00001100
|
||||
* NORMAL_NC 011 01000100
|
||||
* NORMAL 100 11111111
|
||||
* NORMAL_WT 101 10111011
|
||||
*/
|
||||
ldr x5, =MAIR(0x00, MT_DEVICE_nGnRnE) | \
|
||||
MAIR(0x04, MT_DEVICE_nGnRE) | \
|
||||
MAIR(0x0c, MT_DEVICE_GRE) | \
|
||||
MAIR(0x44, MT_NORMAL_NC) | \
|
||||
MAIR(0xff, MT_NORMAL) | \
|
||||
MAIR(0xbb, MT_NORMAL_WT)
|
||||
msr mair_el1, x5
|
||||
|
||||
ret
|
||||
.endfunc
|
||||
|
||||
|
||||
.end
|
||||
5
Ubiquitous/XiZi_AIoT/hardkernel/arch/riscv/Makefile
Normal file
5
Ubiquitous/XiZi_AIoT/hardkernel/arch/riscv/Makefile
Normal file
@@ -0,0 +1,5 @@
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := rv64gc
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,4 @@
|
||||
SRC_DIR := preboot_for_$(BOARD)
|
||||
SRC_FILES := context_switch.S core.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,69 @@
|
||||
/*
|
||||
* 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 context_switch.S
|
||||
* @brief task context switch functions
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.4.10
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: context_switch.S
|
||||
Description: task context switch functions
|
||||
Others:
|
||||
History:
|
||||
*************************************************/
|
||||
|
||||
/*
|
||||
* Integer register context switch
|
||||
* The callee-saved registers must be saved and restored.
|
||||
*
|
||||
* a0: previous thread_struct (must be preserved across the switch)
|
||||
* a1: next thread_struct
|
||||
*
|
||||
*/
|
||||
.global context_switch
|
||||
|
||||
context_switch:
|
||||
sd ra, 0(a0)
|
||||
sd sp, 8(a0)
|
||||
sd s0, 16(a0)
|
||||
sd s1, 24(a0)
|
||||
sd s2, 32(a0)
|
||||
sd s3, 40(a0)
|
||||
sd s4, 48(a0)
|
||||
sd s5, 56(a0)
|
||||
sd s6, 64(a0)
|
||||
sd s7, 72(a0)
|
||||
sd s8, 80(a0)
|
||||
sd s9, 88(a0)
|
||||
sd s10, 96(a0)
|
||||
sd s11, 104(a0)
|
||||
|
||||
ld ra, 0(a1)
|
||||
ld sp, 8(a1)
|
||||
ld s0, 16(a1)
|
||||
ld s1, 24(a1)
|
||||
ld s2, 32(a1)
|
||||
ld s3, 40(a1)
|
||||
ld s4, 48(a1)
|
||||
ld s5, 56(a1)
|
||||
ld s6, 64(a1)
|
||||
ld s7, 72(a1)
|
||||
ld s8, 80(a1)
|
||||
ld s9, 88(a1)
|
||||
ld s10, 96(a1)
|
||||
ld s11, 104(a1)
|
||||
|
||||
mv tp, a1
|
||||
ret
|
||||
74
Ubiquitous/XiZi_AIoT/hardkernel/arch/riscv/rv64gc/core.c
Normal file
74
Ubiquitous/XiZi_AIoT/hardkernel/arch/riscv/rv64gc/core.c
Normal file
@@ -0,0 +1,74 @@
|
||||
/*
|
||||
* 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 core.c
|
||||
* @brief spl boot function
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.04.23
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: core.c
|
||||
Description: cortex-a9 core function, include cpu registers operations、core boot
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2024-04-23
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. first version
|
||||
*************************************************/
|
||||
|
||||
/*********cortex-a55 general register************
|
||||
EL0 | EL1 | EL2 | EL3
|
||||
|
||||
x0;
|
||||
x1;
|
||||
x2;
|
||||
x3;
|
||||
x4;
|
||||
x5;
|
||||
x6;
|
||||
x7;
|
||||
x8;
|
||||
x9;
|
||||
x10;
|
||||
x11;
|
||||
x12;
|
||||
x13;
|
||||
x14;
|
||||
x15;
|
||||
x16;
|
||||
x17;
|
||||
x18;
|
||||
x19;
|
||||
x20;
|
||||
x21;
|
||||
x22;
|
||||
x23;
|
||||
x24;
|
||||
x25;
|
||||
x26;
|
||||
x27;
|
||||
x28;
|
||||
x29;
|
||||
x30;
|
||||
*********cortex-a55 special register************
|
||||
XZR
|
||||
PC
|
||||
SP_EL0 SP_EL1 SP_EL2 SP_EL3
|
||||
SPSR_EL1 SPSR_EL2 SPSR_EL3
|
||||
ELR_EL1 ELR_EL2 ELR_EL3
|
||||
************************************************/
|
||||
|
||||
#include "core.h"
|
||||
220
Ubiquitous/XiZi_AIoT/hardkernel/arch/riscv/rv64gc/core.h
Normal file
220
Ubiquitous/XiZi_AIoT/hardkernel/arch/riscv/rv64gc/core.h
Normal file
@@ -0,0 +1,220 @@
|
||||
/*
|
||||
* 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 core.h
|
||||
* @brief cortex-a55 core function
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.04.11
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: core.h
|
||||
Description: cortex-a55 core function
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
*************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
// Interrupt control bits
|
||||
#define NO_INT 0x80 // disable IRQ.
|
||||
#define DIS_INT 0xc0 // disable both IRQ and FIQ.
|
||||
|
||||
#define MODE_STACK_SIZE 0x1000
|
||||
|
||||
//! @name SPSR fields
|
||||
//@{
|
||||
#define SPSR_EL1_N (1 << 31) //!< Negative
|
||||
#define SPSR_EL1_Z (1 << 30) //!< Zero
|
||||
#define SPSR_EL1_C (1 << 29) //!< Carry
|
||||
#define SPSR_EL1_V (1 << 28) //!< Overflow
|
||||
#define SPSR_EL1_SS (1 << 21) //!< Software Step
|
||||
#define SPSR_EL1_IL (1 << 20) //!< Illegal Exception
|
||||
#define SPSR_EL1_D (1 << 9) //!< Debug mask
|
||||
#define SPSR_EL1_A (1 << 8) //!< SError mask
|
||||
#define SPSR_EL1_I (1 << 7) //!< IRQ mask
|
||||
#define SPSR_EL1_F (1 << 6) //!< FIQ mask
|
||||
#define SPSR_EL1_M (1 << 4) //!< Execution state 0=64-bit 1=32-bit
|
||||
#define SPSR_EL1_MODE (0x7) //!< Current processor mode
|
||||
//@}
|
||||
|
||||
//! @name Interrupt enable bits in SPSR
|
||||
//@{
|
||||
#define I_BIT 0x80 //!< When I bit is set, IRQ is disabled
|
||||
#define F_BIT 0x40 //!< When F bit is set, FIQ is disabled
|
||||
//@}
|
||||
|
||||
// ARM Modes t indicates selecting sp_el0 pointer, h indicates selecting sp_eln pointer
|
||||
#define SPSR_MODE_MASK 0x0f
|
||||
#define ARM_MODE_EL0_t 0x00
|
||||
#define ARM_MODE_EL1_t 0x04
|
||||
#define ARM_MODE_EL1_h 0x05
|
||||
#define ARM_MODE_EL2_t 0x08
|
||||
#define ARM_MODE_EL2_h 0x09
|
||||
#define ARM_MODE_EL3_t 0x0c
|
||||
#define ARM_MODE_EL3_h 0x0d
|
||||
|
||||
#ifndef __ASSEMBLER__
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "cortex.h"
|
||||
#include "asm/csr.h"
|
||||
|
||||
|
||||
#define NR_CPU 1 // maximum number of CPUs
|
||||
|
||||
|
||||
struct __riscv_d_ext_state {
|
||||
uint64_t f[32];
|
||||
uint32_t fcsr;
|
||||
};
|
||||
/* Refer to struct thread_struct in Linux */
|
||||
/* CPU-specific state of a task */
|
||||
struct context {
|
||||
/* Callee-saved registers */
|
||||
unsigned long ra;
|
||||
unsigned long sp; /* Kernel mode stack */
|
||||
unsigned long s[12]; /* s[0]: frame pointer */
|
||||
struct __riscv_d_ext_state fstate;
|
||||
unsigned long bad_cause;
|
||||
};
|
||||
|
||||
/// @brief init task context, set return address to trap return
|
||||
/// @param ctx
|
||||
extern void task_prepare_enter(void);
|
||||
__attribute__((__always_inline__)) static inline void arch_init_context(struct context* ctx)
|
||||
{
|
||||
memset(ctx, 0, sizeof(*ctx));
|
||||
ctx->ra = (uintptr_t)(task_prepare_enter);
|
||||
}
|
||||
|
||||
__attribute__((__always_inline__)) static inline void arch_context_set_sp(struct context* ctx, unsigned long sp)
|
||||
{
|
||||
ctx->sp = sp;
|
||||
}
|
||||
|
||||
/* Refer to struct pt_regs in Linux */
|
||||
struct trapframe {
|
||||
unsigned long epc;
|
||||
unsigned long ra;
|
||||
unsigned long sp;
|
||||
unsigned long gp;
|
||||
unsigned long tp;
|
||||
unsigned long t0;
|
||||
unsigned long t1;
|
||||
unsigned long t2;
|
||||
unsigned long s0;
|
||||
unsigned long s1;
|
||||
unsigned long a0;
|
||||
unsigned long a1;
|
||||
unsigned long a2;
|
||||
unsigned long a3;
|
||||
unsigned long a4;
|
||||
unsigned long a5;
|
||||
unsigned long a6;
|
||||
unsigned long a7;
|
||||
unsigned long s2;
|
||||
unsigned long s3;
|
||||
unsigned long s4;
|
||||
unsigned long s5;
|
||||
unsigned long s6;
|
||||
unsigned long s7;
|
||||
unsigned long s8;
|
||||
unsigned long s9;
|
||||
unsigned long s10;
|
||||
unsigned long s11;
|
||||
unsigned long t3;
|
||||
unsigned long t4;
|
||||
unsigned long t5;
|
||||
unsigned long t6;
|
||||
/* Supervisor/Machine CSRs */
|
||||
unsigned long status;
|
||||
unsigned long badaddr;
|
||||
unsigned long cause;
|
||||
/* a0 value before the syscall */
|
||||
unsigned long orig_a0;
|
||||
};
|
||||
|
||||
/// @brief init task trapframe
|
||||
/// @param tf
|
||||
/// @param sp
|
||||
/// @param pc
|
||||
__attribute__((__always_inline__)) static inline void arch_init_trapframe(struct trapframe* tf, uintptr_t sp, uintptr_t pc)
|
||||
{
|
||||
memset(tf, 0, sizeof(*tf));
|
||||
tf->sp = sp;
|
||||
tf->epc = pc;
|
||||
tf->status = SR_PIE;
|
||||
}
|
||||
|
||||
/// @brief set pc and sp to trapframe
|
||||
/// @param tf
|
||||
/// @param sp
|
||||
/// @param pc
|
||||
__attribute__((__always_inline__)) static inline void arch_trapframe_set_sp_pc(struct trapframe* tf, uintptr_t sp, uintptr_t pc)
|
||||
{
|
||||
tf->sp = sp;
|
||||
tf->epc = pc;
|
||||
}
|
||||
|
||||
/// @brief set params of main(int argc, char** argv) to trapframe (argc, argv)
|
||||
/// @param tf
|
||||
/// @param argc
|
||||
/// @param argv
|
||||
__attribute__((__always_inline__)) static inline void arch_set_main_params(struct trapframe* tf, int argc, uintptr_t argv)
|
||||
{
|
||||
tf->a0 = (uint64_t)argc;
|
||||
tf->a1 = (uint64_t)argv;
|
||||
}
|
||||
|
||||
/// @brief retrieve params to trapframe (up to max number of 6) and pass it to syscall()
|
||||
/// @param sys_num
|
||||
/// @param param1
|
||||
/// @param param2
|
||||
/// @param param3
|
||||
/// @param param4
|
||||
/// @param param5
|
||||
/// @return
|
||||
extern int syscall(int sys_num, uintptr_t param1, uintptr_t param2, uintptr_t param3, uintptr_t param4);
|
||||
__attribute__((__always_inline__)) static inline int arch_syscall(struct trapframe* tf, int* syscall_num)
|
||||
{
|
||||
// call syscall
|
||||
*syscall_num = tf->a7;
|
||||
return syscall(*syscall_num, tf->a0, tf->a1, tf->a2, tf->a3);
|
||||
}
|
||||
|
||||
/// @brief set return reg to trapframe
|
||||
/// @param tf
|
||||
/// @param ret
|
||||
__attribute__((__always_inline__)) static inline void arch_set_return(struct trapframe* tf, int ret)
|
||||
{
|
||||
tf->a0 = (uint64_t)ret;
|
||||
}
|
||||
|
||||
// TODO: refer to jh7110 Linux
|
||||
struct thread_info {
|
||||
unsigned long flags; /* low level flags */
|
||||
long preempt_count; /* 0=>preemptible, <0=>BUG */
|
||||
long kernel_sp; /* Kernel stack pointer */
|
||||
long user_sp; /* User stack pointer */
|
||||
long cpu;
|
||||
};
|
||||
|
||||
|
||||
void cpu_start_secondary(uint8_t cpu_id);
|
||||
void start_smp_cache_broadcast(int cpu_id);
|
||||
#endif
|
||||
@@ -0,0 +1,44 @@
|
||||
#ifndef __ASM_OFFSETS_H__
|
||||
#define __ASM_OFFSETS_H__
|
||||
|
||||
#define PT_SIZE 288 /* sizeof(struct pt_regs) */
|
||||
#define PT_EPC 0 /* offsetof(struct pt_regs, epc) */
|
||||
#define PT_RA 8 /* offsetof(struct pt_regs, ra) */
|
||||
#define PT_FP 64 /* offsetof(struct pt_regs, s0) */
|
||||
#define PT_S0 64 /* offsetof(struct pt_regs, s0) */
|
||||
#define PT_S1 72 /* offsetof(struct pt_regs, s1) */
|
||||
#define PT_S2 144 /* offsetof(struct pt_regs, s2) */
|
||||
#define PT_S3 152 /* offsetof(struct pt_regs, s3) */
|
||||
#define PT_S4 160 /* offsetof(struct pt_regs, s4) */
|
||||
#define PT_S5 168 /* offsetof(struct pt_regs, s5) */
|
||||
#define PT_S6 176 /* offsetof(struct pt_regs, s6) */
|
||||
#define PT_S7 184 /* offsetof(struct pt_regs, s7) */
|
||||
#define PT_S8 192 /* offsetof(struct pt_regs, s8) */
|
||||
#define PT_S9 200 /* offsetof(struct pt_regs, s9) */
|
||||
#define PT_S10 208 /* offsetof(struct pt_regs, s10) */
|
||||
#define PT_S11 216 /* offsetof(struct pt_regs, s11) */
|
||||
#define PT_SP 16 /* offsetof(struct pt_regs, sp) */
|
||||
#define PT_TP 32 /* offsetof(struct pt_regs, tp) */
|
||||
#define PT_A0 80 /* offsetof(struct pt_regs, a0) */
|
||||
#define PT_A1 88 /* offsetof(struct pt_regs, a1) */
|
||||
#define PT_A2 96 /* offsetof(struct pt_regs, a2) */
|
||||
#define PT_A3 104 /* offsetof(struct pt_regs, a3) */
|
||||
#define PT_A4 112 /* offsetof(struct pt_regs, a4) */
|
||||
#define PT_A5 120 /* offsetof(struct pt_regs, a5) */
|
||||
#define PT_A6 128 /* offsetof(struct pt_regs, a6) */
|
||||
#define PT_A7 136 /* offsetof(struct pt_regs, a7) */
|
||||
#define PT_T0 40 /* offsetof(struct pt_regs, t0) */
|
||||
#define PT_T1 48 /* offsetof(struct pt_regs, t1) */
|
||||
#define PT_T2 56 /* offsetof(struct pt_regs, t2) */
|
||||
#define PT_T3 224 /* offsetof(struct pt_regs, t3) */
|
||||
#define PT_T4 232 /* offsetof(struct pt_regs, t4) */
|
||||
#define PT_T5 240 /* offsetof(struct pt_regs, t5) */
|
||||
#define PT_T6 248 /* offsetof(struct pt_regs, t6) */
|
||||
#define PT_GP 24 /* offsetof(struct pt_regs, gp) */
|
||||
#define PT_ORIG_A0 280 /* offsetof(struct pt_regs, orig_a0) */
|
||||
#define PT_STATUS 256 /* offsetof(struct pt_regs, status) */
|
||||
#define PT_BADADDR 264 /* offsetof(struct pt_regs, badaddr) */
|
||||
#define PT_CAUSE 272 /* offsetof(struct pt_regs, cause) */
|
||||
#define PT_SIZE_ON_STACK 288 /* ALIGN(sizeof(struct pt_regs), STACK_ALIGN) */
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,41 @@
|
||||
/* SPDX-License-Identifier: GPL-2.0-only */
|
||||
/*
|
||||
* Copyright (C) 2015 Regents of the University of California
|
||||
*/
|
||||
|
||||
#ifndef _ASM_RISCV_ASM_H
|
||||
#define _ASM_RISCV_ASM_H
|
||||
|
||||
//#define __ASSEMBLY__
|
||||
|
||||
#ifdef __ASSEMBLY__
|
||||
#define __ASM_STR(x) x
|
||||
#else
|
||||
#define __ASM_STR(x) #x
|
||||
#endif
|
||||
|
||||
|
||||
#define REG_L ld
|
||||
#define REG_S sd
|
||||
#define REG_SC sc.d
|
||||
#define REG_ASM .dword
|
||||
#define SZREG 8
|
||||
#define LGREG 3
|
||||
|
||||
|
||||
#define RISCV_PTR .dword
|
||||
#define RISCV_SZPTR 8
|
||||
#define RISCV_LGPTR 3
|
||||
|
||||
|
||||
#define RISCV_INT __ASM_STR(.word)
|
||||
#define RISCV_SZINT __ASM_STR(4)
|
||||
#define RISCV_LGINT __ASM_STR(2)
|
||||
|
||||
|
||||
#define RISCV_SHORT __ASM_STR(.half)
|
||||
#define RISCV_SZSHORT __ASM_STR(2)
|
||||
#define RISCV_LGSHORT __ASM_STR(1)
|
||||
|
||||
|
||||
#endif /* _ASM_RISCV_ASM_H */
|
||||
@@ -0,0 +1,39 @@
|
||||
/* SPDX-License-Identifier: GPL-2.0 WITH Linux-syscall-note */
|
||||
/* const.h: Macros for dealing with constants. */
|
||||
|
||||
#ifndef _UAPI_LINUX_CONST_H
|
||||
#define _UAPI_LINUX_CONST_H
|
||||
|
||||
/* Some constant macros are used in both assembler and
|
||||
* C code. Therefore we cannot annotate them always with
|
||||
* 'UL' and other type specifiers unilaterally. We
|
||||
* use the following macros to deal with this.
|
||||
*
|
||||
* Similarly, _AT() will cast an expression with a type in C, but
|
||||
* leave it unchanged in asm.
|
||||
*/
|
||||
|
||||
//#ifdef __ASSEMBLY__
|
||||
#if 0
|
||||
#define _AC(X,Y) X
|
||||
#define _AT(T,X) X
|
||||
#else
|
||||
#define __AC(X,Y) (X##Y)
|
||||
#define _AC(X,Y) __AC(X,Y)
|
||||
#define _AT(T,X) ((T)(X))
|
||||
#endif
|
||||
|
||||
#define _UL(x) (_AC(x, UL))
|
||||
#define _ULL(x) (_AC(x, ULL))
|
||||
#define UL(x) (_UL(x))
|
||||
#define ULL(x) (_ULL(x))
|
||||
|
||||
#define _BITUL(x) (_UL(1) << (x))
|
||||
#define _BITULL(x) (_ULL(1) << (x))
|
||||
|
||||
#define __ALIGN_KERNEL(x, a) __ALIGN_KERNEL_MASK(x, (typeof(x))(a) - 1)
|
||||
#define __ALIGN_KERNEL_MASK(x, mask) (((x) + (mask)) & ~(mask))
|
||||
|
||||
#define __KERNEL_DIV_ROUND_UP(n, d) (((n) + (d) - 1) / (d))
|
||||
|
||||
#endif /* _UAPI_LINUX_CONST_H */
|
||||
@@ -0,0 +1,295 @@
|
||||
/* SPDX-License-Identifier: GPL-2.0-only */
|
||||
/*
|
||||
* Copyright (C) 2015 Regents of the University of California
|
||||
*/
|
||||
|
||||
#ifndef _ASM_RISCV_CSR_H
|
||||
#define _ASM_RISCV_CSR_H
|
||||
|
||||
#include <asm/asm.h>
|
||||
#include <asm/const.h>
|
||||
|
||||
|
||||
#define CONFIG_64BIT 1
|
||||
|
||||
/* Status register flags */
|
||||
#define SR_SIE _AC(0x00000002, UL) /* Supervisor Interrupt Enable */
|
||||
#define SR_MIE _AC(0x00000008, UL) /* Machine Interrupt Enable */
|
||||
#define SR_SPIE _AC(0x00000020, UL) /* Previous Supervisor IE */
|
||||
#define SR_MPIE _AC(0x00000080, UL) /* Previous Machine IE */
|
||||
#define SR_SPP _AC(0x00000100, UL) /* Previously Supervisor */
|
||||
#define SR_MPP _AC(0x00001800, UL) /* Previously Machine */
|
||||
#define SR_SUM _AC(0x00040000, UL) /* Supervisor User Memory Access */
|
||||
|
||||
#define SR_FS _AC(0x00006000, UL) /* Floating-point Status */
|
||||
#define SR_FS_OFF _AC(0x00000000, UL)
|
||||
#define SR_FS_INITIAL _AC(0x00002000, UL)
|
||||
#define SR_FS_CLEAN _AC(0x00004000, UL)
|
||||
#define SR_FS_DIRTY _AC(0x00006000, UL)
|
||||
|
||||
#define SR_XS _AC(0x00018000, UL) /* Extension Status */
|
||||
#define SR_XS_OFF _AC(0x00000000, UL)
|
||||
#define SR_XS_INITIAL _AC(0x00008000, UL)
|
||||
#define SR_XS_CLEAN _AC(0x00010000, UL)
|
||||
#define SR_XS_DIRTY _AC(0x00018000, UL)
|
||||
|
||||
#ifndef CONFIG_64BIT
|
||||
#define SR_SD _AC(0x80000000, UL) /* FS/XS dirty */
|
||||
#else
|
||||
#define SR_SD _AC(0x8000000000000000, UL) /* FS/XS dirty */
|
||||
#endif
|
||||
|
||||
/* SATP flags */
|
||||
#ifndef CONFIG_64BIT
|
||||
#define SATP_PPN _AC(0x003FFFFF, UL)
|
||||
#define SATP_MODE_32 _AC(0x80000000, UL)
|
||||
#define SATP_MODE SATP_MODE_32
|
||||
#define SATP_ASID_BITS 9
|
||||
#define SATP_ASID_SHIFT 22
|
||||
#define SATP_ASID_MASK _AC(0x1FF, UL)
|
||||
#else
|
||||
#define SATP_PPN _AC(0x00000FFFFFFFFFFF, UL)
|
||||
#define SATP_MODE_39 _AC(0x8000000000000000, UL)
|
||||
#define SATP_MODE SATP_MODE_39
|
||||
#define SATP_ASID_BITS 16
|
||||
#define SATP_ASID_SHIFT 44
|
||||
#define SATP_ASID_MASK _AC(0xFFFF, UL)
|
||||
#endif
|
||||
|
||||
/* Exception cause high bit - is an interrupt if set */
|
||||
#define CAUSE_IRQ_FLAG (_AC(1, UL) << (__riscv_xlen - 1))
|
||||
|
||||
/* Interrupt causes (minus the high bit) */
|
||||
#define IRQ_S_SOFT 1
|
||||
#define IRQ_M_SOFT 3
|
||||
#define IRQ_S_TIMER 5
|
||||
#define IRQ_M_TIMER 7
|
||||
#define IRQ_S_EXT 9
|
||||
#define IRQ_M_EXT 11
|
||||
#define IRQ_PMU_OVF 13
|
||||
|
||||
/* Exception causes */
|
||||
#define EXC_INST_MISALIGNED 0
|
||||
#define EXC_INST_ACCESS 1
|
||||
#define EXC_BREAKPOINT 3
|
||||
#define EXC_LOAD_ACCESS 5
|
||||
#define EXC_STORE_ACCESS 7
|
||||
#define EXC_SYSCALL 8
|
||||
#define EXC_INST_PAGE_FAULT 12
|
||||
#define EXC_LOAD_PAGE_FAULT 13
|
||||
#define EXC_STORE_PAGE_FAULT 15
|
||||
|
||||
/* PMP configuration */
|
||||
#define PMP_R 0x01
|
||||
#define PMP_W 0x02
|
||||
#define PMP_X 0x04
|
||||
#define PMP_A 0x18
|
||||
#define PMP_A_TOR 0x08
|
||||
#define PMP_A_NA4 0x10
|
||||
#define PMP_A_NAPOT 0x18
|
||||
#define PMP_L 0x80
|
||||
|
||||
/* symbolic CSR names: */
|
||||
#define CSR_CYCLE 0xc00
|
||||
#define CSR_TIME 0xc01
|
||||
#define CSR_INSTRET 0xc02
|
||||
#define CSR_HPMCOUNTER3 0xc03
|
||||
#define CSR_HPMCOUNTER4 0xc04
|
||||
#define CSR_HPMCOUNTER5 0xc05
|
||||
#define CSR_HPMCOUNTER6 0xc06
|
||||
#define CSR_HPMCOUNTER7 0xc07
|
||||
#define CSR_HPMCOUNTER8 0xc08
|
||||
#define CSR_HPMCOUNTER9 0xc09
|
||||
#define CSR_HPMCOUNTER10 0xc0a
|
||||
#define CSR_HPMCOUNTER11 0xc0b
|
||||
#define CSR_HPMCOUNTER12 0xc0c
|
||||
#define CSR_HPMCOUNTER13 0xc0d
|
||||
#define CSR_HPMCOUNTER14 0xc0e
|
||||
#define CSR_HPMCOUNTER15 0xc0f
|
||||
#define CSR_HPMCOUNTER16 0xc10
|
||||
#define CSR_HPMCOUNTER17 0xc11
|
||||
#define CSR_HPMCOUNTER18 0xc12
|
||||
#define CSR_HPMCOUNTER19 0xc13
|
||||
#define CSR_HPMCOUNTER20 0xc14
|
||||
#define CSR_HPMCOUNTER21 0xc15
|
||||
#define CSR_HPMCOUNTER22 0xc16
|
||||
#define CSR_HPMCOUNTER23 0xc17
|
||||
#define CSR_HPMCOUNTER24 0xc18
|
||||
#define CSR_HPMCOUNTER25 0xc19
|
||||
#define CSR_HPMCOUNTER26 0xc1a
|
||||
#define CSR_HPMCOUNTER27 0xc1b
|
||||
#define CSR_HPMCOUNTER28 0xc1c
|
||||
#define CSR_HPMCOUNTER29 0xc1d
|
||||
#define CSR_HPMCOUNTER30 0xc1e
|
||||
#define CSR_HPMCOUNTER31 0xc1f
|
||||
#define CSR_CYCLEH 0xc80
|
||||
#define CSR_TIMEH 0xc81
|
||||
#define CSR_INSTRETH 0xc82
|
||||
#define CSR_HPMCOUNTER3H 0xc83
|
||||
#define CSR_HPMCOUNTER4H 0xc84
|
||||
#define CSR_HPMCOUNTER5H 0xc85
|
||||
#define CSR_HPMCOUNTER6H 0xc86
|
||||
#define CSR_HPMCOUNTER7H 0xc87
|
||||
#define CSR_HPMCOUNTER8H 0xc88
|
||||
#define CSR_HPMCOUNTER9H 0xc89
|
||||
#define CSR_HPMCOUNTER10H 0xc8a
|
||||
#define CSR_HPMCOUNTER11H 0xc8b
|
||||
#define CSR_HPMCOUNTER12H 0xc8c
|
||||
#define CSR_HPMCOUNTER13H 0xc8d
|
||||
#define CSR_HPMCOUNTER14H 0xc8e
|
||||
#define CSR_HPMCOUNTER15H 0xc8f
|
||||
#define CSR_HPMCOUNTER16H 0xc90
|
||||
#define CSR_HPMCOUNTER17H 0xc91
|
||||
#define CSR_HPMCOUNTER18H 0xc92
|
||||
#define CSR_HPMCOUNTER19H 0xc93
|
||||
#define CSR_HPMCOUNTER20H 0xc94
|
||||
#define CSR_HPMCOUNTER21H 0xc95
|
||||
#define CSR_HPMCOUNTER22H 0xc96
|
||||
#define CSR_HPMCOUNTER23H 0xc97
|
||||
#define CSR_HPMCOUNTER24H 0xc98
|
||||
#define CSR_HPMCOUNTER25H 0xc99
|
||||
#define CSR_HPMCOUNTER26H 0xc9a
|
||||
#define CSR_HPMCOUNTER27H 0xc9b
|
||||
#define CSR_HPMCOUNTER28H 0xc9c
|
||||
#define CSR_HPMCOUNTER29H 0xc9d
|
||||
#define CSR_HPMCOUNTER30H 0xc9e
|
||||
#define CSR_HPMCOUNTER31H 0xc9f
|
||||
|
||||
#define CSR_SSCOUNTOVF 0xda0
|
||||
|
||||
#define CSR_SSTATUS 0x100
|
||||
#define CSR_SIE 0x104
|
||||
#define CSR_STVEC 0x105
|
||||
#define CSR_SCOUNTEREN 0x106
|
||||
#define CSR_SSCRATCH 0x140
|
||||
#define CSR_SEPC 0x141
|
||||
#define CSR_SCAUSE 0x142
|
||||
#define CSR_STVAL 0x143
|
||||
#define CSR_SIP 0x144
|
||||
#define CSR_SATP 0x180
|
||||
|
||||
#define CSR_MSTATUS 0x300
|
||||
#define CSR_MISA 0x301
|
||||
#define CSR_MIE 0x304
|
||||
#define CSR_MTVEC 0x305
|
||||
#define CSR_MSCRATCH 0x340
|
||||
#define CSR_MEPC 0x341
|
||||
#define CSR_MCAUSE 0x342
|
||||
#define CSR_MTVAL 0x343
|
||||
#define CSR_MIP 0x344
|
||||
#define CSR_PMPCFG0 0x3a0
|
||||
#define CSR_PMPADDR0 0x3b0
|
||||
#define CSR_MVENDORID 0xf11
|
||||
#define CSR_MARCHID 0xf12
|
||||
#define CSR_MIMPID 0xf13
|
||||
#define CSR_MHARTID 0xf14
|
||||
|
||||
#ifdef CONFIG_RISCV_M_MODE
|
||||
# define CSR_STATUS CSR_MSTATUS
|
||||
# define CSR_IE CSR_MIE
|
||||
# define CSR_TVEC CSR_MTVEC
|
||||
# define CSR_SCRATCH CSR_MSCRATCH
|
||||
# define CSR_EPC CSR_MEPC
|
||||
# define CSR_CAUSE CSR_MCAUSE
|
||||
# define CSR_TVAL CSR_MTVAL
|
||||
# define CSR_IP CSR_MIP
|
||||
|
||||
# define SR_IE SR_MIE
|
||||
# define SR_PIE SR_MPIE
|
||||
# define SR_PP SR_MPP
|
||||
|
||||
# define RV_IRQ_SOFT IRQ_M_SOFT
|
||||
# define RV_IRQ_TIMER IRQ_M_TIMER
|
||||
# define RV_IRQ_EXT IRQ_M_EXT
|
||||
#else /* CONFIG_RISCV_M_MODE */
|
||||
# define CSR_STATUS CSR_SSTATUS
|
||||
# define CSR_IE CSR_SIE
|
||||
# define CSR_TVEC CSR_STVEC
|
||||
# define CSR_SCRATCH CSR_SSCRATCH
|
||||
# define CSR_EPC CSR_SEPC
|
||||
# define CSR_CAUSE CSR_SCAUSE
|
||||
# define CSR_TVAL CSR_STVAL
|
||||
# define CSR_IP CSR_SIP
|
||||
|
||||
# define SR_IE SR_SIE
|
||||
# define SR_PIE SR_SPIE
|
||||
# define SR_PP SR_SPP
|
||||
|
||||
# define RV_IRQ_SOFT IRQ_S_SOFT
|
||||
# define RV_IRQ_TIMER IRQ_S_TIMER
|
||||
# define RV_IRQ_EXT IRQ_S_EXT
|
||||
# define RV_IRQ_PMU IRQ_PMU_OVF
|
||||
# define SIP_LCOFIP (_AC(0x1, UL) << IRQ_PMU_OVF)
|
||||
|
||||
#endif /* !CONFIG_RISCV_M_MODE */
|
||||
|
||||
/* IE/IP (Supervisor/Machine Interrupt Enable/Pending) flags */
|
||||
#define IE_SIE (_AC(0x1, UL) << RV_IRQ_SOFT)
|
||||
#define IE_TIE (_AC(0x1, UL) << RV_IRQ_TIMER)
|
||||
#define IE_EIE (_AC(0x1, UL) << RV_IRQ_EXT)
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#define csr_swap(csr, val) \
|
||||
({ \
|
||||
unsigned long __v = (unsigned long)(val); \
|
||||
__asm__ __volatile__ ("csrrw %0, " __ASM_STR(csr) ", %1"\
|
||||
: "=r" (__v) : "rK" (__v) \
|
||||
: "memory"); \
|
||||
__v; \
|
||||
})
|
||||
|
||||
#define csr_read(csr) \
|
||||
({ \
|
||||
register unsigned long __v; \
|
||||
__asm__ __volatile__ ("csrr %0, " __ASM_STR(csr) \
|
||||
: "=r" (__v) : \
|
||||
: "memory"); \
|
||||
__v; \
|
||||
})
|
||||
|
||||
#define csr_write(csr, val) \
|
||||
({ \
|
||||
unsigned long __v = (unsigned long)(val); \
|
||||
__asm__ __volatile__ ("csrw " __ASM_STR(csr) ", %0" \
|
||||
: : "rK" (__v) \
|
||||
: "memory"); \
|
||||
})
|
||||
|
||||
#define csr_read_set(csr, val) \
|
||||
({ \
|
||||
unsigned long __v = (unsigned long)(val); \
|
||||
__asm__ __volatile__ ("csrrs %0, " __ASM_STR(csr) ", %1"\
|
||||
: "=r" (__v) : "rK" (__v) \
|
||||
: "memory"); \
|
||||
__v; \
|
||||
})
|
||||
|
||||
#define csr_set(csr, val) \
|
||||
({ \
|
||||
unsigned long __v = (unsigned long)(val); \
|
||||
__asm__ __volatile__ ("csrs " __ASM_STR(csr) ", %0" \
|
||||
: : "rK" (__v) \
|
||||
: "memory"); \
|
||||
})
|
||||
|
||||
#define csr_read_clear(csr, val) \
|
||||
({ \
|
||||
unsigned long __v = (unsigned long)(val); \
|
||||
__asm__ __volatile__ ("csrrc %0, " __ASM_STR(csr) ", %1"\
|
||||
: "=r" (__v) : "rK" (__v) \
|
||||
: "memory"); \
|
||||
__v; \
|
||||
})
|
||||
|
||||
#define csr_clear(csr, val) \
|
||||
({ \
|
||||
unsigned long __v = (unsigned long)(val); \
|
||||
__asm__ __volatile__ ("csrc " __ASM_STR(csr) ", %0" \
|
||||
: : "rK" (__v) \
|
||||
: "memory"); \
|
||||
})
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
#endif /* _ASM_RISCV_CSR_H */
|
||||
@@ -0,0 +1,177 @@
|
||||
/* SPDX-License-Identifier: GPL-2.0-only */
|
||||
/*
|
||||
* {read,write}{b,w,l,q} based on arch/arm64/include/asm/io.h
|
||||
* which was based on arch/arm/include/io.h
|
||||
*
|
||||
* Copyright (C) 1996-2000 Russell King
|
||||
* Copyright (C) 2012 ARM Ltd.
|
||||
* Copyright (C) 2014 Regents of the University of California
|
||||
*/
|
||||
|
||||
#ifndef _ASM_RISCV_MMIO_H
|
||||
#define _ASM_RISCV_MMIO_H
|
||||
|
||||
//#include <linux/types.h>
|
||||
//#include <asm/mmiowb.h>
|
||||
#include "asm/const.h"
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
#define CONFIG_64BIT 1
|
||||
|
||||
typedef uint8_t u8;
|
||||
typedef uint16_t u16;
|
||||
typedef uint32_t u32;
|
||||
typedef uint64_t u64;
|
||||
|
||||
typedef uint32_t __le32;
|
||||
|
||||
#ifndef __iomem
|
||||
#define __iomem
|
||||
#endif
|
||||
#ifndef asm
|
||||
#define asm __asm__
|
||||
#endif
|
||||
#define __force
|
||||
|
||||
#define cpu_to_le32(x) (x)
|
||||
#define le16_to_cpu(x) (x)
|
||||
#define le32_to_cpu(x) (x)
|
||||
#define le64_to_cpu(x) (x)
|
||||
|
||||
/* Generic IO read/write. These perform native-endian accesses. */
|
||||
#define __raw_writeb __raw_writeb
|
||||
static inline void __raw_writeb(u8 val, volatile void __iomem *addr)
|
||||
{
|
||||
asm volatile("sb %0, 0(%1)" : : "r" (val), "r" (addr));
|
||||
}
|
||||
|
||||
#define __raw_writew __raw_writew
|
||||
static inline void __raw_writew(u16 val, volatile void __iomem *addr)
|
||||
{
|
||||
asm volatile("sh %0, 0(%1)" : : "r" (val), "r" (addr));
|
||||
}
|
||||
|
||||
#define __raw_writel __raw_writel
|
||||
static inline void __raw_writel(u32 val, volatile void __iomem *addr)
|
||||
{
|
||||
asm volatile("sw %0, 0(%1)" : : "r" (val), "r" (addr));
|
||||
}
|
||||
|
||||
#ifdef CONFIG_64BIT
|
||||
#define __raw_writeq __raw_writeq
|
||||
static inline void __raw_writeq(u64 val, volatile void __iomem *addr)
|
||||
{
|
||||
asm volatile("sd %0, 0(%1)" : : "r" (val), "r" (addr));
|
||||
}
|
||||
#endif
|
||||
|
||||
#define __raw_readb __raw_readb
|
||||
static inline u8 __raw_readb(const volatile void __iomem *addr)
|
||||
{
|
||||
u8 val;
|
||||
|
||||
asm volatile("lb %0, 0(%1)" : "=r" (val) : "r" (addr));
|
||||
return val;
|
||||
}
|
||||
|
||||
#define __raw_readw __raw_readw
|
||||
static inline u16 __raw_readw(const volatile void __iomem *addr)
|
||||
{
|
||||
u16 val;
|
||||
|
||||
asm volatile("lh %0, 0(%1)" : "=r" (val) : "r" (addr));
|
||||
return val;
|
||||
}
|
||||
|
||||
#define __raw_readl __raw_readl
|
||||
static inline u32 __raw_readl(const volatile void __iomem *addr)
|
||||
{
|
||||
u32 val;
|
||||
|
||||
asm volatile("lw %0, 0(%1)" : "=r" (val) : "r" (addr));
|
||||
return val;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_64BIT
|
||||
#define __raw_readq __raw_readq
|
||||
static inline u64 __raw_readq(const volatile void __iomem *addr)
|
||||
{
|
||||
u64 val;
|
||||
|
||||
asm volatile("ld %0, 0(%1)" : "=r" (val) : "r" (addr));
|
||||
return val;
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Unordered I/O memory access primitives. These are even more relaxed than
|
||||
* the relaxed versions, as they don't even order accesses between successive
|
||||
* operations to the I/O regions.
|
||||
*/
|
||||
#define readb_cpu(c) ({ u8 __r = __raw_readb(c); __r; })
|
||||
#define readw_cpu(c) ({ u16 __r = le16_to_cpu((__force __le16)__raw_readw(c)); __r; })
|
||||
#define readl_cpu(c) ({ u32 __r = le32_to_cpu((__force __le32)__raw_readl(c)); __r; })
|
||||
|
||||
#define writeb_cpu(v, c) ((void)__raw_writeb((v), (c)))
|
||||
#define writew_cpu(v, c) ((void)__raw_writew((__force u16)cpu_to_le16(v), (c)))
|
||||
#define writel_cpu(v, c) ((void)__raw_writel((__force u32)cpu_to_le32(v), (c)))
|
||||
|
||||
#ifdef CONFIG_64BIT
|
||||
#define readq_cpu(c) ({ u64 __r = le64_to_cpu((__force __le64)__raw_readq(c)); __r; })
|
||||
#define writeq_cpu(v, c) ((void)__raw_writeq((__force u64)cpu_to_le64(v), (c)))
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Relaxed I/O memory access primitives. These follow the Device memory
|
||||
* ordering rules but do not guarantee any ordering relative to Normal memory
|
||||
* accesses. These are defined to order the indicated access (either a read or
|
||||
* write) with all other I/O memory accesses. Since the platform specification
|
||||
* defines that all I/O regions are strongly ordered on channel 2, no explicit
|
||||
* fences are required to enforce this ordering.
|
||||
*/
|
||||
/* FIXME: These are now the same as asm-generic */
|
||||
#define __io_rbr() do {} while (0)
|
||||
#define __io_rar() do {} while (0)
|
||||
#define __io_rbw() do {} while (0)
|
||||
#define __io_raw() do {} while (0)
|
||||
|
||||
#define readb_relaxed(c) ({ u8 __v; __io_rbr(); __v = readb_cpu(c); __io_rar(); __v; })
|
||||
#define readw_relaxed(c) ({ u16 __v; __io_rbr(); __v = readw_cpu(c); __io_rar(); __v; })
|
||||
#define readl_relaxed(c) ({ u32 __v; __io_rbr(); __v = readl_cpu(c); __io_rar(); __v; })
|
||||
|
||||
#define writeb_relaxed(v, c) ({ __io_rbw(); writeb_cpu((v), (c)); __io_raw(); })
|
||||
#define writew_relaxed(v, c) ({ __io_rbw(); writew_cpu((v), (c)); __io_raw(); })
|
||||
#define writel_relaxed(v, c) ({ __io_rbw(); writel_cpu((v), (c)); __io_raw(); })
|
||||
|
||||
#ifdef CONFIG_64BIT
|
||||
#define readq_relaxed(c) ({ u64 __v; __io_rbr(); __v = readq_cpu(c); __io_rar(); __v; })
|
||||
#define writeq_relaxed(v, c) ({ __io_rbw(); writeq_cpu((v), (c)); __io_raw(); })
|
||||
#endif
|
||||
|
||||
/*
|
||||
* I/O memory access primitives. Reads are ordered relative to any
|
||||
* following Normal memory access. Writes are ordered relative to any prior
|
||||
* Normal memory access. The memory barriers here are necessary as RISC-V
|
||||
* doesn't define any ordering between the memory space and the I/O space.
|
||||
*/
|
||||
#define __io_br() do {} while (0)
|
||||
#define __io_ar(v) __asm__ __volatile__ ("fence i,r" : : : "memory")
|
||||
#define __io_bw() __asm__ __volatile__ ("fence w,o" : : : "memory")
|
||||
//#define __io_aw() mmiowb_set_pending()
|
||||
#define __io_aw() do {} while (0)
|
||||
|
||||
#define readb(c) ({ u8 __v; __io_br(); __v = readb_cpu(c); __io_ar(__v); __v; })
|
||||
#define readw(c) ({ u16 __v; __io_br(); __v = readw_cpu(c); __io_ar(__v); __v; })
|
||||
#define readl(c) ({ u32 __v; __io_br(); __v = readl_cpu(c); __io_ar(__v); __v; })
|
||||
|
||||
#define writeb(v, c) ({ __io_bw(); writeb_cpu((v), (c)); __io_aw(); })
|
||||
#define writew(v, c) ({ __io_bw(); writew_cpu((v), (c)); __io_aw(); })
|
||||
#define writel(v, c) ({ __io_bw(); writel_cpu((v), (c)); __io_aw(); })
|
||||
|
||||
#ifdef CONFIG_64BIT
|
||||
#define readq(c) ({ u64 __v; __io_br(); __v = readq_cpu(c); __io_ar(__v); __v; })
|
||||
#define writeq(v, c) ({ __io_bw(); writeq_cpu((v), (c)); __io_aw(); })
|
||||
#endif
|
||||
|
||||
#endif /* _ASM_RISCV_MMIO_H */
|
||||
@@ -0,0 +1,52 @@
|
||||
/* SPDX-License-Identifier: GPL-2.0-only */
|
||||
/*
|
||||
* Copyright (C) 2012 Regents of the University of California
|
||||
*/
|
||||
|
||||
#ifndef _ASM_RISCV_PGTABLE_BITS_H
|
||||
#define _ASM_RISCV_PGTABLE_BITS_H
|
||||
|
||||
#include <asm/const.h>
|
||||
|
||||
#define BIT(nr) (UL(1) << (nr))
|
||||
|
||||
/*
|
||||
* PTE format:
|
||||
* | XLEN-1 10 | 9 8 | 7 | 6 | 5 | 4 | 3 | 2 | 1 | 0
|
||||
* PFN reserved for SW D A G U X W R V
|
||||
*/
|
||||
|
||||
#define _PAGE_ACCESSED_OFFSET 6
|
||||
|
||||
#define _PAGE_PRESENT (1 << 0)
|
||||
#define _PAGE_READ (1 << 1) /* Readable */
|
||||
#define _PAGE_WRITE (1 << 2) /* Writable */
|
||||
#define _PAGE_EXEC (1 << 3) /* Executable */
|
||||
#define _PAGE_USER (1 << 4) /* User */
|
||||
#define _PAGE_GLOBAL (1 << 5) /* Global */
|
||||
#define _PAGE_ACCESSED (1 << 6) /* Set by hardware on any access */
|
||||
#define _PAGE_DIRTY (1 << 7) /* Set by hardware on any write */
|
||||
#define _PAGE_SOFT (1 << 8) /* Reserved for software */
|
||||
|
||||
#define _PAGE_SPECIAL _PAGE_SOFT
|
||||
#define _PAGE_TABLE _PAGE_PRESENT
|
||||
|
||||
/*
|
||||
* _PAGE_PROT_NONE is set on not-present pages (and ignored by the hardware) to
|
||||
* distinguish them from swapped out pages
|
||||
*/
|
||||
#define _PAGE_PROT_NONE _PAGE_READ
|
||||
|
||||
#define _PAGE_PFN_SHIFT 10
|
||||
|
||||
/* Set of bits to preserve across pte_modify() */
|
||||
#define _PAGE_CHG_MASK (~(unsigned long)(_PAGE_PRESENT | _PAGE_READ | \
|
||||
_PAGE_WRITE | _PAGE_EXEC | \
|
||||
_PAGE_USER | _PAGE_GLOBAL))
|
||||
/*
|
||||
* when all of R/W/X are zero, the PTE is a pointer to the next level
|
||||
* of the page table; otherwise, it is a leaf PTE.
|
||||
*/
|
||||
#define _PAGE_LEAF (_PAGE_READ | _PAGE_WRITE | _PAGE_EXEC)
|
||||
|
||||
#endif /* _ASM_RISCV_PGTABLE_BITS_H */
|
||||
@@ -0,0 +1,6 @@
|
||||
SRC_FILES := boot.S \
|
||||
xizi_smp.S \
|
||||
smp.c \
|
||||
cortex.S
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,120 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
#include <asm/csr.h>
|
||||
#include "memlayout.h"
|
||||
|
||||
|
||||
.section ".text", "ax"
|
||||
.globl _boot_start
|
||||
|
||||
|
||||
_boot_start:
|
||||
mv s0, a0
|
||||
call _debug_uart_init_early
|
||||
la a0, debug_string_start
|
||||
call _debug_uart_printascii
|
||||
mv a0, s0
|
||||
|
||||
j _start_kernel
|
||||
|
||||
|
||||
_start_kernel:
|
||||
/* Mask all interrupts */
|
||||
csrw CSR_IE, zero
|
||||
csrw CSR_IP, zero
|
||||
|
||||
/* Clear BSS for flat non-ELF images */
|
||||
la a3, __bss_start
|
||||
la a4, __bss_stop
|
||||
ble a4, a3, clear_bss_done
|
||||
clear_bss:
|
||||
sd zero, (a3)
|
||||
add a3, a3, RISCV_SZPTR
|
||||
blt a3, a4, clear_bss
|
||||
clear_bss_done:
|
||||
|
||||
li a0, 1
|
||||
la a2, boot_cpu_hartid
|
||||
sd a0, (a2)
|
||||
|
||||
la sp, stacks_top
|
||||
|
||||
/* Initialize page tables and relocate to virtual addresses */
|
||||
call setup_vm_early
|
||||
|
||||
la a0, early_pg_dir
|
||||
call relocate_enable_mmu
|
||||
la sp, stacks_top
|
||||
|
||||
call _debug_uart_init
|
||||
|
||||
/* Restore C environment */
|
||||
la tp, init_thread_info
|
||||
sw zero, 32(tp)
|
||||
|
||||
/* Start the kernel */
|
||||
tail main
|
||||
|
||||
relocate_enable_mmu:
|
||||
/* Relocate return address */
|
||||
la a1, kernel_map
|
||||
ld a1, 0(a1)
|
||||
la a2, _start
|
||||
sub a1, a1, a2
|
||||
add ra, ra, a1
|
||||
|
||||
/* Point stvec to virtual address of intruction after satp write */
|
||||
la a2, 1f
|
||||
add a2, a2, a1
|
||||
csrw CSR_TVEC, a2
|
||||
|
||||
/* Compute satp for kernel page tables, but don't load it yet */
|
||||
srl a2, a0, PAGE_SHIFT
|
||||
li a1, SATP_MODE
|
||||
or a2, a2, a1
|
||||
|
||||
/*
|
||||
* Load trampoline page directory, which will cause us to trap to
|
||||
* stvec if VA != PA, or simply fall through if VA == PA. We need a
|
||||
* full fence here because setup_vm() just wrote these PTEs and we need
|
||||
* to ensure the new translations are in use.
|
||||
*/
|
||||
la a0, trampoline_pg_dir
|
||||
srl a0, a0, PAGE_SHIFT
|
||||
or a0, a0, a1
|
||||
sfence.vma
|
||||
csrw CSR_SATP, a0
|
||||
|
||||
1:
|
||||
/* Set trap vector to spin forever to help debug */
|
||||
la a0, .Lsecondary_park
|
||||
csrw CSR_TVEC, a0
|
||||
|
||||
/*
|
||||
* Switch to kernel page tables. A full fence is necessary in order to
|
||||
* avoid using the trampoline translations, which are only correct for
|
||||
* the first superpage. Fetching the fence is guarnteed to work
|
||||
* because that first superpage is translated the same way.
|
||||
*/
|
||||
csrw CSR_SATP, a2
|
||||
sfence.vma
|
||||
ret
|
||||
|
||||
.Lsecondary_park:
|
||||
/* We lack SMP support or have too many harts, so park this hart */
|
||||
wfi
|
||||
j .Lsecondary_park
|
||||
|
||||
|
||||
debug_string_start: .ascii "XiZi jh7110 boot start\n\0"
|
||||
|
||||
@@ -0,0 +1,13 @@
|
||||
export CROSS_COMPILE ?= riscv64-unknown-elf-
|
||||
export ARCH = riscv
|
||||
|
||||
export KBUILD_CFLAGS := -Wall -Wundef -Wno-trigraphs -fno-strict-aliasing -fno-common -fshort-wchar -fno-PIE -Werror=implicit-function-declaration -Werror=implicit-int -Werror=return-type -Wno-format-security -std=gnu89 -Wno-sign-compare -fno-asynchronous-unwind-tables -fno-delete-null-pointer-checks -fno-stack-protector -Wno-main -fomit-frame-pointer -Wvla -Wno-pointer-sign -Wno-array-bounds -fno-strict-overflow -fno-stack-check -Werror=date-time
|
||||
export KBUILD_AFLAGS :=
|
||||
export CHECKFLAGS += -D__riscv -D__riscv_xlen=64
|
||||
|
||||
export DEVICE :=
|
||||
export CFLAGS := $(KBUILD_CFLAGS) $(KBUILD_AFLAGS) $(CHECKFLAGS) -std=c11 -mcmodel=medany
|
||||
export LFLAGS := -T $(KERNEL_ROOT)/hardkernel/arch/riscv/rv64gc/preboot_for_jh7110/jh7110.lds
|
||||
export CXXFLAGS :=
|
||||
|
||||
export DEFINES :=
|
||||
@@ -0,0 +1,36 @@
|
||||
/*!
|
||||
* @file cortex.s
|
||||
* @brief This file contains cortexA55 functions
|
||||
*
|
||||
*/
|
||||
/*************************************************
|
||||
File name: cortex.S
|
||||
Description: This file contains cortexA9 functions
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2024-05-08
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. No modifications
|
||||
*************************************************/
|
||||
.section ".text","ax"
|
||||
|
||||
.global cpu_get_current
|
||||
|
||||
# int cpu_get_current(void)@
|
||||
# get current CPU ID
|
||||
.func cpu_get_current
|
||||
cpu_get_current:
|
||||
li a0, 0
|
||||
ret
|
||||
.endfunc
|
||||
|
||||
.global psci_call
|
||||
psci_call:
|
||||
ret
|
||||
|
||||
|
||||
# ------------------------------------------------------------
|
||||
# End of cortexA55.s
|
||||
# ------------------------------------------------------------
|
||||
.end
|
||||
@@ -0,0 +1,241 @@
|
||||
/*
|
||||
* Copyright (c) 2012, Freescale Semiconductor, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* o Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* o Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
|
||||
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
/**
|
||||
* @file cortex.h
|
||||
* @brief some cortex A55 core functions
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.04.24
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: cortex.h
|
||||
Description: some cortex A55 core functions
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. No modifications
|
||||
*************************************************/
|
||||
|
||||
#if !defined(__CORTEX_A55_H__)
|
||||
#define __CORTEX_A55_H__
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
//! @name Instruction macros
|
||||
//@{
|
||||
//#define NOP() __asm__ volatile("nop\n\t")
|
||||
//#define WFI() __asm__ volatile("wfi\n\t")
|
||||
//#define WFE() __asm__ volatile("wfe\n\t")
|
||||
//#define SEV() __asm__ volatile("sev\n\t")
|
||||
//#define DMB() __asm__ volatile("dmb ish\n\t")
|
||||
//#define DSB() __asm__ volatile("dsb ish\n\t")
|
||||
//#define ISB() __asm__ volatile("isb\n\t")
|
||||
#define NOP() __asm__ volatile("nop\n\t")
|
||||
#define WFI() __asm__ volatile("nop\n\t")
|
||||
#define WFE() __asm__ volatile("nop\n\t")
|
||||
#define SEV() __asm__ volatile("nop\n\t")
|
||||
#define DMB() __asm__ volatile("nop\n\t")
|
||||
#define DSB() __asm__ volatile("nop\n\t")
|
||||
#define ISB() __asm__ volatile("nop\n\t")
|
||||
|
||||
#define _ARM_MRS(coproc, opcode1, Rt, CRn, CRm, opcode2) \
|
||||
__asm__ volatile("mrc p" #coproc ", " #opcode1 ", %[output], c" #CRn ", c" #CRm ", " #opcode2 "\n" : [output] "=r"(Rt))
|
||||
|
||||
#define _ARM_MSR(coproc, opcode1, Rt, CRn, CRm, opcode2) \
|
||||
__asm__ volatile("mcr p" #coproc ", " #opcode1 ", %[input], c" #CRn ", c" #CRm ", " #opcode2 "\n" ::[input] "r"(Rt))
|
||||
|
||||
// #define WriteReg(value, address) (*(volatile unsigned int*)(address) = (value))
|
||||
// #define ReadReg(address) (*(volatile unsigned int*)(address))
|
||||
|
||||
#if defined(__cplusplus)
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
//! @name Misc
|
||||
//@{
|
||||
//! @brief Enable or disable the IRQ and FIQ state.
|
||||
bool arm_set_interrupt_state(bool enable);
|
||||
|
||||
//! @brief Get current CPU ID.
|
||||
int cpu_get_current(void);
|
||||
|
||||
//! @brief Enable the NEON MPE.
|
||||
void enable_neon_fpu(void);
|
||||
|
||||
//! @brief Disable aborts on unaligned accesses.
|
||||
void disable_strict_align_check(void);
|
||||
|
||||
//! @brief Get base address of private perpherial space.
|
||||
//!
|
||||
//! @return The address of the ARM CPU's private peripherals.
|
||||
// uint32_t get_arm_private_peripheral_base(void);
|
||||
//@}
|
||||
|
||||
//! @name Data cache operations
|
||||
//@{
|
||||
|
||||
//! @brief Check if dcache is enabled or disabled.
|
||||
int arm_dcache_state_query();
|
||||
|
||||
//! @brief Enables data cache at any available cache level.
|
||||
//!
|
||||
//! Works only if MMU is enabled!
|
||||
void arm_dcache_enable();
|
||||
|
||||
//! @brief Disables the data cache at any available cache level.
|
||||
void arm_dcache_disable();
|
||||
|
||||
//! @brief Invalidates the entire data cache.
|
||||
void arm_dcache_invalidate();
|
||||
|
||||
//! @brief Invalidate a line of data cache.
|
||||
void arm_dcache_invalidate_line(const void* addr);
|
||||
|
||||
//! @brief Invalidate a number of lines of data cache.
|
||||
//!
|
||||
//! Number of lines depends on length parameter and size of line.
|
||||
//! Size of line for A9 L1 cache is 32B.
|
||||
void arm_dcache_invalidate_mlines(const void* addr, size_t length);
|
||||
|
||||
//! @brief Flush (clean) all lines of cache (all sets in all ways).
|
||||
void arm_dcache_flush();
|
||||
|
||||
//! @brief Flush (clean) one line of cache.
|
||||
void arm_dcache_flush_line(const void* addr);
|
||||
|
||||
// @brief Flush (clean) multiple lines of cache.
|
||||
//!
|
||||
//! Number of lines depends on length parameter and size of line.
|
||||
void arm_dcache_flush_mlines(const void* addr, size_t length);
|
||||
//@}
|
||||
|
||||
//! @name Instrution cache operations
|
||||
//@{
|
||||
|
||||
//! @brief Check if icache is enabled or disabled.
|
||||
int arm_icache_state_query();
|
||||
|
||||
//! @brief Enables instruction cache at any available cache level.
|
||||
//!
|
||||
//! Works without enabled MMU too!
|
||||
void arm_icache_enable();
|
||||
|
||||
//! @brief Disables the instruction cache at any available cache level.
|
||||
void arm_icache_disable();
|
||||
|
||||
//! @brief Invalidates the entire instruction cache.
|
||||
void arm_icache_invalidate();
|
||||
|
||||
//! @brief Invalidates the entire instruction cache inner shareable.
|
||||
void arm_icache_invalidate_is();
|
||||
|
||||
//! @brief Invalidate a line of the instruction cache.
|
||||
void arm_icache_invalidate_line(const void* addr);
|
||||
|
||||
//! @brief Invalidate a number of lines of instruction cache.
|
||||
//!
|
||||
//! Number of lines depends on length parameter and size of line.
|
||||
void arm_icache_invalidate_mlines(const void* addr, size_t length);
|
||||
//@}
|
||||
|
||||
//! @name TLB operations
|
||||
//@{
|
||||
//! @brief Invalidate entire unified TLB.
|
||||
void arm_unified_tlb_invalidate(void);
|
||||
|
||||
//! @brief Invalidate entire unified TLB Inner Shareable.
|
||||
void arm_unified_tlb_invalidate_is(void);
|
||||
//@}
|
||||
|
||||
//! @name Branch predictor operations
|
||||
//@{
|
||||
//! @brief Enable branch prediction.
|
||||
void arm_branch_prediction_enable(void);
|
||||
|
||||
//! @brief Disable branch prediction.
|
||||
void arm_branch_prediction_disable(void);
|
||||
|
||||
//! @brief Invalidate entire branch predictor array.
|
||||
void arm_branch_target_cache_invalidate(void);
|
||||
|
||||
//! @brief Invalidate entire branch predictor array Inner Shareable
|
||||
void arm_branch_target_cache_invalidate_is(void);
|
||||
//@}
|
||||
|
||||
//! @name SCU
|
||||
//@{
|
||||
//! @brief Enables the SCU.
|
||||
void scu_enable(void);
|
||||
|
||||
//! @brief Set this CPU as participating in SMP.
|
||||
void scu_join_smp(void);
|
||||
|
||||
//! @brief Set this CPU as not participating in SMP.
|
||||
void scu_leave_smp(void);
|
||||
|
||||
//! @brief Determine which CPUs are participating in SMP.
|
||||
//!
|
||||
//! The return value is 1 bit per core:
|
||||
//! - bit 0 - CPU 0
|
||||
//! - bit 1 - CPU 1
|
||||
//! - etc...
|
||||
unsigned int scu_get_cpus_in_smp(void);
|
||||
|
||||
//! @brief Enable the broadcasting of cache & TLB maintenance operations.
|
||||
//!
|
||||
//! When enabled AND in SMP, broadcast all "inner sharable"
|
||||
//! cache and TLM maintenance operations to other SMP cores
|
||||
void scu_enable_maintenance_broadcast(void);
|
||||
|
||||
//! @brief Disable the broadcasting of cache & TLB maintenance operations.
|
||||
void scu_disable_maintenance_broadcast(void);
|
||||
|
||||
//! @brief Invalidates the SCU copy of the tag rams for the specified core.
|
||||
//!
|
||||
//! Typically only done at start-up.
|
||||
//! Possible flow:
|
||||
//! - Invalidate L1 caches
|
||||
//! - Invalidate SCU copy of TAG RAMs
|
||||
//! - Join SMP
|
||||
//!
|
||||
//! @param cpu 0x0=CPU 0, 0x1=CPU 1, etc...
|
||||
//! @param ways The ways to invalidate. Pass 0xf to invalidate all ways.
|
||||
void scu_secure_invalidate(unsigned int cpu, unsigned int ways);
|
||||
//@}
|
||||
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif //__CORTEX_A55_H__
|
||||
@@ -0,0 +1,135 @@
|
||||
/*
|
||||
* Copyright (c) 2010-2012, Freescale Semiconductor, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* o Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* o Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
|
||||
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OF THE USE OF THIS
|
||||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file jh7110.lds
|
||||
* @brief
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.10.10
|
||||
*/
|
||||
|
||||
OUTPUT_ARCH(riscv)
|
||||
OUTPUT_FORMAT("elf64-littleriscv", "elf64-littleriscv", "elf64-littleriscv")
|
||||
|
||||
ENTRY( _boot_start )
|
||||
|
||||
MEMORY {
|
||||
vir_ddr3 (rwx) : ORIGIN = (0 - 0x80000000), LENGTH = 1024M
|
||||
phy_ddr3 (rwx) : ORIGIN = 0x40200000, LENGTH = 1024M
|
||||
}
|
||||
|
||||
BOOT_STACK_SIZE = 0x4000;
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
. = ORIGIN(vir_ddr3);
|
||||
_start = .;
|
||||
_boot_start = .;
|
||||
|
||||
.start_sec : {
|
||||
_start_image_addr = .;
|
||||
|
||||
boot.o(.text)
|
||||
ns16550.o(.text .text.*)
|
||||
mmu_init.o(.text .text.*)
|
||||
|
||||
boot.o(.rodata .rodata.*)
|
||||
ns16550.o(.rodata .rodata.*)
|
||||
mmu_init.o(.rodata .rodata.*)
|
||||
|
||||
boot.o(.data .data.*)
|
||||
ns16550.o(.data .data.*)
|
||||
mmu_init.o(.data .data.*)
|
||||
|
||||
PROVIDE(boot_start_addr = .);
|
||||
|
||||
boot.o(.bss .bss.* COMMON)
|
||||
ns16550.o(.bss .bss.* COMMON)
|
||||
mmu_init.o(.bss .bss.* COMMON)
|
||||
|
||||
. = ALIGN(0x1000);
|
||||
PROVIDE(stacks_start = .);
|
||||
. += BOOT_STACK_SIZE;
|
||||
PROVIDE(stacks_end = .);
|
||||
PROVIDE(stacks_top = .);
|
||||
|
||||
PROVIDE(boot_end_addr = .);
|
||||
}
|
||||
|
||||
.text : {
|
||||
. = ALIGN(0x1000);
|
||||
*(.text .text.*)
|
||||
}
|
||||
|
||||
.data : {
|
||||
. = ALIGN(0x1000);
|
||||
*(.data .data.*)
|
||||
|
||||
. = ALIGN(0x1000);
|
||||
PROVIDE(_binary_fs_img_start = .);
|
||||
*(.rawdata_fs_img*)
|
||||
PROVIDE(_binary_fs_img_end = .);
|
||||
. = ALIGN(0x1000);
|
||||
PROVIDE(_binary_init_start = .);
|
||||
*(.rawdata_init*)
|
||||
PROVIDE(_binary_init_end = .);
|
||||
. = ALIGN(0x1000);
|
||||
PROVIDE(_binary_default_fs_start = .);
|
||||
*(.rawdata_memfs*)
|
||||
PROVIDE(_binary_default_fs_end = .);
|
||||
PROVIDE(__init_array_start = .);
|
||||
PROVIDE(__init_array_end = .);
|
||||
}
|
||||
|
||||
.sdata : {
|
||||
. = ALIGN(0x1000);
|
||||
__global_pointer$ = . + 0x800;
|
||||
*(.sdata*)
|
||||
}
|
||||
|
||||
.bss : {
|
||||
. = ALIGN(0x1000);
|
||||
PROVIDE(kernel_data_begin = .);
|
||||
PROVIDE(__bss_start = .);
|
||||
*(.bss .bss.* COMMON)
|
||||
. = ALIGN(0x1000);
|
||||
PROVIDE(__bss_end = .);
|
||||
PROVIDE(kernel_data_end = .);
|
||||
__bss_stop = .;
|
||||
}
|
||||
|
||||
. = ALIGN(0x1000);
|
||||
_image_size = . - _start;
|
||||
|
||||
. = ALIGN((1 << 21));
|
||||
_edata = .;
|
||||
_end = .;
|
||||
}
|
||||
@@ -0,0 +1,86 @@
|
||||
/*
|
||||
* Copyright (c) 2010-2012, Freescale Semiconductor, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* o Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* o Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
|
||||
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file smp.c
|
||||
* @brief start multicore
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.04.10
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: smp.c
|
||||
Description:
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. No modifications
|
||||
*************************************************/
|
||||
#include <stdint.h>
|
||||
|
||||
unsigned long boot_cpu_hartid;
|
||||
|
||||
#define PSCI_CPUON 0xc4000003
|
||||
struct xizi_smccc_res {
|
||||
unsigned long a0;
|
||||
unsigned long a1;
|
||||
unsigned long a2;
|
||||
unsigned long a3;
|
||||
};
|
||||
|
||||
extern void _boot_start();
|
||||
extern void __print();
|
||||
|
||||
extern void __xizi_smccc_smc(unsigned long a0, unsigned long a1, unsigned long a2,
|
||||
unsigned long a3, unsigned long a4, unsigned long a5,
|
||||
unsigned long a6, unsigned long a7, struct xizi_smccc_res* res);
|
||||
|
||||
static struct xizi_smccc_res __invoke_sip_fn_smc(unsigned long function_id,
|
||||
unsigned long arg0,
|
||||
unsigned long arg1,
|
||||
unsigned long arg2)
|
||||
{
|
||||
struct xizi_smccc_res res;
|
||||
|
||||
__xizi_smccc_smc(function_id, arg0, arg1, arg2, 0, 0, 0, 0, &res);
|
||||
return res;
|
||||
}
|
||||
|
||||
void cpu_start_secondary(uint8_t cpu_id)
|
||||
{
|
||||
__invoke_sip_fn_smc(PSCI_CPUON, cpu_id, (uintptr_t)0xa00000, 0);
|
||||
}
|
||||
|
||||
void start_smp_cache_broadcast(int cpu_id)
|
||||
{
|
||||
return;
|
||||
}
|
||||
@@ -0,0 +1,17 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
.global __xizi_smccc_smc
|
||||
|
||||
.func __xizi_smccc_smc
|
||||
__xizi_smccc_smc:
|
||||
1: ret
|
||||
.endfunc
|
||||
@@ -1,3 +1,8 @@
|
||||
ifneq ($(findstring $(BOARD), 3568 imx6q-sabrelite zynq7000-zc702), )
|
||||
SRC_DIR := arm
|
||||
endif
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := riscv
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
5
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/Makefile
vendored
Normal file
5
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/Makefile
vendored
Normal file
@@ -0,0 +1,5 @@
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := rv64gc
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
3
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/Makefile
vendored
Normal file
3
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/Makefile
vendored
Normal file
@@ -0,0 +1,3 @@
|
||||
SRC_FILES := l1_cache.c cache.S
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
184
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/cache.S
vendored
Normal file
184
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/cache.S
vendored
Normal file
@@ -0,0 +1,184 @@
|
||||
/*
|
||||
* (C) Copyright 2013
|
||||
* David Feng <fenghua@phytium.com.cn>
|
||||
*
|
||||
* This file is based on sample code from ARMv8 ARM.
|
||||
*
|
||||
* SPDX-License-Identifier: GPL-2.0+
|
||||
*/
|
||||
|
||||
|
||||
#define ASM_NL ;
|
||||
|
||||
#define SYMBOL_NAME(X) X
|
||||
|
||||
// #define SYMBOL_NAME_LABEL(X) X##:
|
||||
|
||||
#define SYMBOL_NAME_LABEL(X) X:
|
||||
|
||||
#ifndef __ALIGN
|
||||
#define __ALIGN .align 4
|
||||
#endif
|
||||
|
||||
#ifndef __ALIGN_STR
|
||||
#define __ALIGN_STR ".align 4"
|
||||
#endif
|
||||
|
||||
#define ALIGN __ALIGN
|
||||
#define ALIGN_STR __ALIGN_STR
|
||||
|
||||
#define LENTRY(name) \
|
||||
ALIGN ASM_NL \
|
||||
SYMBOL_NAME_LABEL(name)
|
||||
|
||||
#define ENTRY(name) \
|
||||
.globl SYMBOL_NAME(name) ASM_NL \
|
||||
LENTRY(name)
|
||||
|
||||
#define WEAK(name) \
|
||||
.weak SYMBOL_NAME(name) ASM_NL \
|
||||
LENTRY(name)
|
||||
|
||||
|
||||
#define END(name) \
|
||||
.size name, .-name
|
||||
|
||||
#define ENDPROC(name) \
|
||||
.type name STT_FUNC ASM_NL \
|
||||
END(name)
|
||||
|
||||
#define CR_M (1 << 0) /* MMU enable */
|
||||
#define CR_A (1 << 1) /* Alignment abort enable */
|
||||
#define CR_C (1 << 2) /* Dcache enable */
|
||||
#define CR_SA (1 << 3) /* Stack Alignment Check Enable */
|
||||
#define CR_I (1 << 12) /* Icache enable */
|
||||
#define CR_WXN (1 << 19) /* Write Permision Imply XN */
|
||||
#define CR_EE (1 << 25) /* Exception (Big) Endian */
|
||||
|
||||
.macro switch_el, xreg, el3_label, el2_label, el1_label
|
||||
nop
|
||||
.endm
|
||||
|
||||
|
||||
/*
|
||||
* void __asm_dcache_level(level)
|
||||
* flush or invalidate one level cache.
|
||||
*
|
||||
* x0: cache level
|
||||
* x1: 0 clean & invalidate, 1 invalidate only
|
||||
* x2~x9: clobbered
|
||||
*/
|
||||
ENTRY(__asm_dcache_level)
|
||||
nop
|
||||
|
||||
loop_set:
|
||||
nop
|
||||
loop_way:
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_dcache_level)
|
||||
|
||||
|
||||
/*
|
||||
* void __asm_flush_dcache_all(int invalidate_only)
|
||||
*
|
||||
* x0: 0 clean & invalidate, 1 invalidate only
|
||||
*
|
||||
* flush or invalidate all data cache by SET/WAY.
|
||||
*/
|
||||
|
||||
ENTRY(__asm_dcache_all)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_dcache_all)
|
||||
|
||||
|
||||
ENTRY(__asm_flush_dcache_all)
|
||||
j __asm_dcache_all
|
||||
ENDPROC(__asm_flush_dcache_all)
|
||||
|
||||
|
||||
ENTRY(__asm_invalidate_dcache_all)
|
||||
j __asm_dcache_all
|
||||
ENDPROC(__asm_invalidate_dcache_all)
|
||||
|
||||
|
||||
/*
|
||||
* void __asm_flush_dcache_range(start, end)
|
||||
*
|
||||
* clean & invalidate data cache in the range
|
||||
*
|
||||
* x0: start address
|
||||
* x1: end address
|
||||
*/
|
||||
|
||||
ENTRY(__asm_flush_dcache_range)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_flush_dcache_range)
|
||||
|
||||
/*
|
||||
* void __asm_invalidate_dcache_range(start, end)
|
||||
*
|
||||
* invalidate data cache in the range
|
||||
*
|
||||
* x0: start address
|
||||
* x1: end address
|
||||
*/
|
||||
|
||||
ENTRY(__asm_invalidate_dcache_range)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_invalidate_dcache_range)
|
||||
|
||||
|
||||
/*
|
||||
* void __asm_invalidate_icache_all(void)
|
||||
*
|
||||
* invalidate all tlb entries.
|
||||
*/
|
||||
|
||||
ENTRY(__asm_invalidate_icache_all)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_invalidate_icache_all)
|
||||
|
||||
|
||||
|
||||
ENTRY(__asm_invalidate_l3_dcache)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_invalidate_l3_dcache)
|
||||
.weak __asm_invalidate_l3_dcache
|
||||
|
||||
|
||||
|
||||
ENTRY(__asm_flush_l3_dcache)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_flush_l3_dcache)
|
||||
.weak __asm_flush_l3_dcache
|
||||
|
||||
|
||||
|
||||
ENTRY(__asm_invalidate_l3_icache)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_invalidate_l3_icache)
|
||||
.weak __asm_invalidate_l3_icache
|
||||
|
||||
|
||||
/*
|
||||
* void __asm_switch_ttbr(ulong new_ttbr)
|
||||
*
|
||||
* Safely switches to a new page table.
|
||||
*/
|
||||
|
||||
ENTRY(__asm_switch_ttbr)
|
||||
nop
|
||||
ret
|
||||
ENDPROC(__asm_switch_ttbr)
|
||||
|
||||
ENTRY(__asm_invalidate_tlb_all)
|
||||
ret
|
||||
ENDPROC(__asm_invalidate_tlb_all)
|
||||
81
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/l1_cache.c
vendored
Normal file
81
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/l1_cache.c
vendored
Normal file
@@ -0,0 +1,81 @@
|
||||
/**
|
||||
* @file: l1_cache.c
|
||||
* @brief: the general management of L1 cache
|
||||
* @version: 1.0
|
||||
* @author: AIIT XUOS Lab
|
||||
* @date: 2024/04/23
|
||||
*
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: l1_cache.c
|
||||
Description: the general management of L1 cache
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. implement the l1 cache operations
|
||||
2. function names are modified to apply softkernel developement
|
||||
3. function implementations are from modifications of imx6 SDK package
|
||||
*************************************************/
|
||||
|
||||
#include "l1_cache.h"
|
||||
extern void __asm_flush_dcache_all();
|
||||
extern void __asm_flush_l3_dcache();
|
||||
extern void __asm_invalidate_icache_all();
|
||||
extern void __asm_invalidate_l3_icache();
|
||||
|
||||
void InvalidateL1Dcache(uintptr_t start, uintptr_t end)
|
||||
{
|
||||
}
|
||||
|
||||
void InvalidateL1DcacheAll(void)
|
||||
{
|
||||
}
|
||||
|
||||
void CleanL1Dcache(uintptr_t start, uintptr_t end)
|
||||
{
|
||||
}
|
||||
|
||||
void CleanL1DcacheAll(void)
|
||||
{
|
||||
}
|
||||
|
||||
void FlushL1Dcache(uintptr_t start, uintptr_t end)
|
||||
{
|
||||
}
|
||||
|
||||
void FlushL1DcacheAll(void)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void InvalidateL1IcacheAll()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void InvalidateL1Icache(uintptr_t start, uintptr_t end)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void EnableL1Dcache()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void DisableL1Dcache()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void EnableL1Icache()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void DisableL1Icache()
|
||||
{
|
||||
|
||||
}
|
||||
76
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/l1_cache.h
vendored
Normal file
76
Ubiquitous/XiZi_AIoT/hardkernel/cache/L1/riscv/rv64gc/l1_cache.h
vendored
Normal file
@@ -0,0 +1,76 @@
|
||||
/*
|
||||
* 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: l1_cache.h
|
||||
* @brief: the general management of L1 cache
|
||||
* @version: 1.0
|
||||
* @author: AIIT XUOS Lab
|
||||
* @date: 2024/4/23
|
||||
*
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: l1_cache.h
|
||||
Description: the general management of L1 cache
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1、define the l1 cache operations
|
||||
*************************************************/
|
||||
#include "core.h"
|
||||
#include <stdint.h>
|
||||
|
||||
/*
|
||||
* L1 Cache Operation:
|
||||
*
|
||||
* IVAC -Invalidate by Virtual Address, to Point of Coherency AArch32Equivalent :DCIMVAC
|
||||
*
|
||||
* ISW -Invalidate by Set/Way AArch32Equivalent :DCISW
|
||||
*
|
||||
*CVAC -Clean by Virtual Address to Point of Coherency AArch32Equivalent :DCCMVAC
|
||||
*
|
||||
*CSW -Clean by Set/Way AArch32Equivalent :DCCSW
|
||||
*
|
||||
*CVAU -Clean by Virtual Address to Point of Unification AArch32Equivalent :DCCMVAU
|
||||
*
|
||||
*CIVAC -Clean and invalidate data cache line by VA to PoC. AArch32Equivalent :DCCIMVAC
|
||||
*
|
||||
*ISW -Clean and invalidate data cache line by Set/Way. AArch32Equivalent :DCCISW
|
||||
*/
|
||||
|
||||
#define SCTLR_EL1_ICACHE_ENABLE (1 << 12) //!< Instruction cache enable
|
||||
#define SCTLR_EL1_DCACHE_ENABLE (1 << 2) //!< Data cache enable
|
||||
|
||||
void InvalidateL1Dcache(uintptr_t start, uintptr_t end);
|
||||
|
||||
void InvalidateL1DcacheAll(void);
|
||||
|
||||
void CleanL1Dcache(uintptr_t start, uintptr_t end);
|
||||
|
||||
void CleanL1DcacheAll(void);
|
||||
|
||||
void FlushL1Dcache(uintptr_t start, uintptr_t end);
|
||||
|
||||
void FlushL1DcacheAll(void);
|
||||
|
||||
void InvalidateL1IcacheAll(void);
|
||||
|
||||
void InvalidateL1Icache(uintptr_t start, uintptr_t end);
|
||||
|
||||
void EnableL1Icache(void);
|
||||
void DisableL1Icache();
|
||||
|
||||
void EnableL1Dcache();
|
||||
|
||||
void DisableL1Dcache();
|
||||
@@ -1,3 +1,8 @@
|
||||
SRC_DIR:= arm
|
||||
ifneq ($(findstring $(BOARD), 3568 imx6q-sabrelite zynq7000-zc702), )
|
||||
SRC_DIR := arm
|
||||
endif
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := riscv
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
5
Ubiquitous/XiZi_AIoT/hardkernel/clock/riscv/Makefile
Normal file
5
Ubiquitous/XiZi_AIoT/hardkernel/clock/riscv/Makefile
Normal file
@@ -0,0 +1,5 @@
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := rv64gc
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,4 @@
|
||||
SRC_DIR := $(BOARD)
|
||||
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,4 @@
|
||||
SRC_FILES := clock.c timer-clint.c
|
||||
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,8 @@
|
||||
#ifndef _ASM_RISCV_CLINT_H
|
||||
#define _ASM_RISCV_CLINT_H
|
||||
|
||||
#include <asm/mmio.h>
|
||||
|
||||
int clint_timer_init(void);
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,84 @@
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
#include "actracer.h"
|
||||
#include "core.h"
|
||||
|
||||
#include "clock_common_op.h"
|
||||
#include "clint.h"
|
||||
|
||||
//TODO:
|
||||
static void enable_timer()
|
||||
{
|
||||
;
|
||||
}
|
||||
|
||||
static void disable_timer()
|
||||
{
|
||||
;
|
||||
}
|
||||
|
||||
static void reload_timer()
|
||||
{
|
||||
// interval 1ms
|
||||
;
|
||||
}
|
||||
|
||||
|
||||
void _sys_clock_init()
|
||||
{
|
||||
clint_timer_init();
|
||||
disable_timer();
|
||||
reload_timer();
|
||||
enable_timer();
|
||||
}
|
||||
|
||||
static uint32_t _get_clock_int()
|
||||
{
|
||||
return 30;
|
||||
}
|
||||
|
||||
static uint64_t _get_tick()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint64_t _get_second()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
static bool _is_timer_expired()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
static void _clear_clock_intr()
|
||||
{
|
||||
disable_timer();
|
||||
reload_timer();
|
||||
enable_timer();
|
||||
}
|
||||
|
||||
static struct XiziClockDriver hardkernel_clock_driver = {
|
||||
.sys_clock_init = _sys_clock_init,
|
||||
.get_clock_int = _get_clock_int,
|
||||
.get_tick = _get_tick,
|
||||
.get_second = _get_second,
|
||||
.is_timer_expired = _is_timer_expired,
|
||||
.clear_clock_intr = _clear_clock_intr,
|
||||
};
|
||||
|
||||
struct XiziClockDriver* hardkernel_clock_init(struct TraceTag* hardkernel_tag)
|
||||
{
|
||||
hardkernel_clock_driver.sys_clock_init();
|
||||
return &hardkernel_clock_driver;
|
||||
}
|
||||
@@ -0,0 +1,9 @@
|
||||
#include "clint.h"
|
||||
|
||||
|
||||
// Refer to linux/drivers/clocksource/timer-clint.c
|
||||
// TODO:
|
||||
int clint_timer_init(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
@@ -1,4 +1,10 @@
|
||||
ifneq ($(findstring $(BOARD), 3568 imx6q-sabrelite zynq7000-zc702), )
|
||||
SRC_DIR := arm
|
||||
endif
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := riscv
|
||||
endif
|
||||
|
||||
SRC_FILES := spinlock.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -57,7 +57,7 @@ void panic(char* s)
|
||||
/* stack for different mode*/
|
||||
static char mode_stack_pages[NR_CPU][NR_MODE_STACKS][MODE_STACK_SIZE];
|
||||
extern uint32_t _vector_jumper;
|
||||
extern uint32_t _vector_start;
|
||||
extern uint32_t* _vector_start;
|
||||
extern uint32_t _vector_end;
|
||||
|
||||
void init_cpu_mode_stacks(int cpu_id)
|
||||
@@ -75,7 +75,7 @@ static void _sys_irq_init(int cpu_id)
|
||||
/* load exception vectors */
|
||||
init_cpu_mode_stacks(cpu_id);
|
||||
if (cpu_id == 0) {
|
||||
volatile uint32_t* vector_base = &_vector_start;
|
||||
volatile uint32_t* vector_base = (uint32_t*)&_vector_start;
|
||||
|
||||
// Set Interrupt handler start address
|
||||
vector_base[1] = (uint32_t)trap_undefined_instruction; // Undefined Instruction
|
||||
|
||||
@@ -70,12 +70,7 @@ static void _cpu_irq_disable(void)
|
||||
|
||||
static void _single_irq_enable(int irq, int cpu, int prio)
|
||||
{
|
||||
if (irq < 32) {
|
||||
gic_setup_ppi((uint32_t)cpu, (uint32_t)irq);
|
||||
}
|
||||
else {
|
||||
gic_setup_spi((uint32_t)cpu, (uint32_t)irq);
|
||||
}
|
||||
gic_setup_ppi((uint32_t)cpu, (uint32_t)irq);
|
||||
}
|
||||
|
||||
static void _single_irq_disable(int irq, int cpu)
|
||||
|
||||
5
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/Makefile
Normal file
5
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/Makefile
Normal file
@@ -0,0 +1,5 @@
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := rv64gc
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,4 @@
|
||||
SRC_FILES := trampoline.S $(BOARD)/trap_common.c $(BOARD)/trap.c $(BOARD)/plic.c error_debug.c hard_spinlock.S
|
||||
SRC_FILES += $(BOARD)/
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
@@ -0,0 +1,65 @@
|
||||
/* Copyright (c) 2006-2018 Frans Kaashoek, Robert Morris, Russ Cox,
|
||||
* Massachusetts Institute of Technology
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining
|
||||
* a copy of this software and associated documentation files (the
|
||||
* "Software"), to deal in the Software without restriction, including
|
||||
* without limitation the rights to use, copy, modify, merge, publish,
|
||||
* distribute, sublicense, and/or sell copies of the Software, and to
|
||||
* permit persons to whom the Software is furnished to do so, subject to
|
||||
* the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be
|
||||
* included in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
|
||||
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
|
||||
* LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
|
||||
* OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
|
||||
* WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* @file error_debug.c
|
||||
* @brief handle program abort
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.4.25
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: error_debug.c
|
||||
Description: handle program abort
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. Take only armv8 abort reason part(_abort_reason).
|
||||
2. Modify iabort and dabort handler(in dabort_handler() and iabort_handler())
|
||||
*************************************************/
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "assert.h"
|
||||
#include "core.h"
|
||||
#include "log.h"
|
||||
#include "multicores.h"
|
||||
#include "task.h"
|
||||
#include "trap_common.h"
|
||||
|
||||
void dump_tf(struct trapframe* tf)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void dabort_reason(struct trapframe* r)
|
||||
{
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
void iabort_reason(struct trapframe* r)
|
||||
{
|
||||
return;
|
||||
}
|
||||
@@ -0,0 +1,94 @@
|
||||
/*
|
||||
* Copyright (c) 2013, Freescale Semiconductor, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
*
|
||||
* o Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* o Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
|
||||
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
/*
|
||||
* Portions Copyright (c) 2011-2012 ARM Ltd. All rights reserved.
|
||||
*/
|
||||
/**
|
||||
* @file hard_spinlock.S
|
||||
* @brief spinlock implementation
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024.04.11
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: hard_spinlock.S
|
||||
Description: spinlock implementation
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
*************************************************/
|
||||
|
||||
// .arch armv8-a
|
||||
.section ".text","ax"
|
||||
|
||||
.global cpu_get_current
|
||||
|
||||
#define UNLOCKED 0xFF
|
||||
// int spinlock_lock(spinlock_t * lock, uint64_t timeout)
|
||||
.global _spinlock_lock
|
||||
.func _spinlock_lock
|
||||
_spinlock_lock:
|
||||
mv s0, a0
|
||||
li a0, 0 # cpu_get_current
|
||||
mv a1, a0
|
||||
mv a0, s0
|
||||
li a2, UNLOCKED
|
||||
1:
|
||||
lr.w a3, (a0)
|
||||
bne a3, a2, 1b
|
||||
sc.w a4, a1, (a0)
|
||||
bnez a4, 1b
|
||||
ret
|
||||
.endfunc
|
||||
|
||||
|
||||
// void spinlock_unlock(spinlock_t * lock)
|
||||
.global _spinlock_unlock
|
||||
.func _spinlock_unlock
|
||||
_spinlock_unlock:
|
||||
mv s0, a0
|
||||
li a0, 0 # cpu_get_current
|
||||
mv a1, a0
|
||||
mv a0, s0
|
||||
li a2, UNLOCKED
|
||||
lw a3, (a0)
|
||||
bne a3, a1, 1f
|
||||
sw a2, (a0)
|
||||
li a0, 0
|
||||
ret
|
||||
1:
|
||||
li a0, -1
|
||||
ret
|
||||
.endfunc
|
||||
|
||||
.end
|
||||
|
||||
@@ -0,0 +1,110 @@
|
||||
/**
|
||||
* @file irq_numbers.c
|
||||
* @brief irq numbers
|
||||
* @version 3.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023.08.25
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: irq_numbers.c
|
||||
Description: irq numbers
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2023-08-28
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. Add HW_NR_IRQS
|
||||
*************************************************/
|
||||
#if !defined(__IRQ_NUMBERS_H__)
|
||||
#define __IRQ_NUMBERS_H__
|
||||
|
||||
#define HW_NR_IRQS NR_OK1028_INTRS
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Definitions
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//! @brief i.MX6 interrupt numbers.
|
||||
//!
|
||||
//! This enumeration lists the numbers for all of the interrupts available on the i.MX6 series.
|
||||
//! Use these numbers when specifying an interrupt to the GIC.
|
||||
//!
|
||||
//! The first 16 interrupts are special in that they are reserved for software interrupts generated
|
||||
//! by the SWI instruction.
|
||||
|
||||
enum _ls_interrupts {
|
||||
SW_INTERRUPT_0 = 0, //!< Software interrupt 0.
|
||||
SW_INTERRUPT_1 = 1, //!< Software interrupt 1.
|
||||
SW_INTERRUPT_2 = 2, //!< Software interrupt 2.
|
||||
SW_INTERRUPT_3 = 3, //!< Software interrupt 3.
|
||||
SW_INTERRUPT_4 = 4, //!< Software interrupt 4.
|
||||
SW_INTERRUPT_5 = 5, //!< Software interrupt 5.
|
||||
SW_INTERRUPT_6 = 6, //!< Software interrupt 6.
|
||||
SW_INTERRUPT_7 = 7, //!< Software interrupt 7.
|
||||
SW_INTERRUPT_8 = 8, //!< Software interrupt 8.
|
||||
SW_INTERRUPT_9 = 9, //!< Software interrupt 9.
|
||||
SW_INTERRUPT_10 = 10, //!< Software interrupt 10.
|
||||
SW_INTERRUPT_11 = 11, //!< Software interrupt 11.
|
||||
SW_INTERRUPT_12 = 12, //!< Software interrupt 12.
|
||||
SW_INTERRUPT_13 = 13, //!< Software interrupt 13.
|
||||
SW_INTERRUPT_14 = 14, //!< Software interrupt 14.
|
||||
SW_INTERRUPT_15 = 15, //!< Software interrupt 15.
|
||||
RSVD_INTERRUPT_16 = 16, //!< Reserved.
|
||||
RSVD_INTERRUPT_17 = 17, //!< Reserved.
|
||||
RSVD_INTERRUPT_18 = 18, //!< Reserved.
|
||||
RSVD_INTERRUPT_19 = 19, //!< Reserved.
|
||||
RSVD_INTERRUPT_20 = 20, //!< Reserved.
|
||||
RSVD_INTERRUPT_21 = 21, //!< Reserved.
|
||||
|
||||
LS_INT_DEBUG_CC = 22, //!<(cluster-internal) COMMIRQ - Debug communications channel
|
||||
LS_INT_PMU = 23, //!<(cluster-internal) PMUIRQ - Perfmon*
|
||||
LS_INT_CTI = 24, //!<(cluster-internal) CTIIRQ - Cross-trigger interface*
|
||||
LS_INT_VMI = 25, //!<(cluster-internal) VCPUMNTIRQ -Virtual maintenance interface*
|
||||
|
||||
LS_INT_WDOG = 28, //!< Watchdog timer
|
||||
LS_INT_SEC_PHY_TIMER = 29, //!<(cluster-internal) CNTPSIRQ - EL1 Secure physical timer event*
|
||||
LS_INT_NON_SEC_PHY_TIMER = 30, //!<(cluster-internal) CNTPNSIRQ - EL1 Non-secure physical timer event*
|
||||
RSVD_INTERRUPT_31 = 31, //!< Reserved.
|
||||
RSVD_INTERRUPT_32 = 32, //!< Reserved.
|
||||
RSVD_INTERRUPT_33 = 33, //!< Reserved.
|
||||
RSVD_INTERRUPT_34 = 34, //!< Reserved.
|
||||
RSVD_INTERRUPT_35 = 35, //!< Reserved.
|
||||
RSVD_INTERRUPT_36 = 36, //!< Reserved.
|
||||
RSVD_INTERRUPT_37 = 37, //!< Reserved.
|
||||
RSVD_INTERRUPT_38 = 38, //!< Reserved.
|
||||
RSVD_INTERRUPT_39 = 39, //!< Reserved.
|
||||
RSVD_INTERRUPT_40 = 40, //!< Reserved.
|
||||
RSVD_INTERRUPT_41 = 41, //!< Reserved.
|
||||
RSVD_INTERRUPT_42 = 42, //!< Reserved.
|
||||
|
||||
LS_INT_DUART1 = 64, // Logical OR of DUART1 interrupt requests.
|
||||
|
||||
LS_INT_I2C1_2 = 66, //!< I2C1 and I2C2 ORed
|
||||
LS_INT_I2C3_4 = 67, //!< I2C3 and I2C4 ORed
|
||||
LS_INT_GPIO1_2 = 68, //!< GPIO1 and GPIO2 ORed
|
||||
LS_INT_GPIO3 = 69, //!< GPIO3
|
||||
|
||||
LS_INT_FLETIMER1 = 76, //!< ORed all Flextimer 1 interrupt signals
|
||||
LS_INT_FLETIMER2 = 77, //!< ORed all Flextimer 2 interrupt signals
|
||||
LS_INT_FLETIMER3 = 78, //!< ORed all Flextimer 3 interrupt signals
|
||||
LS_INT_FLETIMER4 = 79, //!< ORed all Flextimer 4 interrupt signals
|
||||
|
||||
LS_INT_I2C5_6 = 106, //!< I2C5 and I2C6 ORed
|
||||
LS_INT_I2C7_8 = 107, //!< I2C7 and I2C8 ORed
|
||||
|
||||
LS_INT_USB3_1 = 112, //!< USB1 ORed INT
|
||||
LS_INT_USB3_2 = 113, //!< USB2 ORed INT
|
||||
|
||||
LS_INT_LPUART1 = 264, //!< LPUART1 interrupt request.
|
||||
LS_INT_LPUART2 = 265, //!< LPUART1 interrupt request.
|
||||
LS_INT_LPUART3 = 266, //!< LPUART1 interrupt request.
|
||||
LS_INT_LPUART4 = 267, //!< LPUART1 interrupt request.
|
||||
LS_INT_LPUART5 = 268, //!< LPUART1 interrupt request.
|
||||
LS_INT_LPUART6 = 269, //!< LPUART1 interrupt request.
|
||||
|
||||
NR_OK1028_INTRS,
|
||||
|
||||
};
|
||||
|
||||
#endif //__IRQ_NUMBERS_H__
|
||||
109
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/jh7110/plic.c
Normal file
109
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/jh7110/plic.c
Normal file
@@ -0,0 +1,109 @@
|
||||
/*
|
||||
* This driver implements a version of the RISC-V PLIC with the actual layout
|
||||
* specified in chapter 8 of the SiFive U5 Coreplex Series Manual:
|
||||
*
|
||||
* https://static.dev.sifive.com/U54-MC-RVCoreIP.pdf
|
||||
*
|
||||
*/
|
||||
#include "asm/csr.h"
|
||||
#include "printf.h"
|
||||
#include "plic.h"
|
||||
#include "asm/mmio.h"
|
||||
#include "ptrace.h"
|
||||
|
||||
|
||||
extern unsigned long boot_cpu_hartid;
|
||||
|
||||
#define MAX_CPUS 4
|
||||
#define MAX_PLIC_IRQS 136
|
||||
|
||||
#define CPU_TO_HART(cpu) ((2 * cpu) + 2)
|
||||
|
||||
|
||||
//TODO: to debug
|
||||
void plic_set_priority(int hwirq, int pro)
|
||||
{
|
||||
#if 0
|
||||
unsigned int reg = PLIC_PRIORITY(hwirq);
|
||||
writel(pro, reg);
|
||||
#endif
|
||||
}
|
||||
|
||||
//TODO: to debug
|
||||
void plic_enable_irq(int cpu, int hwirq, int enable)
|
||||
{
|
||||
#if 0
|
||||
unsigned int hwirq_mask = 1 << (hwirq % 32);
|
||||
int hart = CPU_TO_HART(cpu);
|
||||
unsigned int reg = PLIC_MENABLE(hart) + 4 * (hwirq / 32);
|
||||
|
||||
// printk("plic_enable_irq hwirq=%d\n", hwirq);
|
||||
|
||||
if (enable) {
|
||||
writel(readl(reg) | hwirq_mask, reg);
|
||||
}
|
||||
else {
|
||||
writel(readl(reg) & ~hwirq_mask, reg);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
//TODO: to debug
|
||||
//Refer to linux/drivers/irqchip/irq-sifive-plic.c
|
||||
int plic_init(void)
|
||||
{
|
||||
#if 0
|
||||
int i;
|
||||
int hwirq;
|
||||
|
||||
// printk("plic_init boot_cpu_hartid=%lu\n", boot_cpu_hartid);
|
||||
|
||||
for (i = 0; i < MAX_CPUS; i++) {
|
||||
writel(0, PLIC_MTHRESHOLD(CPU_TO_HART(i)));
|
||||
|
||||
for (hwirq = 1; hwirq <= MAX_PLIC_IRQS; hwirq++) {
|
||||
plic_enable_irq(i, hwirq, 0);
|
||||
plic_set_priority(hwirq, 1);
|
||||
}
|
||||
}
|
||||
csr_set(CSR_IE, IE_EIE);
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
void plic_handle_irq(struct pt_regs *regs)
|
||||
{
|
||||
#if 0
|
||||
int hwirq;
|
||||
int hart = CPU_TO_HART(0);
|
||||
unsigned int claim_reg = PLIC_MCLAIM(hart);
|
||||
csr_clear(CSR_IE, IE_EIE);
|
||||
//TODO
|
||||
csr_set(CSR_IE, IE_EIE);
|
||||
#endif
|
||||
}
|
||||
|
||||
void plic_init_hart(uint32_t cpu_id)
|
||||
{
|
||||
;
|
||||
}
|
||||
|
||||
uint32_t plic_read_irq_ack(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
void plic_write_end_of_irq(uint32_t x)
|
||||
{
|
||||
;
|
||||
}
|
||||
|
||||
void intr_on(void)
|
||||
{
|
||||
;
|
||||
}
|
||||
|
||||
void intr_off(void)
|
||||
{
|
||||
;
|
||||
}
|
||||
@@ -0,0 +1,26 @@
|
||||
#ifndef _RISCV_PLIC_H
|
||||
#define _RISCV_PLIC_H
|
||||
|
||||
#include "memlayout.h"
|
||||
#include "ptrace.h"
|
||||
#include <stdint.h>
|
||||
|
||||
#define PLIC_BASE PLIC_VIRTMEM_BASE
|
||||
|
||||
#define PLIC_PRIORITY(hwirq) (PLIC_BASE + (hwirq) * 4)
|
||||
#define PLIC_PENDING(hwirq) (PLIC_BASE + 0x1000 + ((hwirq) / 32) * 4)
|
||||
#define PLIC_MENABLE(hart) (PLIC_BASE + 0x2000 + (hart) * 0x80)
|
||||
#define PLIC_MTHRESHOLD(hart) (PLIC_BASE + 0x200000 + (hart) * 0x1000)
|
||||
#define PLIC_MCLAIM(hart) (PLIC_BASE + 0x200004 + (hart) * 0x1000)
|
||||
|
||||
|
||||
int plic_init(void);
|
||||
void plic_enable_irq(int cpu, int hwirq, int enable);
|
||||
void plic_handle_irq(struct pt_regs *regs);
|
||||
void plic_init_hart(uint32_t cpu_id);
|
||||
uint32_t plic_read_irq_ack(void);
|
||||
void plic_write_end_of_irq(uint32_t x);
|
||||
void intr_on(void);
|
||||
void intr_off(void);
|
||||
|
||||
#endif /* _RISCV_PLIC_H */
|
||||
233
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/jh7110/trap.c
Normal file
233
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/jh7110/trap.c
Normal file
@@ -0,0 +1,233 @@
|
||||
/*
|
||||
* 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 trap.c
|
||||
* @brief trap interface of hardkernel
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023.05.06
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: trap.c
|
||||
Description: trap interface of hardkernel
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. first version
|
||||
*************************************************/
|
||||
#include <stdint.h>
|
||||
|
||||
#include "assert.h"
|
||||
#include "core.h"
|
||||
#include "multicores.h"
|
||||
#include "syscall.h"
|
||||
#include "task.h"
|
||||
|
||||
#include "mmu.h"
|
||||
|
||||
#include "asm/csr.h"
|
||||
#include "ptrace.h"
|
||||
#include "plic.h"
|
||||
|
||||
|
||||
extern void dabort_handler(struct trapframe* r);
|
||||
extern void iabort_handler(struct trapframe* r);
|
||||
|
||||
void kernel_abort_handler(struct trapframe* tf)
|
||||
{
|
||||
uint64_t ec = tf->cause;
|
||||
|
||||
switch (ec) {
|
||||
case 0:
|
||||
case 1:
|
||||
case 2:
|
||||
case 12:
|
||||
iabort_handler(tf);
|
||||
break;
|
||||
case 4:
|
||||
case 5:
|
||||
case 6:
|
||||
case 7:
|
||||
case 13:
|
||||
case 15:
|
||||
dabort_handler(tf);
|
||||
break;
|
||||
default: {
|
||||
ERROR("tf->cause: %016lx\n", tf->cause);
|
||||
ERROR("Current Task: %s.\n", cur_cpu()->task->name);
|
||||
panic("Unimplemented Error Occured.\n");
|
||||
}
|
||||
}
|
||||
panic("Return from abort handler.\n");
|
||||
}
|
||||
|
||||
void kernel_intr_handler(struct trapframe* tf)
|
||||
{
|
||||
panic("Intr at kernel mode should never happen by design.\n");
|
||||
}
|
||||
|
||||
extern void context_switch(struct context*, struct context*);
|
||||
void syscall_arch_handler(struct trapframe* tf)
|
||||
{
|
||||
uint64_t ec = tf->cause;
|
||||
|
||||
switch (ec) {
|
||||
case EXC_SYSCALL:
|
||||
software_irq_dispatch(tf);
|
||||
break;
|
||||
|
||||
default: {
|
||||
ERROR("USYSCALL: unexpected\n");
|
||||
ERROR("tf->cause: %016lx\n", tf->cause);
|
||||
|
||||
extern void dump_tf(struct trapframe * tf);
|
||||
dump_tf(tf);
|
||||
|
||||
// kill error task
|
||||
xizi_enter_kernel();
|
||||
assert(cur_cpu()->task != NULL);
|
||||
ERROR("Error Task: %s\n", cur_cpu()->task->name);
|
||||
sys_exit(cur_cpu()->task);
|
||||
context_switch(cur_cpu()->task->thread_context.context, &cur_cpu()->scheduler);
|
||||
panic("dabort end should never be reashed.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
extern void handle_exception(void);
|
||||
|
||||
void trap_init(void)
|
||||
{
|
||||
csr_write(stvec, handle_exception);
|
||||
csr_write(sie, 0);
|
||||
__asm__ volatile("csrw sscratch, zero" : : : "memory");
|
||||
#if 0
|
||||
printk("trap_init test\n");
|
||||
__asm__ volatile("ebreak");
|
||||
printk("trap_init test ok\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
void trap_set_exception_vector(uint64_t new_tbl_base)
|
||||
{
|
||||
csr_write(stvec, new_tbl_base);
|
||||
}
|
||||
|
||||
static void do_trap_error(struct pt_regs *regs, const char *str)
|
||||
{
|
||||
printk("Oops: %s\n", str);
|
||||
printk("sstatus: 0x%016lx, sbadaddr: 0x%016lx, scause: 0x%016lx\n",
|
||||
regs->status, regs->badaddr, regs->cause);
|
||||
panic("Fatal exception\n");
|
||||
}
|
||||
|
||||
#define DO_ERROR_INFO(name) \
|
||||
static int name(struct pt_regs *regs, const char *str) \
|
||||
{ \
|
||||
do_trap_error(regs, str); \
|
||||
return 0; \
|
||||
}
|
||||
|
||||
DO_ERROR_INFO(do_trap_unknown);
|
||||
DO_ERROR_INFO(do_trap_insn_misaligned);
|
||||
DO_ERROR_INFO(do_trap_insn_fault);
|
||||
DO_ERROR_INFO(do_trap_insn_illegal);
|
||||
DO_ERROR_INFO(do_trap_load_misaligned);
|
||||
DO_ERROR_INFO(do_trap_load_fault);
|
||||
DO_ERROR_INFO(do_trap_store_misaligned);
|
||||
DO_ERROR_INFO(do_trap_store_fault);
|
||||
DO_ERROR_INFO(do_trap_ecall_u);
|
||||
DO_ERROR_INFO(do_trap_ecall_s);
|
||||
DO_ERROR_INFO(do_trap_break);
|
||||
DO_ERROR_INFO(do_page_fault);
|
||||
|
||||
struct fault_info {
|
||||
int (*fn)(struct pt_regs *regs, const char *name);
|
||||
const char *name;
|
||||
};
|
||||
|
||||
static struct fault_info fault_inf[] = {
|
||||
{do_trap_insn_misaligned, "Instruction address misaligned"},
|
||||
{do_trap_insn_fault, "Instruction access fault"},
|
||||
{do_trap_insn_illegal, "Illegal instruction"},
|
||||
{do_trap_break, "Breakpoint"},
|
||||
{do_trap_load_misaligned, "Load address misaligned"},
|
||||
{do_trap_load_fault, "Load access fault"},
|
||||
{do_trap_store_misaligned, "Store/AMO address misaligned"},
|
||||
{do_trap_store_fault, "Store/AMO access fault"},
|
||||
{do_trap_ecall_u, "Environment call from U-mode"},
|
||||
{do_trap_ecall_s, "Environment call from S-mode"},
|
||||
{do_trap_unknown, "unknown 10"},
|
||||
{do_trap_unknown, "unknown 11"},
|
||||
{do_page_fault, "Instruction page fault"},
|
||||
{do_page_fault, "Load page fault"},
|
||||
{do_trap_unknown, "unknown 14"},
|
||||
{do_page_fault, "Store/AMO page fault"},
|
||||
};
|
||||
|
||||
|
||||
struct fault_info * ec_to_fault_info(unsigned long scause)
|
||||
{
|
||||
struct fault_info *inf;
|
||||
if (scause >= (sizeof(fault_inf)/sizeof(fault_inf[0]))) {
|
||||
printk("The cause is out of range Exception Code, scause=0x%lx\n", scause);
|
||||
panic("Fatal exception\n");
|
||||
}
|
||||
inf = &fault_inf[scause];
|
||||
return inf;
|
||||
}
|
||||
|
||||
void handle_irq(struct pt_regs *regs, unsigned long scause)
|
||||
{
|
||||
switch (scause & ~CAUSE_IRQ_FLAG) {
|
||||
case IRQ_S_TIMER:
|
||||
//handle_timer_irq();
|
||||
break;
|
||||
case IRQ_S_EXT:
|
||||
plic_handle_irq(regs);
|
||||
break;
|
||||
case IRQ_S_SOFT:
|
||||
// TODO
|
||||
break;
|
||||
default:
|
||||
panic("unexpected interrupt cause\n");
|
||||
}
|
||||
}
|
||||
|
||||
void do_exception(struct pt_regs *regs, unsigned long scause)
|
||||
{
|
||||
const struct fault_info *inf;
|
||||
|
||||
printk("%s, scause: 0x%lx\n", __func__, scause);
|
||||
|
||||
if (scause & CAUSE_IRQ_FLAG) {
|
||||
intr_irq_dispatch((struct trapframe *)regs);
|
||||
}
|
||||
else {
|
||||
inf = ec_to_fault_info(scause);
|
||||
if (!inf->fn(regs, inf->name)) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#define INIT_THREAD_INFO \
|
||||
{ \
|
||||
.flags = 0, \
|
||||
.preempt_count = 1, \
|
||||
}
|
||||
struct thread_info init_thread_info = INIT_THREAD_INFO;
|
||||
@@ -0,0 +1,145 @@
|
||||
/*
|
||||
* 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 trap_common.c
|
||||
* @brief trap interface of hardkernel
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2023.05.06
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: trap_common.c
|
||||
Description: trap interface of hardkernel
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. first version
|
||||
*************************************************/
|
||||
#include <string.h>
|
||||
|
||||
#include "core.h"
|
||||
#include "cortex.h"
|
||||
|
||||
#include "trap_common.h"
|
||||
|
||||
#include "log.h"
|
||||
#include "multicores.h"
|
||||
|
||||
#include "plic.h"
|
||||
|
||||
static struct XiziTrapDriver xizi_trap_driver;
|
||||
|
||||
extern void trap_init(void);
|
||||
extern void trap_set_exception_vector(uint64_t new_tbl_base);
|
||||
|
||||
void panic(char* s)
|
||||
{
|
||||
KPrintf("panic: %s\n", s);
|
||||
for (;;)
|
||||
;
|
||||
}
|
||||
|
||||
static void _sys_irq_init(int cpu_id)
|
||||
{
|
||||
// primary core init intr
|
||||
if (cpu_id == 0) {
|
||||
plic_init();
|
||||
}
|
||||
plic_init_hart(cpu_id);
|
||||
}
|
||||
|
||||
static void _sys_trap_init(int cpu_id)
|
||||
{
|
||||
if (cpu_id == 0) {
|
||||
trap_init();
|
||||
}
|
||||
_sys_irq_init(cpu_id);
|
||||
}
|
||||
|
||||
static void _cpu_irq_enable(void)
|
||||
{
|
||||
intr_on();
|
||||
}
|
||||
|
||||
static void _cpu_irq_disable(void)
|
||||
{
|
||||
intr_off();
|
||||
}
|
||||
|
||||
static void _single_irq_enable(int irq, int cpu, int prio)
|
||||
{
|
||||
plic_enable_irq(cpu, irq, 1);
|
||||
}
|
||||
|
||||
static void _single_irq_disable(int irq, int cpu)
|
||||
{
|
||||
plic_enable_irq(cpu, irq, 0);
|
||||
}
|
||||
|
||||
static inline uintptr_t* _switch_hw_irqtbl(uintptr_t* new_tbl_base)
|
||||
{
|
||||
trap_set_exception_vector((uintptr_t)new_tbl_base);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static void _bind_irq_handler(int irq, irq_handler_t handler)
|
||||
{
|
||||
xizi_trap_driver.sw_irqtbl[irq].handler = handler;
|
||||
}
|
||||
|
||||
static uint32_t _hw_before_irq()
|
||||
{
|
||||
|
||||
uint32_t iar = plic_read_irq_ack();
|
||||
return iar;
|
||||
}
|
||||
|
||||
static uint32_t _hw_cur_int_num(uint32_t int_info)
|
||||
{
|
||||
return int_info & 0x3FF;
|
||||
}
|
||||
|
||||
static void _hw_after_irq(uint32_t int_info)
|
||||
{
|
||||
plic_write_end_of_irq(int_info);
|
||||
}
|
||||
|
||||
int _cur_cpu_id()
|
||||
{
|
||||
return cpu_get_current();
|
||||
}
|
||||
|
||||
static struct XiziTrapDriver xizi_trap_driver = {
|
||||
.sys_irq_init = _sys_trap_init,
|
||||
.cur_cpu_id = _cur_cpu_id,
|
||||
|
||||
.cpu_irq_enable = _cpu_irq_enable,
|
||||
.cpu_irq_disable = _cpu_irq_disable,
|
||||
.single_irq_enable = _single_irq_enable,
|
||||
.single_irq_disable = _single_irq_disable,
|
||||
.switch_hw_irqtbl = _switch_hw_irqtbl,
|
||||
|
||||
.bind_irq_handler = _bind_irq_handler,
|
||||
|
||||
.hw_before_irq = _hw_before_irq,
|
||||
.hw_cur_int_num = _hw_cur_int_num,
|
||||
.hw_after_irq = _hw_after_irq,
|
||||
};
|
||||
|
||||
struct XiziTrapDriver* hardkernel_intr_init(struct TraceTag* hardkernel_tag)
|
||||
{
|
||||
xizi_trap_driver.sys_irq_init(0);
|
||||
xizi_trap_driver.cpu_irq_disable();
|
||||
return &xizi_trap_driver;
|
||||
}
|
||||
104
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/ptrace.h
Normal file
104
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/ptrace.h
Normal file
@@ -0,0 +1,104 @@
|
||||
#ifndef _ASM_RISCV_PTRACE_H
|
||||
#define _ASM_RISCV_PTRACE_H
|
||||
|
||||
struct pt_regs {
|
||||
unsigned long epc;
|
||||
unsigned long ra;
|
||||
unsigned long sp;
|
||||
unsigned long gp;
|
||||
unsigned long tp;
|
||||
unsigned long t0;
|
||||
unsigned long t1;
|
||||
unsigned long t2;
|
||||
unsigned long s0;
|
||||
unsigned long s1;
|
||||
unsigned long a0;
|
||||
unsigned long a1;
|
||||
unsigned long a2;
|
||||
unsigned long a3;
|
||||
unsigned long a4;
|
||||
unsigned long a5;
|
||||
unsigned long a6;
|
||||
unsigned long a7;
|
||||
unsigned long s2;
|
||||
unsigned long s3;
|
||||
unsigned long s4;
|
||||
unsigned long s5;
|
||||
unsigned long s6;
|
||||
unsigned long s7;
|
||||
unsigned long s8;
|
||||
unsigned long s9;
|
||||
unsigned long s10;
|
||||
unsigned long s11;
|
||||
unsigned long t3;
|
||||
unsigned long t4;
|
||||
unsigned long t5;
|
||||
unsigned long t6;
|
||||
/* Supervisor/Machine CSRs */
|
||||
unsigned long status;
|
||||
unsigned long badaddr;
|
||||
unsigned long cause;
|
||||
/* a0 value before the syscall */
|
||||
unsigned long orig_a0;
|
||||
};
|
||||
|
||||
#define REG_FMT "%016lx"
|
||||
|
||||
#define user_mode(regs) (((regs)->status & SR_PP) == 0)
|
||||
|
||||
//#define MAX_REG_OFFSET offsetof(struct pt_regs, orig_a0)
|
||||
|
||||
/* Helpers for working with the instruction pointer */
|
||||
static inline unsigned long instruction_pointer(struct pt_regs *regs)
|
||||
{
|
||||
return regs->epc;
|
||||
}
|
||||
static inline void instruction_pointer_set(struct pt_regs *regs,
|
||||
unsigned long val)
|
||||
{
|
||||
regs->epc = val;
|
||||
}
|
||||
|
||||
#define profile_pc(regs) instruction_pointer(regs)
|
||||
|
||||
/* Helpers for working with the user stack pointer */
|
||||
static inline unsigned long user_stack_pointer(struct pt_regs *regs)
|
||||
{
|
||||
return regs->sp;
|
||||
}
|
||||
static inline void user_stack_pointer_set(struct pt_regs *regs,
|
||||
unsigned long val)
|
||||
{
|
||||
regs->sp = val;
|
||||
}
|
||||
|
||||
/* Valid only for Kernel mode traps. */
|
||||
static inline unsigned long kernel_stack_pointer(struct pt_regs *regs)
|
||||
{
|
||||
return regs->sp;
|
||||
}
|
||||
|
||||
/* Helpers for working with the frame pointer */
|
||||
static inline unsigned long frame_pointer(struct pt_regs *regs)
|
||||
{
|
||||
return regs->s0;
|
||||
}
|
||||
static inline void frame_pointer_set(struct pt_regs *regs,
|
||||
unsigned long val)
|
||||
{
|
||||
regs->s0 = val;
|
||||
}
|
||||
|
||||
static inline unsigned long regs_return_value(struct pt_regs *regs)
|
||||
{
|
||||
return regs->a0;
|
||||
}
|
||||
|
||||
static inline void regs_set_return_value(struct pt_regs *regs,
|
||||
unsigned long val)
|
||||
{
|
||||
regs->a0 = val;
|
||||
}
|
||||
|
||||
|
||||
#endif /* _ASM_RISCV_PTRACE_H */
|
||||
270
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/trampoline.S
Normal file
270
Ubiquitous/XiZi_AIoT/hardkernel/intr/riscv/rv64gc/trampoline.S
Normal file
@@ -0,0 +1,270 @@
|
||||
/*
|
||||
* 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 trampoline.S
|
||||
* @brief trap in and out code
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024-04-22
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: trampoline.S
|
||||
Description: trap in and out code
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2024-04-22
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. first version
|
||||
*************************************************/
|
||||
|
||||
#include "asm/csr.h"
|
||||
#include "asm/asm-offsets.h"
|
||||
|
||||
|
||||
.align 4
|
||||
.global handle_exception
|
||||
handle_exception:
|
||||
# Here tp is struct thread_info
|
||||
csrrw tp, CSR_SCRATCH, tp
|
||||
bnez tp, _save_context
|
||||
|
||||
_restore_kernel_tpsp:
|
||||
csrr tp, CSR_SCRATCH
|
||||
REG_S sp, 16(tp)
|
||||
|
||||
_save_context:
|
||||
REG_S sp, 24(tp)
|
||||
REG_L sp, 16(tp)
|
||||
# Here sp is struct trapframe
|
||||
addi sp, sp, -(PT_SIZE_ON_STACK)
|
||||
REG_S x1, PT_RA(sp)
|
||||
REG_S x3, PT_GP(sp)
|
||||
REG_S x5, PT_T0(sp)
|
||||
REG_S x6, PT_T1(sp)
|
||||
REG_S x7, PT_T2(sp)
|
||||
REG_S x8, PT_S0(sp)
|
||||
REG_S x9, PT_S1(sp)
|
||||
REG_S x10, PT_A0(sp)
|
||||
REG_S x11, PT_A1(sp)
|
||||
REG_S x12, PT_A2(sp)
|
||||
REG_S x13, PT_A3(sp)
|
||||
REG_S x14, PT_A4(sp)
|
||||
REG_S x15, PT_A5(sp)
|
||||
REG_S x16, PT_A6(sp)
|
||||
REG_S x17, PT_A7(sp)
|
||||
REG_S x18, PT_S2(sp)
|
||||
REG_S x19, PT_S3(sp)
|
||||
REG_S x20, PT_S4(sp)
|
||||
REG_S x21, PT_S5(sp)
|
||||
REG_S x22, PT_S6(sp)
|
||||
REG_S x23, PT_S7(sp)
|
||||
REG_S x24, PT_S8(sp)
|
||||
REG_S x25, PT_S9(sp)
|
||||
REG_S x26, PT_S10(sp)
|
||||
REG_S x27, PT_S11(sp)
|
||||
REG_S x28, PT_T3(sp)
|
||||
REG_S x29, PT_T4(sp)
|
||||
REG_S x30, PT_T5(sp)
|
||||
REG_S x31, PT_T6(sp)
|
||||
|
||||
/*
|
||||
* Disable user-mode memory access as it should only be set in the
|
||||
* actual user copy routines.
|
||||
*
|
||||
* Disable the FPU to detect illegal usage of floating point in kernel
|
||||
* space.
|
||||
*/
|
||||
li t0, SR_SUM | SR_FS
|
||||
|
||||
REG_L s0, 24(tp)
|
||||
csrrc s1, CSR_STATUS, t0
|
||||
csrr s2, CSR_EPC
|
||||
csrr s3, CSR_TVAL
|
||||
csrr s4, CSR_CAUSE
|
||||
csrr s5, CSR_SCRATCH
|
||||
REG_S s0, PT_SP(sp)
|
||||
REG_S s1, PT_STATUS(sp)
|
||||
REG_S s2, PT_EPC(sp)
|
||||
REG_S s3, PT_BADADDR(sp)
|
||||
REG_S s4, PT_CAUSE(sp)
|
||||
REG_S s5, PT_TP(sp)
|
||||
|
||||
/*
|
||||
* Set the scratch register to 0, so that if a recursive exception
|
||||
* occurs, the exception vector knows it came from the kernel
|
||||
*/
|
||||
csrw CSR_SCRATCH, x0
|
||||
|
||||
/* Load the global pointer */
|
||||
.option push
|
||||
.option norelax
|
||||
la gp, __global_pointer$
|
||||
.option pop
|
||||
|
||||
/*
|
||||
* MSB of cause differentiates between
|
||||
* interrupts and exceptions
|
||||
*/
|
||||
bge s4, zero, 1f
|
||||
|
||||
la ra, ret_from_exception
|
||||
|
||||
/* Handle interrupts */
|
||||
move a0, sp /* pt_regs */
|
||||
//la a1, handle_arch_irq
|
||||
la a1, intr_irq_dispatch
|
||||
REG_L a1, (a1)
|
||||
jr a1
|
||||
|
||||
1:
|
||||
/*
|
||||
* Exceptions run with interrupts enabled or disabled depending on the
|
||||
* state of SR_PIE in m/sstatus.
|
||||
*/
|
||||
andi t0, s1, SR_PIE
|
||||
beqz t0, 1f
|
||||
/* kprobes, entered via ebreak, must have interrupts disabled. */
|
||||
li t0, EXC_BREAKPOINT
|
||||
beq s4, t0, 1f
|
||||
|
||||
csrs CSR_STATUS, SR_IE
|
||||
|
||||
1:
|
||||
la ra, ret_from_exception
|
||||
/* Handle syscalls */
|
||||
li t0, EXC_SYSCALL
|
||||
beq s4, t0, handle_syscall
|
||||
|
||||
mv a0, sp
|
||||
mv a1, s4
|
||||
tail do_exception
|
||||
|
||||
handle_syscall:
|
||||
/* save the initial A0 value (needed in signal handlers) */
|
||||
REG_S a0, PT_ORIG_A0(sp)
|
||||
/*
|
||||
* Advance SEPC to avoid executing the original
|
||||
* scall instruction on sret
|
||||
*/
|
||||
addi s2, s2, 0x4
|
||||
REG_S s2, PT_EPC(sp)
|
||||
|
||||
/* Trace syscalls, but only if requested by the user. */
|
||||
j handle_syscall_trace_enter
|
||||
|
||||
ret
|
||||
|
||||
|
||||
/* Slow paths for ptrace. */
|
||||
handle_syscall_trace_enter:
|
||||
csrr s0, satp
|
||||
la a0, riscv_kernel_satp
|
||||
ld a0, 0(a0)
|
||||
csrw satp, a0
|
||||
sfence.vma
|
||||
|
||||
move a0, sp
|
||||
//call do_syscall_trace_enter
|
||||
call syscall_arch_handler
|
||||
move t0, a0
|
||||
REG_L a0, PT_A0(sp)
|
||||
REG_L a1, PT_A1(sp)
|
||||
REG_L a2, PT_A2(sp)
|
||||
REG_L a3, PT_A3(sp)
|
||||
REG_L a4, PT_A4(sp)
|
||||
REG_L a5, PT_A5(sp)
|
||||
REG_L a6, PT_A6(sp)
|
||||
REG_L a7, PT_A7(sp)
|
||||
//bnez t0, ret_from_syscall_rejected
|
||||
//j check_syscall_nr
|
||||
handle_syscall_trace_exit:
|
||||
move a0, sp
|
||||
//call do_syscall_trace_exit
|
||||
|
||||
csrw satp, s0
|
||||
sfence.vma
|
||||
|
||||
j ret_from_exception
|
||||
|
||||
|
||||
ret_from_exception:
|
||||
REG_L s0, PT_STATUS(sp)
|
||||
csrc CSR_STATUS, SR_IE
|
||||
|
||||
andi s0, s0, SR_SPP
|
||||
bnez s0, resume_kernel
|
||||
|
||||
resume_userspace:
|
||||
/* Save unwound kernel stack pointer in thread_info */
|
||||
addi s0, sp, PT_SIZE_ON_STACK
|
||||
REG_S s0, 16(tp)
|
||||
|
||||
/*
|
||||
* Save TP into the scratch register , so we can find the kernel data
|
||||
* structures again.
|
||||
*/
|
||||
csrw CSR_SCRATCH, tp
|
||||
|
||||
restore_all:
|
||||
REG_L a0, PT_STATUS(sp)
|
||||
|
||||
REG_L a2, PT_EPC(sp)
|
||||
REG_SC x0, a2, PT_EPC(sp)
|
||||
|
||||
csrw CSR_STATUS, a0
|
||||
csrw CSR_EPC, a2
|
||||
|
||||
REG_L x1, PT_RA(sp)
|
||||
REG_L x3, PT_GP(sp)
|
||||
REG_L x4, PT_TP(sp)
|
||||
REG_L x5, PT_T0(sp)
|
||||
REG_L x6, PT_T1(sp)
|
||||
REG_L x7, PT_T2(sp)
|
||||
REG_L x8, PT_S0(sp)
|
||||
REG_L x9, PT_S1(sp)
|
||||
REG_L x10, PT_A0(sp)
|
||||
REG_L x11, PT_A1(sp)
|
||||
REG_L x12, PT_A2(sp)
|
||||
REG_L x13, PT_A3(sp)
|
||||
REG_L x14, PT_A4(sp)
|
||||
REG_L x15, PT_A5(sp)
|
||||
REG_L x16, PT_A6(sp)
|
||||
REG_L x17, PT_A7(sp)
|
||||
REG_L x18, PT_S2(sp)
|
||||
REG_L x19, PT_S3(sp)
|
||||
REG_L x20, PT_S4(sp)
|
||||
REG_L x21, PT_S5(sp)
|
||||
REG_L x22, PT_S6(sp)
|
||||
REG_L x23, PT_S7(sp)
|
||||
REG_L x24, PT_S8(sp)
|
||||
REG_L x25, PT_S9(sp)
|
||||
REG_L x26, PT_S10(sp)
|
||||
REG_L x27, PT_S11(sp)
|
||||
REG_L x28, PT_T3(sp)
|
||||
REG_L x29, PT_T4(sp)
|
||||
REG_L x30, PT_T5(sp)
|
||||
REG_L x31, PT_T6(sp)
|
||||
|
||||
REG_L x2, PT_SP(sp)
|
||||
|
||||
sret
|
||||
|
||||
resume_kernel:
|
||||
j restore_all
|
||||
|
||||
|
||||
.global task_prepare_enter
|
||||
task_prepare_enter:
|
||||
call xizi_leave_kernel
|
||||
j ret_from_exception
|
||||
@@ -1,4 +1,9 @@
|
||||
ifneq ($(findstring $(BOARD), 3568 imx6q-sabrelite zynq7000-zc702), )
|
||||
SRC_DIR := arm
|
||||
endif
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := riscv
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
|
||||
@@ -1 +1,5 @@
|
||||
ifneq ($(findstring $(BOARD), jh7110), )
|
||||
SRC_DIR := rv64gc
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
@@ -0,0 +1,4 @@
|
||||
SRC_FILES := mmu_init.c mmu.c pagetable_attr.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
||||
@@ -0,0 +1,79 @@
|
||||
/*
|
||||
* 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 mmu.h
|
||||
* @brief mmu related configure and registers
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2024-04-26
|
||||
*/
|
||||
/*************************************************
|
||||
File name: mmu.h
|
||||
Description: mmu related configure and registers
|
||||
Others:
|
||||
History:
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. first version
|
||||
*************************************************/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "memlayout.h"
|
||||
|
||||
// #define TCR_SH1_INNER (0b11 << 28)
|
||||
// #define TCR_ORGN1_IRGN1_WRITEBACK_WRITEALLOC ((0b01 << 26) | (0b01 << 24))
|
||||
// #define TCR_SH0_INNER (0b11 << 12)
|
||||
// #define TCR_ORGN0_IRGN0_WRITEBACK_WRITEALLOC ((0b01 << 10) | (0b01 << 8))
|
||||
#define TCR_IPS (0 << 0)
|
||||
#define TCR_TG1_4K (0b10 << 30)
|
||||
#define TCR_TOSZ (0b11001 << 0)
|
||||
#define TCR_T1SZ (0b11001 << 16)
|
||||
#define TCR_TG0_4K (0 << 14)
|
||||
|
||||
#define TCR_VALUE \
|
||||
(TCR_IPS | TCR_TG1_4K | TCR_TG0_4K | TCR_TOSZ | TCR_T1SZ)
|
||||
|
||||
enum AccessPermission {
|
||||
AccessPermission_NoAccess = 0,
|
||||
AccessPermission_KernelOnly = 1, // EL1
|
||||
AccessPermission_Reserved = 2,
|
||||
AccessPermission_KernelUser = 3, // EL1&EL0
|
||||
};
|
||||
|
||||
void GetDevPteAttr(uintptr_t* attr);
|
||||
void GetUsrPteAttr(uintptr_t* attr);
|
||||
void GetUsrDevPteAttr(uintptr_t* attr);
|
||||
void GetKernPteAttr(uintptr_t* attr);
|
||||
void GetPdeAttr(uintptr_t* attr);
|
||||
|
||||
/*
|
||||
Enable MMU, cache, write buffer, etc.
|
||||
*/
|
||||
//#define SCTLR_R(val) __asm__ volatile("mrs %0, sctlr_el1" : "=r"(val)::"memory")
|
||||
//#define SCTLR_W(val) __asm__ volatile("msr sctlr_el1, %0" ::"r"(val) : "memory")
|
||||
#define SCTLR_R(val) 0
|
||||
#define SCTLR_W(val) 0
|
||||
|
||||
/*
|
||||
Read and write mmu pagetable register base addr
|
||||
*/
|
||||
|
||||
|
||||
#ifndef __ASSEMBLER__
|
||||
#include <stdint.h>
|
||||
__attribute__((always_inline)) static inline uint64_t v2p(void* a) { return ((uint64_t)(a)) - KERN_MEM_BASE; }
|
||||
__attribute__((always_inline)) static inline void* p2v(uint64_t a) { return (void*)((a) + KERN_MEM_BASE); }
|
||||
#endif
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user