浏览代码

增加电子围栏消息发送到界面,删除电子围栏日志,修复plc读取数据变化的问题, 已测试.

zx 5 年之前
父节点
当前提交
61bb08fda5

+ 5 - 0
CMakeLists.txt

@@ -43,6 +43,11 @@ aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/system_manager SYS_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/wj_lidar WJLIDAR_SRC )
 
 
+add_executable(fence_debug  test/plc_s7.cpp wj_lidar/wj_lidar_msg.pb.cc)
+target_link_libraries(fence_debug ${GLOG_LIBRARIES} ${PROTOBUF_LIBRARIES} /usr/local/lib/libglog.a
+        /usr/local/lib/libgflags.a nnxx nanomsg)
+
+
 add_executable(locate  main.cpp ${LOCATE_SRC} ${PLC_SRC} ${TERMINOR_SRC} ${TASK_MANAGER_SRC} ${LASER_SRC} ${ERROR_SRC}
         ${TOOL_SRC} ${SYS_SRC} ${VERIFY_SRC} ${WJLIDAR_SRC})
 target_link_libraries(locate ${OpenCV_LIBS}

+ 34 - 9
terminor/terminal_command_executor.cpp

@@ -467,7 +467,6 @@ Error_manager Terminor_Command_Executor::scanning_measuring()
     t_wj_command.timeout_in_milliseconds=2000;
     wj_task->set_command(t_wj_command);
     code=mp_wj_lidar->execute_task(wj_task);
-    LOG(WARNING)<<" leave wj execute task";
     if(code!=SUCCESS)
     {
         return code;
@@ -518,14 +517,9 @@ Error_manager Terminor_Command_Executor::scanning_measuring()
         rotated_rect.angle = m_measure_information.locate_theta;
         float ext_length=720;
         float robot_width=2650.0;
-        if (m_measure_information.locate_theta > 0 && m_measure_information.locate_theta <= 90) {
-            rotated_rect.size.height = m_measure_information.locate_length+ext_length*2.0;
-            rotated_rect.size.width = robot_width;
-        }
-        else {
-            rotated_rect.size.height = robot_width;
-            rotated_rect.size.width = m_measure_information.locate_length+ext_length*2.0;
-        }
+        float new_length=m_measure_information.locate_length+ext_length*2.0;
+        rotated_rect=create_rotate_rect(new_length,robot_width,m_measure_information.locate_theta,
+                                        m_measure_information.locate_x, m_measure_information.locate_y);
         code = mp_verify_tool->verify(rotated_rect,m_measure_information.locate_hight, false);
         m_measure_information.locate_correct = (code == SUCCESS);
         return code;
@@ -533,4 +527,35 @@ Error_manager Terminor_Command_Executor::scanning_measuring()
     }
 
     return code;
+}
+
+cv::RotatedRect Terminor_Command_Executor::create_rotate_rect(float length,float width,float angle,float cx,float cy)
+{
+    const double C_PI=3.14159265;
+    float theta=C_PI*(angle/180.0);
+    float a00=cos(theta);
+    float a01=-sin(theta);
+    float a10=sin(theta);
+    float a11=cos(theta);
+    cv::Point2f point[4];
+    point[0].x=-length/2.0;
+    point[0].y=-width/2.0;
+
+    point[1].x=-length/2.0;
+    point[1].y=width/2.0;
+
+    point[2].x=length/2.0;
+    point[2].y=-width/2.0;
+
+    point[3].x=length/2.0;
+    point[3].y=width/2.0;
+
+    std::vector<cv::Point2f> point_vec;
+    for(int i=0;i<4;++i)
+    {
+        float x=point[i].x*a00+point[i].y*a01+cx;
+        float y=point[i].x*a10+point[i].y*a11+cy;
+        point_vec.push_back(cv::Point2f(x,y));
+    }
+    return cv::minAreaRect(point_vec);
 }

+ 4 - 0
terminor/terminal_command_executor.h

@@ -80,6 +80,10 @@ protected:
      * plc终端编号从1开始
      */
     Error_manager post_measure_information();
+    /*
+     * 根据长宽,角度,生成cv::RotateRect
+     */
+    static cv::RotatedRect create_rotate_rect(float length,float width,float angle,float x,float y);
 protected:
     TerminorStatu               m_terminor_statu;
     //指令流程线程

+ 45 - 0
test/plc_s7.cpp

@@ -0,0 +1,45 @@
+//
+// Created by zx on 2020/1/16.
+//
+
+#include <nnxx/message.h>
+#include <nnxx/message_control.h>
+#include <nnxx/socket.h>
+#include <nnxx/pubsub.h>
+#include <nnxx/timeout.h>
+#include <nnxx/error.h>
+#include <iostream>
+#include "../wj_lidar/wj_lidar_msg.pb.h"
+#include <thread>
+
+int main()
+{
+    nnxx::socket s{nnxx::SP,nnxx::SUB};
+    s.connect("tcp://127.0.0.1:10080");
+    nnxx::subscribe(s);
+    std::string message;
+    while(true)
+    {
+        message=s.recv<std::string>(0);
+        if(message.length()>0)
+        {
+            wj_lidar_message::Fence_statu_message fence_statu;
+            if(fence_statu.ParseFromString(message))
+            {
+                if(fence_statu.fence_statu_size()==0)
+                {
+                    std::this_thread::yield();
+                    continue;
+                }
+                char buf[255] = {0};
+                sprintf(buf, " terminal status: ");
+                for (int i = 0; i < fence_statu.fence_statu_size(); ++i) {
+                    sprintf(buf+strlen(buf), "[%d, %d]   ", fence_statu.fence_statu(i).cloud_statu(),
+                            fence_statu.fence_statu(i).position_statu());
+                }
+                std::cout << buf << std::endl;
+            }
+        }
+    }
+
+}

+ 4 - 3
tool/s7_plc.cpp

@@ -39,11 +39,12 @@ bool S7PLC::ReadShorts(int DBNumber,int start,int size,short* pdata)
     bool S7PLC::WriteShorts(int DBNumber,int start,int size,short* pdata)
     {
         short* plc_data=(short*)malloc(size*sizeof(short));
-        reverse_byte(pdata,size*sizeof(short),plc_data);
+        memcpy(plc_data,pdata,size*sizeof(short));
         for(int i=0;i<size;++i)
-            pdata[i]=plc_data[size-i-1];
+            plc_data[i]=HTON(plc_data[i]);
+
+        bool ret=write_dbs(DBNumber,start*sizeof(short),size*sizeof(short),plc_data);
         free(plc_data);
-        bool ret=write_dbs(DBNumber,start*sizeof(short),size*sizeof(short),pdata);
         return ret;
     }
 

+ 2 - 0
tool/s7_plc.h

@@ -7,6 +7,8 @@
 
 class S7PLC
 {
+public:
+#define HTON(T) ((T) << 8) | ((T) >> 8)
 protected:
     bool        bConnected_;
     std::mutex  mutex_;

+ 61 - 13
verify/Verify_result.cpp

@@ -5,6 +5,42 @@
 #include "Verify_result.h"
 #include <glog/logging.h>
 
+
+/*
+ * 显示rotate rect
+ */
+
+void display(cv::RotatedRect rect,cv::Scalar color)
+{
+    return ;
+    cv::Point2f points_src[4];
+    rect.points(points_src);
+
+    cv::Mat image=cv::Mat::zeros(1000,500,CV_8UC3);
+    cv::RotatedRect t_rect=rect;
+    t_rect.center=cv::Point2f(250,500);
+    t_rect.size.width/=10.0;
+    t_rect.size.height/=10.0;
+    cv::Point2f points[4];
+    t_rect.points(points);
+    float min_x=10000,max_x=0;
+    for(int i=0;i<4;++i)
+    {
+        if(points_src[i].x<min_x)
+            min_x=points_src[i].x;
+        if(points_src[i].x>max_x)
+            max_x=points_src[i].x;
+        cv::line(image, points[i%4],points[(i+1)%4],color,2);
+    }
+    char buf[255]={0};
+    sprintf(buf,"(%.1f,%.1f)[%.1f,%.1f] c:%.1f",t_rect.size.height*10.0,t_rect.size.width*10.0,min_x,max_x,t_rect.angle);
+    cv::putText(image,buf,cv::Point(10,50),1,1.0,color);
+    cv::namedWindow("debug",0);
+    cv::imshow("debug",image);
+    cv::waitKey(0);
+}
+
+
 /*
      * 构造函数
      * parameter:硬件限制配置参数
@@ -54,8 +90,27 @@ Error_manager Verify_result::verify(cv::RotatedRect rotate_rect,float height,boo
         return Error_manager(HARDWARE_LIMIT_HEIGHT_OUT_RANGE,NORMAL,description);
     }
     //第三步,检验角度
+    //计算角度到 0-180
+    // 长边向量
+    cv::Point2f vec;
+    cv::Point2f vertice[4];
+    rotate_rect.points(vertice);
+
+    float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
+    float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
+    // 寻找长边,倾角为长边与x轴夹角
+    if (len1 > len2)
+    {
+        vec.x = vertice[0].x - vertice[1].x;
+        vec.y = vertice[0].y - vertice[1].y;
+    }
+    else
+    {
+        vec.x = vertice[1].x - vertice[2].x;
+        vec.y = vertice[1].y - vertice[2].y;
+    }
+    float angle_x = 180.0 / M_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
     bool tb_theta_verify=false;
-    float angle_x=rotate_rect.angle;
     for(int i=0;i<m_hardware_parameter.theta_range_size();++i)
     {
         Hardware_limit::Theta_range theta_range=m_hardware_parameter.theta_range(i);
@@ -111,15 +166,8 @@ Error_manager Verify_result::verify(cv::RotatedRect rotate_rect,float height,boo
      */
 Error_manager Verify_result::verify(cv::RotatedRect rotate_rect,int terminal_id,int& code)
 {
-    cv::Point2f points[4];
-    rotate_rect.points(points);
-    char buf[255]={0};
-    for(int i=0;i<4;++i)
-    {
-        sprintf(buf+strlen(buf),"(%.1f %.1f)  ",points[i].x,points[i].y);
-    }
-    LOG(WARNING)<<"-----------------------------  :"<<buf;
-//    LOG(INFO)<<"verify   input  : "<<this;
+    display(rotate_rect,cv::Scalar(0,255,0));
+
     code=0x000000;
     //第一步,检验边界
     float minx=m_hardware_parameter.min_x();
@@ -132,12 +180,12 @@ Error_manager Verify_result::verify(cv::RotatedRect rotate_rect,int terminal_id,
     //前超界
     if(center_y<miny)
     {
-        code|=LIMIT_FRONT_ERROR;
+        code|=LIMIT_BACK_ERROR;
     }
     //后超界
     if(center_y>maxy)
     {
-        code|=LIMIT_BACK_ERROR;
+        code|=LIMIT_FRONT_ERROR;
     }
     ////第二步,根据id,检验左右栏杆
     int left_id=terminal_id;
@@ -148,7 +196,7 @@ Error_manager Verify_result::verify(cv::RotatedRect rotate_rect,int terminal_id,
         Hardware_limit::Railing railing_left_parameter=m_hardware_parameter.railing_parameter(left_id);
         Railing* tp_left_railing=new Railing(railing_left_parameter.pa(),railing_left_parameter.pb(),railing_left_parameter.pc(),
                                              railing_left_parameter.railing_width());
-        Hardware_limit::Railing railing_right_parameter=m_hardware_parameter.railing_parameter(left_id);
+        Hardware_limit::Railing railing_right_parameter=m_hardware_parameter.railing_parameter(right_id);
         Railing* tp_right_railing=new Railing(railing_right_parameter.pa(),railing_right_parameter.pb(),railing_right_parameter.pc(),
                                               railing_right_parameter.railing_width());
 

+ 3 - 2
wj_lidar/fence_controller.cpp

@@ -64,7 +64,8 @@ Error_manager Fence_controller::initialize(wj::wjManagerParams params)
     }
     else
     {
-        LOG(ERROR) << "create plc data handler error";
+//        LOG(ERROR) << "create plc data handler error";
+        return Error_manager(Error_code::WJ_MANAGER_UNINITIALIZED,NORMAL,"万集plc连接失败");
     }
 
     // init lidar instances
@@ -75,7 +76,7 @@ Error_manager Fence_controller::initialize(wj::wjManagerParams params)
         // 错误码信息已在内部打印
         if (code != SUCCESS)
         {
-            LOG(WARNING) << "No " << i << " wj lidar failed to initialize";
+            return Error_manager(Error_code::WJ_MANAGER_UNINITIALIZED,NORMAL,"万集雷达连接失败");
         }
     }
     // init region_detector instances

+ 30 - 58
wj_lidar/plc_data.cpp

@@ -4,7 +4,8 @@
 
 #include "plc_data.h"
 #include <string.h>
-
+#include "wj_lidar_msg.pb.h"
+#include "../tool/MeasureTopicPublisher.h"
 Plc_data *Plc_data::g_ins = 0;
 std::mutex Plc_data::g_lock;
 
@@ -73,17 +74,14 @@ Plc_data *Plc_data::get_instance(std::string ip)
 /**
  * 更新区域状态
  * */
-void Plc_data::update_data(int state_code, int id)
+void Plc_data::update_data(int state_code, int border_status, int id)
 {
 //     LOG(INFO) << "plc data 更新数据 id: "<<id<<", code: "<<state_code;
-    const int length = 1;
-    int offset = id * length;
-    short data = 0;
-    data = (short)state_code;
+    if(id<0 || id>=MAX_REGIONS)
+        return ;
     std::lock_guard<std::mutex> lock(g_lock);
-    ////判断越界, 更新数据
-    if (offset >= 0 && offset + length <= MAX_REGIONS)
-        memcpy(m_data + offset, &data, length * sizeof(short));
+    m_data[2 * id] = state_code;
+    m_data[2 * id + 1] = border_status;
 }
 
 /**
@@ -98,60 +96,34 @@ void Plc_data::plc_update_thread(Plc_data *p)
     }
     while (!p->m_cond_exit.WaitFor(1))
     {
-        // LOG(INFO) << "------- trying to update plc info ";
-        if (p == 0)
-        {
-            LOG(ERROR) << "plc update thread null pointer";
-            return;
-        }
-        // std::lock_guard<std::mutex> lock(g_lock);
-        g_lock.lock();
-        // 显示雷达结果
-        std::cout << "result: [";
-        for (int i = 0; i < MAX_REGIONS; ++i)
-        {
-            std::cout << p->m_data[i] << " ";
-        }
-        std::cout << "]" << std::endl;
-        g_lock.unlock();
 
         // 判断plc状态
         if (p->m_plc.getConnection() && p->mb_is_ready)
         {
-            // 读取门状态
-            g_lock.lock();
-            p->mb_is_ready = p->mb_is_ready && p->m_plc.ReadShorts(CENTRAL_CONTROLLER_DB_NUM, DOOR_STATUS_OFFSET, ELE_FENCE_COUNT, p->m_door_status);
-            g_lock.unlock();
-
             // 写入电子围栏状态
-            if (p->mb_is_ready)
+            wj_lidar_message::Fence_statu_message fence_message;
+
+            for (int i = 0; i < ELE_FENCE_COUNT; ++i)
             {
-                short temp = 0;
-                for (int i = 0; i < ELE_FENCE_COUNT; ++i)
-                {
-                    g_lock.lock();
-                    temp = *(p->m_data + i);
-                    //                temp =HTON(temp);
-                    //printf("%d ---->%d\n",*(p->m_data+i), temp);
-                    // 门处于开启状态,判断车辆状态,聚类数量错误则不提示
-                    if (p->m_door_status[i] == 1)
-                    {
-                        p->mb_is_ready = p->mb_is_ready && p->m_plc.WriteShorts(ELE_FENCE_DB_NUM, ELE_FENCE_BOUNDARY_START_ADDR + i * ELE_FENCE_OFFSET, 1, &temp);
-                    }
-                    // 门处于关闭状态,异物入侵判断模式,只要存在识别错误情况就输入1,否则0
-                    else
-                    {
-                        // plc是否安全位,0表示不安全,1表示安全
-                        if(temp != 1 && temp != 0)
-                            temp = 0;
-                        else
-                            temp = 1;
-                        p->mb_is_ready = p->mb_is_ready && p->m_plc.WriteShorts(ELE_FENCE_DB_NUM, ELE_FENCE_SAFE_START_ADDR + i * ELE_FENCE_OFFSET, 1, &temp);
-                    }
-                    g_lock.unlock();
-                    usleep(50 * 1000);
-                }
+
+                g_lock.lock();
+                p->mb_is_ready = p->m_plc.WriteShorts(ELE_FENCE_DB_NUM,
+                                                      ELE_FENCE_BOUNDARY_START_ADDR + i * ELE_FENCE_OFFSET,
+                                                      2,
+                                                      p->m_data + (i * 2));
+                memcpy(p->m_last_data + (i * 2), p->m_data + (i * 2), 2 * sizeof(short));
+                ///post 消息
+                fence_message.add_fence_statu();
+                int index=fence_message.fence_statu_size()-1;
+                fence_message.mutable_fence_statu(index)->set_terminal_id(i);
+                fence_message.mutable_fence_statu(index)->set_cloud_statu(p->m_data[i * 2]);
+                fence_message.mutable_fence_statu(index)->set_position_statu(p->m_data[i * 2+1]);
+
+                g_lock.unlock();
+                usleep(10 * 1000);
             }
+            MeasureTopicPublisher::GetInstance()->Publish(fence_message.SerializeAsString());
+
         }
         else
         {
@@ -188,8 +160,8 @@ Plc_data::Plc_data(std::string ip) : mp_update_thread(0),
                                      mb_is_ready(0)
 {
     m_ip_str = ip;
-    memset(m_data, 0, MAX_REGIONS * sizeof(short));
-    memset(m_door_status, 0, MAX_REGIONS * sizeof(short));
+    memset(m_data, 0, MAX_REGIONS*2 * sizeof(short));
+    memset(m_last_data, 0, MAX_REGIONS*2 * sizeof(short));
     // p_plc = new S7PLC();
     if (m_ip_str != "")
     {

+ 4 - 6
wj_lidar/plc_data.h

@@ -16,8 +16,7 @@
 #include "glog/logging.h"
 
 #define MAX_REGIONS 6
-#define ELE_FENCE_SAFE_START_ADDR 3
-#define ELE_FENCE_BOUNDARY_START_ADDR 4
+#define ELE_FENCE_BOUNDARY_START_ADDR 3
 #define ELE_FENCE_DB_NUM 95
 #define ELE_FENCE_OFFSET 7
 #define ELE_FENCE_COUNT 6
@@ -25,7 +24,6 @@
 #define CENTRAL_CONTROLLER_DB_NUM 41
 #define DOOR_STATUS_OFFSET 18
 
-#define HTON(T) ((T) << 8) | ((T) >> 8)
 
 class Plc_data
 {
@@ -34,7 +32,7 @@ public:
     static Plc_data *get_instance(std::string ip = "");
     // static void Release();
     // 更新区域状态数据
-    void update_data(int state_code, int id);
+    void update_data(int state_code, int border_status, int id);
     // plc更新线程
     static void plc_update_thread(Plc_data *p);
     // 获取plc实时状态
@@ -69,8 +67,8 @@ private:
     // static CGarbo Garbo;	//--->1
 
 protected:
-    short m_data[MAX_REGIONS];
-    short m_door_status[ELE_FENCE_COUNT];
+    short m_data[MAX_REGIONS*2];
+    short m_last_data[MAX_REGIONS*2];
     std::string m_ip_str;
 };
 

+ 15 - 3
wj_lidar/region_detect.cpp

@@ -236,6 +236,10 @@ Error_manager Region_detector::isRect(std::vector<cv::Point2f> &points, bool pri
     }
 }
 
+
+
+
+
 /**
  * 聚类并通过矩形判断函数
  * 传入原始点云,传出角点与聚类出的点云
@@ -307,13 +311,16 @@ Error_manager Region_detector::clustering(pcl::PointCloud<pcl::PointXYZ>::Ptr cl
 
         float center_x = sumX / float(seg_clouds[i]->size());
         float center_y = sumY / float(seg_clouds[i]->size());
-        corner_points.push_back(cv::Point2f(center_x*1000.0, center_y*1000.0));
+        corner_points.push_back(cv::Point2f(center_x, center_y));
     }
-    char buf[255]={0};
+    /*char buf[255]={0};
     for (int k = 0; k < corner_points.size(); ++k) {
         sprintf(buf+strlen(buf), "point %d: (%.2f, %.2f)__", k, corner_points[k].x, corner_points[k].y);
     }
-    LOG(WARNING) << buf;
+    LOG(WARNING) << buf;*/
+
+    cv::RotatedRect t_rect=cv::minAreaRect(corner_points);
+    //display(t_rect,cv::Scalar(255,0,0));
     return isRect(corner_points, print);
 }
 /**
@@ -336,6 +343,9 @@ Error_manager Region_detector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_
     return result;
 }
 
+
+
+
 /**
  * 输出中心点、角度、轮距与宽度的四轮点云检测函数
  * */
@@ -376,6 +386,8 @@ Error_manager Region_detector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud
     // add center point to the input cloud for further check
     cloud_in->points.push_back(pcl::PointXYZ(x, y, 0.0));
 
+
+
     // 长边向量
     cv::Point2f vec;
     cv::Point2f vertice[4];

+ 52 - 21
wj_lidar/region_worker.cpp

@@ -99,6 +99,8 @@ void Region_worker::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in)
     mb_cloud_updated = true;
 }
 
+
+
 /**
  * 实时检测与更新线程函数
  * */
@@ -117,13 +119,14 @@ void Region_worker::detect_loop(Region_worker *worker)
         if (worker->mb_cloud_updated)
         {
             std::lock_guard<std::mutex> lck(worker->m_mutex);
-            int code = REGION_WORKER_VERIFY_OK;
+            int code = REGION_WORKER_RESULT_DEFAULT;
+            int border_status = REGION_WORKER_RESULT_DEFAULT;
             worker->mb_cloud_updated = false;
             double x,y,angle,wheelbase,width;
-            Error_manager result = worker->m_detector->detect(worker->m_cloud, x, y, angle, wheelbase, width, true);
+            Error_manager result = worker->m_detector->detect(worker->m_cloud, x, y, angle, wheelbase, width, false);
+
             if(worker->mp_verify_handle == nullptr)
             {
-                code = REGION_WORKER_NULL_POINTER;
                 LOG(WARNING) << "verify handle null pointer";
                 continue;
             }
@@ -135,31 +138,26 @@ void Region_worker::detect_loop(Region_worker *worker)
             else if (result == SUCCESS)
             {
                 cv::RotatedRect car_border;
-                car_border.center = cv::Point2f(1000.0*x,1000.0*y);
-                car_border.angle = angle;
-                const int default_car_width = 2650;
-                const int ext_length = 700;
-                car_border.size.width = default_car_width;
-                car_border.size.height = wheelbase+ext_length*2;
+                float ext_length=720;
+                float new_length=wheelbase*1000.0+2.0*ext_length;
+                float new_width=2650;
+                car_border=create_rotate_rect(new_length,new_width,angle,1000.0*x,1000.0*y);
+
                 int verify_return_code = 0;
                 int terminal_id=worker->get_id();
                 Error_manager verify_error_code = worker->mp_verify_handle->verify(car_border, terminal_id, verify_return_code);
 //                Error_manager verify_error_code = SUCCESS;
                 if(verify_error_code == SUCCESS) {
-                    code = REGION_WORKER_VERIFY_OK;
-                    LOG(INFO) << "region worker verify ok";
+                    code = REGION_WORKER_HAS_CAR;
                 }else{
-                    code |= verify_return_code;
-                    LOG(WARNING) << "region worker verify result: " << code;
+                    code = REGION_WORKER_HAS_CAR;
+                    border_status = verify_return_code;
+                    //LOG(WARNING) << "region worker verify result: " << code;
                 }
             }
-            else if (result == WJ_REGION_CLUSTER_SIZE_ERROR)
-            {
-                code = REGION_WORKER_CLUSTER_SIZE_ERROR;
-            }
             else
             {
-                code = REGION_WORKER_OTHER_ERROR;
+                code = REGION_WORKER_DETECT_ERROR;
             }
             // LOG(INFO) << "worker detect loop 000";
             // 判断与上次读取是否相同,并计数
@@ -170,9 +168,9 @@ void Region_worker::detect_loop(Region_worker *worker)
             worker->m_last_read_code = code;
             worker->m_read_code_count += 1;
 
-            if(worker->get_id() == 4) {
+            /*if(worker->get_id() == 3) {
                 LOG(WARNING) << "worker id: " << worker->get_id()<<" code: "<<code;
-            }
+            }*/
             // 写入plc,加入写入频率限制
             int duration = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::steady_clock::now() - worker->m_update_plc_time).count();
             Plc_data *p = Plc_data::get_instance();
@@ -180,9 +178,42 @@ void Region_worker::detect_loop(Region_worker *worker)
             if (p!=0 && duration > 500 && worker->m_last_sent_code != worker->m_last_read_code && worker->m_read_code_count > 3)
             {
                 worker->m_last_sent_code = worker->m_last_read_code;
-                p->update_data(code, worker->m_detector->get_region_id());
+                p->update_data(code, border_status, worker->m_detector->get_region_id());
                 worker->m_update_plc_time = std::chrono::steady_clock::now();
             }
         }
     }
+}
+
+
+
+cv::RotatedRect Region_worker::create_rotate_rect(float length,float width,float angle,float cx,float cy)
+{
+    const double C_PI=3.14159265;
+    float theta=C_PI*(angle/180.0);
+    float a00=cos(theta);
+    float a01=-sin(theta);
+    float a10=sin(theta);
+    float a11=cos(theta);
+    cv::Point2f point[4];
+    point[0].x=-length/2.0;
+    point[0].y=-width/2.0;
+
+    point[1].x=-length/2.0;
+    point[1].y=width/2.0;
+
+    point[2].x=length/2.0;
+    point[2].y=-width/2.0;
+
+    point[3].x=length/2.0;
+    point[3].y=width/2.0;
+
+    std::vector<cv::Point2f> point_vec;
+    for(int i=0;i<4;++i)
+    {
+        float x=point[i].x*a00+point[i].y*a01+cx;
+        float y=point[i].x*a10+point[i].y*a11+cy;
+        point_vec.push_back(cv::Point2f(x,y));
+    }
+    return cv::minAreaRect(point_vec);
 }

+ 11 - 6
wj_lidar/region_worker.h

@@ -21,11 +21,15 @@
 class Region_worker
 {
 public:
-#define REGION_WORKER_VERIFY_OK 0x0000
-#define REGION_WORKER_EMPTY_SPACE 0x0010
-#define REGION_WORKER_CLUSTER_SIZE_ERROR 0x0020
-#define REGION_WORKER_OTHER_ERROR 0x0040
-#define REGION_WORKER_NULL_POINTER 0x0080
+#define REGION_WORKER_RESULT_DEFAULT 0x0000
+//#define REGION_WORKER_VERIFY_OK 0x0001
+//#define REGION_WORKER_EMPTY_SPACE 0x0020
+//#define REGION_WORKER_CLUSTER_SIZE_ERROR 0x0040
+//#define REGION_WORKER_OTHER_ERROR 0x0080
+//#define REGION_WORKER_NULL_POINTER 0x0100
+#define REGION_WORKER_EMPTY_SPACE 1
+#define REGION_WORKER_HAS_CAR 2
+#define REGION_WORKER_DETECT_ERROR 3
 public:
     // 有参构造
     Region_worker(int id, wj::Region region, Verify_result* verify_handle);
@@ -39,7 +43,8 @@ public:
     int get_id();
     // 获得中心点、角度等测量数据
     Error_manager get_wheel_result(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_in, double &x, double &y, double &c, double &wheelbase, double &width);
-
+private:
+    static cv::RotatedRect create_rotate_rect(float length,float width,float angle,float x,float y);
 private:
     Region_detector *m_detector;                             // 区域检测算法实例
     pcl::PointCloud<pcl::PointXYZ>::Ptr m_cloud;             // 自动区域检测用点云

+ 760 - 0
wj_lidar/wj_lidar_msg.pb.cc

@@ -0,0 +1,760 @@
+// Generated by the protocol buffer compiler.  DO NOT EDIT!
+// source: wj_lidar_msg.proto
+
+#include "wj_lidar_msg.pb.h"
+
+#include <algorithm>
+
+#include <google/protobuf/stubs/common.h>
+#include <google/protobuf/stubs/port.h>
+#include <google/protobuf/stubs/once.h>
+#include <google/protobuf/io/coded_stream.h>
+#include <google/protobuf/wire_format_lite_inl.h>
+#include <google/protobuf/descriptor.h>
+#include <google/protobuf/generated_message_reflection.h>
+#include <google/protobuf/reflection_ops.h>
+#include <google/protobuf/wire_format.h>
+// This is a temporary google only hack
+#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS
+#include "third_party/protobuf/version.h"
+#endif
+// @@protoc_insertion_point(includes)
+namespace wj_lidar_message {
+class Terminal_fence_statuDefaultTypeInternal {
+ public:
+  ::google::protobuf::internal::ExplicitlyConstructed<Terminal_fence_statu>
+      _instance;
+} _Terminal_fence_statu_default_instance_;
+class Fence_statu_messageDefaultTypeInternal {
+ public:
+  ::google::protobuf::internal::ExplicitlyConstructed<Fence_statu_message>
+      _instance;
+} _Fence_statu_message_default_instance_;
+}  // namespace wj_lidar_message
+namespace protobuf_wj_5flidar_5fmsg_2eproto {
+void InitDefaultsTerminal_fence_statuImpl() {
+  GOOGLE_PROTOBUF_VERIFY_VERSION;
+
+#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS
+  ::google::protobuf::internal::InitProtobufDefaultsForceUnique();
+#else
+  ::google::protobuf::internal::InitProtobufDefaults();
+#endif  // GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS
+  {
+    void* ptr = &::wj_lidar_message::_Terminal_fence_statu_default_instance_;
+    new (ptr) ::wj_lidar_message::Terminal_fence_statu();
+    ::google::protobuf::internal::OnShutdownDestroyMessage(ptr);
+  }
+  ::wj_lidar_message::Terminal_fence_statu::InitAsDefaultInstance();
+}
+
+void InitDefaultsTerminal_fence_statu() {
+  static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+  ::google::protobuf::GoogleOnceInit(&once, &InitDefaultsTerminal_fence_statuImpl);
+}
+
+void InitDefaultsFence_statu_messageImpl() {
+  GOOGLE_PROTOBUF_VERIFY_VERSION;
+
+#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS
+  ::google::protobuf::internal::InitProtobufDefaultsForceUnique();
+#else
+  ::google::protobuf::internal::InitProtobufDefaults();
+#endif  // GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS
+  protobuf_wj_5flidar_5fmsg_2eproto::InitDefaultsTerminal_fence_statu();
+  {
+    void* ptr = &::wj_lidar_message::_Fence_statu_message_default_instance_;
+    new (ptr) ::wj_lidar_message::Fence_statu_message();
+    ::google::protobuf::internal::OnShutdownDestroyMessage(ptr);
+  }
+  ::wj_lidar_message::Fence_statu_message::InitAsDefaultInstance();
+}
+
+void InitDefaultsFence_statu_message() {
+  static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+  ::google::protobuf::GoogleOnceInit(&once, &InitDefaultsFence_statu_messageImpl);
+}
+
+::google::protobuf::Metadata file_level_metadata[2];
+
+const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = {
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Terminal_fence_statu, _has_bits_),
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Terminal_fence_statu, _internal_metadata_),
+  ~0u,  // no _extensions_
+  ~0u,  // no _oneof_case_
+  ~0u,  // no _weak_field_map_
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Terminal_fence_statu, terminal_id_),
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Terminal_fence_statu, cloud_statu_),
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Terminal_fence_statu, position_statu_),
+  0,
+  1,
+  2,
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Fence_statu_message, _has_bits_),
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Fence_statu_message, _internal_metadata_),
+  ~0u,  // no _extensions_
+  ~0u,  // no _oneof_case_
+  ~0u,  // no _weak_field_map_
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj_lidar_message::Fence_statu_message, fence_statu_),
+  ~0u,
+};
+static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = {
+  { 0, 8, sizeof(::wj_lidar_message::Terminal_fence_statu)},
+  { 11, 17, sizeof(::wj_lidar_message::Fence_statu_message)},
+};
+
+static ::google::protobuf::Message const * const file_default_instances[] = {
+  reinterpret_cast<const ::google::protobuf::Message*>(&::wj_lidar_message::_Terminal_fence_statu_default_instance_),
+  reinterpret_cast<const ::google::protobuf::Message*>(&::wj_lidar_message::_Fence_statu_message_default_instance_),
+};
+
+void protobuf_AssignDescriptors() {
+  AddDescriptors();
+  ::google::protobuf::MessageFactory* factory = NULL;
+  AssignDescriptors(
+      "wj_lidar_msg.proto", schemas, file_default_instances, TableStruct::offsets, factory,
+      file_level_metadata, NULL, NULL);
+}
+
+void protobuf_AssignDescriptorsOnce() {
+  static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+  ::google::protobuf::GoogleOnceInit(&once, &protobuf_AssignDescriptors);
+}
+
+void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD;
+void protobuf_RegisterTypes(const ::std::string&) {
+  protobuf_AssignDescriptorsOnce();
+  ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2);
+}
+
+void AddDescriptorsImpl() {
+  InitDefaults();
+  static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = {
+      "\n\022wj_lidar_msg.proto\022\020wj_lidar_message\"X"
+      "\n\024Terminal_fence_statu\022\023\n\013terminal_id\030\001 "
+      "\002(\003\022\023\n\013cloud_statu\030\002 \002(\003\022\026\n\016position_sta"
+      "tu\030\003 \002(\003\"R\n\023Fence_statu_message\022;\n\013fence"
+      "_statu\030\001 \003(\0132&.wj_lidar_message.Terminal"
+      "_fence_statu"
+  };
+  ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
+      descriptor, 212);
+  ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
+    "wj_lidar_msg.proto", &protobuf_RegisterTypes);
+}
+
+void AddDescriptors() {
+  static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+  ::google::protobuf::GoogleOnceInit(&once, &AddDescriptorsImpl);
+}
+// Force AddDescriptors() to be called at dynamic initialization time.
+struct StaticDescriptorInitializer {
+  StaticDescriptorInitializer() {
+    AddDescriptors();
+  }
+} static_descriptor_initializer;
+}  // namespace protobuf_wj_5flidar_5fmsg_2eproto
+namespace wj_lidar_message {
+
+// ===================================================================
+
+void Terminal_fence_statu::InitAsDefaultInstance() {
+}
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
+const int Terminal_fence_statu::kTerminalIdFieldNumber;
+const int Terminal_fence_statu::kCloudStatuFieldNumber;
+const int Terminal_fence_statu::kPositionStatuFieldNumber;
+#endif  // !defined(_MSC_VER) || _MSC_VER >= 1900
+
+Terminal_fence_statu::Terminal_fence_statu()
+  : ::google::protobuf::Message(), _internal_metadata_(NULL) {
+  if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) {
+    ::protobuf_wj_5flidar_5fmsg_2eproto::InitDefaultsTerminal_fence_statu();
+  }
+  SharedCtor();
+  // @@protoc_insertion_point(constructor:wj_lidar_message.Terminal_fence_statu)
+}
+Terminal_fence_statu::Terminal_fence_statu(const Terminal_fence_statu& from)
+  : ::google::protobuf::Message(),
+      _internal_metadata_(NULL),
+      _has_bits_(from._has_bits_),
+      _cached_size_(0) {
+  _internal_metadata_.MergeFrom(from._internal_metadata_);
+  ::memcpy(&terminal_id_, &from.terminal_id_,
+    static_cast<size_t>(reinterpret_cast<char*>(&position_statu_) -
+    reinterpret_cast<char*>(&terminal_id_)) + sizeof(position_statu_));
+  // @@protoc_insertion_point(copy_constructor:wj_lidar_message.Terminal_fence_statu)
+}
+
+void Terminal_fence_statu::SharedCtor() {
+  _cached_size_ = 0;
+  ::memset(&terminal_id_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&position_statu_) -
+      reinterpret_cast<char*>(&terminal_id_)) + sizeof(position_statu_));
+}
+
+Terminal_fence_statu::~Terminal_fence_statu() {
+  // @@protoc_insertion_point(destructor:wj_lidar_message.Terminal_fence_statu)
+  SharedDtor();
+}
+
+void Terminal_fence_statu::SharedDtor() {
+}
+
+void Terminal_fence_statu::SetCachedSize(int size) const {
+  GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+  _cached_size_ = size;
+  GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* Terminal_fence_statu::descriptor() {
+  ::protobuf_wj_5flidar_5fmsg_2eproto::protobuf_AssignDescriptorsOnce();
+  return ::protobuf_wj_5flidar_5fmsg_2eproto::file_level_metadata[kIndexInFileMessages].descriptor;
+}
+
+const Terminal_fence_statu& Terminal_fence_statu::default_instance() {
+  ::protobuf_wj_5flidar_5fmsg_2eproto::InitDefaultsTerminal_fence_statu();
+  return *internal_default_instance();
+}
+
+Terminal_fence_statu* Terminal_fence_statu::New(::google::protobuf::Arena* arena) const {
+  Terminal_fence_statu* n = new Terminal_fence_statu;
+  if (arena != NULL) {
+    arena->Own(n);
+  }
+  return n;
+}
+
+void Terminal_fence_statu::Clear() {
+// @@protoc_insertion_point(message_clear_start:wj_lidar_message.Terminal_fence_statu)
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  cached_has_bits = _has_bits_[0];
+  if (cached_has_bits & 7u) {
+    ::memset(&terminal_id_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&position_statu_) -
+        reinterpret_cast<char*>(&terminal_id_)) + sizeof(position_statu_));
+  }
+  _has_bits_.Clear();
+  _internal_metadata_.Clear();
+}
+
+bool Terminal_fence_statu::MergePartialFromCodedStream(
+    ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure
+  ::google::protobuf::uint32 tag;
+  // @@protoc_insertion_point(parse_start:wj_lidar_message.Terminal_fence_statu)
+  for (;;) {
+    ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u);
+    tag = p.first;
+    if (!p.second) goto handle_unusual;
+    switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+      // required int64 terminal_id = 1;
+      case 1: {
+        if (static_cast< ::google::protobuf::uint8>(tag) ==
+            static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) {
+          set_has_terminal_id();
+          DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+                   ::google::protobuf::int64, ::google::protobuf::internal::WireFormatLite::TYPE_INT64>(
+                 input, &terminal_id_)));
+        } else {
+          goto handle_unusual;
+        }
+        break;
+      }
+
+      // required int64 cloud_statu = 2;
+      case 2: {
+        if (static_cast< ::google::protobuf::uint8>(tag) ==
+            static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) {
+          set_has_cloud_statu();
+          DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+                   ::google::protobuf::int64, ::google::protobuf::internal::WireFormatLite::TYPE_INT64>(
+                 input, &cloud_statu_)));
+        } else {
+          goto handle_unusual;
+        }
+        break;
+      }
+
+      // required int64 position_statu = 3;
+      case 3: {
+        if (static_cast< ::google::protobuf::uint8>(tag) ==
+            static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) {
+          set_has_position_statu();
+          DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+                   ::google::protobuf::int64, ::google::protobuf::internal::WireFormatLite::TYPE_INT64>(
+                 input, &position_statu_)));
+        } else {
+          goto handle_unusual;
+        }
+        break;
+      }
+
+      default: {
+      handle_unusual:
+        if (tag == 0) {
+          goto success;
+        }
+        DO_(::google::protobuf::internal::WireFormat::SkipField(
+              input, tag, _internal_metadata_.mutable_unknown_fields()));
+        break;
+      }
+    }
+  }
+success:
+  // @@protoc_insertion_point(parse_success:wj_lidar_message.Terminal_fence_statu)
+  return true;
+failure:
+  // @@protoc_insertion_point(parse_failure:wj_lidar_message.Terminal_fence_statu)
+  return false;
+#undef DO_
+}
+
+void Terminal_fence_statu::SerializeWithCachedSizes(
+    ::google::protobuf::io::CodedOutputStream* output) const {
+  // @@protoc_insertion_point(serialize_start:wj_lidar_message.Terminal_fence_statu)
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  cached_has_bits = _has_bits_[0];
+  // required int64 terminal_id = 1;
+  if (cached_has_bits & 0x00000001u) {
+    ::google::protobuf::internal::WireFormatLite::WriteInt64(1, this->terminal_id(), output);
+  }
+
+  // required int64 cloud_statu = 2;
+  if (cached_has_bits & 0x00000002u) {
+    ::google::protobuf::internal::WireFormatLite::WriteInt64(2, this->cloud_statu(), output);
+  }
+
+  // required int64 position_statu = 3;
+  if (cached_has_bits & 0x00000004u) {
+    ::google::protobuf::internal::WireFormatLite::WriteInt64(3, this->position_statu(), output);
+  }
+
+  if (_internal_metadata_.have_unknown_fields()) {
+    ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+        _internal_metadata_.unknown_fields(), output);
+  }
+  // @@protoc_insertion_point(serialize_end:wj_lidar_message.Terminal_fence_statu)
+}
+
+::google::protobuf::uint8* Terminal_fence_statu::InternalSerializeWithCachedSizesToArray(
+    bool deterministic, ::google::protobuf::uint8* target) const {
+  (void)deterministic; // Unused
+  // @@protoc_insertion_point(serialize_to_array_start:wj_lidar_message.Terminal_fence_statu)
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  cached_has_bits = _has_bits_[0];
+  // required int64 terminal_id = 1;
+  if (cached_has_bits & 0x00000001u) {
+    target = ::google::protobuf::internal::WireFormatLite::WriteInt64ToArray(1, this->terminal_id(), target);
+  }
+
+  // required int64 cloud_statu = 2;
+  if (cached_has_bits & 0x00000002u) {
+    target = ::google::protobuf::internal::WireFormatLite::WriteInt64ToArray(2, this->cloud_statu(), target);
+  }
+
+  // required int64 position_statu = 3;
+  if (cached_has_bits & 0x00000004u) {
+    target = ::google::protobuf::internal::WireFormatLite::WriteInt64ToArray(3, this->position_statu(), target);
+  }
+
+  if (_internal_metadata_.have_unknown_fields()) {
+    target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+        _internal_metadata_.unknown_fields(), target);
+  }
+  // @@protoc_insertion_point(serialize_to_array_end:wj_lidar_message.Terminal_fence_statu)
+  return target;
+}
+
+size_t Terminal_fence_statu::RequiredFieldsByteSizeFallback() const {
+// @@protoc_insertion_point(required_fields_byte_size_fallback_start:wj_lidar_message.Terminal_fence_statu)
+  size_t total_size = 0;
+
+  if (has_terminal_id()) {
+    // required int64 terminal_id = 1;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::Int64Size(
+        this->terminal_id());
+  }
+
+  if (has_cloud_statu()) {
+    // required int64 cloud_statu = 2;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::Int64Size(
+        this->cloud_statu());
+  }
+
+  if (has_position_statu()) {
+    // required int64 position_statu = 3;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::Int64Size(
+        this->position_statu());
+  }
+
+  return total_size;
+}
+size_t Terminal_fence_statu::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:wj_lidar_message.Terminal_fence_statu)
+  size_t total_size = 0;
+
+  if (_internal_metadata_.have_unknown_fields()) {
+    total_size +=
+      ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+        _internal_metadata_.unknown_fields());
+  }
+  if (((_has_bits_[0] & 0x00000007) ^ 0x00000007) == 0) {  // All required fields are present.
+    // required int64 terminal_id = 1;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::Int64Size(
+        this->terminal_id());
+
+    // required int64 cloud_statu = 2;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::Int64Size(
+        this->cloud_statu());
+
+    // required int64 position_statu = 3;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::Int64Size(
+        this->position_statu());
+
+  } else {
+    total_size += RequiredFieldsByteSizeFallback();
+  }
+  int cached_size = ::google::protobuf::internal::ToCachedSize(total_size);
+  GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+  _cached_size_ = cached_size;
+  GOOGLE_SAFE_CONCURRENT_WRITES_END();
+  return total_size;
+}
+
+void Terminal_fence_statu::MergeFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_merge_from_start:wj_lidar_message.Terminal_fence_statu)
+  GOOGLE_DCHECK_NE(&from, this);
+  const Terminal_fence_statu* source =
+      ::google::protobuf::internal::DynamicCastToGenerated<const Terminal_fence_statu>(
+          &from);
+  if (source == NULL) {
+  // @@protoc_insertion_point(generalized_merge_from_cast_fail:wj_lidar_message.Terminal_fence_statu)
+    ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+  } else {
+  // @@protoc_insertion_point(generalized_merge_from_cast_success:wj_lidar_message.Terminal_fence_statu)
+    MergeFrom(*source);
+  }
+}
+
+void Terminal_fence_statu::MergeFrom(const Terminal_fence_statu& from) {
+// @@protoc_insertion_point(class_specific_merge_from_start:wj_lidar_message.Terminal_fence_statu)
+  GOOGLE_DCHECK_NE(&from, this);
+  _internal_metadata_.MergeFrom(from._internal_metadata_);
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  cached_has_bits = from._has_bits_[0];
+  if (cached_has_bits & 7u) {
+    if (cached_has_bits & 0x00000001u) {
+      terminal_id_ = from.terminal_id_;
+    }
+    if (cached_has_bits & 0x00000002u) {
+      cloud_statu_ = from.cloud_statu_;
+    }
+    if (cached_has_bits & 0x00000004u) {
+      position_statu_ = from.position_statu_;
+    }
+    _has_bits_[0] |= cached_has_bits;
+  }
+}
+
+void Terminal_fence_statu::CopyFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:wj_lidar_message.Terminal_fence_statu)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+void Terminal_fence_statu::CopyFrom(const Terminal_fence_statu& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:wj_lidar_message.Terminal_fence_statu)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+bool Terminal_fence_statu::IsInitialized() const {
+  if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false;
+  return true;
+}
+
+void Terminal_fence_statu::Swap(Terminal_fence_statu* other) {
+  if (other == this) return;
+  InternalSwap(other);
+}
+void Terminal_fence_statu::InternalSwap(Terminal_fence_statu* other) {
+  using std::swap;
+  swap(terminal_id_, other->terminal_id_);
+  swap(cloud_statu_, other->cloud_statu_);
+  swap(position_statu_, other->position_statu_);
+  swap(_has_bits_[0], other->_has_bits_[0]);
+  _internal_metadata_.Swap(&other->_internal_metadata_);
+  swap(_cached_size_, other->_cached_size_);
+}
+
+::google::protobuf::Metadata Terminal_fence_statu::GetMetadata() const {
+  protobuf_wj_5flidar_5fmsg_2eproto::protobuf_AssignDescriptorsOnce();
+  return ::protobuf_wj_5flidar_5fmsg_2eproto::file_level_metadata[kIndexInFileMessages];
+}
+
+
+// ===================================================================
+
+void Fence_statu_message::InitAsDefaultInstance() {
+}
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
+const int Fence_statu_message::kFenceStatuFieldNumber;
+#endif  // !defined(_MSC_VER) || _MSC_VER >= 1900
+
+Fence_statu_message::Fence_statu_message()
+  : ::google::protobuf::Message(), _internal_metadata_(NULL) {
+  if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) {
+    ::protobuf_wj_5flidar_5fmsg_2eproto::InitDefaultsFence_statu_message();
+  }
+  SharedCtor();
+  // @@protoc_insertion_point(constructor:wj_lidar_message.Fence_statu_message)
+}
+Fence_statu_message::Fence_statu_message(const Fence_statu_message& from)
+  : ::google::protobuf::Message(),
+      _internal_metadata_(NULL),
+      _has_bits_(from._has_bits_),
+      _cached_size_(0),
+      fence_statu_(from.fence_statu_) {
+  _internal_metadata_.MergeFrom(from._internal_metadata_);
+  // @@protoc_insertion_point(copy_constructor:wj_lidar_message.Fence_statu_message)
+}
+
+void Fence_statu_message::SharedCtor() {
+  _cached_size_ = 0;
+}
+
+Fence_statu_message::~Fence_statu_message() {
+  // @@protoc_insertion_point(destructor:wj_lidar_message.Fence_statu_message)
+  SharedDtor();
+}
+
+void Fence_statu_message::SharedDtor() {
+}
+
+void Fence_statu_message::SetCachedSize(int size) const {
+  GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+  _cached_size_ = size;
+  GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* Fence_statu_message::descriptor() {
+  ::protobuf_wj_5flidar_5fmsg_2eproto::protobuf_AssignDescriptorsOnce();
+  return ::protobuf_wj_5flidar_5fmsg_2eproto::file_level_metadata[kIndexInFileMessages].descriptor;
+}
+
+const Fence_statu_message& Fence_statu_message::default_instance() {
+  ::protobuf_wj_5flidar_5fmsg_2eproto::InitDefaultsFence_statu_message();
+  return *internal_default_instance();
+}
+
+Fence_statu_message* Fence_statu_message::New(::google::protobuf::Arena* arena) const {
+  Fence_statu_message* n = new Fence_statu_message;
+  if (arena != NULL) {
+    arena->Own(n);
+  }
+  return n;
+}
+
+void Fence_statu_message::Clear() {
+// @@protoc_insertion_point(message_clear_start:wj_lidar_message.Fence_statu_message)
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  fence_statu_.Clear();
+  _has_bits_.Clear();
+  _internal_metadata_.Clear();
+}
+
+bool Fence_statu_message::MergePartialFromCodedStream(
+    ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure
+  ::google::protobuf::uint32 tag;
+  // @@protoc_insertion_point(parse_start:wj_lidar_message.Fence_statu_message)
+  for (;;) {
+    ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u);
+    tag = p.first;
+    if (!p.second) goto handle_unusual;
+    switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+      // repeated .wj_lidar_message.Terminal_fence_statu fence_statu = 1;
+      case 1: {
+        if (static_cast< ::google::protobuf::uint8>(tag) ==
+            static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) {
+          DO_(::google::protobuf::internal::WireFormatLite::ReadMessage(input, add_fence_statu()));
+        } else {
+          goto handle_unusual;
+        }
+        break;
+      }
+
+      default: {
+      handle_unusual:
+        if (tag == 0) {
+          goto success;
+        }
+        DO_(::google::protobuf::internal::WireFormat::SkipField(
+              input, tag, _internal_metadata_.mutable_unknown_fields()));
+        break;
+      }
+    }
+  }
+success:
+  // @@protoc_insertion_point(parse_success:wj_lidar_message.Fence_statu_message)
+  return true;
+failure:
+  // @@protoc_insertion_point(parse_failure:wj_lidar_message.Fence_statu_message)
+  return false;
+#undef DO_
+}
+
+void Fence_statu_message::SerializeWithCachedSizes(
+    ::google::protobuf::io::CodedOutputStream* output) const {
+  // @@protoc_insertion_point(serialize_start:wj_lidar_message.Fence_statu_message)
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  // repeated .wj_lidar_message.Terminal_fence_statu fence_statu = 1;
+  for (unsigned int i = 0,
+      n = static_cast<unsigned int>(this->fence_statu_size()); i < n; i++) {
+    ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+      1, this->fence_statu(static_cast<int>(i)), output);
+  }
+
+  if (_internal_metadata_.have_unknown_fields()) {
+    ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+        _internal_metadata_.unknown_fields(), output);
+  }
+  // @@protoc_insertion_point(serialize_end:wj_lidar_message.Fence_statu_message)
+}
+
+::google::protobuf::uint8* Fence_statu_message::InternalSerializeWithCachedSizesToArray(
+    bool deterministic, ::google::protobuf::uint8* target) const {
+  (void)deterministic; // Unused
+  // @@protoc_insertion_point(serialize_to_array_start:wj_lidar_message.Fence_statu_message)
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  // repeated .wj_lidar_message.Terminal_fence_statu fence_statu = 1;
+  for (unsigned int i = 0,
+      n = static_cast<unsigned int>(this->fence_statu_size()); i < n; i++) {
+    target = ::google::protobuf::internal::WireFormatLite::
+      InternalWriteMessageToArray(
+        1, this->fence_statu(static_cast<int>(i)), deterministic, target);
+  }
+
+  if (_internal_metadata_.have_unknown_fields()) {
+    target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+        _internal_metadata_.unknown_fields(), target);
+  }
+  // @@protoc_insertion_point(serialize_to_array_end:wj_lidar_message.Fence_statu_message)
+  return target;
+}
+
+size_t Fence_statu_message::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:wj_lidar_message.Fence_statu_message)
+  size_t total_size = 0;
+
+  if (_internal_metadata_.have_unknown_fields()) {
+    total_size +=
+      ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+        _internal_metadata_.unknown_fields());
+  }
+  // repeated .wj_lidar_message.Terminal_fence_statu fence_statu = 1;
+  {
+    unsigned int count = static_cast<unsigned int>(this->fence_statu_size());
+    total_size += 1UL * count;
+    for (unsigned int i = 0; i < count; i++) {
+      total_size +=
+        ::google::protobuf::internal::WireFormatLite::MessageSize(
+          this->fence_statu(static_cast<int>(i)));
+    }
+  }
+
+  int cached_size = ::google::protobuf::internal::ToCachedSize(total_size);
+  GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+  _cached_size_ = cached_size;
+  GOOGLE_SAFE_CONCURRENT_WRITES_END();
+  return total_size;
+}
+
+void Fence_statu_message::MergeFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_merge_from_start:wj_lidar_message.Fence_statu_message)
+  GOOGLE_DCHECK_NE(&from, this);
+  const Fence_statu_message* source =
+      ::google::protobuf::internal::DynamicCastToGenerated<const Fence_statu_message>(
+          &from);
+  if (source == NULL) {
+  // @@protoc_insertion_point(generalized_merge_from_cast_fail:wj_lidar_message.Fence_statu_message)
+    ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+  } else {
+  // @@protoc_insertion_point(generalized_merge_from_cast_success:wj_lidar_message.Fence_statu_message)
+    MergeFrom(*source);
+  }
+}
+
+void Fence_statu_message::MergeFrom(const Fence_statu_message& from) {
+// @@protoc_insertion_point(class_specific_merge_from_start:wj_lidar_message.Fence_statu_message)
+  GOOGLE_DCHECK_NE(&from, this);
+  _internal_metadata_.MergeFrom(from._internal_metadata_);
+  ::google::protobuf::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  fence_statu_.MergeFrom(from.fence_statu_);
+}
+
+void Fence_statu_message::CopyFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:wj_lidar_message.Fence_statu_message)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+void Fence_statu_message::CopyFrom(const Fence_statu_message& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:wj_lidar_message.Fence_statu_message)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+bool Fence_statu_message::IsInitialized() const {
+  if (!::google::protobuf::internal::AllAreInitialized(this->fence_statu())) return false;
+  return true;
+}
+
+void Fence_statu_message::Swap(Fence_statu_message* other) {
+  if (other == this) return;
+  InternalSwap(other);
+}
+void Fence_statu_message::InternalSwap(Fence_statu_message* other) {
+  using std::swap;
+  fence_statu_.InternalSwap(&other->fence_statu_);
+  swap(_has_bits_[0], other->_has_bits_[0]);
+  _internal_metadata_.Swap(&other->_internal_metadata_);
+  swap(_cached_size_, other->_cached_size_);
+}
+
+::google::protobuf::Metadata Fence_statu_message::GetMetadata() const {
+  protobuf_wj_5flidar_5fmsg_2eproto::protobuf_AssignDescriptorsOnce();
+  return ::protobuf_wj_5flidar_5fmsg_2eproto::file_level_metadata[kIndexInFileMessages];
+}
+
+
+// @@protoc_insertion_point(namespace_scope)
+}  // namespace wj_lidar_message
+
+// @@protoc_insertion_point(global_scope)

+ 439 - 0
wj_lidar/wj_lidar_msg.pb.h

@@ -0,0 +1,439 @@
+// Generated by the protocol buffer compiler.  DO NOT EDIT!
+// source: wj_lidar_msg.proto
+
+#ifndef PROTOBUF_wj_5flidar_5fmsg_2eproto__INCLUDED
+#define PROTOBUF_wj_5flidar_5fmsg_2eproto__INCLUDED
+
+#include <string>
+
+#include <google/protobuf/stubs/common.h>
+
+#if GOOGLE_PROTOBUF_VERSION < 3005000
+#error This file was generated by a newer version of protoc which is
+#error incompatible with your Protocol Buffer headers.  Please update
+#error your headers.
+#endif
+#if 3005000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
+#error This file was generated by an older version of protoc which is
+#error incompatible with your Protocol Buffer headers.  Please
+#error regenerate this file with a newer version of protoc.
+#endif
+
+#include <google/protobuf/io/coded_stream.h>
+#include <google/protobuf/arena.h>
+#include <google/protobuf/arenastring.h>
+#include <google/protobuf/generated_message_table_driven.h>
+#include <google/protobuf/generated_message_util.h>
+#include <google/protobuf/metadata.h>
+#include <google/protobuf/message.h>
+#include <google/protobuf/repeated_field.h>  // IWYU pragma: export
+#include <google/protobuf/extension_set.h>  // IWYU pragma: export
+#include <google/protobuf/unknown_field_set.h>
+// @@protoc_insertion_point(includes)
+
+namespace protobuf_wj_5flidar_5fmsg_2eproto {
+// Internal implementation detail -- do not use these members.
+struct TableStruct {
+  static const ::google::protobuf::internal::ParseTableField entries[];
+  static const ::google::protobuf::internal::AuxillaryParseTableField aux[];
+  static const ::google::protobuf::internal::ParseTable schema[2];
+  static const ::google::protobuf::internal::FieldMetadata field_metadata[];
+  static const ::google::protobuf::internal::SerializationTable serialization_table[];
+  static const ::google::protobuf::uint32 offsets[];
+};
+void AddDescriptors();
+void InitDefaultsTerminal_fence_statuImpl();
+void InitDefaultsTerminal_fence_statu();
+void InitDefaultsFence_statu_messageImpl();
+void InitDefaultsFence_statu_message();
+inline void InitDefaults() {
+  InitDefaultsTerminal_fence_statu();
+  InitDefaultsFence_statu_message();
+}
+}  // namespace protobuf_wj_5flidar_5fmsg_2eproto
+namespace wj_lidar_message {
+class Fence_statu_message;
+class Fence_statu_messageDefaultTypeInternal;
+extern Fence_statu_messageDefaultTypeInternal _Fence_statu_message_default_instance_;
+class Terminal_fence_statu;
+class Terminal_fence_statuDefaultTypeInternal;
+extern Terminal_fence_statuDefaultTypeInternal _Terminal_fence_statu_default_instance_;
+}  // namespace wj_lidar_message
+namespace wj_lidar_message {
+
+// ===================================================================
+
+class Terminal_fence_statu : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:wj_lidar_message.Terminal_fence_statu) */ {
+ public:
+  Terminal_fence_statu();
+  virtual ~Terminal_fence_statu();
+
+  Terminal_fence_statu(const Terminal_fence_statu& from);
+
+  inline Terminal_fence_statu& operator=(const Terminal_fence_statu& from) {
+    CopyFrom(from);
+    return *this;
+  }
+  #if LANG_CXX11
+  Terminal_fence_statu(Terminal_fence_statu&& from) noexcept
+    : Terminal_fence_statu() {
+    *this = ::std::move(from);
+  }
+
+  inline Terminal_fence_statu& operator=(Terminal_fence_statu&& from) noexcept {
+    if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) {
+      if (this != &from) InternalSwap(&from);
+    } else {
+      CopyFrom(from);
+    }
+    return *this;
+  }
+  #endif
+  inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+    return _internal_metadata_.unknown_fields();
+  }
+  inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+    return _internal_metadata_.mutable_unknown_fields();
+  }
+
+  static const ::google::protobuf::Descriptor* descriptor();
+  static const Terminal_fence_statu& default_instance();
+
+  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
+  static inline const Terminal_fence_statu* internal_default_instance() {
+    return reinterpret_cast<const Terminal_fence_statu*>(
+               &_Terminal_fence_statu_default_instance_);
+  }
+  static PROTOBUF_CONSTEXPR int const kIndexInFileMessages =
+    0;
+
+  void Swap(Terminal_fence_statu* other);
+  friend void swap(Terminal_fence_statu& a, Terminal_fence_statu& b) {
+    a.Swap(&b);
+  }
+
+  // implements Message ----------------------------------------------
+
+  inline Terminal_fence_statu* New() const PROTOBUF_FINAL { return New(NULL); }
+
+  Terminal_fence_statu* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL;
+  void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
+  void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
+  void CopyFrom(const Terminal_fence_statu& from);
+  void MergeFrom(const Terminal_fence_statu& from);
+  void Clear() PROTOBUF_FINAL;
+  bool IsInitialized() const PROTOBUF_FINAL;
+
+  size_t ByteSizeLong() const PROTOBUF_FINAL;
+  bool MergePartialFromCodedStream(
+      ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL;
+  void SerializeWithCachedSizes(
+      ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL;
+  ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray(
+      bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL;
+  int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; }
+  private:
+  void SharedCtor();
+  void SharedDtor();
+  void SetCachedSize(int size) const PROTOBUF_FINAL;
+  void InternalSwap(Terminal_fence_statu* other);
+  private:
+  inline ::google::protobuf::Arena* GetArenaNoVirtual() const {
+    return NULL;
+  }
+  inline void* MaybeArenaPtr() const {
+    return NULL;
+  }
+  public:
+
+  ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL;
+
+  // nested types ----------------------------------------------------
+
+  // accessors -------------------------------------------------------
+
+  // required int64 terminal_id = 1;
+  bool has_terminal_id() const;
+  void clear_terminal_id();
+  static const int kTerminalIdFieldNumber = 1;
+  ::google::protobuf::int64 terminal_id() const;
+  void set_terminal_id(::google::protobuf::int64 value);
+
+  // required int64 cloud_statu = 2;
+  bool has_cloud_statu() const;
+  void clear_cloud_statu();
+  static const int kCloudStatuFieldNumber = 2;
+  ::google::protobuf::int64 cloud_statu() const;
+  void set_cloud_statu(::google::protobuf::int64 value);
+
+  // required int64 position_statu = 3;
+  bool has_position_statu() const;
+  void clear_position_statu();
+  static const int kPositionStatuFieldNumber = 3;
+  ::google::protobuf::int64 position_statu() const;
+  void set_position_statu(::google::protobuf::int64 value);
+
+  // @@protoc_insertion_point(class_scope:wj_lidar_message.Terminal_fence_statu)
+ private:
+  void set_has_terminal_id();
+  void clear_has_terminal_id();
+  void set_has_cloud_statu();
+  void clear_has_cloud_statu();
+  void set_has_position_statu();
+  void clear_has_position_statu();
+
+  // helper for ByteSizeLong()
+  size_t RequiredFieldsByteSizeFallback() const;
+
+  ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_;
+  ::google::protobuf::internal::HasBits<1> _has_bits_;
+  mutable int _cached_size_;
+  ::google::protobuf::int64 terminal_id_;
+  ::google::protobuf::int64 cloud_statu_;
+  ::google::protobuf::int64 position_statu_;
+  friend struct ::protobuf_wj_5flidar_5fmsg_2eproto::TableStruct;
+  friend void ::protobuf_wj_5flidar_5fmsg_2eproto::InitDefaultsTerminal_fence_statuImpl();
+};
+// -------------------------------------------------------------------
+
+class Fence_statu_message : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:wj_lidar_message.Fence_statu_message) */ {
+ public:
+  Fence_statu_message();
+  virtual ~Fence_statu_message();
+
+  Fence_statu_message(const Fence_statu_message& from);
+
+  inline Fence_statu_message& operator=(const Fence_statu_message& from) {
+    CopyFrom(from);
+    return *this;
+  }
+  #if LANG_CXX11
+  Fence_statu_message(Fence_statu_message&& from) noexcept
+    : Fence_statu_message() {
+    *this = ::std::move(from);
+  }
+
+  inline Fence_statu_message& operator=(Fence_statu_message&& from) noexcept {
+    if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) {
+      if (this != &from) InternalSwap(&from);
+    } else {
+      CopyFrom(from);
+    }
+    return *this;
+  }
+  #endif
+  inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+    return _internal_metadata_.unknown_fields();
+  }
+  inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+    return _internal_metadata_.mutable_unknown_fields();
+  }
+
+  static const ::google::protobuf::Descriptor* descriptor();
+  static const Fence_statu_message& default_instance();
+
+  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
+  static inline const Fence_statu_message* internal_default_instance() {
+    return reinterpret_cast<const Fence_statu_message*>(
+               &_Fence_statu_message_default_instance_);
+  }
+  static PROTOBUF_CONSTEXPR int const kIndexInFileMessages =
+    1;
+
+  void Swap(Fence_statu_message* other);
+  friend void swap(Fence_statu_message& a, Fence_statu_message& b) {
+    a.Swap(&b);
+  }
+
+  // implements Message ----------------------------------------------
+
+  inline Fence_statu_message* New() const PROTOBUF_FINAL { return New(NULL); }
+
+  Fence_statu_message* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL;
+  void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
+  void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
+  void CopyFrom(const Fence_statu_message& from);
+  void MergeFrom(const Fence_statu_message& from);
+  void Clear() PROTOBUF_FINAL;
+  bool IsInitialized() const PROTOBUF_FINAL;
+
+  size_t ByteSizeLong() const PROTOBUF_FINAL;
+  bool MergePartialFromCodedStream(
+      ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL;
+  void SerializeWithCachedSizes(
+      ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL;
+  ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray(
+      bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL;
+  int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; }
+  private:
+  void SharedCtor();
+  void SharedDtor();
+  void SetCachedSize(int size) const PROTOBUF_FINAL;
+  void InternalSwap(Fence_statu_message* other);
+  private:
+  inline ::google::protobuf::Arena* GetArenaNoVirtual() const {
+    return NULL;
+  }
+  inline void* MaybeArenaPtr() const {
+    return NULL;
+  }
+  public:
+
+  ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL;
+
+  // nested types ----------------------------------------------------
+
+  // accessors -------------------------------------------------------
+
+  // repeated .wj_lidar_message.Terminal_fence_statu fence_statu = 1;
+  int fence_statu_size() const;
+  void clear_fence_statu();
+  static const int kFenceStatuFieldNumber = 1;
+  const ::wj_lidar_message::Terminal_fence_statu& fence_statu(int index) const;
+  ::wj_lidar_message::Terminal_fence_statu* mutable_fence_statu(int index);
+  ::wj_lidar_message::Terminal_fence_statu* add_fence_statu();
+  ::google::protobuf::RepeatedPtrField< ::wj_lidar_message::Terminal_fence_statu >*
+      mutable_fence_statu();
+  const ::google::protobuf::RepeatedPtrField< ::wj_lidar_message::Terminal_fence_statu >&
+      fence_statu() const;
+
+  // @@protoc_insertion_point(class_scope:wj_lidar_message.Fence_statu_message)
+ private:
+
+  ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_;
+  ::google::protobuf::internal::HasBits<1> _has_bits_;
+  mutable int _cached_size_;
+  ::google::protobuf::RepeatedPtrField< ::wj_lidar_message::Terminal_fence_statu > fence_statu_;
+  friend struct ::protobuf_wj_5flidar_5fmsg_2eproto::TableStruct;
+  friend void ::protobuf_wj_5flidar_5fmsg_2eproto::InitDefaultsFence_statu_messageImpl();
+};
+// ===================================================================
+
+
+// ===================================================================
+
+#ifdef __GNUC__
+  #pragma GCC diagnostic push
+  #pragma GCC diagnostic ignored "-Wstrict-aliasing"
+#endif  // __GNUC__
+// Terminal_fence_statu
+
+// required int64 terminal_id = 1;
+inline bool Terminal_fence_statu::has_terminal_id() const {
+  return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void Terminal_fence_statu::set_has_terminal_id() {
+  _has_bits_[0] |= 0x00000001u;
+}
+inline void Terminal_fence_statu::clear_has_terminal_id() {
+  _has_bits_[0] &= ~0x00000001u;
+}
+inline void Terminal_fence_statu::clear_terminal_id() {
+  terminal_id_ = GOOGLE_LONGLONG(0);
+  clear_has_terminal_id();
+}
+inline ::google::protobuf::int64 Terminal_fence_statu::terminal_id() const {
+  // @@protoc_insertion_point(field_get:wj_lidar_message.Terminal_fence_statu.terminal_id)
+  return terminal_id_;
+}
+inline void Terminal_fence_statu::set_terminal_id(::google::protobuf::int64 value) {
+  set_has_terminal_id();
+  terminal_id_ = value;
+  // @@protoc_insertion_point(field_set:wj_lidar_message.Terminal_fence_statu.terminal_id)
+}
+
+// required int64 cloud_statu = 2;
+inline bool Terminal_fence_statu::has_cloud_statu() const {
+  return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void Terminal_fence_statu::set_has_cloud_statu() {
+  _has_bits_[0] |= 0x00000002u;
+}
+inline void Terminal_fence_statu::clear_has_cloud_statu() {
+  _has_bits_[0] &= ~0x00000002u;
+}
+inline void Terminal_fence_statu::clear_cloud_statu() {
+  cloud_statu_ = GOOGLE_LONGLONG(0);
+  clear_has_cloud_statu();
+}
+inline ::google::protobuf::int64 Terminal_fence_statu::cloud_statu() const {
+  // @@protoc_insertion_point(field_get:wj_lidar_message.Terminal_fence_statu.cloud_statu)
+  return cloud_statu_;
+}
+inline void Terminal_fence_statu::set_cloud_statu(::google::protobuf::int64 value) {
+  set_has_cloud_statu();
+  cloud_statu_ = value;
+  // @@protoc_insertion_point(field_set:wj_lidar_message.Terminal_fence_statu.cloud_statu)
+}
+
+// required int64 position_statu = 3;
+inline bool Terminal_fence_statu::has_position_statu() const {
+  return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void Terminal_fence_statu::set_has_position_statu() {
+  _has_bits_[0] |= 0x00000004u;
+}
+inline void Terminal_fence_statu::clear_has_position_statu() {
+  _has_bits_[0] &= ~0x00000004u;
+}
+inline void Terminal_fence_statu::clear_position_statu() {
+  position_statu_ = GOOGLE_LONGLONG(0);
+  clear_has_position_statu();
+}
+inline ::google::protobuf::int64 Terminal_fence_statu::position_statu() const {
+  // @@protoc_insertion_point(field_get:wj_lidar_message.Terminal_fence_statu.position_statu)
+  return position_statu_;
+}
+inline void Terminal_fence_statu::set_position_statu(::google::protobuf::int64 value) {
+  set_has_position_statu();
+  position_statu_ = value;
+  // @@protoc_insertion_point(field_set:wj_lidar_message.Terminal_fence_statu.position_statu)
+}
+
+// -------------------------------------------------------------------
+
+// Fence_statu_message
+
+// repeated .wj_lidar_message.Terminal_fence_statu fence_statu = 1;
+inline int Fence_statu_message::fence_statu_size() const {
+  return fence_statu_.size();
+}
+inline void Fence_statu_message::clear_fence_statu() {
+  fence_statu_.Clear();
+}
+inline const ::wj_lidar_message::Terminal_fence_statu& Fence_statu_message::fence_statu(int index) const {
+  // @@protoc_insertion_point(field_get:wj_lidar_message.Fence_statu_message.fence_statu)
+  return fence_statu_.Get(index);
+}
+inline ::wj_lidar_message::Terminal_fence_statu* Fence_statu_message::mutable_fence_statu(int index) {
+  // @@protoc_insertion_point(field_mutable:wj_lidar_message.Fence_statu_message.fence_statu)
+  return fence_statu_.Mutable(index);
+}
+inline ::wj_lidar_message::Terminal_fence_statu* Fence_statu_message::add_fence_statu() {
+  // @@protoc_insertion_point(field_add:wj_lidar_message.Fence_statu_message.fence_statu)
+  return fence_statu_.Add();
+}
+inline ::google::protobuf::RepeatedPtrField< ::wj_lidar_message::Terminal_fence_statu >*
+Fence_statu_message::mutable_fence_statu() {
+  // @@protoc_insertion_point(field_mutable_list:wj_lidar_message.Fence_statu_message.fence_statu)
+  return &fence_statu_;
+}
+inline const ::google::protobuf::RepeatedPtrField< ::wj_lidar_message::Terminal_fence_statu >&
+Fence_statu_message::fence_statu() const {
+  // @@protoc_insertion_point(field_list:wj_lidar_message.Fence_statu_message.fence_statu)
+  return fence_statu_;
+}
+
+#ifdef __GNUC__
+  #pragma GCC diagnostic pop
+#endif  // __GNUC__
+// -------------------------------------------------------------------
+
+
+// @@protoc_insertion_point(namespace_scope)
+
+}  // namespace wj_lidar_message
+
+// @@protoc_insertion_point(global_scope)
+
+#endif  // PROTOBUF_wj_5flidar_5fmsg_2eproto__INCLUDED

+ 14 - 0
wj_lidar/wj_lidar_msg.proto

@@ -0,0 +1,14 @@
+syntax = "proto2";
+package wj_lidar_message;
+
+message Terminal_fence_statu
+{
+    required int64 terminal_id=1;
+    required int64 cloud_statu=2;
+    required int64 position_statu=3;
+}
+
+message Fence_statu_message
+{
+    repeated Terminal_fence_statu  fence_statu=1;
+}