Compare commits

..

23 Commits

Author SHA1 Message Date
96745618e4 上传文件至 src 2025-06-10 16:40:04 +08:00
48afdbf662 删除 src/6.10main.cpp 2025-06-10 16:39:51 +08:00
6111475b3f 上传文件至 src 2025-06-10 15:48:55 +08:00
060d02d7d9 上传文件至 / 2025-05-27 17:10:52 +08:00
c05c6d23aa 删除 README.md 2025-05-27 17:10:32 +08:00
a386df5401 上传文件至 / 2025-05-27 17:08:21 +08:00
81af2e2fa0 删除 README.md 2025-05-27 17:07:58 +08:00
4794a062dc 上传文件至 include 2025-05-26 19:29:55 +08:00
e8732009f2 上传文件至 src 2025-05-26 19:29:40 +08:00
f48627f6fa 上传文件至 src 2025-05-26 19:29:11 +08:00
e2e229ebf0 删除 src/main.h 2025-05-26 19:27:39 +08:00
fe65c81e3f 删除 src/main.cpp 2025-05-26 19:27:31 +08:00
bf45251b76 上传文件至 / 2025-05-20 10:49:28 +08:00
9da1ec5861 删除 README.md 2025-05-20 10:49:01 +08:00
6a65fce840 上传文件至 src 2025-05-20 10:40:47 +08:00
a9eb288f8d 上传文件至 src 2025-05-20 10:40:22 +08:00
b7ba69c736 删除 src/drm_func.c 2025-05-20 10:39:13 +08:00
bec8a43c72 删除 src/rga_func.c 2025-05-20 10:39:07 +08:00
8c0451dae8 删除 src/main.h 2025-05-20 10:39:00 +08:00
9e6195c5ca 删除 src/yolov5_detect_postprocess.cpp 2025-05-20 10:38:51 +08:00
4866767048 删除 src/yolov5_detect.cpp 2025-05-20 10:38:35 +08:00
4cc773d30c 删除 src/yuanbenmain.cpp 2025-05-20 10:38:04 +08:00
e16eb29887 删除 src/main.cpp 2025-05-20 10:37:49 +08:00
9 changed files with 3615 additions and 2348 deletions

View File

@ -1,6 +1,8 @@
# rknn_yolo_EAI_pic
# 本串口协议必备要求:先发送在接收
### 作者:崔志佳
## 注本项目已经通过串口测试传感器为115200摄像头为9500每次报警前会识别设备名称序号然后反馈到串口输出序列中
# rknn_yolo_EAI_pic
#### 简要说明

81
include/jlinux_uart.h Normal file
View File

@ -0,0 +1,81 @@
/***********************************************************************
* @file jlinux_uart.h
JLINUX_UART
* @brief header file
* @history
* Date Version Author description
* ========== ======= ========= =======================================
* 2022-07-27 V1.0 Lucky,lukai@jovision.com Create
*
* @Copyright (C) 2022 Jovision Technology Co., Ltd.
***********************************************************************/
#ifndef __JLINUX_UART_H__
#define __JLINUX_UART_H__
#ifdef __cplusplus
extern "C"
{
#endif
typedef struct _uart_ctx *juart_hdl_t;
typedef struct
{
int baudrate; //波特率:1200/2400/4800/9600/19200/38400/57600/115200/230400/380400/460800/921600
int datawidth; //数据位宽度:5/6/7/8
int stopbit; //停止位宽度:1/2
int parity; //奇偶校验:0无校验1奇校验2偶校验
}JUartAttr_t;
/**
*@brief 485jctrl_rs485相关接口使用
*@param name /dev/ttyS0
*@return
*/
juart_hdl_t juart_open(const char *name);
/**
*@brief
*@param handle
*/
int juart_close(juart_hdl_t handle);
/**
*@brief
*@param handle
*@param attr
*/
int juart_set_attr(juart_hdl_t handle, JUartAttr_t *attr);
int juart_get_fd(juart_hdl_t uart);
/**
*@brief
*@param handle
*@param data buffer
*@param len
*@return 0
*/
int juart_send(juart_hdl_t handle, char *data, int len);
/**
*@brief
*@param handle
*@param data buffer
*@param len buffer的长度
*@param timeout
*@return
*/
int juart_recv(juart_hdl_t handle, char *data, int len, int timeout);
/**
*@brief rs485模式
*@param handle
*@param mode 0:0
*@return 0
*/
int juart_set_rs485(juart_hdl_t handle, int mode);
#ifdef __cplusplus
}
#endif
#endif // __JLINUX_UART_H__

1826
src/6.10main .cpp Normal file

File diff suppressed because it is too large Load Diff

313
src/jlinux_uart.cpp Normal file
View File

@ -0,0 +1,313 @@
/***********************************************************************
* @file jctrl_uart.cpp
JCTRL_UART
* @brief header file
* @history
* Date Version Author description
* ========== ======= ========= =======================================
* 2022-07-21 V1.0 Lucky,lukai@jovision.com Create
*
* @Copyright (C) 2022 Jovision Technology Co., Ltd.
***********************************************************************/
#include <termios.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <linux/stat.h>
#include <sys/prctl.h>
#include <sys/ioctl.h>
#include <sys/types.h>
#include <fcntl.h>
#include <linux/serial.h>
#include "jlinux_uart.h"
struct _uart_ctx{
int fd;
};
int _get_baudrate(int nBaud)
{
switch(nBaud)
{
case 1200:
return B1200; //注B1200为系统定义
case 2400:
return B2400;
case 4800:
return B4800;
case 9600:
return B9600;
case 19200 :
return B19200;
case 38400:
return B38400;
case 57600:
return B57600;
case 115200:
return B115200;
default:
return B2400;
}
}
juart_hdl_t juart_open(const char *name){
juart_hdl_t uart = new _uart_ctx;
uart->fd = open(name, O_RDWR | O_NONBLOCK | O_NOCTTY | O_EXCL|O_SYNC);
return uart;
}
int juart_close(juart_hdl_t uart){
if(uart->fd>0)
close(uart->fd);
uart->fd = 0;
return 0;
}
int juart_get_fd(juart_hdl_t uart){
return uart->fd;
}
int juart_set_attr(juart_hdl_t uart, JUartAttr_t *attr){
if (uart->fd <= 0)
{
printf("jv_uart_recv_ex fd error\n");
return -1;
}
struct termios newtio, oldtio;
memset(&oldtio, 0, sizeof(oldtio));
/* save the old serial port configuration */
if (tcgetattr(uart->fd, &oldtio) != 0) {
perror("set_port/tcgetattr");
return -1;
}
memset(&newtio, 0, sizeof(newtio));
//设置波特率
int nBaud = _get_baudrate(attr->baudrate);
switch (nBaud)
{
case B300:
case B1200:
case B2400:
case B4800:
case B9600:
case B19200:
case B38400:
case B57600:
case B115200:
cfsetospeed(&newtio, nBaud);
cfsetispeed(&newtio, nBaud);
break;
default:
printf("jv_uart_set_attr:Unsupported baudrate!\n");
return -1;
}
/* ignore modem control lines and enable receiver */
newtio.c_cflag |= CLOCAL | CREAD;
newtio.c_cflag &= ~CSIZE;
/* set character size */
switch (attr->datawidth) {
case 5:
newtio.c_cflag |= CS5;
break;
case 6:
newtio.c_cflag |= CS6;
break;
case 7:
newtio.c_cflag |= CS7;
break;
case 8:
default:
newtio.c_cflag |= CS8;
break;
}
/* set the stop bits */
switch (attr->stopbit) {
default:
case 1:
newtio.c_cflag &= ~CSTOPB;
break;
case 2:
newtio.c_cflag |= CSTOPB;
break;
}
/* set the parity */
switch (attr->parity) {
case 'o':
case 'O':
case 1:
newtio.c_cflag |= PARENB;
newtio.c_cflag |= PARODD;
newtio.c_iflag |= INPCK;
break;
case 'e':
case 'E':
case 2:
newtio.c_cflag |= PARENB;
newtio.c_cflag &= ~PARODD;
newtio.c_iflag |= INPCK;
break;
case 'n':
case 'N':
case 0:
default:
newtio.c_cflag &= ~PARENB;
newtio.c_iflag &= ~INPCK;
break;
}
/* Raw input */
newtio.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
/* Software flow control is disabled */
newtio.c_iflag &= ~(IXON | IXOFF | IXANY);
/* Raw ouput */
newtio.c_oflag &=~ OPOST;
/* set timeout in deciseconds for non-canonical read */
newtio.c_cc[VTIME] = 0;
/* set minimum number of characters for non-canonical read */
newtio.c_cc[VMIN] = 0;
/* flushes data received but not read */
tcflush(uart->fd, TCIFLUSH);
/* set the parameters associated with the terminal from
the termios structure and the change occurs immediately */
if ((tcsetattr(uart->fd, TCSANOW, &newtio)) != 0) {
perror("set_port/tcsetattr");
return -1;
}
return 0;
}
int juart_send(juart_hdl_t uart, char *data, int len){
if (uart->fd > 0)
{
int ret = write(uart->fd, data, len);
if (ret == len)
return 0;
}
return -1;
}
int _modbus_rtu_select(juart_hdl_t uart, struct timeval *tv)
{
fd_set rfds;
FD_ZERO(&rfds);
FD_SET(uart->fd, &rfds);
int s_rc;
while ((s_rc = select(uart->fd+1, &rfds, NULL, NULL, tv)) == -1) {
if (errno == EINTR) {
fprintf(stderr, "A non blocked signal was caught\n");
/* Necessary after an error */
FD_ZERO(&rfds);
FD_SET(uart->fd, &rfds);
} else {
return -1;
}
}
if (s_rc == 0) {
/* Timeout */
errno = ETIMEDOUT;
return -1;
}
return s_rc;
}
int juart_recv(juart_hdl_t uart, char *data, int len, int timeout){
if (uart->fd > 0)
{
struct timeval tv;
tv.tv_sec = 0;
tv.tv_usec = timeout*1000;
if(_modbus_rtu_select(uart, &tv) > 0){
return read(uart->fd, data, len);
}
return -1;
}else{
usleep(timeout*1000);
}
return -1;
}
/**
*@brief start开始接收stop返回
*@param handle
*@param data
*@param len
*@param start nstart个字节
*@param nstart
*@param stop nstop个字节
*@param nstop
*/
extern "C" int juart_recv_ex(juart_hdl_t handle, char *data, int len, char *start, int nstart, char *stop, int nstop, int timeout);
int juart_recv_ex(juart_hdl_t uart, char *data, int len, char *start, int nstart, char *stop, int nstop, int timeout){
if (uart->fd <= 0)
{
printf("jv_uart_recv_ex fd error\n");
return -1;
}
int offset = 0;
int offset_end = 0;
int bytes_read = 0;
while (1)
{
bytes_read = read(uart->fd, &data[offset], 1);
if (bytes_read == 1 && offset < nstart && data[offset] == start[offset])
{
offset++;
}
if (offset == nstart)
break;
if (bytes_read < 1)
usleep(0);
}
while (offset < len)
{
if (data[offset] == stop[offset_end])
{
offset_end++;
}
if (offset_end == nstop)
break;
bytes_read = read(uart->fd, &data[offset], 1);
if (bytes_read == 1)
{
offset++;
}
else
{
usleep(0);
}
}
return offset;
}
/**
*@brief rs485模式
*@param handle
*@param mode 0:0
*@return 0
*/
int juart_set_rs485(juart_hdl_t handle, int mode)
{
struct serial_rs485 rs485;
if (ioctl(handle->fd, TIOCGRS485, &rs485) == -1)
{
printf("TIOCGRS485 ioctl error.\n");
return -1;
}
rs485.flags |= SER_RS485_ENABLED;
if (mode == 0)
{
rs485.flags &= ~SER_RS485_RTS_ON_SEND;
rs485.flags |= SER_RS485_RTS_AFTER_SEND;
}
else
{
rs485.flags |= SER_RS485_RTS_ON_SEND;
rs485.flags &= ~SER_RS485_RTS_AFTER_SEND;
}
rs485.delay_rts_before_send = 0;
rs485.delay_rts_after_send = 0;
if (ioctl(handle->fd, TIOCSRS485, &rs485) == -1)
{
printf("TIOCSRS485 ioctrl error.\n");
return -1;
}
return 0;
}

View File

@ -39,7 +39,9 @@
#include <jbus.h>
#include <jes/jes_mss.h>
#include <jes/jes_isp.h>
#include <jlinux/jlinux_mem.h>
#include <jes/jes_spk.h>
#include <jes/jes_bas.h>
#include "jlinux_uart.h"
#include <termios.h>
#include <cmath>
@ -53,9 +55,8 @@ static jmss_hdl_t g_jmss;
static jisp_hdl_t g_jisp;
static bool g_running;
jmss_stm_t* g_stm[5];
static jbas_hdl_t jbas_handle;
//配置文件路径
#define modelpath_fire "/demo/bin/fire2025_pre.rknn"
#define DOWNLOAD_VERSION_PATH "/tmp/version"
#define ID_FILE_PWD "/etc/DeviceID"
@ -72,31 +73,62 @@ static int serialPortInfraredSensor;
static int serialPortSolenoid;
float temperature_img[24][32];
unsigned char buffer[1544];
std::mutex mtx;
std::vector<uint8_t> ControlInstructions(16, 0x00);
#define BAS_TEST_BUS_NAME "bastest"
jbas_hdl_t g_jbas;
#define PRSTR(val) printf("%s: %s\n", #val, (val) ? (val) : "(null)")
using namespace cv;
using namespace std;
using json = nlohmann::json; //使用nlohmann JSON 库
using json = nlohmann::json;
// 定义GPIO控制引脚假设GPIO2_B0已经设置好
#define RELAY_GPIO_PIN 72 // 使用GPIO 72控制继电器
#define RELAY_GPIO_PIN 116 // 使用GPIO 72控制继电器
void hexdump(const char *buf, int len)
{
//printf("hexdump: len:%d \n", len);
for (int i = 0; i < len; i++)
{
printf("\033[0m\033[1;33m%02X \033[0m", buf[i], buf[i]);
}
printf("\n");
}
// 控制继电器复位的函数
void reset_relay() {
// 导出GPIO引脚
system("echo 72 > /sys/class/gpio/export");
system("echo 116 > /sys/class/gpio/export");
// 设置GPIO引脚为输出
system("echo out > /sys/class/gpio/gpio72/direction");
system("echo out > /sys/class/gpio/gpio116/direction");
// 复位继电器
system("echo 1 > /sys/class/gpio/gpio72/value"); // 设置高电平
system("echo 1 > /sys/class/gpio/gpio116/value"); // 设置高电平
usleep(1000000); // 等待1秒
system("echo 0 > /sys/class/gpio/gpio72/value"); // 设置低电平
system("echo 0 > /sys/class/gpio/gpio116/value"); // 设置低电平
std::cout << "Relay reset!" << std::endl;
}
// 播放音频的函数
void play_audio(const std::string& file_path, jspk_hdl_t jspk) {
JES_SPK_PlayFile(jspk, file_path.c_str());
while (JES_SPK_IsBusy(jspk)) {
sleep(1);
}
std::cout << "Audio played: " << file_path << std::endl;
}
constexpr auto CONFIG_FILE = "/demo/bin/jh.json";
constexpr auto ID_FILE_PATH = "/etc/DeviceID";
constexpr auto LICENSE_FILE = "/demo/bin/activation.lic";
@ -114,14 +146,14 @@ mutex activation_mutex;
class Config {
public:
static string getActivationUrl() { // 静态成员函数,用于获取激活 URL
static string getActivationUrl() {
try {
ifstream file(CONFIG_FILE);
if (!file) {
throw runtime_error("Config file not found");
}
json config = json::parse(file); // 使用 nlohmann JSON 库解析配置文件
json config = json::parse(file);
if (config.contains("activation_url")) {
string url = config["activation_url"];
cout << "[INFO] Using activation URL from JSON config: " << url << endl;
@ -129,8 +161,9 @@ class Config {
}
throw runtime_error("activation_url not found in config");
} catch (const exception& e) {
cerr << "[WARN] " << e.what() << " - Using default URL" << endl; //捕获异常
}
catch (const exception& e) {
cerr << "[WARN] " << e.what() << " - Using default URL" << endl;
return "http://183.238.1.242:8889/api/label/security";
}
}
@ -158,7 +191,8 @@ class Config {
for (char c : value) {
if (isalnum(c) || c == '-' || c == '_' || c == '.' || c == '~') {
escaped << c;
} else {
}
else {
escaped << '%' << setw(2) << int((unsigned char)c);
}
}
@ -192,7 +226,8 @@ class Config {
result = base64Encode(encrypted.data(), len);
} catch (const exception& e) {
}
catch (const exception& e) {
cerr << "[ERROR] RSA encryption failed: " << e.what() << endl;
ERR_print_errors_fp(stderr);
result.clear();
@ -318,8 +353,6 @@ class Config {
return processOnlineActivation();
}
// 内部函数实现checkLocalLicense, validateLicense, processOnlineActivation, generateLicenseFile
private:
string device_id_;
string mac_;
@ -379,7 +412,8 @@ class Config {
}
return false;
} catch (const json::exception& e) {
}
catch (const json::exception& e) {
cerr << "[ERROR] JSON parse error: " << e.what() << endl;
}
}
@ -421,6 +455,29 @@ class Config {
}
// 获取设备信息
int g_camera_number = 1;
std::string generateIndices(char result[4], Alarm* Alarm) {
std::string indices(16, '0');
int CA_ID = g_camera_number;
int start = (CA_ID - 1) * 4;
for (int i = 0; i < 4; ++i) {
if (result[i] == '1') {
indices[start + i] = '1';
Alarm->ifalarm = 1;
}
}
return indices;
}
int ALARM_TEMPERATURE;
int WARN_TEMPERATURE;
int MOVE_THRESHOLD;
@ -434,7 +491,7 @@ vector<vector<int>> now_result;
int width = 1920, height = 1080;
JMediaRawFrameType_e type = JMEDIA_RAWFRAMETYPE_NV12;
//查看是否重合
bool check_whether_in_last_result(vector<vector<int>>& last_result, vector<int>& now, std::ofstream& temperature_log) {
if (last_result.empty()) return true;
//查找now的框坐标是否有出现在上一帧
@ -454,7 +511,6 @@ bool check_whether_in_last_result(vector<vector<int>> &last_result, vector<int>
}
//获取当前系统时间
string Get_Time(int input) {
// 获取当前系统时间
std::time_t alarmTime_std = std::time(nullptr);
@ -477,7 +533,8 @@ string Get_Time(int input){
<< std::setw(2) << hour << ":"
<< std::setw(2) << minute << ":"
<< std::setw(2) << second;
}else{
}
else {
oss_alarmTime << std::setfill('0')
<< std::setw(2) << month << "_"
<< std::setw(2) << day << "_"
@ -559,23 +616,27 @@ void readFileAndStoreInGlobal(const std::string& filename) {
if (file.is_open()) {
std::getline(file, DeviceID); // 读取一行并存储在全局字符串中
file.close();
} else {
}
else {
std::cerr << "无法打开文件: " << filename << std::endl;
}
}
std::string generateIndices(char result[4],Alarm* Alarm) {
std::string indices;
for (int i = 0; i < 4; ++i) {
if (result[i] == '1') {
// 将索引值加入到生成的字符串中
indices += std::to_string(i + 1);
Alarm->ifalarm = 1;
}
}
return indices;
}
// std::string generateIndices(char result[4],Alarm* Alarm) {
// std::string indices;
// for (int i = 0; i < 4; ++i) {
// if (result[i] == '1') {
// // 将索引值加入到生成的字符串中
// indices += std::to_string(i + 1);
// Alarm->ifalarm = 1;
// }
// }
// return indices;
// }
void checkCoverage(int x1, int x2, int width, char result[4]) {
@ -689,7 +750,8 @@ bool directoryExists(const std::string &path) {
struct stat info;
if (stat(path.c_str(), &info) != 0) {
return false; // 文件夹不存在
} else if (info.st_mode & S_IFDIR) {
}
else if (info.st_mode & S_IFDIR) {
return true; // 文件夹存在
}
return false; // 存在但不是文件夹
@ -701,11 +763,13 @@ bool createDirectory(const std::string &path) {
if (mkdir(path.c_str(), 0755) == 0) {
std::cout << "文件夹创建成功: " << path << std::endl;
return true;
} else {
}
else {
std::cerr << "文件夹创建失败: " << strerror(errno) << std::endl;
return false;
}
} else {
}
else {
std::cout << "文件夹已存在: " << path << std::endl;
return true;
}
@ -733,11 +797,58 @@ void printVector(const std::vector<uint8_t>& vec) {
int main(int argc, char** argv)
{
std::string folderPath = "/demo/pic"; //保存图片的文件夹路径
std::string folderPath = "/demo/pic";
if (!createDirectory(folderPath)) {
return 0;
}
// 获取设备信息
jbus_hdl_t jbus = jbus_init("devinfo_test_app");
if (!jbus) {
fprintf(stderr, "Error: jbus_init() failed.\n");
return EXIT_FAILURE;
}
jbas_handle = JES_BAS_Init(jbus);
if (!jbas_handle) {
fprintf(stderr, "Error: JES_BAS_Init() failed.\n");
jbus_cleanup(jbus);
return EXIT_FAILURE;
}
JBASDevInfo_t devinfo;
int results = JES_BAS_GetDevInfo(jbas_handle, &devinfo, JFALSE);
if (results == 0) {
printf("Successfully retrieved device information:\n");
PRSTR(devinfo.devname);
string CA_ID = devinfo.devname;
PRSTR(devinfo.language);
//获取设备
// 提取设备名称中的摄像头编号
if (!CA_ID.empty()) {
char lastChar = CA_ID.back(); // 获取最后一个字符
if (isdigit(lastChar) && lastChar >= '1' && lastChar <= '4') {
g_camera_number = lastChar - '0'; // 转换为整数,例如 '2' -> 2
}
else {
g_camera_number = 1; // 默认值
fprintf(stderr, "Warning: Invalid device name format: %s\n", CA_ID.c_str());
}
}
else {
g_camera_number = 1; // 默认值
fprintf(stderr, "Warning: Device name is empty\n");
}
// 打印验证
printf("Camera number: %d\n", g_camera_number);
}
// 打开 JSON 文件
cout << "解析JSON文件" << endl;
std::ifstream file("/demo/bin/config.json");
@ -834,6 +945,10 @@ int main(int argc, char **argv)
pthread_t fire_rknn_tidp;
pthread_t smog_rknn_tidp;
pthread_t heart_beat_tidp;
pthread_t storage_serial;
pthread_create(&storage_serial, NULL, storage_serial_thread, NULL);
pthread_create(&fire_rknn_tidp, NULL, rkmedia_rknn_thread, model_fire);
// pthread_create(&heart_beat_tidp, NULL, heart_beat, NULL);
//串口读数据线程
@ -841,6 +956,7 @@ int main(int argc, char **argv)
pthread_create(&read_serial, NULL, read_serial_thread, NULL);
printf("%s initial finish\n", __func__);
while (!quit)
{
usleep(500000);
@ -850,51 +966,23 @@ int main(int argc, char **argv)
JES_ISP_Deinit(g_jisp);
jbus_cleanup(g_jbus);
} catch (const exception& e) {
}
catch (const exception& e) {
cerr << "[FATAL] " << e.what() << endl;
return EXIT_FAILURE;
}
return EXIT_SUCCESS;
}
//初始化串口
void* rkmedia_rknn_thread(void* args)
{
pthread_detach(pthread_self());
//打开协议串口
serialPortSolenoid = open(SERIAL_PORT_SOLENOID, O_RDWR | O_NOCTTY | O_NDELAY);
if (serialPortSolenoid == -1) {
printf("Failed to open serial port: %s\n", SERIAL_PORT_SOLENOID);
return 0;
}
struct termios tty;
memset(&tty, 0, sizeof(tty));
if (tcgetattr(serialPortSolenoid, &tty) != 0) {
printf("Failed to get serial port attributes\n");
close(serialPortSolenoid);
return 0;
}
cfsetospeed(&tty, BAUD_RATE);
cfsetispeed(&tty, BAUD_RATE);
tty.c_cflag = (tty.c_cflag & ~CSIZE) | CS8;
tty.c_cflag &= ~(PARENB | PARODD);
tty.c_cflag &= ~CSTOPB;
tty.c_cflag |= CREAD | CLOCAL;
tty.c_iflag = IGNPAR;
tty.c_oflag = 0;
tty.c_lflag = 0;
if (tcsetattr(serialPortSolenoid, TCSANOW, &tty) != 0) {
printf("Failed to set serial port attributes\n");
close(serialPortSolenoid);
return 0;
}
//初始化协议信息
std::vector<uint8_t> ControlInstructions(20,0x00);
ControlInstructions[0] = 0xCA; //协议头
ControlInstructions[1] = 0x14; //总长度
ControlInstructions[2] = 0x01; //操作指令
// ControlInstructions[0] = 0xCA; //协议头
// ControlInstructions[1] = 0x14; //总长度
// ControlInstructions[2] = 0x01; //操作指令
//打开JES的通道
jmss_raw_t* rawchn = JES_MSS_RawOpen(g_jmss, 0, width, height, type);
@ -940,6 +1028,8 @@ void *rkmedia_rknn_thread(void *args)
compression_params.push_back(30); // 设置压缩质量,范围为 0-100
int overtem_cnt = 0;
std::vector<int> over_tmp_deque(10, 0);
/* 算法运行 */
while (!quit) {
int time2run = 1;
@ -961,6 +1051,13 @@ void *rkmedia_rknn_thread(void *args)
Alarm.ifalarm = 0;
Alarm.ifwarn = 0;
// // int JES_MCS_GetLinkageList(jmcs_hdl_t hdl, JMCSLinkageList_t *list);
// JBOOL reverse = JTRUE;
// JBASDevInfo_t devinfo;
// JES_BAS_GetDevInfo(g_jbas, &devinfo, JTRUE);
// PRSTR(devinfo.devname);
// PRSTR(devinfo.language);
Mat src;
NV12ToRGB(width, height, frm.buffer, src);
//裁剪
@ -971,10 +1068,22 @@ void *rkmedia_rknn_thread(void *args)
char result_warn[4] = { '0','0','0','0' };
char result_fire_rknn[4] = { '0','0','0','0' };
//初始化ControlInstructions
ControlInstructions[3]=0x00;
ControlInstructions[4]=0x00;
ControlInstructions[5]=0x00;
ControlInstructions[6]=0x00;
// ControlInstructions[3]=0x00;
// ControlInstructions[4]=0x00;
// ControlInstructions[5]=0x00;
// ControlInstructions[6]=0x00;
// ControlInstructions[7]=0x00;
// ControlInstructions[8]=0x00;
// ControlInstructions[9]=0x00;
// ControlInstructions[10]=0x00;
// ControlInstructions[11]=0x00;
// ControlInstructions[12]=0x00;
// ControlInstructions[13]=0x00;
// ControlInstructions[14]=0x00;
// ControlInstructions[15]=0x00;
// ControlInstructions[16]=0x00;
// ControlInstructions[17]=0x00;
// ControlInstructions[18]=0x00;
if (time2run) {
cout << "run ." << endl;
@ -1050,10 +1159,12 @@ void *rkmedia_rknn_thread(void *args)
Alarm.ifalarm = 1;
over_tmp_deque.assign(9, 0);
over_tmp_deque.push_back(1);
}else{
}
else {
memset(result, '0', 4 * sizeof(char));
}
}else{
}
else {
over_tmp_deque.push_back(0);
// 保持队列长度为10如果超过长度则移除最前面的元素
if (over_tmp_deque.size() > 10) {
@ -1089,7 +1200,8 @@ void *rkmedia_rknn_thread(void *args)
std::string resultString_warn(result_warn, 4);
std::cout << WARN_TEMPERATURE << "度结果: " << resultString_warn << std::endl;
temperature_log << WARN_TEMPERATURE << "度结果: " << resultString_warn << std::endl;
}else if(Alarm.ifwarn){
}
else if (Alarm.ifwarn) {
printf("temprature > %d°C !\n", WARN_TEMPERATURE);
std::string resultString_warn(result_warn, 4);
std::cout << WARN_TEMPERATURE << "结果: " << resultString_warn << std::endl;
@ -1097,7 +1209,6 @@ void *rkmedia_rknn_thread(void *args)
}
}
if (Alarm.ifwarn) {
struct timeval start;
struct timeval end;
@ -1115,7 +1226,7 @@ void *rkmedia_rknn_thread(void *args)
auto current_time_now = std::chrono::high_resolution_clock::now();// 时间
auto value_time = std::chrono::duration_cast<std::chrono::milliseconds>(current_time_now - last_result_time);// 计算距离开始时间的时间差
if (value_time.count() - 10000 > 0) { //如果上下帧大于十秒,则清除上一帧
if (value_time.count() - 10000 > 0) {
last_result.clear();
}
}
@ -1138,7 +1249,6 @@ void *rkmedia_rknn_thread(void *args)
cout << "Detected object: " << det_result->name << endl;
//报警打印
if (Alarm.ifwarn) {
printf("%s @ (%d %d %d %d) %f\n",
det_result->name,
@ -1189,11 +1299,13 @@ void *rkmedia_rknn_thread(void *args)
or_result(result, result_warn);
temperature_log << "报警输入:" << string(result, 4) << endl;
//处理ControlInstructions数据
if(result[0] == '1') ControlInstructions[3]=0x01;
if(result[1] == '1') ControlInstructions[4]=0x01;
if(result[2] == '1') ControlInstructions[5]=0x01;
if(result[3] == '1') ControlInstructions[6]=0x01;
if (result[0] == '1') ControlInstructions[(g_camera_number - 1) * 4] = 0x01;
if (result[1] == '1') ControlInstructions[(g_camera_number - 1) * 4] = 0x01;
if (result[2] == '1') ControlInstructions[(g_camera_number - 1) * 4] = 0x01;
if (result[3] == '1') ControlInstructions[(g_camera_number - 1) * 4] = 0x01;
std::string indices = generateIndices(result, &Alarm);
std::cout << "结果: " << indices << std::endl;
Alarm.alarmCoverage = indices;
}
@ -1209,12 +1321,30 @@ void *rkmedia_rknn_thread(void *args)
exit(0); // 子进程完成继电器控制后退出
}
//计算校验位并发送
ControlInstructions[19] = calculateChecksum(ControlInstructions);
write(serialPortSolenoid, ControlInstructions.data(), ControlInstructions.size());
//打印串口协议
cout << "串口发送信息:";
printVector(ControlInstructions);
// 创建第二个子进程:播放音频
pid_t audio_pid = fork();
if (audio_pid == 0) {
printf("yuyin bobao\n");
jbus_hdl_t jbus = jbus_init("spktest");
jmss_hdl_t jms = JES_MSS_Init(jbus);
jspk_hdl_t jspk = JES_SPK_Init(jbus);
JMediaAencParam_t adec;
JES_SPK_GetParam(jspk, &adec, JFALSE);
adec.attr.volume = 80;
adec.attr.encType = JVMEDIA_AUDIO_TYPE_G711_A;
JES_SPK_SetParam(jspk, &adec);
// 播放音频
play_audio("/demo/bin/Sound.g711u", jspk);
// 清理
JES_SPK_Deinit(jspk);
JES_MSS_Deinit(jms);
jbus_cleanup(jbus);
exit(0); // 子进程完成音频播放后退出
}
cv::Mat rgb_img;
@ -1237,7 +1367,8 @@ void *rkmedia_rknn_thread(void *args)
int ret = pthread_create(&upload_message_controller_tidp, NULL, upload_message_controller, static_cast<void*>(&Alarm));
if (ret != 0) {
std::cerr << "Error creating controller thread: " << strerror(ret) << std::endl;
} else {
}
else {
std::cerr << "success creating controller thread" << std::endl;
}
}
@ -1337,7 +1468,8 @@ R"({
// fprintf(stderr, "curl_easy_perform() failed: %s\n",curl_easy_strerror(res));
if (res != CURLE_OK) {
std::cerr << "Failed to perform cURL request: " << curl_easy_strerror(res) << std::endl;
} else {
}
else {
std::cout << "Request successful!" << std::endl;
std::cout << "Response: " << response << std::endl;
}
@ -1417,29 +1549,24 @@ R"({
// fprintf(stderr, "curl_easy_perform() failed: %s\n",curl_easy_strerror(res));
if (res != CURLE_OK) {
std::cerr << "controller: Failed to perform cURL request: " << curl_easy_strerror(res) << std::endl;
} else {
}
else {
std::cout << "controller: Request successful!" << std::endl;
// std::cout << "controller: Response: " << response << std::endl;
}
// 清理 cURL 资源
curl_easy_cleanup(curl);
}
curl_global_cleanup(); // 清理全局 cURL 资源
curl_global_cleanup();
}
void* heart_beat(void* args) {
pthread_detach(pthread_self()); // 分离线程,使线程结束时系统自动回收资源
pthread_detach(pthread_self());
auto last_time = std::chrono::high_resolution_clock::now();// 记录开始时间
int time2run = 1;
// 当全局变量 quit 未置为真时,持续运行心跳线程
while (!quit) {
//获取时间
auto current_time = std::chrono::high_resolution_clock::now();
auto elapsed_time = std::chrono::duration_cast<std::chrono::milliseconds>(current_time - last_time);// 计算距离开始时间的时间差
@ -1488,7 +1615,8 @@ R"({
// fprintf(stderr, "curl_easy_perform() failed: %s\n",curl_easy_strerror(res));
if (res != CURLE_OK) {
std::cerr << "heart beat: Failed to perform cURL request: " << curl_easy_strerror(res) << std::endl;
} else {
}
else {
std::cout << "heart beat: Request successful!" << std::endl;
std::cout << "heart beat: Response: " << response << std::endl;
// 解析 JSON 字符串
@ -1499,7 +1627,8 @@ R"({
response_controllerId = jsonData["controllerId"];
std::cout << "Controller ID: " << response_controllerId << std::endl;
} catch (const json::parse_error& e) {
}
catch (const json::parse_error& e) {
std::cerr << "JSON parsing error: " << e.what() << std::endl;
}
}
@ -1518,8 +1647,6 @@ void *read_serial_thread(void *args)
{
pthread_detach(pthread_self());
ssize_t bytesRead;
// 打开红外传感器对应的串口设备
serialPortInfraredSensor = open(SERIAL_PORT_INFRARED_SENSOR, O_RDWR | O_NOCTTY | O_NDELAY);
if (serialPortInfraredSensor == -1) {
printf("Failed to open serial port: %s\n", SERIAL_PORT_INFRARED_SENSOR);
@ -1527,13 +1654,12 @@ void *read_serial_thread(void *args)
}
struct termios tty;
memset(&tty, 0, sizeof(tty)); // 初始化配置结构体,清零
memset(&tty, 0, sizeof(tty));
if (tcgetattr(serialPortInfraredSensor, &tty) != 0) {
printf("Failed to get serial port attributes\n");
close(serialPortInfraredSensor);
return 0;
}
// 设置串口输入和输出波特率
cfsetospeed(&tty, BAUD_RATE);
cfsetispeed(&tty, BAUD_RATE);
tty.c_cflag = (tty.c_cflag & ~CSIZE) | CS8;
@ -1549,26 +1675,9 @@ void *read_serial_thread(void *args)
return 0;
}
// while(1){
// mtx.lock();
// bytesRead = read(serialPortInfraredSensor, buffer, sizeof(buffer));
// mtx.unlock();
// if (bytesRead>0) {
// if((buffer[0]== 0x5a)&&(buffer[1]==0x5a)) {
// // printf("readed serialPortInfraredSensor date\n");
// }else{
// // printf("read failed\n");
// }
// }else{
// // printf("empty to read\n");
// }
// }
// 设置文件描述符集合和超时时间,准备使用 select() 进行串口数据的检测
fd_set readfds;
struct timeval timeout;
int selectResult;
// 此处后续可以继续添加使用 select() 监听串口数据的逻辑…
while (1) {
FD_ZERO(&readfds);
@ -1588,18 +1697,126 @@ void *read_serial_thread(void *args)
if (bytesRead > 0) {
if (buffer[0] == 0x5a && buffer[1] == 0x5a) {
// printf("readed serialPortInfraredSensor date\n");
} else {
}
else {
// printf("read failed\n");
}
}
}
} else if (selectResult == 0) {
}
else if (selectResult == 0) {
// 超时,没有数据可读
// printf("Timeout, no data available\n");
} else {
}
else {
// select出错
printf("select() failed\n");
break;
}
}
}
// pthread_t storage_serial;
// pthread_create(&storage_serial, NULL, storage_serial_thread, NULL);
// 首先定义协议相关的常量
#define PROTOCOL_HEAD 0x7E
#define PROTOCOL_VERSION 1
#define PROTOCOL_LENGTH 22
#define SOLENOID_VALVE_COUNT 16
#define COMMAND_QUERY 1
#define COMMAND_RESPONSE 2
// 定义协议结构体
typedef struct tagCamera485Protocol {
uint8_t m_head; // 协议头 0x7e
uint8_t m_version; // 版本1~255
uint8_t m_length; // 协议总长度,包含校验位
uint8_t m_address; // 地址0~255
uint8_t m_command; // 操作指令
uint8_t m_solenoidValve[SOLENOID_VALVE_COUNT]; // 电磁阀状态
uint8_t m_checkSum; // 校验和
} CCamera485Protocol;
// 优化后的storage_serial_thread函数
void* storage_serial_thread(void* args) {
pthread_detach(pthread_self());
// {
// test *ptest1 = NULL;
// test *ptest2[2] = {};
// if (ptest1 == ptest2[0])
// {
// printf("ptest1 == ptest2");
// }
// else
// {
// printf("ptest1 != ptest2");
// }
// return 0;
// }
juart_hdl_t hdl = juart_open("/dev/ttyS5");
JUartAttr_t attr = {.baudrate = 9600,
.datawidth = 8,
.stopbit = 1,
.parity = 0};
juart_set_attr(hdl, &attr);
juart_set_rs485(hdl, 0);
unsigned char hexData[] = {0x01, 0x03, 0x00, 0x00, 0x00, 0x02, 0xC4, 0x0B};
juart_send(hdl, (char*)hexData, sizeof(hexData));
printf("send: ");
hexdump((char*)hexData, sizeof(hexData));
while (1)
{
CCamera485Protocol protocol;
int len = juart_recv(hdl, (char *)&protocol, sizeof(CCamera485Protocol), 6000);
if (len <= 0)
{
printf("==============>>>: %s,%d: recv timeout!\n", strrchr(__FILE__,'/'),__LINE__);
}
if (len == sizeof(CCamera485Protocol))
{
hexdump((char*)&protocol,len);
// 处理协议
if (protocol.m_head == PROTOCOL_HEAD &&
protocol.m_command == COMMAND_QUERY &&
protocol.m_address == (g_camera_number - 1))
{
// 构造响应
uint8_t response_array[22] = {0};
// 1. 填充头部
response_array[0] = PROTOCOL_HEAD; // 协议头
response_array[1] = PROTOCOL_VERSION; // 版本
response_array[2] = PROTOCOL_LENGTH; // 长度
response_array[3] = g_camera_number - 1; // 地址
response_array[4] = COMMAND_RESPONSE; // 命令
// 2. 填充电磁阀状态
mtx.lock();
for (int i = 0; i < SOLENOID_VALVE_COUNT; i++) {
response_array[5 + i] = ControlInstructions[i];
}
mtx.unlock();
// 3. 计算校验和前21字节累加和
uint8_t sum = 0;
for (int i = 0; i < 21; i++) {
sum += response_array[i];
}
response_array[21] = sum; // 校验和
juart_send(hdl, (char*)response_array, sizeof(response_array));
hexdump((char*)&response_array,sizeof(response_array));
std::fill(ControlInstructions.begin(), ControlInstructions.end(), 0x00);
sleep(2);
}
}
}
juart_close(hdl);
return 0;
}

View File

@ -62,6 +62,8 @@ void *upload_message_controller(void *args);
void *heart_beat(void *args); //上传心跳检测
void *distortion(void *args); //矫正
void *read_serial_thread(void *args); //读取串口传来的红外温度数据
void *storage_serial_thread(void *args);
struct Alarm {
int ifalarm;

View File

@ -23,6 +23,7 @@
static char labels[YOLOV5_CLASS_NUM][30] = {"0", "1"};
// static char labels[YOLOV5_CLASS_NUM][30] = {"fire"};
const int anchor0[6] = {10, 13, 16, 30, 33, 23};
const int anchor1[6] = {30, 61, 62, 45, 59, 119};

File diff suppressed because it is too large Load Diff