Browse Source

初始化

LiuZe 1 year ago
parent
commit
b2cacc22c5

+ 36 - 0
CMakeLists.txt

@@ -0,0 +1,36 @@
+set(SON_PROJECT_NAME clamp_lidar)
+message("========== Load son project ${SON_PROJECT_NAME} ==========" )
+option(OPTION_COMMUNICATION_WITH_PLC "plc通信" ON)
+message("<=${SON_PROJECT_NAME}=> OPTION_COMMUNICATION_WITH_PLC: " ${OPTION_COMMUNICATION_WITH_PLC})
+
+if (OPTION_COMMUNICATION_WITH_PLC)
+    add_definitions(-DOPTION_COMMUNICATION_WITH_PLC=1)
+else ()
+    add_definitions(-DOPTION_COMMUNICATION_WITH_PLC=0)
+endif ()
+
+include_directories(
+        /usr/local/include/snap7
+)
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/plc plc)
+
+set(SON_PROJECT_SOURCE_LIST
+        ${plc}
+        ${CMAKE_CURRENT_LIST_DIR}/main.cpp
+)
+
+set(SON_PROJECT_DEPEND_LIST
+    libplc
+)
+
+add_executable(${SON_PROJECT_NAME} ${SON_PROJECT_SOURCE_LIST})
+target_link_libraries(${SON_PROJECT_NAME} ${SON_PROJECT_DEPEND_LIST})
+target_compile_definitions(${SON_PROJECT_NAME} PRIVATE PROJECT_NAME="${SON_PROJECT_NAME}")
+
+install(TARGETS ${SON_PROJECT_NAME}
+        LIBRARY DESTINATION lib  # 动态库安装路径
+        ARCHIVE DESTINATION lib  # 静态库安装路径
+        RUNTIME DESTINATION bin  # 可执行文件安装路径
+        PUBLIC_HEADER DESTINATION include  # 头文件安装路径
+)
+

+ 329 - 0
detect/clamp_safety_detect.cpp

@@ -0,0 +1,329 @@
+#include "clamp_safety_detect.h"
+
+bool clamp_safety_detect::fit_line(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Line &line) {
+    if (cloud->size() < 20)
+        return false;
+
+    Eigen::MatrixXd A, B;
+    A.resize(cloud->size(), 2);
+    B.resize(cloud->size(), 1);
+    for (int i = 0; i < cloud->size(); ++i) {
+        A(i, 0) = cloud->points[i].x;
+        A(i, 1) = 1.0;
+        B(i, 0) = cloud->points[i].y;
+    }
+    Eigen::MatrixXd P = (A.transpose() * A).inverse() * (A.transpose()) * B;
+
+    float a = P(0, 0);
+    float b = -1.0;
+    float c = P(1, 0);
+    float sum = 0;
+    float sumx = 0, sumy = 0, w = 0, sumw = 0;
+
+    for (int i = 0; i < cloud->size(); ++i) {
+        pcl::PointXYZ pt = cloud->points[i];
+        w = float(1 / pow(cos(atan(fabs(pt.x / pt.y))), 2));
+        sumw += w;
+        sumx += w * pt.x;
+        sumy += pt.y;
+        sum += std::pow(a * pt.x + b * pt.y + c, 2) / (a * a + b * b);
+    }
+
+    line.cov = sqrt(sum) / float(cloud->size());
+    line.cx = sumx / sumw;
+    line.cy = sumy / float(cloud->size());
+
+    line.a = a;
+    line.b = b;
+    line.c = c;
+    line.theta_by_x = acos(abs(b / sqrt(a * a + b * b))) * 180.0 / M_PI;
+    line.cloud = cloud;
+
+    //printf(" abc(%f,%f,%f) line.vonv  cov:%f,%f,%f,%f,%f\n",a,b,c,line.theta_by_x,line.cov);
+    return true;
+
+}
+
+bool compare_r(const Line &line1, const Line &line2) {
+    return line1.theta_by_x < line2.theta_by_x;
+}
+
+bool pca(pcl::PointCloud<pcl::PointXY>::Ptr neighber, float &theta) {
+
+    if (neighber->size() < 10) {
+        return false;
+    }
+    float sumx = 0, sumy = 0;
+    for (int i = 0; i < neighber->size(); ++i) {
+
+        sumx += neighber->points[i].x;
+        sumy += neighber->points[i].y;
+
+    }
+    float mean_x = sumx / float(neighber->size());
+    float mean_y = sumy / float(neighber->size());
+    Eigen::MatrixXd A(2, neighber->size());
+    for (int i = 0; i < neighber->size(); ++i) {
+        pcl::PointXY pt = neighber->points[i];
+        A(0, i) = pt.x - mean_x;
+        A(1, i) = pt.y - mean_y;
+
+    }
+    Eigen::MatrixXd cov = A * A.transpose();
+    Eigen::EigenSolver<Eigen::MatrixXd> es(cov);
+
+    Eigen::VectorXd values = es.eigenvalues().real().normalized();
+    Eigen::MatrixXd vectors = es.eigenvectors().real();
+    //printf("pca values: %.5f  %.5f ",values[0],values[1]);
+    float max_value = values[0];
+    Eigen::Vector2d normal = vectors.col(0);
+    if (values[1] > values[0]) {
+        max_value = values[1];
+        normal = vectors.col(1);
+    }
+
+    if (isnanf(max_value)) {
+        return false;
+    }
+    if (max_value < 0.90) {
+        return false;
+    }
+
+
+    float r = 90 * 0.005 / (2. * M_PI);
+    theta = acos(abs(normal[0])) * r;
+
+    return true;
+}
+
+void pca_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::PointCloud<pcl::PointXYZ>::Ptr features, int length) {
+    if (cloud->size() < length) {
+        printf("ERROR  pca points size < %d\n", length);
+        return;
+    }
+    features->clear();
+    int fail_pca = 0;
+    for (int i = length / 2; i < cloud->size() - length / 2; ++i) {
+        pcl::PointCloud<pcl::PointXY>::Ptr neighber(new pcl::PointCloud<pcl::PointXY>);
+        for (int j = i - length / 2; j < i + length / 2; ++j) {
+            pcl::PointXYZ pt = cloud->points[j];
+            if (pt.y < 0.05 || pt.y > 0.5 || fabs(pt.x) > 0.5)
+                continue;
+            pcl::PointXY p_xy;
+            p_xy.x = cloud->points[j].x;
+            p_xy.y = cloud->points[j].y;
+            if (isnan(p_xy.x) || isnan(p_xy.y))
+                continue;
+            neighber->push_back(p_xy);
+        }
+        float theta = 0;
+        if (pca(neighber, theta)) {
+            pcl::PointXYZ pt = cloud->points[i];
+            pt.z = theta;
+            features->push_back(pt);
+
+        } else {
+            fail_pca++;
+        }
+    }
+
+}
+
+void pca_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::PointCloud<pcl::PointXYZ>::Ptr features, float radius) {
+    if (cloud->size() < 200)
+        return;
+
+    pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
+    //pcl::KdTreeFLANN<pcl::PointXYZ> tree;
+    tree->setInputCloud(cloud);
+    features->clear();
+    for (int i = 0; i < cloud->size(); ++i) {
+        std::vector<float> distances;    //distance Vector
+        std::vector<int> neighber_ids;
+        tree->radiusSearch(cloud->points[i], radius, neighber_ids, distances); //KD tree
+
+        pcl::PointCloud<pcl::PointXY>::Ptr neighber(new pcl::PointCloud<pcl::PointXY>);
+        for (int neighber_id : neighber_ids) {
+            pcl::PointXY p_xy{};
+            p_xy.x = cloud->points[neighber_id].x;
+            p_xy.y = cloud->points[neighber_id].y;
+            neighber->push_back(p_xy);
+        }
+        float theta = 0;
+        if (pca(neighber, theta)) {
+            pcl::PointXYZ pt = cloud->points[i];
+            pt.z = theta;
+            features->push_back(pt);
+        }
+    }
+
+}
+
+
+clamp_safety_detect::clamp_safety_detect() = default;
+
+clamp_safety_detect::~clamp_safety_detect() = default;
+
+#if __VIEW__PCL
+
+void clamp_safety_detect::set_viewer(pcl::visualization::PCLVisualizer* viewer,int port)
+{
+    m_viewer=viewer;
+    m_port=port;
+}
+
+void clamp_safety_detect::view_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,std::string name,int r,int g,int b)
+{
+    pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color2(cloud,r,g,b);
+    m_viewer->addPointCloud(cloud, single_color2, name,m_port);
+    m_viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, name,m_port);
+}
+
+#endif
+
+
+std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> clamp_safety_detect::classify_cloud(
+        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
+    std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> cluster_cloud;
+    //printf("  cloud size():%d\n",cloud->size());
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_r(new pcl::PointCloud<pcl::PointXYZ>);
+
+    pca_cloud(cloud, cloud_r, 20);
+
+    if (cloud_r->size() == 0) {
+        return cluster_cloud;
+    }
+    pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
+
+    tree->setInputCloud(cloud_r);
+
+    std::vector<pcl::PointIndices> cluster_indices;
+    pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
+    ec.setClusterTolerance(0.1);
+    ec.setMinClusterSize(100);
+    ec.setMaxClusterSize(1000);
+    ec.setSearchMethod(tree);
+    ec.setInputCloud(cloud_r);
+    ec.extract(cluster_indices);
+
+
+    cluster_cloud.resize(cluster_indices.size());
+
+    for (int i = 0; i < cluster_indices.size(); ++i) {
+        pcl::PointCloud<pcl::PointXYZ>::Ptr clust(new pcl::PointCloud<pcl::PointXYZ>);
+        for (int j = 0; j < cluster_indices[i].indices.size(); ++j) {
+            pcl::PointXYZ pt;
+            pcl::PointXYZ ptr = cloud_r->points[cluster_indices[i].indices[j]];
+            pt.x = ptr.x;
+            pt.y = ptr.y;
+            pt.z = ptr.z; //z表示角度
+            clust->push_back(pt);
+        }
+        cluster_cloud[i] = clust;
+
+    }
+
+    return cluster_cloud;
+}
+
+bool clamp_safety_detect::check_wheel_line(const Line &line, Safety_status &safety) {
+    if (line.cloud->size() < 20) {
+        printf("line cloud size <20\n");
+        return false;
+    }
+    ///判断轮胎
+    pcl::PointXYZ minp, maxp;
+    pcl::getMinMax3D(*line.cloud, minp, maxp);
+    float length = maxp.x - minp.x;
+    if (line.cov < 0.03 && fabs(line.theta_by_x) < 10.
+        && (length > 0.1 && length < 0.5)) {
+        //前方直线是轮胎,判断中心是否居中、直线长度是否在范围内
+
+        safety.cx = line.cx;
+        // printf("safety.cx = %.3f\n", safety.cx);
+        //雷达距离轮胎的距离   间隙
+        safety.gap = fabs(line.cy);
+        //中心偏差5cm内,可夹,plc决定
+        safety.wheel_exist = true;
+    }
+#if __VIEW__PCL
+    char name[64]={0};
+    //显示直线,正确为绿,偏移为黄,错误为红,
+    char buf[64]={0};
+    sprintf(buf,"cx:%.4f,gap:%.4f,Θ:%.4f cov:%.4f",safety.cx,fabs(line.cy),line.theta_by_x,line.cov);
+    sprintf(name,"wheel_%d",m_port);
+    m_viewer->addText3D(buf,pcl::PointXYZ(line.cx-0.2,line.cy,0),0.01,0,1,0,"wheel",m_port);
+
+    float x1=line.cx-0.2;
+    float x2=line.cx+0.2;
+    float y1=-(x1*line.a/line.b+line.c/line.b);
+    float y2=-(x2*line.a/line.b+line.c/line.b);
+
+    sprintf(name,"line_%d",m_port);
+    if (safety.wheel_exist)
+    {
+        m_viewer->addLine(pcl::PointXYZ(x1,y1,0), pcl::PointXYZ(x2,y2,0), 0, 255, 0, name,m_port);
+    }
+    else if (fabs(safety.cx) < 0.5)
+    {
+        m_viewer->addLine(pcl::PointXYZ(x1,y1,0), pcl::PointXYZ(x2,y2,0), 255, 255, 0, name,m_port);
+    }
+    else
+    {
+        m_viewer->addLine(pcl::PointXYZ(x1,y1,0), pcl::PointXYZ(x2,y2,0), 255, 0, 0, name,m_port);
+    }
+#endif
+    return safety.wheel_exist;
+
+}
+
+bool clamp_safety_detect::check_clamp_lines(const Line &line1, const Line &line2, Safety_status &safety) {
+    if (fabs(line1.theta_by_x - line2.theta_by_x) > 10 || line1.cov > 0.03 || line2.cov > 0.03) {
+
+    }
+
+    if (fabs(line1.theta_by_x - 90.) < 15. && fabs(line2.theta_by_x - 90.) < 15.)
+        safety.clamp_completed = true;
+
+#if __VIEW__PCL
+    char name[64]={0};
+    float x1=line1.cx-0.2;
+    float x2=line1.cx+0.2;
+    float y1=-(x1*line1.a/line1.b+line1.c/line1.b);
+    float y2=-(x2*line1.a/line1.b+line1.c/line1.b);
+    sprintf(name,"line1_%d",m_port);
+    m_viewer->addLine(pcl::PointXYZ(x1,y1,0), pcl::PointXYZ(x2,y2,0), 255, 0, 0, name,m_port);
+    char buf[32]={0};
+    sprintf(buf,"cx:%.3f,Θ:%.1f cov:%.3f",line1.cx,line1.theta_by_x,line1.cov);
+    sprintf(name,"line1_txt_%d",m_port);
+    m_viewer->addText3D(buf,pcl::PointXYZ(line1.cx-0.15,line1.cy,0),0.01,0,1,0,name,m_port);
+
+    x1=line2.cx-0.2;
+    x2=line2.cx+0.2;
+    y1=-(x1*line2.a/line2.b+line2.c/line2.b);
+    y2=-(x2*line2.a/line2.b+line2.c/line2.b);
+    sprintf(name,"line2_%d",m_port);
+    m_viewer->addLine(pcl::PointXYZ(x1,y1,0), pcl::PointXYZ(x2,y2,0), 255, 0, 0, name,m_port);
+    memset(buf,0,32);
+    sprintf(buf,"cx:%.3f,Θ:%.3f cov:%.3f",line2.cx,line2.theta_by_x,line2.cov);
+    sprintf(name,"line2_txt%d",m_port);
+    m_viewer->addText3D(buf,pcl::PointXYZ(line2.cx-0.15,line2.cy,0),0.01,0,1,0,name,m_port);
+#endif
+    return true;
+}
+
+bool clamp_safety_detect::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Safety_status &safety) {
+#if __VIEW__PCL
+    m_viewer->removeAllPointClouds(m_port);
+    m_viewer->removeAllShapes(m_port);
+    char buf[32]={0};
+    sprintf(buf,"cloud_%d",m_port);
+    view_cloud(cloud,buf,255,255,255);
+#endif
+    //找直线,记录内点率,直线与x轴夹角,斜率b/a
+    Line line;
+    if (fit_line(cloud, line) && check_wheel_line(line, safety)) {
+        return true;
+    }
+    return false;
+}

+ 120 - 0
detect/clamp_safety_detect.h

@@ -0,0 +1,120 @@
+//
+// Created by zx on 22-8-30.
+//
+
+#pragma once
+
+#include <pcl/point_types.h>
+#include <pcl/point_cloud.h>
+#include <pcl/io/pcd_io.h>
+#include <pcl/segmentation/sac_segmentation.h>
+#include <pcl/ModelCoefficients.h>
+#include <pcl/filters/extract_indices.h>
+#include <pcl/segmentation/extract_clusters.h>
+#include <pcl/point_representation.h>
+#include <pcl/filters/statistical_outlier_removal.h>
+#include <pcl/visualization/cloud_viewer.h>
+#include <pcl/common/common_headers.h>
+#include <glog/logging.h>
+#include <iostream>
+#include <cmath>
+
+#if __VIEW__PCL
+#include <pcl/visualization/pcl_visualizer.h>
+#endif
+
+//ax+by+c=0
+typedef struct {
+    float a;
+    float b;
+    float c;
+    float cx;
+    float cy;
+    float theta_by_x;
+    float cov;
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud;
+} Line;
+
+class Safety_status {
+public:
+    Safety_status() {
+        clamp_completed = false;
+        wheel_exist = false;
+        cx = 0;
+        gap = 0;
+        time_point = std::chrono::steady_clock::now();
+        timeout_s = 0.5;
+    };
+
+    ~Safety_status() = default;
+
+    Safety_status(const Safety_status &other) {
+        clamp_completed = other.clamp_completed;
+        wheel_exist = other.wheel_exist;
+        cx = other.cx;
+        gap = other.gap;
+        time_point = other.time_point;
+        timeout_s = other.timeout_s;
+    }
+
+    Safety_status &operator=(const Safety_status &other) {
+        clamp_completed = other.clamp_completed;
+        wheel_exist = other.wheel_exist;
+        cx = other.cx;
+        gap = other.gap;
+        time_point = other.time_point;
+        timeout_s = other.timeout_s;
+        return *this;
+    }
+
+    void set_timeout(float s) {
+        timeout_s = s;
+    }
+
+    bool is_timeout() const {
+        auto t2 = std::chrono::steady_clock::now();
+        auto duration = std::chrono::duration_cast<std::chrono::microseconds>(t2 - time_point);
+
+        double time = double(duration.count()) * std::chrono::microseconds::period::num /
+                      std::chrono::microseconds::period::den;
+        DLOG(INFO) << "time " << time;
+        return time > timeout_s;
+    }
+
+    bool clamp_completed;
+    bool wheel_exist;           //点云直线是否是轮子
+    float cx;
+    float gap;                  //轮子距离雷达
+    std::chrono::steady_clock::time_point time_point;
+    float timeout_s;
+    std::mutex mutex_;
+};
+
+class clamp_safety_detect {
+public:
+    clamp_safety_detect();
+
+    ~clamp_safety_detect();
+
+#if __VIEW__PCL
+    void set_viewer(pcl::visualization::PCLVisualizer* m_viewer,int port);
+#endif
+
+    bool detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Safety_status &safety);
+
+    bool fit_line(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Line &line);
+
+    bool check_wheel_line(const Line &line, Safety_status &safety);
+
+protected:
+    std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> classify_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
+
+    bool check_clamp_lines(const Line &line1, const Line &line2, Safety_status &safety);
+
+#if __VIEW__PCL
+    void view_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,std::string name,int r,int g,int b);
+     pcl::visualization::PCLVisualizer* m_viewer;
+     int m_port;
+#endif
+};
+

+ 314 - 0
lidar/async_client.cpp

@@ -0,0 +1,314 @@
+#include "async_client.h"
+
+// 构造
+Async_Client::Async_Client() : m_socket(m_io_service) {
+    m_communication_status = E_UNKNOWN;    //通信状态
+    m_is_reconnection_flag = false;        // 断线是否重连的标志位, true:断线自动重连, false:断线不重连, 保持断线状态.
+
+    mp_thread_receive = NULL;        // 接受线程, 内存由本模块管理
+    mp_thread_check_connect = NULL;        // 检查线程, 内存由本模块管理
+    m_check_connect_wait_time_ms = 0;    // 检查连接线程 的等待时间
+
+    m_data_updata_time = std::chrono::system_clock::now() - std::chrono::hours(1);
+
+    memset(m_data_buf, 0, DATA_LENGTH_MAX);
+    mp_communication_data_queue = NULL;
+}
+
+/**
+ * 析构函数
+ * */
+Async_Client::~Async_Client() {
+    uninit();
+}
+
+//初始化, 默认重连
+Error_manager Async_Client::init(std::string ip, int port, Thread_safe_queue<Binary_buf *> *p_communication_data_queue,
+                                 bool is_reconnection_flag) {
+    if (p_communication_data_queue == NULL) {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "  POINTER IS NULL ");
+    }
+
+    m_is_reconnection_flag = is_reconnection_flag;
+
+    m_check_connect_wait_time_ms = 0;    // 检查连接线程 的等待时间, 第一次直接通过
+
+    boost::asio::ip::tcp::endpoint t_ep(boost::asio::ip::address_v4::from_string(ip), port);
+    m_ep = t_ep;
+    mp_communication_data_queue = p_communication_data_queue;
+
+    //接受线程, 默认等待
+    m_condition_receive.reset(false, false, false);
+    mp_thread_receive = new std::thread(&Async_Client::thread_receive, this);
+    //检查连接线程, 默认等待, 内部的wait_for会让其通过
+    m_condition_check_connect.reset(false, false, false);
+    mp_thread_check_connect = new std::thread(&Async_Client::thread_check_connect, this);
+
+    return Error_code::SUCCESS;
+}
+
+//反初始化
+Error_manager Async_Client::uninit() {
+    //注注注注注意了, 这里一定要在关闭通信线程之前, 关闭socket,
+    //因为异步操作自带一个线程, 这个线程可能会卡住我们的线程...
+    //关闭通信
+    m_socket.close();
+
+    //杀死2个线程,强制退出
+    if (mp_thread_receive) {
+        m_condition_receive.kill_all();
+    }
+    if (mp_thread_check_connect) {
+        m_condition_check_connect.kill_all();
+    }
+
+    //回收2个线程的资源
+    if (mp_thread_receive) {
+        mp_thread_receive->join();
+        delete mp_thread_receive;
+        mp_thread_receive = NULL;
+    }
+    if (mp_thread_check_connect) {
+        mp_thread_check_connect->join();
+        delete mp_thread_check_connect;
+        mp_thread_check_connect = NULL;
+    }
+
+
+    m_io_service.stop();
+
+
+    mp_communication_data_queue = NULL;
+
+    if (m_communication_status != E_FAULT) {
+        m_communication_status = E_UNKNOWN;
+    }
+    return Error_code::SUCCESS;
+}
+
+//检查状态
+Error_manager Async_Client::check_status() {
+    if (m_communication_status == E_READY) {
+        return Error_code::SUCCESS;
+    } else if (m_communication_status == E_UNKNOWN) {
+        return Error_manager(Error_code::WJ_LIDAR_COMMUNICATION_UNINITIALIZED, Error_level::MINOR_ERROR,
+                             " Async_Client::check_status() error ");
+    } else if (m_communication_status == E_DISCONNECT) {
+        return Error_manager(Error_code::WJ_LIDAR_COMMUNICATION_DISCONNECT, Error_level::MINOR_ERROR,
+                             " Async_Client::check_status() error ");
+    } else {
+        return Error_manager(Error_code::WJ_LIDAR_COMMUNICATION_FAULT, Error_level::MINOR_ERROR,
+                             " Async_Client::check_status() error ");
+    }
+}
+
+//判断是否正常
+bool Async_Client::is_ready() {
+    return (m_communication_status == E_READY);
+}
+
+//获取状态
+Async_Client::Communication_status Async_Client::get_status() {
+    return m_communication_status;
+}
+
+
+//线程接受函数,包括连接,重连和接受数据
+void Async_Client::thread_receive() {
+    LOG(INFO) << " ---Async_Client::thread_receive start ---" << this;
+
+    //接受雷达消息,包括连接,重连和接受数据
+    while (m_condition_receive.is_alive()) {
+        m_condition_receive.wait();
+        if (m_condition_receive.is_alive()) {
+            std::this_thread::yield();
+
+            // 连接成功后开启异步读
+            client_async_read();
+
+        }
+    }
+    LOG(INFO) << " Async_Client::thread_receive end :" << this;
+    return;
+}
+
+//线程检查连接函数,进行连接, 并检查消息是否按时更新, 如果超时, 那么触发重连
+void Async_Client::thread_check_connect() {
+    LOG(INFO) << " ---Async_Client::thread_check_connect start ---" << this;
+
+    //检查连接, 连接, 重连, 判断时间
+    while (m_condition_check_connect.is_alive()) {
+        m_condition_check_connect.wait_for_millisecond(m_check_connect_wait_time_ms);
+        if (m_condition_check_connect.is_alive()) {
+            std::this_thread::yield();
+
+            switch ((Communication_status) m_communication_status) {
+                case E_UNKNOWN: {
+                    //连接
+                    socket_connect();
+                    break;
+                }
+                case E_DISCONNECT: {
+                    //重连
+                    socket_reconnect();
+                    break;
+                }
+                case E_READY: {
+                    //检查
+                    socket_check();
+                    break;
+                }
+                default: {
+
+                    break;
+                }
+            }
+
+        }
+    }
+    LOG(INFO) << " Async_Client::thread_check_connect end :" << this;
+}
+
+
+// 开启连接
+void Async_Client::socket_connect() {
+    m_io_service.reset();
+    //开启异步连接, 使用m_ep里面的ip和port进行tcp异步连接
+    // 只有在run()之后, 才会真正的执行连接函数
+    m_socket.async_connect(m_ep, boost::bind(&Async_Client::handle_connect, this, boost::asio::placeholders::error));
+    //注注注注注注意了:async_connect是阻塞函数, 如果连接不上就会一直卡在这, 而不是通过之后, 回调返回错误码.
+    //这个函数大约1分钟之后就会通过, 并调用里面的回调函数,返回我们错误码.
+    //如果硬件恢复连接, 那么这个函数会立即连上,
+    //如果我们中途退出, 一定要 m_socket.close()退出异步通信他自己后台的线程, 防止这里卡死, 影响我们的线程关闭........
+    m_io_service.run();
+}
+
+//关闭连接
+void Async_Client::socket_close() {
+    m_socket.close();
+}
+
+// 重新连接
+void Async_Client::socket_reconnect() {
+    if (m_is_reconnection_flag) {
+        //关闭原有的连接
+        socket_close();
+        // 开启连接
+        socket_connect();
+    }
+}
+
+// 检查连接
+void Async_Client::socket_check() {
+    // 判断距上次读取到数据超时时间,过长则主动断开并重连
+    int duration = std::chrono::duration_cast<std::chrono::milliseconds>(
+            std::chrono::system_clock::now() - m_data_updata_time).count();
+    if (duration > READ_TIMEOUT_MILLISECONDS) {
+        LOG(WARNING) << "connection check thread found read timeout, close socket and try to reinitialize/reconnect.";
+
+        // 通信超时后, 修改状态为断连,
+        m_communication_status = E_DISCONNECT;
+        //检查连接等待时间变为 RECONNECTION_WAIT_TIME_MS,
+        m_check_connect_wait_time_ms = RECONNECTION_WAIT_TIME_MS;
+        //关闭接受线程
+        m_condition_receive.notify_all(false);
+    }
+}
+
+// 异步写入
+void Async_Client::client_async_write(char *buf, int len) {
+    m_io_service.run();
+    boost::asio::async_write(m_socket,
+                             boost::asio::buffer(buf, len),
+                             boost::bind(&Async_Client::handle_write, this,
+                                         boost::asio::placeholders::error));
+    m_io_service.run();
+}
+
+// 异步读取
+void Async_Client::client_async_read() {
+    //异步读取, 在run()之后, 会自动接受数据, 并存入mp_data_buf里面,
+    // 然后调用回调函数handle_read(), bytes_transferred是返回的数据有效长度
+
+    m_io_service.reset();
+    m_socket.async_read_some(boost::asio::buffer(m_data_buf, DATA_LENGTH_MAX),
+                             boost::bind(&Async_Client::handle_read, this,
+                                         boost::asio::placeholders::error,
+                                         boost::asio::placeholders::bytes_transferred));
+    //注:async_read_some, 如果断连, 那么就会回调handle_read, 并填充错误码 boost::asio::placeholders::error
+    m_io_service.run();
+}
+
+
+//异步连接回调, 失败后重连
+void Async_Client::handle_connect(const boost::system::error_code &error) {
+    if (!error) {
+        LOG(INFO) << "Async_Client::handle_connect Connection Successful! " << m_ep.address().to_string() << ":"
+                  << m_ep.port();
+        // 连接成功后修改状态为正常待机,
+        m_communication_status = E_READY;
+        //检查连接等待时间变为 CHECK_WAIT_TIME_MS,
+        m_check_connect_wait_time_ms = CHECK_WAIT_TIME_MS;
+        //唤醒接受线程
+        m_condition_receive.notify_all(true);
+
+
+    } else {
+        LOG(WARNING) << "connect failed, " << boost::system::system_error(error).what() << ", waiting for reconnection "
+                     << m_ep.address().to_string() << ":" << m_ep.port();
+        // 连接失败后修改状态为断连,
+        m_communication_status = E_DISCONNECT;
+        //检查连接等待时间变为 RECONNECTION_WAIT_TIME_MS,
+        m_check_connect_wait_time_ms = RECONNECTION_WAIT_TIME_MS;
+        //关闭接受线程
+        m_condition_receive.notify_all(false);
+    }
+}
+
+
+//异步读取回调, 失败后重连. bytes_transferred是返回的数据有效长度
+void Async_Client::handle_read(const boost::system::error_code &error,
+                               size_t bytes_transferred) {
+    if (!error) {
+        Binary_buf *tp_binary_buf = new Binary_buf(m_data_buf, bytes_transferred);
+        if (mp_communication_data_queue != NULL) {
+            //将数据添加到队列中, 然后内存权限转交给队列.
+            mp_communication_data_queue->push(tp_binary_buf);
+        }
+
+        //更新时间
+        m_data_updata_time = std::chrono::system_clock::now();
+
+    } else {
+        LOG(WARNING) << "handle_read, " << boost::system::system_error(error).what() << ", waiting for reconnection "
+                     << m_ep.address().to_string() << ":" << m_ep.port();
+
+        // 读取失败后修改状态为断连,
+        m_communication_status = E_DISCONNECT;
+        //检查连接等待时间变为 RECONNECTION_WAIT_TIME_MS,
+        m_check_connect_wait_time_ms = RECONNECTION_WAIT_TIME_MS;
+        //关闭接受线程
+        m_condition_receive.notify_all(false);
+    }
+}
+
+
+//异步写入回调, 失败后重连
+void Async_Client::handle_write(const boost::system::error_code &error) {
+    if (!error) {
+        //发送成功, 暂时不做处理
+//		LOG(INFO) << "handle write no error";
+    } else {
+        LOG(WARNING) << "handle_write, " << boost::system::system_error(error).what() << ", waiting for reconnection "
+                     << m_ep.address().to_string() << ":" << m_ep.port();
+        // 读取失败后修改状态为断连,
+        m_communication_status = E_DISCONNECT;
+        //检查连接等待时间变为 RECONNECTION_WAIT_TIME_MS,
+        m_check_connect_wait_time_ms = RECONNECTION_WAIT_TIME_MS;
+        //关闭接受线程
+        m_condition_receive.notify_all(false);
+    }
+}
+
+

+ 189 - 0
lidar/async_client.h

@@ -0,0 +1,189 @@
+/*
+ * 	//启动异步服务
+ *
+ * 必须使用如下三步
+	m_io_service.reset();
+ 	//异步事件函数
+ 	m_io_service.run();
+
+
+	//run运行之后, 代码会卡在run()这里
+	//socket.async_connect() socket.async_read_some() boost::asio::async_write()等函数内部才会真正的执行,
+	// 执行完成后就会自动调用里面的回调函数,
+ //里面的事件函数执行完之后, 才会结束run(), 此时才会执行run()后面的代码
+
+	//异步通信的机制就是, 如上3个函数,在被调用的时候会先跳过,
+	//并执行后面的其他代码, 只有在run之后, 才会启动如上3个函数,
+	//由m_io_service.run() m_io_service.stop() m_io_service.reset() m_socket.close() 来控制
+	//功能有点像线程的条件变量.
+
+ //注, run()函数只能启动前面的异步事件,
+ 在run之后, 如果还有异步事件, 那么需要reset和run再次使用.
+
+ //注注注注注意了
+	//m_io_service.run(), m_io_service.stop() , m_io_service.reset()只是控制异步服务的事件函数
+	//m_socket.close() 控制通信
+
+ * */
+
+
+
+#ifndef ASYNC_CLIENT_H
+#define ASYNC_CLIENT_H
+
+#include <iostream>
+#include <stdio.h>
+#include <time.h>
+#include <boost/asio.hpp>
+#include <boost/bind.hpp>
+#include <boost/thread.hpp>
+#include <chrono>
+#include <mutex>
+#include <thread>
+#include <atomic>
+#include <string>
+#include <unistd.h>
+#include "glog/logging.h"
+
+#include "error_code/error_code.hpp"
+#include "tool/thread_condition.h"
+#include "tool/binary_buf.h"
+#include "tool/thread_safe_queue.hpp"
+
+
+/**
+ * 异步tcp通信客户端
+ * */
+class Async_Client {
+
+public:
+#define DATA_LENGTH_MAX 50000            //接受消息的缓存长度50000byte, 实际通信数据不能超过它, 如果超过了, 则需要增大
+#define RECONNECTION_WAIT_TIME_MS 1000    //每隔1000ms重连一次
+#define CHECK_WAIT_TIME_MS 75            //每隔75ms检查一次通信, 万集雷达15HZ, 必须要大于一个通信周期, 防止重连之后没有及时刷新消息就又超时断连了
+#define READ_TIMEOUT_MILLISECONDS 5000    //通信数据更新 的超时时间5000ms, 如果数据一直不更新那么就断开然后重连
+    //注:隐藏bug:如果通信正常,但是服务端
+
+    typedef void (*fundata_t)(const char *data, const int len, const void *p);
+
+    typedef void (*Callback_function)(const char *data, const int len, const void *p);
+
+    //通信状态
+    enum Communication_status {//default  = 0
+        E_UNKNOWN = 0,    //未知
+        E_READY = 1,    //正常待机
+        E_DISCONNECT = 2,    //断连
+
+        E_FAULT = 10,    //故障
+    };
+public:
+    // 构造
+    Async_Client();
+
+    // 析构
+    ~Async_Client();
+
+    //初始化, 默认重连
+    Error_manager init(std::string ip, int port, Thread_safe_queue<Binary_buf *> *p_communication_data_queue,
+                       bool is_reconnection_flag = true);
+
+    //反初始化
+    Error_manager uninit();
+
+    //检查状态
+    Error_manager check_status();
+
+    //判断是否正常
+    bool is_ready();
+
+    //获取状态
+    Communication_status get_status();
+
+protected:
+    //线程接受函数,自动接受数据到 mp_data_buf, 然后触发回调函数,
+    void thread_receive();
+
+    //线程检查连接函数,进行连接, 并检查消息是否按时更新, 如果超时, 那么触发重连
+    void thread_check_connect();
+
+    // 开启连接
+    void socket_connect();
+
+    // 关闭连接
+    void socket_close();
+
+    // 重新连接
+    void socket_reconnect();
+
+    // 检查连接
+    void socket_check();
+
+    // 异步写入
+    void client_async_write(char *buf, int len);
+
+    // 异步读取
+    void client_async_read();
+
+    // 异步连接回调
+    void handle_connect(const boost::system::error_code &error);
+
+    //异步读取回调, 失败后重连. bytes_transferred是返回的数据有效长度
+    void handle_read(const boost::system::error_code &error, size_t bytes_transferred);
+
+    // 异步写回调
+    void handle_write(const boost::system::error_code &error);
+
+protected:
+    //状态
+    std::atomic<Communication_status> m_communication_status;    //通信状态
+    std::atomic<bool> m_is_reconnection_flag;        // 断线是否重连的标志位, true:断线自动重连, false:断线不重连, 保持断线状态.
+
+    //通信
+    //把m_io_service作为参数, 构造m_socket, 那么m_io_service.run()可以异步启动m_socket的通信
+    boost::asio::io_service m_io_service;        // 异步控制服务, 负责异步操作, run启动异步服务, stop停止异步服务
+    boost::asio::ip::tcp::socket m_socket;            // socket句柄, 负责tcp通信, 主要是connect,read,write,close
+    //m_socket.async_connect() 传入m_ep, 可以tcp连接 指定的ip和port
+    boost::asio::ip::tcp::endpoint m_ep;                // 连接参数, 主要是ip和port
+
+    //数据
+    char m_data_buf[DATA_LENGTH_MAX];            // 通信消息接受缓存, 默认50000byte
+    std::chrono::system_clock::time_point m_data_updata_time;            // 数据更新时间
+    Thread_safe_queue<Binary_buf *> *mp_communication_data_queue;    //通信数据队列, 内存由上级管理
+
+
+    //接受数据的线程, 自动接受数据到 mp_data_buf, 然后存入队列
+    std::thread *mp_thread_receive;        // 接受线程, 内存由本模块管理
+    Thread_condition m_condition_receive;    //接受线程的条件变量
+    // 检查连接线程, 进行连接, 并检查消息是否按时更新, 如果超时, 那么触发重连
+    std::thread *mp_thread_check_connect;        // 检查连接线程, 内存由本模块管理
+    Thread_condition m_condition_check_connect;        //检查连接线程的条件变量
+    int m_check_connect_wait_time_ms;    // 检查连接线程 的等待时间
+
+};
+
+#endif // ASYNC_CLIENT_H
+
+
+/*
+ * boost::asio::io_service使用时的注意事项:
+
+①请让boost::asio::io_service和boost::asio::io_service::work搭配使用。
+
+②想让event按照进入(strand)时的顺序被执行,需要boost::asio::io_service要和boost::asio::io_service::strand搭配使用。
+
+③一般情况下,io_service的成员函数的使用顺序:
+
+boost::asio::io_service构造,
+boost::asio::io_service::run(),
+boost::asio::io_service::stop(),
+boost::asio::io_service::reset(),
+boost::asio::io_service::run(),
+......
+boost::asio::io_service析构,
+④不论有没有使用io_service::work,run()都会执行完io_service里面的event,(若没有用work,run就会退出)。
+⑤一个新创建的io_service不需要执行reset()函数。
+⑥在调用stop()后,在调用run()之前,请先调用reset()函数。
+⑦函数stop()和reset()并不能清除掉io_service里面尚未执行的event。
+我个人认为,也只有析构掉io_service,才能清空它里面的那些尚未执行的event了。(可以用智能指针)。
+
+⑧函数stop(),stopped(),reset(),很简单,请单步调试,以明白它在函数里做了什么。
+ */

+ 239 - 0
lidar/lidarsJsonConfig.cpp

@@ -0,0 +1,239 @@
+/**
+  * @project shutter_verify
+  * @brief   $BRIEF$
+  * @author  lz
+  * @data    2023/4/13
+ **/
+#include "lidarsJsonConfig.h"
+
+#include <utility>
+
+lidarsJsonConfig::lidarsJsonConfig(std::string path) {
+    m_path = path;
+}
+
+bool lidarsJsonConfig::getLidarConfig(int ordinal, lidarsJsonConfig::LidarConfig &lidarconfig) {
+    if (m_config.empty() && !update()) {
+        return false;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return false;
+    }
+    JV_DOUBLE(m_config[ordinal], "angle_min", lidarconfig.angle_min, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal], "angle_max", lidarconfig.angle_max, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal], "angle_increment", lidarconfig.angle_increment, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal], "time_increment", lidarconfig.time_increment, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "minx", lidarconfig.scan_box_limit.minx, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "maxx", lidarconfig.scan_box_limit.maxx, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "miny", lidarconfig.scan_box_limit.miny, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "maxy", lidarconfig.scan_box_limit.maxy, DEFAULT_DOUBLE)
+    JV_INT(m_config[ordinal], "range_min", lidarconfig.range_min, DEFAULT_INT)
+    JV_INT(m_config[ordinal], "range_max", lidarconfig.range_max, DEFAULT_INT)
+    JV_INT(m_config[ordinal]["net_config"], "port", lidarconfig.net_config.port, DEFAULT_INT)
+    JV_INT(m_config[ordinal]["scan_box_limit"], "dist_limit", lidarconfig.scan_box_limit.dist_limit, DEFAULT_INT)
+    JV_STRING(m_config[ordinal]["net_config"], "ip_address", lidarconfig.net_config.ip_address, DEFAULT_STRING)
+    return true;
+}
+
+bool lidarsJsonConfig::getNetConfig(int ordinal, lidarsJsonConfig::NetConfig &net_config) {
+    if (m_config.empty() && !update()) {
+        return false;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return false;
+    }
+
+    JV_INT(m_config[ordinal]["net_config"], "port", net_config.port, DEFAULT_INT)
+    JV_STRING(m_config[ordinal]["net_config"], "ip_address", net_config.ip_address, DEFAULT_STRING)
+
+    return true;
+}
+
+bool lidarsJsonConfig::getScanBoxLimit(int ordinal, lidarsJsonConfig::ScanBoxLimit &scan_box_limit) {
+    if (m_config.empty() && !update()) {
+        return false;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return false;
+    }
+
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "minx", scan_box_limit.minx, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "maxx", scan_box_limit.maxx, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "miny", scan_box_limit.miny, DEFAULT_DOUBLE)
+    JV_DOUBLE(m_config[ordinal]["scan_box_limit"], "maxy", scan_box_limit.maxy, DEFAULT_DOUBLE)
+    JV_INT(m_config[ordinal]["scan_box_limit"], "dist_limit", scan_box_limit.dist_limit, DEFAULT_INT)
+
+    return true;
+}
+
+bool lidarsJsonConfig::update() {
+    Json::Value config;
+    if (!ReadJsonFile(m_path, config)) {
+        LOG(ERROR) << "Read json etc file " << m_path << " failture, exit 0.";
+        exit(0);
+    }
+
+    for (int i = 0; i < config.size(); i++) {
+        JV_DOUBLE(config[i], "angle_min", m_config[i]["angle_min"], DEFAULT_DOUBLE)
+        JV_DOUBLE(config[i], "angle_max", m_config[i]["angle_max"], DEFAULT_DOUBLE)
+        JV_DOUBLE(config[i], "angle_increment", m_config[i]["angle_increment"], DEFAULT_DOUBLE)
+        JV_DOUBLE(config[i], "time_increment", m_config[i]["time_increment"], DEFAULT_DOUBLE)
+        JV_DOUBLE(config[i]["scan_box_limit"], "minx", m_config[i]["scan_box_limit"]["minx"], DEFAULT_DOUBLE)
+        JV_DOUBLE(config[i]["scan_box_limit"], "maxx", m_config[i]["scan_box_limit"]["maxx"], DEFAULT_DOUBLE)
+        JV_DOUBLE(config[i]["scan_box_limit"], "miny", m_config[i]["scan_box_limit"]["miny"], DEFAULT_DOUBLE)
+        JV_DOUBLE(config[i]["scan_box_limit"], "maxy", m_config[i]["scan_box_limit"]["maxy"], DEFAULT_DOUBLE)
+        JV_INT(config[i], "range_min", m_config[i]["range_min"], DEFAULT_INT)
+        JV_INT(config[i], "range_max", m_config[i]["range_max"], DEFAULT_INT)
+        JV_INT(config[i]["net_config"], "port", m_config[i]["net_config"]["port"], DEFAULT_INT)
+        JV_INT(config[i]["scan_box_limit"], "dist_limit", m_config[i]["scan_box_limit"]["dist_limit"], DEFAULT_INT)
+        JV_STRING(config[i]["net_config"], "ip_address", m_config[i]["net_config"]["ip_address"], DEFAULT_STRING)
+    }
+
+    return true;
+}
+
+double lidarsJsonConfig::angle_min(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["angle_min"].asDouble();
+}
+
+double lidarsJsonConfig::angle_max(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["angle_max"].asDouble();
+}
+
+double lidarsJsonConfig::angle_increment(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["angle_increment"].asDouble();
+}
+
+double lidarsJsonConfig::time_increment(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["time_increment"].asDouble();
+}
+
+int lidarsJsonConfig::range_min(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_INT;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_INT;
+    }
+    return m_config[ordinal]["range_min"].asInt();
+}
+
+int lidarsJsonConfig::range_max(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_INT;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_INT;
+    }
+    return m_config[ordinal]["range_max"].asInt();
+}
+
+std::string lidarsJsonConfig::ip_address(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_STRING;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_STRING;
+    }
+    return m_config[ordinal]["net_config"]["ip_address"].asString();
+}
+
+int lidarsJsonConfig::port(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_INT;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_INT;
+    }
+    return m_config[ordinal]["net_config"]["port"].asInt();
+}
+
+int lidarsJsonConfig::dist_limit(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_INT;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_INT;
+    }
+    return m_config[ordinal]["scan_box_limit"]["dist_limit"].asInt();
+}
+
+double lidarsJsonConfig::minx(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["scan_box_limit"]["minx"].asDouble();
+}
+
+double lidarsJsonConfig::maxx(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["scan_box_limit"]["maxx"].asDouble();
+}
+
+double lidarsJsonConfig::miny(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["scan_box_limit"]["miny"].asDouble();
+}
+
+double lidarsJsonConfig::maxy(int ordinal) {
+    if (m_config.empty() && !update()) {
+        return DEFAULT_DOUBLE;
+    }
+
+    if (m_config.size() <= ordinal) {
+        return DEFAULT_DOUBLE;
+    }
+    return m_config[ordinal]["scan_box_limit"]["maxy"].asDouble();
+}

+ 100 - 0
lidar/lidarsJsonConfig.h

@@ -0,0 +1,100 @@
+/**
+  * @project shutter_verify
+  * @brief   $BRIEF$
+  * @author  lz
+  * @data    2023/4/13
+ **/
+#pragma once
+
+#include "json/json.h"
+#include "defines.hpp"
+
+class lidarsJsonConfig {
+public:
+    struct NetConfig {
+        std::string ip_address;
+        int port;
+
+        void info() {
+            printf("---Debug %s %d : ip_address %s .\n", __func__, __LINE__, ip_address.c_str());
+            printf("---Debug %s %d : port %d .\n", __func__, __LINE__, port);
+        }
+    };
+    struct ScanBoxLimit {
+        int dist_limit;
+        double minx;
+        double maxx;
+        double miny;
+        double maxy;
+
+        void info() {
+            printf("---Debug %s %d : minx %f .\n", __func__, __LINE__, minx);
+            printf("---Debug %s %d : maxx %f .\n", __func__, __LINE__, maxx);
+            printf("---Debug %s %d : miny %f .\n", __func__, __LINE__, miny);
+            printf("---Debug %s %d : maxy %f .\n", __func__, __LINE__, maxy);
+        }
+    };
+    struct LidarConfig {
+        double angle_min;
+        double angle_max;
+        double angle_increment;
+        double time_increment;
+        int range_min;
+        int range_max;
+        NetConfig net_config;
+        ScanBoxLimit scan_box_limit;
+
+        void info() {
+            printf("---Debug %s %d : angle_min %f .\n", __func__, __LINE__, angle_min);
+            printf("---Debug %s %d : angle_max %f .\n", __func__, __LINE__, angle_max);
+            printf("---Debug %s %d : angle_increment %f .\n", __func__, __LINE__, angle_increment);
+            printf("---Debug %s %d : time_increment %f .\n", __func__, __LINE__, time_increment);
+            printf("---Debug %s %d : range_min %d .\n", __func__, __LINE__, range_min);
+            printf("---Debug %s %d : range_max %d .\n", __func__, __LINE__, range_max);
+            net_config.info();
+            scan_box_limit.info();
+        }
+    };
+public:
+    explicit lidarsJsonConfig(std::string path);
+
+    ~lidarsJsonConfig() = default;
+
+    bool getLidarConfig(int ordinal, LidarConfig &lidarconfig);
+
+    bool getNetConfig(int ordinal, NetConfig &net_config);
+
+    bool getScanBoxLimit(int ordinal, ScanBoxLimit &scan_box_limit);
+
+    double angle_min(int ordinal);
+
+    double angle_max(int ordinal);
+
+    double angle_increment(int ordinal);
+
+    double time_increment(int ordinal);
+
+    int range_min(int ordinal);
+
+    int range_max(int ordinal);
+
+    std::string ip_address(int ordinal);
+
+    int port(int ordinal);
+
+    int dist_limit(int ordinal);
+
+    double minx(int ordinal);
+
+    double maxx(int ordinal);
+
+    double miny(int ordinal);
+
+    double maxy(int ordinal);
+
+    bool update();
+
+private:
+    std::string m_path;
+    Json::Value m_config;
+};

+ 220 - 0
lidar/wanji_716N_device.cpp

@@ -0,0 +1,220 @@
+#include "wanji_716N_device.h"
+
+
+// 万集雷达封装类构造函数
+Wanji_716N_lidar_device::Wanji_716N_lidar_device() {
+    m_wanji_lidar_device_status = E_UNKNOWN;
+}
+
+// 万集雷达封装类析构函数
+Wanji_716N_lidar_device::~Wanji_716N_lidar_device() {
+    uninit();
+}
+
+// 初始化
+Error_manager Wanji_716N_lidar_device::init(std::string t_ip, int t_port,
+                                            Point2D_tool::Polar_coordinates_box t_polar_coordinates_box,
+                                            Point2D_tool::Point2D_box t_point2D_box,
+                                            Point2D_tool::Point2D_transform t_point2D_transform) {
+    Error_manager t_error;
+    LOG(INFO) << " Wanji_716N_lidar_device::init " << t_ip << this;
+
+    //唤醒队列
+    m_communication_data_queue.wake_queue();
+
+
+    t_point2D_transform.m00 = 1;
+    t_point2D_transform.m01 = 0;
+    t_point2D_transform.m02 = 0;
+    t_point2D_transform.m10 = 0;
+    t_point2D_transform.m11 = 1;
+    t_point2D_transform.m12 = 0;
+
+    //初始化通信协议
+    t_error = m_protocol.init(&m_communication_data_queue, t_polar_coordinates_box, t_point2D_box, t_point2D_transform);
+    if (t_error != SUCCESS) {
+        return t_error;
+    }
+
+    //初始化雷达通信模块
+
+    t_error = m_async_client.init(t_ip, t_port, &m_communication_data_queue);
+    if (t_error != SUCCESS) {
+        return t_error;
+    }
+
+
+    //启动 内部线程。默认wait。
+    m_execute_condition.reset(false, false, false);
+    // mp_execute_thread = new std::thread(&Wanji_716N_lidar_device::execute_thread_fun, this);
+
+    m_wanji_lidar_device_status = E_READY;
+
+    return t_error;
+}
+
+//反初始化
+Error_manager Wanji_716N_lidar_device::uninit() {
+//终止队列,防止 wait_and_pop 阻塞线程。
+    m_communication_data_queue.termination_queue();
+
+    //关闭线程
+    if (mp_execute_thread) {
+        m_execute_condition.kill_all();
+    }
+    //回收线程的资源
+    if (mp_execute_thread) {
+        mp_execute_thread->join();
+        delete mp_execute_thread;
+        mp_execute_thread = NULL;
+    }
+
+    m_async_client.uninit();
+    m_protocol.uninit();
+
+//清空队列
+    m_communication_data_queue.clear_and_delete();
+
+    if (m_wanji_lidar_device_status != E_FAULT) {
+        m_wanji_lidar_device_status = E_UNKNOWN;
+    }
+    return Error_code::SUCCESS;
+}
+
+//检查雷达状态,是否正常运行
+Error_manager Wanji_716N_lidar_device::check_status() {
+    updata_status();
+    if (m_wanji_lidar_device_status == E_READY) {
+        return Error_code::SUCCESS;
+    } else if (m_wanji_lidar_device_status == E_BUSY) {
+        return Error_manager(Error_code::WANJI_LIDAR_DEVICE_STATUS_BUSY, Error_level::NEGLIGIBLE_ERROR,
+                             "  Wanji_716N_lidar_device::check_status() error ");
+    } else {
+        return Error_manager(Error_code::WANJI_LIDAR_DEVICE_STATUS_ERROR, Error_level::MINOR_ERROR,
+                             " Wanji_716N_lidar_device::check_status() error ");
+    }
+    return Error_code::SUCCESS;
+}
+
+//判断是否为待机,如果已经准备好,则可以执行任务。
+bool Wanji_716N_lidar_device::is_ready() {
+    updata_status();
+    return m_wanji_lidar_device_status == E_READY;
+}
+
+//外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
+Error_manager
+Wanji_716N_lidar_device::get_new_cloud_and_wait(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                                std::chrono::system_clock::time_point command_time, int timeout_ms) {
+    if (p_mutex == NULL || p_cloud.get() == NULL) {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "  POINTER IS NULL ");
+    }
+    //判断是否超时
+    while (std::chrono::system_clock::now() - command_time < std::chrono::milliseconds(timeout_ms)) {
+        //获取指令时间之后的点云, 如果没有就会循环
+        if (m_protocol.get_scan_time() > command_time) {
+            std::unique_lock<std::mutex> lck(*p_mutex);
+            Error_manager code = m_protocol.get_scan_points(p_cloud);
+            return code;
+        }
+        //else 等待下一次数据更新
+
+        //等1ms
+        std::this_thread::sleep_for(std::chrono::milliseconds(1));
+    }
+    //超时退出就报错
+    return Error_manager(Error_code::WJ_LIDAR_GET_CLOUD_TIMEOUT, Error_level::MINOR_ERROR,
+                         " Wanji_716N_lidar_device::get_new_cloud_and_wait error ");
+}
+
+//外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
+Error_manager
+Wanji_716N_lidar_device::get_current_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                           std::chrono::system_clock::time_point command_time) {
+    if (p_mutex == NULL || p_cloud.get() == NULL) {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "  POINTER IS NULL ");
+    }
+    //获取指令时间之后的点云, 如果没有就会报错, 不会等待
+    if (m_protocol.get_scan_time() > command_time) {
+        std::unique_lock<std::mutex> lck(*p_mutex);
+        Error_manager code = m_protocol.get_scan_points(p_cloud);
+        return code;
+    } else {
+        return Error_manager(Error_code::WANJI_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
+                             " Wanji_716N_lidar_device::get_current_cloud error ");
+    }
+}
+
+//外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
+Error_manager Wanji_716N_lidar_device::get_last_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                                      std::chrono::system_clock::time_point command_time) {
+    if (p_mutex == NULL || p_cloud.get() == NULL) {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "  POINTER IS NULL ");
+    }
+    int t_scan_cycle_ms = m_protocol.get_scan_cycle();
+    //将指令时间提前一个扫描周期, 然后获取这个时间后面的点云.
+    //就是说, 在收到指令的时候, 可以使用一个周期以前的数据, 不用获取最新的点云.
+    if (m_protocol.get_scan_time() > command_time - std::chrono::milliseconds(t_scan_cycle_ms)) {
+        std::unique_lock<std::mutex> lck(*p_mutex);
+        Error_manager code = m_protocol.get_scan_points(p_cloud);
+        return code;
+    } else {
+        return Error_manager(Error_code::WANJI_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
+                             " Wanji_716N_lidar_device::get_last_cloud error ");
+    }
+}
+
+//外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
+//注:函数内部不加锁, 由外部统一加锁.
+Error_manager Wanji_716N_lidar_device::get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                                      std::chrono::system_clock::time_point command_time) {
+    if (p_cloud.get() == NULL) {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "  POINTER IS NULL ");
+    }
+    int t_scan_cycle_ms = m_protocol.get_scan_cycle();
+    //将指令时间提前一个扫描周期, 然后获取这个时间后面的点云.
+    //就是说, 在收到指令的时候, 可以使用一个周期以前的数据, 不用获取最新的点云.
+    if (m_protocol.get_scan_time() > command_time - std::chrono::milliseconds(t_scan_cycle_ms * 2)) {
+        Error_manager code = m_protocol.get_scan_points(p_cloud);
+        // LOG(WARNING) << " !!!!!!!!!!!!! wj scan cloud: "<<p_cloud->size();
+        return code;
+    } else {
+        //    LOG(WARNING) << "get cloud failed..... "<<m_protocol.get_scan_time().time_since_epoch().count()<<", "<<command_time.time_since_epoch().count();
+        return Error_manager(Error_code::WANJI_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
+                             " Wanji_716N_lidar_device::get_last_cloud error ");
+    }
+}
+
+Wanji_716N_lidar_device::Wanji_716N_device_status Wanji_716N_lidar_device::get_status() {
+    updata_status();
+    return m_wanji_lidar_device_status;
+}
+
+void Wanji_716N_lidar_device::updata_status() {
+    Async_Client::Communication_status communication_status = m_async_client.get_status();
+    // Wj_716N_lidar_protocol::Wanji_716N_device_status wanji_lidar_protocol_status = m_protocol.get_status();
+
+    if (communication_status == Async_Client::Communication_status::E_FAULT)// ||
+        //  wanji_lidar_protocol_status == Wj_716N_lidar_protocol::Wanji_716N_device_status::E_FAULT)
+    {
+        m_wanji_lidar_device_status = E_FAULT;
+    }
+    if (communication_status == Async_Client::Communication_status::E_DISCONNECT) {
+        m_wanji_lidar_device_status = E_DISCONNECT;
+    } else if (communication_status == Async_Client::Communication_status::E_READY)// &&
+        //   wanji_lidar_protocol_status == Wj_716N_lidar_protocol::Wanji_716N_device_status::E_READY )
+    {
+        if (m_execute_condition.get_pass_ever()) {
+            m_wanji_lidar_device_status = E_BUSY;
+        } else {
+            m_wanji_lidar_device_status = E_READY;
+        }
+    } else {
+        m_wanji_lidar_device_status = E_UNKNOWN;
+    }
+}
+

+ 90 - 0
lidar/wanji_716N_device.h

@@ -0,0 +1,90 @@
+/*
+ * @Author: yct 18202736439@163.com
+ * @Date: 2022-09-22 18:00:51
+ * @LastEditors: yct 18202736439@163.com
+ * @LastEditTime: 2022-09-25 22:10:59
+ * @FilePath: /puai_wj_2021/wanji_lidar/wanji_716N_device.h
+ * @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
+ */
+#pragma once
+#include <chrono>
+#include <mutex>
+#include <thread>
+#include <atomic>
+#include <string>
+#include <unistd.h>
+#include <glog/logging.h>
+
+#include "async_client.h"
+#include "wj_716N_lidar_protocol.h"
+
+class Wanji_716N_lidar_device {
+public:
+    //万集设备身状态
+    enum Wanji_716N_device_status {
+        E_UNKNOWN = 0,      //未知
+        E_READY = 1,        //正常待机
+        E_DISCONNECT = 2,   //断连
+        E_BUSY = 3,         //工作正忙
+        E_FAULT = 10,       //故障
+    };
+
+public:
+    Wanji_716N_lidar_device();
+    ~Wanji_716N_lidar_device();
+
+    // 初始化
+    Error_manager init(std::string ip, int port,
+                       Point2D_tool::Polar_coordinates_box t_polar_coordinates_box,
+                       Point2D_tool::Point2D_box t_point2D_box,
+                       Point2D_tool::Point2D_transform t_point2D_transform);
+
+    //反初始化
+    Error_manager uninit();
+
+    //检查雷达状态,是否正常运行
+    Error_manager check_status();
+
+    //判断是否为待机,如果已经准备好,则可以执行任务。
+    bool is_ready();
+
+    //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
+    Error_manager get_new_cloud_and_wait(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                         std::chrono::system_clock::time_point command_time, int timeout_ms = 1500);
+
+    //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
+    Error_manager get_current_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                    std::chrono::system_clock::time_point command_time);
+
+    //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
+    Error_manager get_last_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                 std::chrono::system_clock::time_point command_time);
+
+    //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
+    //注:函数内部不加锁, 由外部统一加锁.
+    Error_manager get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
+                                 std::chrono::system_clock::time_point command_time);
+
+public:
+    Wanji_716N_device_status get_status();
+
+protected:
+    void updata_status();
+
+protected:
+    //状态
+    Wanji_716N_device_status    m_wanji_lidar_device_status;    //万集设备身状态
+
+    //子模块
+    Async_Client            m_async_client;        //异步客户端, 负责雷达通信, 接受雷达数据
+    wj_716N_lidar_protocol  m_protocol;            // 万集雷达协议
+
+    //中间缓存
+    Thread_safe_queue<Binary_buf *> m_communication_data_queue;    //通信数据队列
+
+    //任务执行线程
+    std::thread         *mp_execute_thread;             //执行的线程指针,内存由本类管理
+    Thread_condition    m_execute_condition;            //执行的条件变量
+
+};
+

+ 392 - 0
lidar/wj_716N_lidar_protocol.cpp

@@ -0,0 +1,392 @@
+#include "wj_716N_lidar_protocol.h"
+#include <iostream>
+
+
+wj_716N_lidar_protocol::wj_716N_lidar_protocol() {
+    memset(&m_sdata, 0, sizeof(m_sdata));
+    long scan_time = std::chrono::duration_cast<std::chrono::milliseconds>(
+            std::chrono::system_clock::now().time_since_epoch()).count();
+    scan.header.stamp.msecs = scan_time;
+
+    mp_communication_data_queue = nullptr;
+
+    freq_scan = 1;
+    m_u32PreFrameNo = 0;
+    m_u32ExpectedPackageNo = 0;
+    m_n32currentDataNo = 0;
+    total_point = 1081;
+
+    scan.header.frame_id = "wj_716N_lidar_frame";
+    scan.angle_min = -2.35619449;
+    scan.angle_max = 2.35619449;
+    scan.angle_increment = 0.017453 / 4;
+    scan.time_increment = 1 / 15.00000000 / 1440;
+    scan.range_min = 0;
+    scan.range_max = 30;
+    scan.ranges.resize(1081);
+    scan.intensities.resize(1081);
+    scan.x.resize(1081);
+    scan.y.resize(1081);
+    scan.angle_to_point.resize(1081);
+
+    index_start = (config_.min_ang + 2.35619449) / scan.angle_increment;
+    // adjust angle_max to max_ang config param
+    index_end = 1081 - ((2.35619449 - config_.max_ang) / scan.angle_increment);
+
+    mp_scan_points = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
+    mp_thread_analysis = nullptr;
+
+    std::cout << "wj_716N_lidar_protocl start success" << std::endl;
+}
+
+bool wj_716N_lidar_protocol::setConfig(wj_716_lidarConfig &new_config, uint32_t level) {
+
+    config_ = new_config;
+    scan.header.frame_id = config_.frame_id;
+    scan.angle_min = config_.min_ang;
+    scan.angle_max = config_.max_ang;
+    scan.range_min = config_.range_min;
+    scan.range_max = config_.range_max;
+    freq_scan = config_.frequency_scan;
+
+    scan.angle_increment = 0.017453 / 4;
+    if (freq_scan == 1) //0.25°_15hz
+    {
+        scan.time_increment = 1 / 15.00000000 / 1440;
+        total_point = 1081;
+    } else if (freq_scan == 2) //0.25°_25hz
+    {
+        scan.time_increment = 1 / 25.00000000 / 1440;
+        total_point = 1081;
+    }
+
+    // adjust angle_min to min_ang config param
+    index_start = (config_.min_ang + 2.35619449) / scan.angle_increment;
+
+    // adjust angle_max to max_ang config param
+    index_end = 1081 - ((2.35619449 - config_.max_ang) / scan.angle_increment);
+    int samples = index_end - index_start;
+
+    std::cout << "frame_id:" << scan.header.frame_id << std::endl;
+    std::cout << "min_ang:" << scan.angle_min << std::endl;
+    std::cout << "max_ang:" << scan.angle_max << std::endl;
+    std::cout << "angle_increment:" << scan.angle_increment << std::endl;
+    std::cout << "time_increment:" << scan.time_increment << std::endl;
+    std::cout << "range_min:" << scan.range_min << std::endl;
+    std::cout << "range_max:" << scan.range_max << std::endl;
+    std::cout << "samples_per_scan:" << samples << std::endl;
+    return true;
+}
+
+// 初始化
+Error_manager wj_716N_lidar_protocol::init(Thread_safe_queue<Binary_buf *> *p_communication_data_queue,
+                                           Point2D_tool::Polar_coordinates_box polar_coordinates_box,
+                                           Point2D_tool::Point2D_box point2D_box,
+                                           Point2D_tool::Point2D_transform point2D_transform) {
+    if (p_communication_data_queue == NULL) {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "  POINTER IS NULL ");
+    }
+    wj_716_lidarConfig t_config;
+    t_config.min_ang = polar_coordinates_box.angle_min;
+    t_config.max_ang = polar_coordinates_box.angle_max;
+    t_config.range_min = polar_coordinates_box.distance_min;
+    t_config.range_max = polar_coordinates_box.distance_max;
+    t_config.frequency_scan = 1;
+    setConfig(t_config, 0);
+
+    mp_communication_data_queue = p_communication_data_queue;
+    m_point2D_box = point2D_box;
+    std::cout << "box xmin:" << m_point2D_box.x_min << std::endl;
+    std::cout << "box xmax:" << m_point2D_box.x_max << std::endl;
+    std::cout << "box ymin:" << m_point2D_box.y_min << std::endl;
+    std::cout << "box ymax:" << m_point2D_box.y_max << std::endl;
+    m_point2D_transform = point2D_transform;
+    //接受线程, 默认开启循环, 在内部的wait_and_pop进行等待
+    m_condition_analysis.reset(false, true, false);
+    mp_thread_analysis = new std::thread(&wj_716N_lidar_protocol::thread_analysis, this);
+
+    return Error_code::SUCCESS;
+}
+
+//反初始化
+Error_manager wj_716N_lidar_protocol::uninit() {
+    LOG(INFO) << " ---wj_716N_lidar_protocol uninit --- " << this;
+
+    if (mp_communication_data_queue) {
+        //终止队列,防止 wait_and_pop 阻塞线程。
+        mp_communication_data_queue->termination_queue();
+    }
+
+    //关闭线程
+    if (mp_thread_analysis) {
+        m_condition_analysis.kill_all();
+    }
+    //回收线程的资源
+    if (mp_thread_analysis) {
+        mp_thread_analysis->join();
+        delete mp_thread_analysis;
+        mp_thread_analysis = nullptr;
+    }
+
+    if (mp_communication_data_queue) {
+        //清空队列
+        mp_communication_data_queue->clear_and_delete();
+    }
+    //队列的内存由上级管理, 这里写空就好了.
+    mp_communication_data_queue = nullptr;
+
+    return Error_code::SUCCESS;
+}
+
+//获取扫描点云
+Error_manager wj_716N_lidar_protocol::get_scan_points(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_out) {
+    if (p_cloud_out.get() == nullptr) {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             " Wj_716_lidar_protocol::get_scan_points POINTER IS NULL ");
+    }
+    std::unique_lock<std::mutex> lck(m_scan_mutex);
+    //将扫描点云追加到p_cloud_out后面, 不要清除p_cloud_out原有的数据
+    (*p_cloud_out) += (*mp_scan_points);
+
+    return Error_code::SUCCESS;
+}
+
+//解析线程函数
+void wj_716N_lidar_protocol::thread_analysis() {
+    LOG(INFO) << " ---Wj_716_lidar_protocol::thread_analysis start ---" << this;
+
+    Error_manager t_error;
+    //接受雷达消息,包括连接,重连和接受数据
+    while (m_condition_analysis.is_alive()) {
+        m_condition_analysis.wait();
+        if (m_condition_analysis.is_alive()) {
+            std::this_thread::yield();
+
+            if (mp_communication_data_queue != nullptr) {
+                Binary_buf *tp_binary_buf = nullptr;
+                bool is_pop = mp_communication_data_queue->wait_and_pop(tp_binary_buf);
+                if (is_pop && tp_binary_buf != nullptr) {
+                    if (dataProcess((unsigned char *) tp_binary_buf->get_buf(), tp_binary_buf->get_length())) {
+                        t_error = SUCCESS;
+                    } else {
+                        t_error = ERROR;
+                    }
+                    //else 错误不管, 当做无效消息处理
+                    delete (tp_binary_buf);
+                }
+            }
+        }
+    }
+    LOG(INFO) << " -Wj_716_lidar_protocol::thread_analysis end :" << this;
+}
+
+
+bool wj_716N_lidar_protocol::dataProcess(unsigned char *data, const int reclen) {
+
+    if (reclen > MAX_LENGTH_DATA_PROCESS) {
+        m_sdata.m_u32out = 0;
+        m_sdata.m_u32in = 0;
+        return false;
+    }
+
+    if (m_sdata.m_u32in + reclen > MAX_LENGTH_DATA_PROCESS) {
+        m_sdata.m_u32out = 0;
+        m_sdata.m_u32in = 0;
+        return false;
+    }
+    memcpy(&m_sdata.m_acdata[m_sdata.m_u32in], data, reclen * sizeof(char));
+    m_sdata.m_u32in += reclen;
+    while (m_sdata.m_u32out < m_sdata.m_u32in) {
+        if (m_sdata.m_acdata[m_sdata.m_u32out] == 0xFF && m_sdata.m_acdata[m_sdata.m_u32out + 1] == 0xAA) {
+            unsigned l_u32reallen = (m_sdata.m_acdata[m_sdata.m_u32out + 2] << 8) |
+                                    (m_sdata.m_acdata[m_sdata.m_u32out + 3] << 0);
+            l_u32reallen = l_u32reallen + 4;
+
+            if (l_u32reallen <= (m_sdata.m_u32in - m_sdata.m_u32out + 1)) {
+                if (OnRecvProcess(&m_sdata.m_acdata[m_sdata.m_u32out], l_u32reallen)) {
+                    m_sdata.m_u32out += l_u32reallen;
+                } else {
+                    LOG_EVERY_N(WARNING, 10) << "continuous search frame header";
+                    m_sdata.m_u32out++;
+                }
+            } else if (l_u32reallen >= MAX_LENGTH_DATA_PROCESS) {
+                m_sdata.m_u32out++;
+            } else {
+                break;
+            }
+        } else {
+            m_sdata.m_u32out++;
+        }
+    } //end while(m_sdata.m_u32out < m_sdata.m_u32in)
+
+    if (m_sdata.m_u32out >= m_sdata.m_u32in) {
+        m_sdata.m_u32out = 0;
+        m_sdata.m_u32in = 0;
+    } else if (m_sdata.m_u32out < m_sdata.m_u32in && m_sdata.m_u32out != 0) {
+        movedata(m_sdata);
+    }
+    return true;
+}
+
+void wj_716N_lidar_protocol::movedata(DataCache &sdata) {
+    for (int i = sdata.m_u32out; i < sdata.m_u32in; i++) {
+        sdata.m_acdata[i - sdata.m_u32out] = sdata.m_acdata[i];
+    }
+    sdata.m_u32in = sdata.m_u32in - sdata.m_u32out;
+    sdata.m_u32out = 0;
+}
+
+bool wj_716N_lidar_protocol::OnRecvProcess(unsigned char *data, int len) {
+    if (len > 0) {
+        if (checkXor(data, len)) {
+            protocl(data, len);
+        } else {
+            return false;
+        }
+    } else {
+        return false;
+    }
+    return true;
+}
+
+bool wj_716N_lidar_protocol::protocl(unsigned char *data, const int len) {
+
+    if ((data[22] == 0x02 && data[23] == 0x02) || (data[22] == 0x02 && data[23] == 0x01)) //command type:0x02 0x01/0X02
+    {
+
+        heartstate = true;
+        int l_n32TotalPackage = data[80];
+        int l_n32PackageNo = data[81];
+        unsigned int l_u32FrameNo = (data[75] << 24) + (data[76] << 16) + (data[77] << 8) + data[78];
+        int l_n32PointNum = (data[83] << 8) + data[84];
+        int l_n32Frequency = data[79];
+
+        if (l_n32Frequency != freq_scan) {
+            std::cout << "The scan frequency " << l_n32Frequency << " does not match the one you setted " << freq_scan
+                      << " !" << std::endl;
+            return false;
+        }
+
+
+        if (m_u32PreFrameNo != l_u32FrameNo) {
+            m_u32PreFrameNo = l_u32FrameNo;
+            m_u32ExpectedPackageNo = 1;
+            m_n32currentDataNo = 0;
+        }
+
+        if (l_n32PackageNo == m_u32ExpectedPackageNo && m_u32PreFrameNo == l_u32FrameNo) {
+            if (data[82] == 0x00) //Dist
+            {
+                for (int j = 0; j < l_n32PointNum; j++) {
+                    scandata[m_n32currentDataNo] = (((unsigned char) data[85 + j * 2]) << 8) +
+                                                   ((unsigned char) data[86 + j * 2]);
+                    scandata[m_n32currentDataNo] /= 1000.0;
+                    scanintensity[m_n32currentDataNo] = 0;
+                    if (scandata[m_n32currentDataNo] > scan.range_max ||
+                        scandata[m_n32currentDataNo] < scan.range_min || scandata[m_n32currentDataNo] == 0) {
+                        scandata[m_n32currentDataNo] = NAN;
+                    }
+                    m_n32currentDataNo++;
+                }
+                m_u32ExpectedPackageNo++;
+            } else if (data[82] == 0x01 && m_n32currentDataNo >= total_point) //intensities
+            {
+                for (int j = 0; j < l_n32PointNum; j++) {
+                    scanintensity[m_n32currentDataNo - total_point] = (((unsigned char) data[85 + j * 2]) << 8) +
+                                                                      ((unsigned char) data[86 + j * 2]);
+                    m_n32currentDataNo++;
+                }
+                m_u32ExpectedPackageNo++;
+            }
+
+            if (m_u32ExpectedPackageNo - 1 == l_n32TotalPackage) {
+
+                m_read_write_mtx.lock();
+                mp_scan_points->clear();
+                for (int i = index_start; i < index_end; i++) {
+                    scan.ranges[i - index_start] = scandata[i];
+                    //std::cout<<scan.ranges[i - index_start]<<std::endl;
+                    update_data(i - index_start);
+
+                    if (scandata[i - index_start] == NAN) {
+                        scan.intensities[i - index_start] = 0;
+                        continue;
+                    } else {
+                        scan.intensities[i - index_start] = scanintensity[i];
+                    }
+
+                    pcl::PointXYZ point;
+                    //判断平面坐标点是否在限制范围
+                    double x = scan.x[i - index_start];
+                    double y = scan.y[i - index_start];
+                    if (Point2D_tool::limit_with_point2D_box(x, y, &m_point2D_box)) {
+                        //平面坐标的转换, 可以进行旋转和平移, 不能缩放
+                        point.x = x * m_point2D_transform.m00 + y * m_point2D_transform.m01 + m_point2D_transform.m02;
+                        point.y = x * m_point2D_transform.m10 + y * m_point2D_transform.m11 + m_point2D_transform.m12;
+                        //添加到最终点云
+                        mp_scan_points->push_back(point);
+                    }
+                }
+                scan.header.stamp.msecs = std::chrono::duration_cast<std::chrono::milliseconds>(
+                        std::chrono::system_clock::now().time_since_epoch()).count();
+                m_read_write_mtx.unlock();
+
+//                    ros::Time scan_time = ros::Time::now();
+//                    scan.header.stamp = scan_time;
+//                    marker_pub.publish(scan);
+            }
+        }
+        return true;
+    } else {
+        return false;
+    }
+}
+
+//index点数组下标【0~l_n32PointCount-1】 l_n32PointCount总点数
+void wj_716N_lidar_protocol::update_data(int index) {
+    if (index >= total_point) {
+        return;
+    }
+
+//    每个下标对应的弧度
+    scan.angle_to_point[index] =
+            scan.angle_min + (total_point - 1 - index) * (scan.angle_max - scan.angle_min) / (total_point - 1);
+    scan.y[index] = scan.ranges[index] * cos(scan.angle_min +
+                                             (total_point - 1 - index) * (scan.angle_max - scan.angle_min) /
+                                             (total_point - 1));
+    scan.x[index] = scan.ranges[index] * sin(scan.angle_min +
+                                             (total_point - 1 - index) * (scan.angle_max - scan.angle_min) /
+                                             (total_point - 1));
+}
+
+bool wj_716N_lidar_protocol::checkXor(unsigned char *recvbuf, int recvlen) {
+    int i = 0;
+    unsigned char check = 0;
+    unsigned char *p = recvbuf;
+    int len;
+    if (*p == 0xFF) {
+        p = p + 2;
+        len = recvlen - 6;
+        for (i = 0; i < len; i++) {
+            check ^= *p++;
+        }
+        p++;
+        if (check == *p) {
+            return true;
+        } else
+            return false;
+    } else {
+        return false;
+    }
+}
+
+std::chrono::system_clock::time_point wj_716N_lidar_protocol::get_scan_time() const {
+    return std::chrono::time_point<std::chrono::system_clock, std::chrono::milliseconds>(
+            std::chrono::milliseconds(scan.header.stamp.msecs));
+}
+
+int wj_716N_lidar_protocol::get_scan_cycle() const {
+    return (config_.frequency_scan == 1 ? 67 : 40);
+}
+

+ 154 - 0
lidar/wj_716N_lidar_protocol.h

@@ -0,0 +1,154 @@
+#pragma once
+
+#include <iostream>
+#include <mutex>
+#include <chrono>
+#include <math.h>
+
+#include "glog/logging.h"
+#include "string.h"
+
+#include "error_code/error_code.hpp"
+#include "tool/binary_buf.h"
+#include "tool/thread_safe_queue.hpp"
+#include "tool/thread_condition.h"
+#include "tool/point2D_tool.h"
+
+#include <boost/shared_ptr.hpp>
+#include <boost/asio.hpp>
+#include <boost/asio/placeholders.hpp>
+#include <boost/system/error_code.hpp>
+#include <boost/bind/bind.hpp>
+
+#include "pcl/point_types.h"
+#include "pcl/point_cloud.h"
+#include "pcl/conversions.h"
+#include "pcl/common/common.h"
+
+typedef struct {
+    std::string frame_id = "laser";
+    double min_ang = -2.35619449;
+    double max_ang = 2.35619449;
+    double range_min = 0.0;
+    double range_max = 30.0;
+    int frequency_scan = 1;
+} wj_716_lidarConfig;
+
+#define MAX_LENGTH_DATA_PROCESS 200000
+typedef struct TagDataCache {
+    unsigned char m_acdata[MAX_LENGTH_DATA_PROCESS];
+    unsigned int m_u32in;
+    unsigned int m_u32out;
+} DataCache;
+
+struct Stamp            //    Laser内参
+{
+    long msecs;
+};
+
+struct Header           //    Laser内参
+{
+    int seq;
+    //替换成只用ms表示
+    Stamp stamp;
+    std::string frame_id;
+};
+
+struct Laser            //    雷达数据及雷达参数
+{
+    Header header;
+    double angle_min;
+    double angle_max;
+    double angle_increment;
+
+    double range_min;
+    double range_max;
+
+    double time_increment;
+    long long scan_time;
+
+    std::vector<double> ranges;
+    std::vector<double> x;
+    std::vector<double> y;
+    std::vector<double> angle_to_point;
+    std::vector<double> intensities;
+};
+
+
+class wj_716N_lidar_protocol {
+public:
+    wj_716N_lidar_protocol();
+
+    // 初始化
+    Error_manager init(Thread_safe_queue<Binary_buf *> *p_communication_data_queue,
+                       Point2D_tool::Polar_coordinates_box polar_coordinates_box,
+                       Point2D_tool::Point2D_box point2D_box,
+                       Point2D_tool::Point2D_transform point2D_transform);
+
+    //反初始化
+    Error_manager uninit();
+
+    //获取扫描周期
+    int get_scan_cycle() const;
+
+    // 获取扫描点云
+    Error_manager get_scan_points(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_out);
+
+    // 获取扫描点云更新时间点
+    std::chrono::system_clock::time_point get_scan_time() const;
+
+    bool setConfig(wj_716_lidarConfig &new_config, uint32_t level);
+
+    void update_data(int index);
+
+private:
+    //解析线程函数
+    void thread_analysis();
+
+    void movedata(DataCache &sdata);
+
+    bool dataProcess(unsigned char *data, int reclen);
+
+    bool OnRecvProcess(unsigned char *data, int len);
+
+    bool checkXor(unsigned char *recvbuf, int recvlen);
+
+    bool protocl(unsigned char *data, int len);
+
+
+public:
+    Laser scan;
+    int freq_scan;
+    int resizeNum;
+    int index_start;
+    int index_end;
+    bool heartstate;
+    int total_point;
+    std::mutex m_read_write_mtx;            // 点云获取互斥锁
+    std::mutex m_scan_mutex;                // 扫描点的锁
+
+    Thread_safe_queue<Binary_buf *> *mp_communication_data_queue;    //通信数据队列, 内存由上级管理
+
+    // 雷达扫描点平面坐标
+    pcl::PointCloud<pcl::PointXYZ>::Ptr mp_scan_points;                //扫描点的点云, 内存由本类管理
+
+    // 控制参数
+    Point2D_tool::Polar_coordinates_box m_polar_coordinates_box;    //极坐标的限定范围
+    Point2D_tool::Point2D_box m_point2D_box;                        //平面坐标的限定范围
+    Point2D_tool::Point2D_transform m_point2D_transform;            //平面坐标的转换矩阵
+
+    // 解析数据的线程, 自动从队列取出原始数据, 然后解析为点云
+    std::thread *mp_thread_analysis;                // 解析线程, 内存由本模块管理
+    Thread_condition m_condition_analysis;          //解析线程的条件变量
+
+private:
+    DataCache m_sdata;
+    wj_716_lidarConfig config_;
+    unsigned int m_u32PreFrameNo;
+    unsigned int m_u32ExpectedPackageNo;
+    int   m_n32currentDataNo;
+    float scandata[1081];
+    float scanintensity[1081];
+
+};
+

+ 0 - 0
main.c


+ 13 - 0
main.cpp

@@ -0,0 +1,13 @@
+//
+// Created by zx on 2023/10/26.
+//
+#include <iostream>
+#include "error_code/error_code.hpp"
+
+int main(int argc, char **argv) {
+#ifdef PROJECT_NAME
+    std::cout <<  PROJECT_NAME;
+#endif
+
+    return EXIT_SUCCESS;
+}

+ 116 - 0
plc/snap7_clamp.cpp

@@ -0,0 +1,116 @@
+//
+// Created by huli on 2020/9/25.
+//
+
+#include "snap7_clamp.h"
+
+Snap7Clamp::Snap7Clamp() = default;
+Snap7Clamp::~Snap7Clamp() = default;
+
+//初始化 通信 模块。如下三选一
+Error_manager Snap7Clamp::communication_init()
+{
+	int t_index = 0;
+	std::vector<Snap7_buf::Variable_information>		t_variable_information_vector;
+
+	//往map通信缓存里面添加所需要的buf
+	std::unique_lock<std::mutex> t_lock1(m_receive_buf_lock);
+	std::unique_lock<std::mutex> t_lock2(m_send_buf_lock);
+	Snap7_buf t_snap7_buf;
+
+    // plcData
+    t_index = 0;
+    t_variable_information_vector.clear();
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"pingpong", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"wheel_exist", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"offset", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"gap", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"clamp_completed", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"wheel_exist", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"offset", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"gap", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"clamp_completed", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"wheel_exist", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"offset", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"gap", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"clamp_completed", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"wheel_exist", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"offset", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"gap", typeid(float ).name(), t_index,sizeof(float), 1 });
+    t_index += sizeof(float)*1;
+    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"clamp_completed", typeid(unsigned short ).name(), t_index,sizeof(unsigned short), 1 });
+    t_index += sizeof(unsigned short)*1;
+
+    LOG(INFO) << t_index;
+
+    t_snap7_buf.init(CLAMP_SAFETY_PLC_DBNUMBER , 0, sizeof(PLCData), t_variable_information_vector, Snap7_buf::LOOP_COMMUNICATION);
+	m_send_buf_map[0] = t_snap7_buf;
+
+//    t_index = 0;
+//    t_variable_information_vector.clear();
+//    t_variable_information_vector.push_back(Snap7_buf::Variable_information{"heart", typeid(unsigned short).name(), t_index,sizeof(unsigned short), 1 });
+//
+//    t_snap7_buf.init(CLAMP_SAFETY_PLC_DBNUMBER , 50, sizeof(unsigned short), t_variable_information_vector, Snap7_buf::LOOP_COMMUNICATION);
+//    m_receive_buf_map[0] = t_snap7_buf;
+
+    plcJsonConfig config(ETC_PATH"/ClampSafety/plc.json");
+    return Snap7_communication_base::communication_init(config.ip());
+    return SUCCESS;
+}
+
+//反初始化 通信 模块。
+Error_manager Snap7Clamp::communication_uninit()
+{
+	return Snap7_communication_base::communication_uninit();
+}
+
+//更新数据
+Error_manager Snap7Clamp::updata_receive_buf()
+{
+//	std::unique_lock<std::mutex> t_lock1(m_receive_buf_lock);
+//	std::unique_lock<std::mutex> t_lock2(m_data_lock);
+//    static unsigned short heart;
+//    memcpy(&heart, m_receive_buf_map[0].mp_buf_obverse, m_receive_buf_map[0].m_size);
+
+    Error_manager ret = Error_code::SUCCESS;
+
+//    if (heart == m_heart) {
+//        printf("---Debug %s %d : heart not change %d ---> %d\n", __func__, __LINE__, m_heart, heart);
+//        ret = Error_code::FAILED;
+//    }
+//    m_heart = heart;
+	return ret;
+}
+
+Error_manager Snap7Clamp::updata_send_buf()
+{
+	std::unique_lock<std::mutex> t_lock1(m_send_buf_lock);
+	std::unique_lock<std::mutex> t_lock2(m_data_lock);
+
+    if (plcData.pingpong != 0) {
+        plcData.info();
+    }
+
+	memcpy(m_send_buf_map[0].mp_buf_obverse, &plcData, m_send_buf_map[0].m_size);
+
+    return Error_code::SUCCESS;
+}
+
+
+
+

+ 105 - 0
plc/snap7_clamp.h

@@ -0,0 +1,105 @@
+//
+// Created by huli on 2020/9/25.
+//
+#pragma once
+
+#include "thread/singleton.h"
+#include "plc/snap7_communication_base.h"
+#include <glog/logging.h>
+
+class Snap7Clamp:public Singleton<Snap7Clamp>, public Snap7_communication_base
+{
+public:
+	//发送db快的标记位, 保证先发数据再发唯一码
+	enum Send_database_flag
+	{
+		E_SEND_UNKNOW					= 0,
+		E_SEND_DATA_START              	= 1,    //开始发送数据
+		E_SEND_DATA_END              	= 2,    //结束发送数据
+		E_SEND_KEY_START				= 3,	//开始发送唯一码
+		E_SEND_KEY_END					= 4,	//结束发送唯一码
+	};
+
+
+#pragma pack(push, 1)	//struct按照1个byte对齐
+#define CLAMP_SAFETY_HEART_DBNUMBER		9070
+#define CLAMP_SAFETY_PLC_DBNUMBER		9070
+    struct WheeLData {
+        unsigned short wheel_exist;
+        float offset;
+        float gap;
+        unsigned short clamp_completed;
+
+        void info() const {
+            if (wheel_exist == 0) {
+                return;
+            }
+            LOG(INFO) << "wheel_exist = " << wheel_exist
+                       << ", offset = " << offset
+                       << ", gap = " << gap
+                       << ", clamp_completed = " << clamp_completed;
+        }
+
+        void clear() {
+            wheel_exist = false;
+            offset = 0;
+            gap = 0;
+            clamp_completed = 0;
+        }
+    };
+
+    struct PLCData {
+        unsigned short pingpong;
+
+        struct WheeLData wheels[4];
+
+        void info() {
+            LOG(INFO) << "pingdong = " << pingpong;
+            wheels[0].info();
+            wheels[1].info();
+            wheels[2].info();
+            wheels[3].info();
+        }
+
+        void clear() {
+            wheels[0].clear();
+            wheels[1].clear();
+            wheels[2].clear();
+            wheels[3].clear();
+        }
+    };
+#pragma pack(pop)		//取消对齐
+
+    // 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
+	friend class Singleton<Snap7Clamp>;
+
+private:
+	// 父类的构造函数必须保护,子类的构造函数必须私有。
+    Snap7Clamp();
+
+public:
+	//必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
+    Snap7Clamp(const Snap7Clamp& other) = delete;
+    Snap7Clamp& operator =(const Snap7Clamp& other) = delete;
+	~Snap7Clamp() override;
+
+public://API functions
+	//初始化 通信 模块。如下三选一
+	Error_manager communication_init();
+	//反初始化 通信 模块。
+	Error_manager communication_uninit() override;
+
+protected://member functions
+	//更新数据
+    Error_manager updata_receive_buf() override;
+    Error_manager updata_send_buf() override;
+
+protected://member variable
+public:
+	std::mutex      m_data_lock;						//数据锁
+
+	PLCData         plcData{};
+    unsigned short            m_heart;
+private:
+
+};