较多变动主要是在于改变了编码,代码格式发生变化; 代码变动主要在syncworkthread.cpp,修复了相机断开后数据仍在变动的问题。

main
seiyu 1 year ago
parent c7c63a3b2e
commit 1864c6cf04

@ -1,12 +1,9 @@
#include "AlarmInfo.h"
AlarmInfo::AlarmInfo()
{
}
AlarmInfo::~AlarmInfo()
{
}

@ -7,9 +7,8 @@ public:
~AlarmInfo();
public:
std::string alarm_start; //报警发生时间
std::string alarm_handle; //报警处理时间
std::string alarm_msg; //报警信息
int alarm_code; //报警代码
std::string alarm_start; //报警发生时间
std::string alarm_handle; //报警处理时间
std::string alarm_msg; //报警信息
int alarm_code; //报警代码
};

@ -2,7 +2,7 @@
#include "common.h"
#include "exportData.h"
extern bool g_debug_mode; //相机调试模式,工作模式必须停止状态才能打开
extern bool g_debug_mode; //相机调试模式,工作模式必须停止状态才能打开
extern SyncQueue<_XMLExportDataInfo>* export_XMLData_Info_queue;
//-----------------------------------------------------------------------------
@ -31,7 +31,7 @@ void CaptureThread::process( void )
{
try
{
//Line5回调
//Line5回调
mvIMPACT::acquire::GenICam::EventControl pEventCtrl_(pDev_);
//pEventCtrl_.eventSelector.writeS("Line5FallingEdge");
//pEventCtrl_.eventNotification.writeS("Off");
@ -65,14 +65,14 @@ void CaptureThread::process( void )
m_threadFunc.p_result_queue_ = p_result_queue;
m_threadFunc.p_double_queue_ = p_double_queue;
//相机掉线回调
//相机掉线回调
CIwtCameraLostCallbackMV cam_lost_cb;
cam_lost_cb.channel_ = Local_Num;
if (cam_lost_cb.registerComponent(pDev_->state) != true)
{
std::cout << "ERROR: Unable to register the camera's lost CallBack function!\n";
}
//图像采集循环
//图像采集循环
TDMR_ERROR result = DMR_NO_ERROR;
while ((result = static_cast<TDMR_ERROR>(pFI_->imageRequestSingle())) == DMR_NO_ERROR) {};
if (result != DEV_NO_FREE_REQUEST_AVAILABLE)
@ -105,14 +105,14 @@ void CaptureThread::process( void )
if (!g_debug_mode)
{
#ifdef IMM_PROCESS
p_image_queue->put(std::make_pair(1,image_clone)); //放入临时队列
p_image_queue->put(std::make_pair(1, image_clone)); //放入临时队列
#else
p_unit_queue->put(image_clone); //放入临时队列
p_unit_queue->put(image_clone); //放入临时队列
#endif
}
else
{
p_debug_queue->put(image_clone); //放入调试队列
p_debug_queue->put(image_clone); //放入调试队列
}
cnt++;
// display some statistics

@ -4,7 +4,7 @@
#include "common.h"
#include <windows.h>
#include "exportData.h"
extern bool g_debug_mode; //相机调试模式,工作模式必须停止状态才能打开
extern bool g_debug_mode; //相机调试模式,工作模式必须停止状态才能打开
extern SingleCamInfoStruct SingleCamInfo[NumberOfSupportedCameras];
extern SyncQueue<_XMLExportDataInfo>* export_XMLData_Info_queue;
extern PLCDevice* m_PLCDevice;
@ -48,6 +48,7 @@ inline void FallingGpioEventfunction(MV_EVENT_OUT_INFO* pEventInfo, void* pUser)
{
CaptureThreadHIKptr->p_image_sync_queue->put(CaptureThreadHIKptr->p_image_sync_arr->image_sync_arr);
CaptureThreadHIKptr->p_image_sync_arr->collect_cnt = 0;
//CaptureThreadHIKptr->p_image_sync_arr->image_sync_arr.swap(std::vector<std::pair<int, cv::Mat>>());
}
}
#else
@ -58,7 +59,15 @@ inline void FallingGpioEventfunction(MV_EVENT_OUT_INFO* pEventInfo, void* pUser)
CaptureThreadHIKptr->p_unit_queue->clear();
}
catch (...) {
std::cout << "FallingGpioEventfunction error" << std::endl;
//std::cout << "FallingGpioEventfunction error" << std::endl;
std::exception_ptr p = std::current_exception();
try {
if (p)
std::rethrow_exception(p);
}
catch (const std::exception& e) {
qDebug() << "Caught an exception: " << e.what();
}
}
}
inline void RisingGpioEventfunction(MV_EVENT_OUT_INFO* pEventInfo, void* pUser) {
@ -247,7 +256,7 @@ void CaptureThreadHIK::process( void )
nRet = MV_CC_RegisterExceptionCallBack(CamHandle, LossCallBack[Local_Num], this);
if (nRet) { std::cout << "can not register loss callback" << std::endl; nnRet = nRet; }
//#ifdef IMM_FEED_BACK ///不打开无反馈等( 延后一次两次用ifndef // 不延后用ifdef)
//#ifdef IMM_FEED_BACK ///不打开无反馈等( 延后一次两次用ifndef // 不延后用ifdef)
nRet = MV_CC_SetEnumValueByString(CamHandle, "EventSelector", "Line0FallingEdge");
if (nRet) { std::cout << "can not set EventSelector" << std::endl; nnRet = nRet; }
@ -293,12 +302,12 @@ void CaptureThreadHIK::process( void )
#ifdef IMM_PROCESS
p_image_queue->put(std::make_pair(1, image_clone));
#else
p_unit_queue->put(image_clone); //放入临时队列
p_unit_queue->put(image_clone); //放入临时队列
#endif
}
else
{
p_debug_queue->put(image_clone); //放入调试队列
p_debug_queue->put(image_clone); //放入调试队列
}
}
#if defined (IMM_FEED_BACK) || defined (CAP_FEED_BACK)

@ -249,10 +249,6 @@
<ExcludedFromBuild Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">true</ExcludedFromBuild>
<ExcludedFromBuild Condition="'$(Configuration)|$(Platform)'=='Release|x64'">true</ExcludedFromBuild>
</ClCompile>
<ClCompile Include="GeneratedFiles\Debug\moc_SyncWorkThread.cpp">
<ExcludedFromBuild Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">true</ExcludedFromBuild>
<ExcludedFromBuild Condition="'$(Configuration)|$(Platform)'=='Release|x64'">true</ExcludedFromBuild>
</ClCompile>
<ClCompile Include="GeneratedFiles\qrc_cigarette.cpp">
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
</PrecompiledHeader>

@ -263,9 +263,6 @@
<ClCompile Include="SyncWorkThread.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="GeneratedFiles\Debug\moc_SyncWorkThread.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="GeneratedFiles\Release\moc_SyncWorkThread.cpp">
<Filter>Source Files</Filter>
</ClCompile>

@ -18,56 +18,56 @@ private:
public:
FtpManager() {
/* 设置通讯协议 */
/* 设置通讯协议 */
url.setScheme("ftp");
/* 设置用户名 */
/* 设置用户名 */
url.setUserName("FTP2");
/* 设置密码 */
/* 设置密码 */
url.setPassword("123");
/* 设置主机,也可以是域名 */
/* 设置主机,也可以是域名 */
url.setHost("192.168.1.170");
/* 设置端口号一般为21 */
/* 设置端口号一般为21 */
url.setPort(666);
}
void uploadSingleFile(QString filePath, QString remotePath) {
// 设置路径
// 设置路径
url.setPath(remotePath);
qDebug() << "uploadSingleFile path " << url.path();
// 装载本地文件
// 装载本地文件
QFile file(filePath);
bool isopen = false;
isopen = file.open(QIODevice::ReadOnly);
qDebug() << "Open file " << isopen;
if (isopen) {
// 读取本地文件数据
// 读取本地文件数据
QByteArray data = file.readAll();
file.close();
// 上传数据,上传成功后会在远端创建文件
// 上传数据,上传成功后会在远端创建文件
manager.setNetworkAccessible(QNetworkAccessManager::Accessible);
QNetworkReply* reply = manager.put(QNetworkRequest(url), data);
QEventLoop eventLoop;
//QObject::connect(reply, SIGNAL(finished()), &eventLoop, SLOT(quit()));
//// 进入等待,但事件循环依然进行 */
//// 进入等待,但事件循环依然进行 */
//eventLoop.exec();
//QObject::connect(reply, &QNetworkReply::finished, [&]() {
// if (reply->error() == QNetworkReply::NoError) {
// // 读取响应数据
// // 读取响应数据
// QByteArray responseData = reply->readAll();
// // 处理响应数据
// // 处理响应数据
// qDebug() << "Received response:" << responseData;
// }
// else {
// // 处理错误
// // 处理错误
// qDebug() << "Error occurred:" << reply->errorString();
// }
// // 清理资源
// // 清理资源
// reply->deleteLater();
// });
}

@ -1,4 +1,4 @@
#pragma once
#pragma once
#include <QDialog>
#include "ui_alarmdialog.h"

@ -1,5 +1,5 @@
#include "alg_jd.h"
#include <direct.h> //所需的库文件
#include <direct.h> //所需的库文件
extern SysConf g_sys_conf;
@ -20,7 +20,7 @@ bool AlgJd::init(QString model_path, QString model_name)
QString image_path;
if (model_path.length() > 0 && model_name.length() > 0) {
// 拼凑的模型文件路径
// 拼凑的模型文件路径
modelWeights = model_path.toStdString() + "/" + model_name.toStdString();
modelConfiguration = model_path.toStdString() + "/jd.cfg";
classesFile = model_path.toStdString() + "/jd.names";
@ -60,14 +60,14 @@ bool AlgJd::init(QString model_path, QString model_name)
image = cv::imread("D:/Release/alg_jd.bmp");
}*/
//识别一张图测试模型是否正确并且完成GPU数据加载
if (!image.data) return false; //判断测试图片是否正常读取
//识别一张图测试模型是否正确并且完成GPU数据加载
if (!image.data) return false; //判断测试图片是否正常读取
std::vector<std::pair<int, cv::Rect> > results;
detect(image, image, results);
if (results.size() > 0)
return true; //检测到目标,则初始化成功
return true; //检测到目标,则初始化成功
else
return false; //否则初始化失败
return false; //否则初始化失败
}
bool AlgJd::test_detect()
@ -356,10 +356,10 @@ void AlgJd::post_process_batch(std::vector<cv::Mat>& vec_frame, std::vector<cv::
{
int idx = indices[j];
cv::Rect box = boxes[i][idx];
if (confidences[i][idx] > g_sys_conf.ConfThreshold * 0.01)///识别度低于阈值NG处理
if (confidences[i][idx] > g_sys_conf.ConfThreshold * 0.01)///识别度低于阈值NG处理
{
if (box.width > 15)
{//识别框宽度大于15显示识别小于认为无胶点NG处理
{//识别框宽度大于15显示识别小于认为无胶点NG处理
drawPred(classIds[i][idx], confidences[i][idx], box.x, box.y,
box.x + box.width, box.y + box.height, vec_frame[k]);
results.push_back(std::make_pair(classIds[i][idx], box));

@ -12,12 +12,12 @@
#define BaslerClassID 0x02
#define c_maxCamerasToUse (size_t)2
//5:╩ри╚
//6:╨зи╚
//1:╨Ли╚
//2:╩фи╚
//3:╟ви╚
//4:бли╚
//5:灰色
//6:黑色
//1:红色
//2:黄色
//3:白色
//4:绿色
class BaslerCamera : public BaseCamera
{

@ -38,7 +38,7 @@ void change_shift::on_pushButton_apply_released()
QTime timeA;
QTime timeB;
QTime timeC;
if (ui.radioButton_auto->isChecked()) { /// ÒÑÒþ²Ø
if (ui.radioButton_auto->isChecked()) { /// 已隐藏
g_sys_conf.auto_shift = 1;
g_sys_conf.timing_shift = 0;
g_sys_conf.shift_byhand = 0;

File diff suppressed because it is too large Load Diff

@ -5,24 +5,24 @@
#include "basecamera.h"
#include "QtCore\qdatetime.h"
//#define __DEBUG //debug信息输出功能
//#define __UDPSend //网络发送功能
#define __TCPSend // TCP发送
#define USB_BASLER_NEW_FW //使用basler定制固件
//#define IMM_PROCESS //拍照后立马处理,不等校验信号
//#define IMM_FEED_BACK //处理完后立马反馈,不等校验信号
#define ONE_TIME_SHIFT //错开一拍发送反馈(默认错开两次)
#define AI_WARM_UP //AI识别开始前的热身动作
//#define LICENSE_VERIFY //开启license文件校验
//CAP_FEED_BACK和DOUBLE_FEED_BACK不要一起开
//#define __DEBUG //debug信息输出功能
//#define __UDPSend //网络发送功能
#define __TCPSend // TCP发送
#define USB_BASLER_NEW_FW //使用basler定制固件
//#define IMM_PROCESS //拍照后立马处理,不等校验信号
//#define IMM_FEED_BACK //处理完后立马反馈,不等校验信号
#define ONE_TIME_SHIFT //错开一拍发送反馈(默认错开两次)
#define AI_WARM_UP //AI识别开始前的热身动作
//#define LICENSE_VERIFY //开启license文件校验
//CAP_FEED_BACK和DOUBLE_FEED_BACK不要一起开
#if defined (ONE_TIME_SHIFT)
//#define CAP_FEED_BACK //拍照时也检测有没有测试结果,有的话就反馈
//#define DOUBLE_FEED_BACK //一次ng两次反馈ng信号
//#define CAP_FEED_BACK //拍照时也检测有没有测试结果,有的话就反馈
//#define DOUBLE_FEED_BACK //一次ng两次反馈ng信号
#endif
//#define identify_Hik_YSXID//识别海康相机YSXID
//#define __ExportData // 输出检测数据到XML文档
#define DRAW_RECT // 鼠标画框功能
#define SYNC_CAMERA //相机同步处理图片
//#define identify_Hik_YSXID//识别海康相机YSXID
//#define __ExportData // 输出检测数据到XML文档
#define DRAW_RECT // 鼠标画框功能
#define SYNC_CAMERA //相机同步处理图片
#define Queue_Size 15
#define Unit_Queue_Size Queue_Size*3
@ -34,21 +34,21 @@
#define DEBUG(format, ...)
#endif
// 主界面基本参数配置文件
// 主界面基本参数配置文件
#define CONFPATH "D:/conf/conf_path.txt"
//#define CONFIGURE_FILE "D:/conf/conf.txt"
// 相机旋转角度配置文件
// 相机旋转角度配置文件
#define ROTATE_FILE "rotate.txt"
#define MODBUS_CONFIGURE_FILE "modbus.txt"
#define PLC_CONFIG_FILE "plc.txt"
#define SELECT_RECTS_FILE "SelectRects%d%d.txt"
#define STATISTIC_FILE "camera%1_statistic.txt"
#define ALARM_RECORD_FILE "alarm.txt"
#define OUTPUT_HIGH_WIDTH 20000 //输出信号的脉冲宽度,微秒
#define OUTPUT_HIGH_WIDTH 20000 //输出信号的脉冲宽度,微秒
#define OP_TIME 300 //OP权限时长默认300秒
#define ADMIN_TIME 600 //ADMIN权限时长默认300秒
#define STOP_SECONDS 3 //检查多少次不变触发自动换班
#define OP_TIME 300 //OP权限时长默认300秒
#define ADMIN_TIME 600 //ADMIN权限时长默认300秒
#define STOP_SECONDS 3 //检查多少次不变触发自动换班
int string_split(std::string str, std::string pattern, std::vector<std::string>& out);
std::string format(const char* pszFmt, ...);
@ -63,9 +63,9 @@ std::vector<std::string> SpiteStringCharacter(std::string context);
class ConfPath {
public:
QString config_path; // 配置文件路径
//QString config_name; // 配置文件名
QString save_pics_path; // 保存图片存储路径
QString config_path; // 配置文件路径
//QString config_name; // 配置文件名
QString save_pics_path; // 保存图片存储路径
ConfPath() {
config_path = "";
@ -78,52 +78,52 @@ class SysConf
{
public:
std::mutex lock;
int save; //图片是否保存0不保存1保存NG, 2全部保存
int MisMatchAct; //错位行为1NG,0ok
int save_days; ///照片保存天数
int freesize; /// 设定清理图片最小空间
std::string ComPort; ///COM口
int ConfThreshold; //识别率
int auto_open; //是否自动打开相机0否1是
int auto_work; //是否自动开始工作0否1是
int auto_shift; //是否自动换班0否1是
int shift_byhand; // 是否手动换班0否1是
QTime shiftA; //A换班时间
QTime shiftB; //B换班时间
QTime shiftC; //C换班时间
QString location; // 所在地
QString model_path; // 模型文件夹路径
QString model_name; // 模型名
QString model_jpg_path; // 模型图片路径
int timing_shift; //是否定时换班0否1是
int expo[NumberOfSupportedCameras]; //相机曝光时间,单位微秒
int gain[NumberOfSupportedCameras]; //相机模拟增益范围0~64
int filter[NumberOfSupportedCameras];//相机滤波时间
int save; //图片是否保存0不保存1保存NG, 2全部保存
int MisMatchAct; //错位行为1NG,0ok
int save_days; ///照片保存天数
int freesize; /// 设定清理图片最小空间
std::string ComPort; ///COM口
int ConfThreshold; //识别率
int auto_open; //是否自动打开相机0否1是
int auto_work; //是否自动开始工作0否1是
int auto_shift; //是否自动换班0否1是
int shift_byhand; // 是否手动换班0否1是
QTime shiftA; //A换班时间
QTime shiftB; //B换班时间
QTime shiftC; //C换班时间
QString location; // 所在地
QString model_path; // 模型文件夹路径
QString model_name; // 模型名
QString model_jpg_path; // 模型图片路径
int timing_shift; //是否定时换班0否1是
int expo[NumberOfSupportedCameras]; //相机曝光时间,单位微秒
int gain[NumberOfSupportedCameras]; //相机模拟增益范围0~64
int filter[NumberOfSupportedCameras];//相机滤波时间
int UserID[NumberOfSupportedCameras];
int no[NumberOfSupportedCameras][3];//拍摄图片最少合格胶点数
int shoot[NumberOfSupportedCameras];//拍摄次数
std::string MonitorIP; //远程监控端的IP
int no[NumberOfSupportedCameras][3];//拍摄图片最少合格胶点数
int shoot[NumberOfSupportedCameras];//拍摄次数
std::string MonitorIP; //远程监控端的IP
int MonitorPort;
int FeedbackPort;
int FilePort;
//MonitorPort为数据端口
//MonitorPort+NumberOfSupportedCameras为图像端口
//MonitorPort+NumberOfSupportedCameras*2为发送命令端口,也就是FeedbackPort
//MonitorPort+NumberOfSupportedCameras*2+1为接受命令端口
//MonitorPort为数据端口
//MonitorPort+NumberOfSupportedCameras为图像端口
//MonitorPort+NumberOfSupportedCameras*2为发送命令端口,也就是FeedbackPort
//MonitorPort+NumberOfSupportedCameras*2+1为接受命令端口
SysConf()
{
save=0; //图片是否保存0不保存1保存NG, 2全部保存
MisMatchAct=1; //错位行为1NG,0ok
save_days = 1; ///照片保存天数
freesize = 10; /// 设定清理图片最小空间
ComPort = "COM1"; ///COM口
ConfThreshold = 1; ///百分比识别率
auto_open=1; //是否自动打开相机0否1是
auto_work=1; //是否自动开始工作0否1是
auto_shift=0; //是否自动换班0否1是
shift_byhand = 1; //是否手动换班0否1是
timing_shift = 0; //是否定时换班0否1是
save = 0; //图片是否保存0不保存1保存NG, 2全部保存
MisMatchAct = 1; //错位行为1NG,0ok
save_days = 1; ///照片保存天数
freesize = 10; /// 设定清理图片最小空间
ComPort = "COM1"; ///COM口
ConfThreshold = 1; ///百分比识别率
auto_open = 1; //是否自动打开相机0否1是
auto_work = 1; //是否自动开始工作0否1是
auto_shift = 0; //是否自动换班0否1是
shift_byhand = 1; //是否手动换班0否1是
timing_shift = 0; //是否定时换班0否1是
location = "";
model_path = "";
model_name = "";
@ -161,18 +161,18 @@ public:
}
};
#endif
//Modbus地址设置
//Modbus地址设置
class ModbusConf
{
public:
int kick[NumberOfSupportedCameras];
int quantity; //当班产量地址
int shift; //换班地址
int work; //开始/停止
int no_kick; //只拍照不剔除模式
int debug; //调试模式PLC产生模拟的line4信号
int reset; //复位
int alarm; //报警
int quantity; //当班产量地址
int shift; //换班地址
int work; //开始/停止
int no_kick; //只拍照不剔除模式
int debug; //调试模式PLC产生模拟的line4信号
int reset; //复位
int alarm; //报警
ModbusConf()
{
@ -181,18 +181,18 @@ public:
kick[i] = 0;
#endif
}
quantity=0; //当班产量地址
shift=0; //换班地址
work=0; //开始/停止
no_kick=0; //只拍照不剔除模式
debug=0; //调试模式PLC产生模拟的line4信号
reset=0; //复位
alarm=0; //报警
quantity = 0; //当班产量地址
shift = 0; //换班地址
work = 0; //开始/停止
no_kick = 0; //只拍照不剔除模式
debug = 0; //调试模式PLC产生模拟的line4信号
reset = 0; //复位
alarm = 0; //报警
}
};
#define DisplayLabel_Type_Bit 0x01 //1:打开范围识别功能0:关闭范围识别功能
#define DisplayLabel_Conf_Bit 0x02 //1:可以绘制矩形框0:不能绘制矩形框
#define DisplayLabel_Type_Bit 0x01 //1:打开范围识别功能0:关闭范围识别功能
#define DisplayLabel_Conf_Bit 0x02 //1:可以绘制矩形框0:不能绘制矩形框
class RectRatio
{
public:
@ -205,12 +205,12 @@ class DisplayLabelConf
{
public:
std::mutex lock;
bool leftButtonDownFlag = false; //左键单击后视频暂停播放的标志位
cv::Point2f originalPoint; //矩形框起点
cv::Point2f processPoint; //矩形框终点
bool leftButtonDownFlag = false; //左键单击后视频暂停播放的标志位
cv::Point2f originalPoint; //矩形框起点
cv::Point2f processPoint; //矩形框终点
cv::Mat g_last_mat[2];
bool g_max[2] = {false}; //视图是否最大化
bool g_max[2] = { false }; //视图是否最大化
uint8_t Flag[2] = { 0 };
std::vector<RectRatio> RectVet[2];
};

@ -14,7 +14,6 @@
extern SyncQueue<cv::Mat>* g_debug_queue[NumberOfSupportedCameras]; //相机调试模式图像队列
extern DisplayLabelConf g_display_label_conf[NumberOfSupportedCameras];
extern SingleCamInfoStruct SingleCamInfo[NumberOfSupportedCameras];
extern int rotationAngle[NumberOfSupportedCameras]; //图片旋转角度
extern bool isNeedRotate[NumberOfSupportedCameras];
class DebugThread : public QThread

@ -1,9 +1,6 @@
#include "dialogin.hpp"
#include "dialogin.hpp"
#include <QCryptographicHash>
#include <qdebug.h>
#include <qmessagebox.h>
extern bool g_op_mode; //是否操作员模式

@ -1,4 +1,4 @@
#pragma once
#pragma once
#include <QDialog>
#include "ui_dialogin.h"

@ -1,12 +1,12 @@
#pragma once
#pragma once
#include <QDialog>
#include "ui_dialogsetup.h"
#include "basecamera.h"
#include <qdebug.h>
#include <common.h>
#include <camera_glue.h>
#include <output_statistic.h>
#include <change_shift.h>
#include "common.h"
#include "camera_glue.h"
#include "output_statistic.h"
#include "change_shift.h"
class DialogSetup : public QDialog {
Q_OBJECT

@ -1,4 +1,4 @@
#include "dialogsetuppasswd.hpp"
#include "dialogsetuppasswd.hpp"
#include <QCryptographicHash>

@ -1,4 +1,4 @@
#pragma once
#pragma once
#include <QDialog>
#include "ui_dialogsetuppasswd.h"

@ -60,20 +60,20 @@ void ExportDataThread::stop()
}
bool ExportDataThread::ConnectFtp() {
// FTP地址
// FTP地址
string ftpServer = "192.168.1.170";
/* 端口号一般为21 */
/* 端口号一般为21 */
int port = 666;
/* 用户名 */
/* 用户名 */
string userName = "FTP2";
/* 密码 */
/* 密码 */
string pwd = "123";
if (hftp != NULL) {
InternetCloseHandle(hftp);
hftp = NULL;
}
// 创建ftp连接
// 创建ftp连接
hftp = InternetConnectA(hint, ftpServer.c_str(), port, userName.c_str(), pwd.c_str(), INTERNET_SERVICE_FTP, 0, 0);
if (hftp == NULL) {
qDebug() << "ftp connect failed because " << GetLastError();
@ -121,7 +121,7 @@ bool _ExportDataInfo::getAverageData(map<string, float> &averageData, int index)
XMLElement* TimeCostNode = userNode->FirstChildElement("TimeCost");
data["TimeCost"] += stof(TimeCostNode->GetText());
}
userNode = userNode->NextSiblingElement();//下一个兄弟节点
userNode = userNode->NextSiblingElement();//下一个兄弟节点
}
if (data["Total"] == 0)
return false;
@ -143,8 +143,8 @@ int ExportDataThread::insertXMLNode(const char* xmlPath, _XMLExportDataInfo& dat
//return 0;
}
/// 总统计数据
// 总检测数量
/// 总统计数据
// 总检测数量
XMLElement* Total = pDocument[data.cameraId]->NewElement("TotalDatas");
XMLElement* time = pDocument[data.cameraId]->NewElement("CurrentTime");
@ -157,52 +157,52 @@ int ExportDataThread::insertXMLNode(const char* xmlPath, _XMLExportDataInfo& dat
TotalCheckNum->InsertEndChild(pDocument[data.cameraId]->NewText(itoa(data.TotalCheckNum, s, 10)));
Total->InsertEndChild(TotalCheckNum);
// 总剔除数量
// 总剔除数量
XMLElement* TotalKickNum = pDocument[data.cameraId]->NewElement("TotalKickNum");
TotalKickNum->InsertEndChild(pDocument[data.cameraId]->NewText(itoa(data.TotalKickNum, s, 10)));
Total->InsertEndChild(TotalKickNum);
root->InsertEndChild(Total);
/// 各相机数据
// 相机id & 总数
/// 各相机数据
// 相机id & 总数
XMLElement* CameraNode = pDocument[data.cameraId]->NewElement("Camera");
CameraNode->SetAttribute("Count ", data.cameraTotal);
CameraNode->SetAttribute("Id", data.cameraId);
XMLElement* JudgeNum = pDocument[data.cameraId]->NewElement("JudgeNum");
// 各相机检测数量
// 各相机检测数量
XMLElement* checkNum = pDocument[data.cameraId]->NewElement("CheckNum");
checkNum->InsertEndChild(pDocument[data.cameraId]->NewText(itoa(data.checkNum, s, 10)));
JudgeNum->InsertEndChild(checkNum);
// 各相机ok数量
// 各相机ok数量
XMLElement* okNum = pDocument[data.cameraId]->NewElement("OkNum");
okNum->InsertEndChild(pDocument[data.cameraId]->NewText(itoa(data.okNum, s, 10)));
JudgeNum->InsertEndChild(okNum);
// 各相机ng数量
// 各相机ng数量
XMLElement* ngNum = pDocument[data.cameraId]->NewElement("NgNum");
ngNum->InsertEndChild(pDocument[data.cameraId]->NewText(itoa(data.ngNum, s, 10)));
JudgeNum->InsertEndChild(ngNum);
// 各相机实际剔除数量(单通道剔除时为总剔除数量)
// 各相机实际剔除数量(单通道剔除时为总剔除数量)
XMLElement* kickNum = pDocument[data.cameraId]->NewElement("KickNum");
kickNum->InsertEndChild(pDocument[data.cameraId]->NewText(itoa(data.kickNum, s, 10)));
JudgeNum->InsertEndChild(kickNum);
// 合格率
// 合格率
XMLElement* PassRate = pDocument[data.cameraId]->NewElement("PassRate");
std::string temp_str = std::to_string(data.PassRate * 100) + "%";
const char* temp_char = temp_str.c_str();
PassRate->InsertEndChild(pDocument[data.cameraId]->NewText(temp_char));
JudgeNum->InsertEndChild(PassRate);
// 剔除率
// 剔除率
XMLElement* KickRate = pDocument[data.cameraId]->NewElement("KickRate");
temp_str = std::to_string(data.KickRate * 100) + "%";
temp_char = temp_str.c_str();
KickRate->InsertEndChild(pDocument[data.cameraId]->NewText(temp_char));
JudgeNum->InsertEndChild(KickRate);
// 各相机胶点识别个数
// 各相机胶点识别个数
XMLElement* JdNum = pDocument[data.cameraId]->NewElement("JdNum");
JdNum->InsertEndChild(pDocument[data.cameraId]->NewText(data.jdNum.toStdString().c_str()));
JudgeNum->InsertEndChild(JdNum);
@ -213,13 +213,13 @@ int ExportDataThread::insertXMLNode(const char* xmlPath, _XMLExportDataInfo& dat
CameraNode->InsertEndChild(JudgeNum);
// 各相机采集速度
// 各相机采集速度
XMLElement* speed = pDocument[data.cameraId]->NewElement("Speed");
XMLElement* AcquisitionSpeed = pDocument[data.cameraId]->NewElement("AcquisitionSpeed");
AcquisitionSpeed->InsertEndChild(pDocument[data.cameraId]->NewText(data.AcquisitionSpeed.toStdString().c_str()));
speed->InsertEndChild(AcquisitionSpeed);
// 各相机检测速度
// 各相机检测速度
XMLElement* DetectSpeed = pDocument[data.cameraId]->NewElement("DetectSpeed");
DetectSpeed->InsertEndChild(pDocument[data.cameraId]->NewText(data.DetectSpeed.toStdString().c_str()));
speed->InsertEndChild(DetectSpeed);
@ -254,17 +254,17 @@ void ExportDataThread::run()
}
}
//*****************************************已经调试好,没有理清逻辑前不要动**********************
//*****************************************已经调试好,没有理清逻辑前不要动**********************
void ExportDataThread::check_save_dir(std::string dir_path)
{
// 如果目的路径不存在,一级一级创建
// 目的路径格式为:"./dir/dir1/.../"
// 如果目的路径不存在,一级一级创建
// 目的路径格式为:"./dir/dir1/.../"
if (FALSE == FtpSetCurrentDirectoryA(hftp, dir_path.c_str())) {
FtpSetCurrentDirectoryA(hftp, "/");
int pos = 1;
while (pos > 0) {
// 从第二个“/”开始依次找到目的路径中的“/”位置
// 从第二个“/”开始依次找到目的路径中的“/”位置
pos = dir_path.find_first_of('/', pos + 1);
if (pos == -1)
break;
@ -284,18 +284,18 @@ void ExportDataThread::ConnectServer(QString srcPath, QString destPath) {
string remotePath = destPath.toLocal8Bit().constData();
std::vector<string> files;
// 判断上传的是文件还是文件夹标识
// 判断上传的是文件还是文件夹标识
int size = 0;
struct stat st;
stat(filePath.c_str(), &st);
if (st.st_mode & S_IFDIR) {
//qDebug() << "filePath is Directory";
// 获取文件夹下所有文件名
// 获取文件夹下所有文件名
GetFiles(filePath, files);
size = files.size();
}
// 上传文件源为一个文件
// 上传文件源为一个文件
if (size == 0) {
int pos = remotePath.find_last_of('/');
string destFileName = remotePath.substr(pos + 1);
@ -303,7 +303,7 @@ void ExportDataThread::ConnectServer(QString srcPath, QString destPath) {
check_save_dir(tempPath);
if (!InternetGetConnectedState(NULL, 0)) {
qDebug() << "计算机未连接到互联网";
qDebug() << "计算机未连接到互联网";
}
else {
while (!FtpPutFileA(hftp, filePath.c_str(), remotePath.c_str(), FTP_TRANSFER_TYPE_BINARY, 0)) {
@ -313,11 +313,11 @@ void ExportDataThread::ConnectServer(QString srcPath, QString destPath) {
}
}
}
// 上传源为一个文件夹
// 上传源为一个文件夹
else {
for (int i = 0; i < size; i++) {
string tempFilePath = (string(files[i]).erase(0, filePath.length() + 1)).c_str();
// 获取上传路径中的文件名
// 获取上传路径中的文件名
int pos = tempFilePath.find_last_of('/');
string destFileName = tempFilePath.substr(pos + 1);
check_save_dir(remotePath + tempFilePath.substr(0, pos + 1));
@ -333,20 +333,20 @@ void ExportDataThread::GetDataFromSaveThread(QString filePath) {
ConnectServer(filePath, remotePath);
}
//*****************************************已经调试好,没有理清逻辑前不要动**********************
//*****************************************已经调试好,没有理清逻辑前不要动**********************
void ExportDataThread::GetFiles(string path, std::vector<string>& files) {
//文件句柄
//文件句柄
intptr_t hFile = 0;
//文件信息的结构体
//文件信息的结构体
struct _finddata_t fileinfo;
string p;
if ((hFile = _findfirst(p.assign(path).append("\\*").c_str(), &fileinfo)) != -1)
{
// "\\*"是指读取文件夹下的所有类型的文件
// "\\*"是指读取文件夹下的所有类型的文件
do
{
//如果是目录,迭代之
//如果不是,加入列表
//如果是目录,迭代之
//如果不是,加入列表
if ((fileinfo.attrib & _A_SUBDIR))
{
if (strcmp(fileinfo.name, ".") != 0 && strcmp(fileinfo.name, "..") != 0)

@ -18,45 +18,45 @@ using namespace tinyxml2;
class _XMLExportDataInfo {
public:
// 总的统计数据
// 总的统计数据
long long cameraTotal;
int TotalCheckNum; // 总检测数量
int TotalKickNum; // 总剔除数量
double PassRate; // 合格率
double KickRate; // 剔除率
// 各相机数据
int TotalCheckNum; // 总检测数量
int TotalKickNum; // 总剔除数量
double PassRate; // 合格率
double KickRate; // 剔除率
// 各相机数据
int cameraId;
int shotCounts; // 拍摄张数
int checkNum; // 各相机检测个数
int okNum; // 各相机ok数量
int ngNum; // 各相机ng数量
int kickNum; // 各相机实际剔除数量(单通道剔除时为总剔除数量)
QString AcquisitionSpeed; // 各相机采集速度
QString jdNum; // 各相机胶点识别个数
QString DetectSpeed; // 各相机检测速度(识别时间)
int shotCounts; // 拍摄张数
int checkNum; // 各相机检测个数
int okNum; // 各相机ok数量
int ngNum; // 各相机ng数量
int kickNum; // 各相机实际剔除数量(单通道剔除时为总剔除数量)
QString AcquisitionSpeed; // 各相机采集速度
QString jdNum; // 各相机胶点识别个数
QString DetectSpeed; // 各相机检测速度(识别时间)
_XMLExportDataInfo() {
// 总的统计数据
TotalCheckNum = 0; // 总检测数量
TotalKickNum = 0; // 总剔除数量
PassRate = 0.0; // 合格率
KickRate = 0.0; // 剔除率
// 总的统计数据
TotalCheckNum = 0; // 总检测数量
TotalKickNum = 0; // 总剔除数量
PassRate = 0.0; // 合格率
KickRate = 0.0; // 剔除率
cameraId = -1;
jdNum = QString("0,0,0");
// 各相机数据
// 各相机数据
shotCounts = 0;
checkNum = 0;
okNum = 0;
ngNum = 0;
kickNum = 0; // 各相机实际剔除数量(单通道剔除时为总剔除数量)
AcquisitionSpeed = "0"; // 各相机采集速度
DetectSpeed = "0"; // 各相机检测速度
kickNum = 0; // 各相机实际剔除数量(单通道剔除时为总剔除数量)
AcquisitionSpeed = "0"; // 各相机采集速度
DetectSpeed = "0"; // 各相机检测速度
}
};
class _ExportDataInfo
{
struct JdPoint //创建点的数据
struct JdPoint //创建点的数据
{
string x;
string y;

@ -7,9 +7,9 @@ public:
PlcItem();
~PlcItem();
public:
std::string func_desc; //功能描述
int address; //modbus地址
std::string memo; //备注
int value; //初始值
std::string func_desc; //功能描述
int address; //modbus地址
std::string memo; //备注
int value; //初始值
};

@ -1,4 +1,4 @@
#pragma once
#pragma once
#include <QDialog>
#include <QPushButton>
#include "ui_plcsetup.h"

@ -12,7 +12,7 @@
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc/types_c.h>
extern SyncQueue<std::pair<std::string, cv::Mat>>* g_save_queue; //ͼÏñ±£´æ¶ÓÁÐ
extern SyncQueue<std::pair<std::string, cv::Mat>>* g_save_queue; //图像保存队列
class SaveThread : public QThread
{

@ -8,17 +8,18 @@
#include "exportData.h"
#include <QMap>
extern AlgJd alg_jd[NumberOfSupportedCameras]; //检测胶点的AI算法
extern AlgJd alg_jd[NumberOfSupportedCameras]; //检测胶点的AI算法
extern ConfPath g_conf_path;
extern SysConf g_sys_conf; //系统配置参数
extern SysConf g_sys_conf; //系统配置参数
extern DisplayLabelConf g_display_label_conf[NumberOfSupportedCameras];
extern int rotationAngle[NumberOfSupportedCameras]; //图片旋转角度
extern int rotationAngle[NumberOfSupportedCameras]; //图片旋转角度
extern bool isNeedRotate[NumberOfSupportedCameras];
extern int work_camera_nums;
extern SingleCamInfoStruct SingleCamInfo[NumberOfSupportedCameras];
extern SyncQueue<std::pair<std::string, cv::Mat> >* g_save_queue; //图片保存队列
extern SyncQueue<std::pair<int, cv::Mat>>* g_image_queue[NumberOfSupportedCameras]; //int表示一个目标拍了几张
extern SyncQueue<std::pair<std::string, cv::Mat> >* g_save_queue; //图片保存队列
extern SyncQueue<std::pair<int, cv::Mat>>* g_image_queue[NumberOfSupportedCameras]; //int表示一个目标拍了几张
#ifdef __UDPSend
extern SyncQueue<_UDPSendInfo>* UDP_Info_queue;
#endif
@ -70,16 +71,19 @@ void SyncWorkThread::run()
bool IsNGForAll = false;
int merge_index;
cv::Rect roi;
int j = 0; // 实际工作的相机标识element_vec中可能有相机没在工作
for (int i = 0; i < element_vec.size(); i++)//每个相机的图轮流遍历
int j = 0; // 实际工作的相机标识element_vec中可能有相机没在工作
for (int i = 0; i < element_vec.size(); i++)//每个相机的图轮流遍历
{
if (!SingleCamInfo[i].Detect || !SingleCamInfo[i].IsOpen || SingleCamInfo[i].OffLine)
continue;
local_camera_number = i;
int isWork = element_vec[i].first;
std::pair<int, cv::Mat> element;
element = element_vec[i];
int unit_count = element.first;
cv::Mat image = element.second;
{//不要删掉这个括号,用来定义锁的作用域
{//不要删掉这个括号,用来定义锁的作用域
std::lock_guard<std::mutex> locker(g_sys_conf.lock);
local_SysConf.save = g_sys_conf.save;
local_SysConf.shoot[local_camera_number] = g_sys_conf.shoot[local_camera_number];
@ -110,12 +114,12 @@ void SyncWorkThread::run()
#endif
if (!image.data)
{
continue; //图像为空,跳过
continue; //图像为空,跳过
}
cv::Mat merge_image = cv::Mat::zeros(512 * work_camera_nums, 640 * g_sys_conf.shoot[i], CV_8UC3);
if (image.channels() == 1)
{
cv::cvtColor(image, image, CV_BGR2RGB); //灰度图像转为彩色图像
cv::cvtColor(image, image, CV_BGR2RGB); //灰度图像转为彩色图像
}
cv::resize(image, image, cv::Size(640, 512 * unit_count));
if (local_SysConf.shoot[local_camera_number] == unit_count)
@ -183,15 +187,15 @@ void SyncWorkThread::run()
IsNG |= true;
ngReason = 1;
}
//if (vec_results[index].size() != 1)IsNG |= true;//反向训练
//if (vec_results[index].size() != 1)IsNG |= true;//反向训练
if (local_SysConf.ConfThreshold == 0)
{
IsNG = false;
ngReason = 0;
}
if (local_SysConf.save == 2)//三张照片分别存储
if (local_SysConf.save == 2)//三张照片分别存储
{
/// 合成element_vec.size() * unit_count 宫格图像
/// 合成element_vec.size() * unit_count 宫格图像
cv::Mat m = vec_in[index].clone();
QString file_name;
merge_index = j * unit_count + index + 1;
@ -303,7 +307,6 @@ void SyncWorkThread::run()
#ifdef SYNC_CAMERA
if (!g_debug_mode)
{
if(isWork != 0)
emit display_check_total(local_camera_number, ++frame_total[local_camera_number]);
//exportDataInfo.cameraTotal = frame_total;
emit notify(local_camera_number, 0, image1);
@ -316,7 +319,7 @@ void SyncWorkThread::run()
else
{
#ifdef SYNC_CAMERA
//保证不错位
//保证不错位
if (!g_debug_mode)
{
if (local_SysConf.MisMatchAct == 1)//as ng

@ -31,15 +31,15 @@ void threadReceive::init(std::string IP,int port)
void threadReceive::processPendingDatagram()
{
// 拥有等待的数据报
// 拥有等待的数据报
while (mSocket->hasPendingDatagrams())
{
QByteArray datagram;
// 让datagram的大小为等待处理的数据报的大小这样才能接收到完整的数据
// 让datagram的大小为等待处理的数据报的大小这样才能接收到完整的数据
datagram.resize(mSocket->pendingDatagramSize());
// 接收数据报将其存放到datagram中
// 接收数据报将其存放到datagram中
mSocket->readDatagram(datagram.data(), datagram.size());
QString data = datagram;
@ -51,14 +51,14 @@ void threadReceive::fileprocessPendingDatagram()
{
QString filename;
std::fstream file;
// 拥有等待的数据报
// 拥有等待的数据报
while (filemSocket->hasPendingDatagrams())
{
QByteArray datagram;
// 让datagram的大小为等待处理的数据报的大小这样才能接收到完整的数据
// 让datagram的大小为等待处理的数据报的大小这样才能接收到完整的数据
datagram.resize(filemSocket->pendingDatagramSize());
// 接收数据报将其存放到datagram中
// 接收数据报将其存放到datagram中
filemSocket->readDatagram(datagram.data(), datagram.size());
QString data = datagram;

@ -6,7 +6,6 @@
#pragma comment(lib, "ws2_32.lib")
void threadSendTCP::init(SyncQueue<_TCPSendInfo>* p_TCP_Info_queue, std::string ip_, int port_) {
ip = QString::fromStdString(ip_);
port = port_;
qDebug() << "tcp ip:" << ip << "| tcp port:" << port;
@ -27,9 +26,9 @@ void threadSendTCP::stop()
bool threadSendTCP::connectTCP() {
mySocket = new QTcpSocket();
// 取消已有的连接
// 取消已有的连接
mySocket->abort();
// 连接服务器
// 连接服务器
mySocket->connectToHost(ip, port);
if (!mySocket->waitForConnected(30000)) {
qDebug() << "connect failed!";

@ -227,7 +227,8 @@ char* StrPair::ParseText( char* p, const char* endTag, int strFlags, int* curLin
if (*p == endChar && strncmp(p, endTag, length) == 0) {
Set(start, p, strFlags);
return p + length;
} else if (*p == '\n') {
}
else if (*p == '\n') {
++(*curLineNumPtr);
}
++p;
@ -2712,7 +2713,8 @@ void XMLPrinter::PrepareForNewNode( bool compactMode )
if (_firstElement) {
PrintSpace(_depth);
} else if ( _textDepth < 0) {
}
else if (_textDepth < 0) {
Putc('\n');
PrintSpace(_depth);
}

@ -8,16 +8,16 @@
#include "exportData.h"
#include <QMap>
extern AlgJd alg_jd[NumberOfSupportedCameras]; //检测胶点的AI算法
extern AlgJd alg_jd[NumberOfSupportedCameras]; //检测胶点的AI算法
extern ConfPath g_conf_path;
extern SysConf g_sys_conf; //系统配置参数
extern SysConf g_sys_conf; //系统配置参数
extern DisplayLabelConf g_display_label_conf[NumberOfSupportedCameras];
extern int rotationAngle[NumberOfSupportedCameras]; //图片旋转角度
extern int rotationAngle[NumberOfSupportedCameras]; //图片旋转角度
extern bool isNeedRotate[NumberOfSupportedCameras];
extern SyncQueue<std::pair<std::string, cv::Mat> >* g_save_queue; //图片保存队列
extern SyncQueue<std::pair<int, cv::Mat>>* g_image_queue[NumberOfSupportedCameras]; //int表示一个目标拍了几张
extern SyncQueue<std::pair<std::string, cv::Mat> >* g_save_queue; //图片保存队列
extern SyncQueue<std::pair<int, cv::Mat>>* g_image_queue[NumberOfSupportedCameras]; //int表示一个目标拍了几张
#ifdef __UDPSend
extern SyncQueue<_UDPSendInfo>* UDP_Info_queue;
#endif
@ -61,7 +61,7 @@ void WorkThread::run()
try {
uint32_t result_index = 0;
while (!b_quit) {
{//不要删掉这个括号,用来定义锁的作用域
{//不要删掉这个括号,用来定义锁的作用域
std::lock_guard<std::mutex> locker(g_sys_conf.lock);
local_SysConf.save = g_sys_conf.save;
local_SysConf.shoot[local_camera_number] = g_sys_conf.shoot[local_camera_number];
@ -98,11 +98,11 @@ void WorkThread::run()
#endif
if (!image.data)
{
continue; //图像为空,跳过
continue; //图像为空,跳过
}
if (image.channels() == 1)
{
cv::cvtColor(image, image, CV_BGR2RGB); //灰度图像转为彩色图像
cv::cvtColor(image, image, CV_BGR2RGB); //灰度图像转为彩色图像
}
if (local_SysConf.shoot[local_camera_number] == unit_count)
{
@ -131,7 +131,8 @@ void WorkThread::run()
alg_jd[local_camera_number].detect(imagein, imageout, results);
vec_out.push_back(imageout.clone());
vec_results.push_back(results);
}else{
}
else {
alg_jd[local_camera_number].detect_batch(vec_in, vec_out, vec_results);
}
QDateTime ts_jd = QDateTime::currentDateTime();
@ -171,13 +172,13 @@ void WorkThread::run()
IsNG |= true;
ngReason = 1;
}
//if (vec_results[index].size() != 1)IsNG |= true;//反向训练
//if (vec_results[index].size() != 1)IsNG |= true;//反向训练
if (local_SysConf.ConfThreshold == 0)
{
IsNG = false;
ngReason = 0;
}
if (local_SysConf.save == 2)//三张照片分别存储
if (local_SysConf.save == 2)//三张照片分别存储
{
cv::Mat m = vec_in[index].clone();
QString file_name = g_conf_path.save_pics_path + "/ALL/" +
@ -205,7 +206,8 @@ void WorkThread::run()
ngReason = 2;
}
#endif
}else {
}
else {
image1 = vec_out[0].clone();
#ifdef DRAW_RECT
IsNG |= CheckSelectRects(image1, vec_results, 0, local_DisplayLabelConf, 0);
@ -298,7 +300,7 @@ void WorkThread::run()
#ifndef SYNC_CAMERA
else
{
//保证不错位
//保证不错位
if (!g_debug_mode)
{
if (local_SysConf.MisMatchAct == 1)//as ng

Loading…
Cancel
Save