Browse Source

增加雷达检验,未添加plc

zx 3 years ago
parent
commit
61033afad0

+ 3 - 2
CMakeLists.txt

@@ -37,7 +37,7 @@ link_directories("/usr/local/lib")
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/error_code ERROR_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/tool TOOL_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/laser LASER )
-#aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/plc PLC_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/plc PLC_SRC )
 #aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/task TASK_MANAGER_SRC )
 #aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/verify VERIFY )
 #aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/verify/match3d MATCH3D )
@@ -45,12 +45,13 @@ aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/laser LASER )
 
 add_executable(shutter_verify ./main.cpp setting.pb.cc
 		safety_excutor.cpp
-		${ERROR_SRC} ${LASER}
+		${ERROR_SRC} ${LASER} ${PLC_SRC}
 		${TOOL_SRC} )
 target_link_libraries(shutter_verify ${OpenCV_LIBS}
 		${PCL_LIBRARIES} ${PROTOBUF_LIBRARIES} ${CERES_LIBRARIES}
 		/usr/local/lib/libglog.a /usr/local/lib/libgflags.a
 		/usr/local/lib/liblivox_sdk_static.a
+		snap7
 		)
 
 

+ 13 - 0
laser/LivoxMid70.cpp

@@ -61,12 +61,24 @@ bool TimedLivoxExtendRawPoint::is_timeout(){
 
 
 LivoxMid70::LivoxMid70(){
+
     m_idx=0;
     m_fps=2.0;
     m_transform=Eigen::Affine3f::Identity();
 }
 LivoxMid70::~LivoxMid70(){}
 
+
+bool LivoxMid70::is_connected()
+{
+    auto tic=std::chrono::steady_clock::now();
+    auto duration = std::chrono::duration_cast<std::chrono::microseconds>(tic - m_last_data_tp);
+
+    double tm=double(duration.count()) * std::chrono::microseconds::period::num /
+            std::chrono::microseconds::period::den;
+    return tm<1.0;
+}
+
 void LivoxMid70::SetTransformParam(Eigen::Vector3f rpy,Eigen::Vector3f transpose)
 {
     Eigen::AngleAxisf rollAngle(Eigen::AngleAxisf(rpy(0),Eigen::Vector3f::UnitX()));
@@ -139,6 +151,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr LivoxMid70::GetCloud()
 
 void LivoxMid70::LidarDataCallback(uint8_t handle, LivoxEthPacket *data, uint32_t data_num)
 {
+    m_last_data_tp=std::chrono::steady_clock::now();
     LivoxEthPacket *eth_packet = data;
 
     if (!data || !data_num || (handle >= kMaxLidarCount))

+ 4 - 3
laser/LivoxMid70.h

@@ -45,15 +45,16 @@ class LivoxMid70 : public LdsLidar
     }
     pcl::PointCloud<pcl::PointXYZ>::Ptr GetCloud();
     void SetTransformParam(Eigen::Vector3f rpy,Eigen::Vector3f transpose);
-
+    bool is_connected();
  private:
     virtual void LidarDataCallback(uint8_t handle, LivoxEthPacket *data,uint32_t data_num);
 
 
  protected:
+    std::chrono::steady_clock::time_point       m_last_data_tp;
     std::mutex                      m_mutex;
-    TimedLivoxExtendRawPoint     m_frames[MAX_FRAME];
-    int                     m_idx;
+    TimedLivoxExtendRawPoint        m_frames[MAX_FRAME];
+    int                             m_idx;
 
     float                   m_fps;
     Eigen::Affine3f         m_transform;

+ 33 - 12
main.cpp

@@ -1,17 +1,19 @@
 //
 // Created by zx on 2019/12/28.
 //
+
+
 #include <fcntl.h>
 #include <iostream>
-#include "plc/plc_communicator.h"
-//#include "laser/Laser.h"
-#include "plc/plc_communicator.h"
 #include "tool/pathcreator.h"
 #include <glog/logging.h>
 #include "verifier.h"
-#include "proto_tool.h"
+#include <google/protobuf/io/zero_copy_stream_impl.h>
+#include <google/protobuf/text_format.h>
 #include <livox_sdk.h>
 #include "LivoxMid70.h"
+#include "snap7_communication_base.h"
+#include <thread>
 using google::protobuf::io::FileInputStream;
 using google::protobuf::io::FileOutputStream;
 using google::protobuf::io::ZeroCopyInputStream;
@@ -78,9 +80,6 @@ void init_glog()
     FLAGS_stop_logging_if_full_disk = true;
 }
 
-std::mutex   mut;
-pcl::visualization::PCLVisualizer viewer("Cloud");
-
 
 
 //读取protobuf 配置文件
@@ -97,6 +96,10 @@ bool read_proto_param(std::string file, ::google::protobuf::Message& parameter)
     return success;
 }
 
+#if VIEW
+extern pcl::visualization::PCLVisualizer viewer;
+#endif
+
 int Working()
 {
 
@@ -282,7 +285,9 @@ int main(int argc,char* argv[])
 {
     //初始化日志
     init_glog();
+#if VIEW
     viewer.addCoordinateSystem(2.0,0,0,0,"car_center");
+#endif
 
     int ret = livox::LdsLidar::InitLdsLidar();
 
@@ -336,17 +341,33 @@ int main(int argc,char* argv[])
     usleep(3000*1000);
 
 
-
-
     //lidar1.AddSNCode(sn1);
     //lidar2.AddSNCode(sn2);
 
     std::thread* thread=new std::thread(Working);
-
+    tagMeasureData  measure_data;
+    struct PLCData
+    {
+        int   pingpong;
+        unsigned short  safety;
+        float left_space;
+        float right_space;
+        float theta;
+        float offset_x;
+    };
+    int PING=0;
     while(1)
     {
-        excutor->verify();
-        /**/
+        excutor->verify(measure_data);
+        struct PLCData plc_data;
+        plc_data.pingpong=(PING++)%10000;
+        plc_data.offset_x=measure_data.offset_x;
+        plc_data.left_space=measure_data.left_space;
+        plc_data.right_space=measure_data.right_space;
+        plc_data.theta=measure_data.theta;
+        plc_data.safety=measure_data.safety;
+
+
         usleep(33*1000);
     }
 

+ 0 - 116
plc/LibmodbusWrapper.cpp

@@ -1,116 +0,0 @@
-
-#include "LibmodbusWrapper.h"
-
-namespace modbus
-{
-    CLibmodbusWrapper::CLibmodbusWrapper()
-        :_ctx(NULL)
-        , _ip("")
-        ,_port(-1)
-        ,_slave_id(-1)
-    {
-    }
-
-
-    CLibmodbusWrapper::~CLibmodbusWrapper()
-    {
-        deinitialize();
-    }
-
-    void CLibmodbusWrapper::deinitialize()
-    {
-        if (_ctx)
-        {
-            modbus_close(_ctx);
-            modbus_free(_ctx);
-            _ctx = NULL;
-            _ip = "";
-            _port = -1;
-            _slave_id = -1;
-        }
-    }
-    int CLibmodbusWrapper::initialize(const char *ip, int port, int slave_id)
-    {
-        int rc = 0;
-
-        this->deinitialize();
-
-        _ctx = modbus_new_tcp(ip, port);
-        if (_ctx == NULL)
-        {
-            //����ʧ��
-            fprintf(stderr, "CLibmodbusWrapper: Unable to allocate libmodbus context\n");
-            return -3;
-        }
-
-        // ���õ���ģʽ
-        modbus_set_debug(_ctx, FALSE);
-
-        // �������ӵ�slave�ţ��˴�Ϊ1
-        rc = modbus_set_slave(_ctx, slave_id);
-        if (rc == -1)
-        {
-            fprintf(stderr, "CLibmodbusWrapper: Invalid slave ID\n");
-            modbus_free(_ctx);
-            _ctx = NULL;
-            return -2;
-        }
-
-        rc = modbus_connect(_ctx);
-        if (rc == -1)
-        {
-            fprintf(stderr, "CLibmodbusWrapper: Connection failed: %s\n", modbus_strerror(errno));
-            modbus_free(_ctx);
-            _ctx = NULL;
-            return -1;
-        }
-
-        _ip = ip;
-        _port = port;
-        _slave_id = slave_id;
-
-        return 0;
-    }
-
-    int CLibmodbusWrapper::read_registers(int addr, int nb, uint16_t *dest)
-    {
-        if (modbus_read_registers(_ctx, addr, nb, dest) == -1)
-        {
-            fprintf(stderr, "CLibmodbusWrapper: Read registers failed: %s\n", modbus_strerror(errno));
-            // printf("%s---%s, %d\n", modbus_strerror(errno), "Broken pipe", strcmp(modbus_strerror(errno), "Broken pipe")==0?1:0);
-            return -1;
-        }
-        return 0;
-    }
-
-    int CLibmodbusWrapper::write_registers(int addr, int nb, uint16_t *dest)
-    {
-        if (modbus_write_registers(_ctx, addr, nb, dest) == -1)
-        {
-            fprintf(stderr, "CLibmodbusWrapper: Write registers failed: %s\n", modbus_strerror(errno));
-            return -1;
-        }
-        return 0;
-    }
-
-
-    int CLibmodbusWrapper::read_register(int addr, uint16_t *dest)
-    {
-        if (modbus_read_registers(_ctx, addr, 1, dest) == -1)
-        {
-            fprintf(stderr, "CLibmodbusWrapper: Read registers failed: %s\n", modbus_strerror(errno));
-            return -1;
-        }
-        return 0;
-    }
-
-    int CLibmodbusWrapper::write_register(int addr, uint16_t *dest)
-    {
-        if (modbus_write_registers(_ctx, addr, 1, dest) == -1)
-        {
-            fprintf(stderr, "CLibmodbusWrapper: Write registers failed: %s\n", modbus_strerror(errno));
-            return -1;
-        }
-        return 0;
-    }
-}

+ 0 - 37
plc/LibmodbusWrapper.h

@@ -1,37 +0,0 @@
-#pragma once
-#include <stdio.h>
-#include <errno.h>
-#include <string>
-#include <string.h>
-#include "modbus/modbus.h"
-
-namespace modbus
-{
-    class CLibmodbusWrapper
-    {
-    public:
-        CLibmodbusWrapper();
-        virtual ~CLibmodbusWrapper();
-        int initialize(const char *ip, int port, int slave_id);
-        void deinitialize();
-
-    public:
-        int read_registers(int addr, int nb, uint16_t *dest);
-        int write_registers(int addr, int nb, uint16_t *dest);
-
-        int read_register(int addr, uint16_t *dest);
-        int write_register(int addr, uint16_t *dest);
-
-        inline bool is_connected() { return (0 == _ctx) ? false : true; };
-        inline std::string getIP() { return _ip; };
-        inline int getPort() { return _port; };
-        inline int getSlave() { return _slave_id; };
-
-    private:
-        modbus_t* _ctx;
-    private:
-        std::string _ip;
-        int _port;
-        int _slave_id;
-    };
-};

+ 0 - 447
plc/plc_communicator.cpp

@@ -1,447 +0,0 @@
-#include "plc_communicator.h"
-#include <glog/logging.h>
-
-// ××××××××××× 构造与析构 ×××××××××××
-Plc_Communicator::Plc_Communicator(plc_module::plc_connection_params connection_params) : mb_plc_initialized(false),
-                                                                             mb_plc_is_connected(false),
-                                                                             mb_plc_is_updating(false),
-                                                                             mp_plc_owner(0),
-                                                                             m_plc_thread(0),
-                                                                             m_plc_message_thread(0)
-{
-    m_plc_ip_str = connection_params.ip();
-    m_plc_port = connection_params.port();
-    m_plc_slave_id = connection_params.slave_id();
-    m_plc_current_error = Error_manager(Error_code::SUCCESS, Error_level::NORMAL, "初始状态正常");
-    m_plc_status_update_timeout = 10000;
-    for (size_t i = 0; i < PLC_REGION_NUM; i++)
-    {
-        m_plc_region_status[i].last_time_point = std::chrono::steady_clock::now();
-        m_plc_region_status[i].current_status = 255;
-        m_plc_region_status[i].cmd = 0;
-    }
-
-    m_plc_data.resize(PLC_REGION_NUM * PLC_SIGNAL_NUM_PER_REGION);
-    m_plc_current_error = connect();
-    m_plc_cond_exit.Notify(false);
-    m_plc_thread = new std::thread(plc_update_thread, this);
-    m_plc_message_thread=new std::thread(plc_publish_message, this);
-    mb_plc_initialized = true;
-}
-
-Plc_Communicator::~Plc_Communicator()
-{
-    m_plc_cond_exit.Notify(true);
-    if (m_plc_thread)
-    {
-        if (m_plc_thread->joinable())
-            m_plc_thread->join();
-        delete m_plc_thread;
-        m_plc_thread = 0;
-    }
-
-    if (m_plc_message_thread)
-    {
-        if (m_plc_message_thread->joinable())
-            m_plc_message_thread->join();
-        delete m_plc_message_thread;
-        m_plc_message_thread = 0;
-    }
-    disconnect();
-}
-
-// ××××××××××× getters setters ×××××××××××
-bool Plc_Communicator::get_connection()
-{
-    return mb_plc_is_connected;
-}
-
-Error_manager Plc_Communicator::get_error(){
-    if(mb_plc_is_connected){
-        return Error_manager(Error_code::SUCCESS, Error_level::NORMAL, "连接正常");
-    }else{
-        return Error_manager(Error_code::FAILED, Error_level::NEGLIGIBLE_ERROR, "连接失败");
-    }
-}
-
-bool Plc_Communicator::get_initialize_status()
-{
-    return mb_plc_initialized;
-}
-
-Error_manager Plc_Communicator::set_plc_callback(Command_Callback callback, void *p_owner)
-{
-    if (callback == 0 || p_owner == 0)
-        return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR, "回调设置参数错误");
-    m_plc_callback = callback;
-    mp_plc_owner = p_owner;
-    return Error_manager(Error_code::SUCCESS, Error_level::NORMAL, "回调设置参数正确");
-}
-
-Error_manager Plc_Communicator::set_status_update_timeout(int millisecond)
-{
-    m_plc_status_update_timeout = millisecond;
-    return Error_manager(Error_code::SUCCESS, Error_level::NORMAL, "设置状态更新超时时间成功");
-}
-
-// ××××××××××× 内部调用连接与重连 ×××××××××××
-Error_manager Plc_Communicator::connect()
-{
-    m_plc_mutex.lock();
-    int rc = m_plc_wrapper.initialize(m_plc_ip_str.c_str(), m_plc_port, m_plc_slave_id);
-    m_plc_mutex.unlock();
-    switch (rc)
-    {
-    case 0:
-        mb_plc_is_connected = true;
-        return Error_manager(Error_code::SUCCESS, Error_level::NORMAL, "plc连接成功");
-    case -1:
-        mb_plc_is_connected = false;
-        return Error_manager(Error_code::DISCONNECT, Error_level::MINOR_ERROR, "plc掉线");
-    case -2:
-        mb_plc_is_connected = false;
-        return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR, "plc的从站id错误");
-    case -3:
-        mb_plc_is_connected = false;
-        return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR, "plc的ip或端口设置错误");
-    default:
-        mb_plc_is_connected = false;
-        return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR, "plc连接时出现未知返回值");
-    }
-}
-
-Error_manager Plc_Communicator::disconnect()
-{
-    m_plc_mutex.lock();
-    m_plc_wrapper.deinitialize();
-    mb_plc_is_connected = false;
-    m_plc_mutex.unlock();
-    return Error_manager(Error_code::SUCCESS);
-}
-
-// ××××××××××× 外部调用执行任务单 ×××××××××××
-Error_manager Plc_Communicator::execute_task(Task_Base *task)
-{
-    if (task == 0)
-        return Error_manager(Error_code::PARAMETER_ERROR, Error_level::NEGLIGIBLE_ERROR, "传入空任务");
-    if (task->get_task_type() != Task_type::PLC_TASK)
-    {
-        return Error_manager(Error_code::PARAMETER_ERROR, Error_level::NEGLIGIBLE_ERROR, "传入非plc任务");
-    }
-    Plc_Task *plc_task_temp = (Plc_Task *)task;
-    plc_task_temp->update_statu(Task_statu::TASK_SIGNED, "received by plc_communicator.");
-
-    struct measure_result measure_result_temp;
-    Error_manager err = plc_task_temp->get_result(measure_result_temp);
-    if (err.is_equal_error_manager(Error_manager(Error_code::SUCCESS)))
-    {
-        Error_manager write_err = write_result_to_plc(measure_result_temp);
-        plc_task_temp->update_statu(Task_statu::TASK_OVER, "executed by plc_communicator.");
-        return write_err;
-    }
-    else
-    {
-        return err;
-    }
-}
-
-// ××××××××××× 外部调用获取数据, 终端id[1-6], -1则获取所有数据 ×××××××××××
-Error_manager Plc_Communicator::get_plc_data(std::vector<uint16_t> &plc_data, int terminal_id)
-{
-    std::lock_guard<std::mutex> lck(m_plc_mutex);
-    plc_data.clear();
-    if (terminal_id == -1)
-    {
-        plc_data.operator=(m_plc_data);
-    }
-    else if (terminal_id <= PLC_REGION_NUM && terminal_id * PLC_SIGNAL_NUM_PER_REGION <= m_plc_data.size())
-    {
-        for (size_t i = (terminal_id - 1) * PLC_SIGNAL_NUM_PER_REGION; i < terminal_id * PLC_SIGNAL_NUM_PER_REGION; i++)
-        {
-            plc_data.push_back(m_plc_data[i]);
-        }
-        return Error_manager(Error_code::SUCCESS);
-    }
-    else
-        return Error_manager(Error_code::ERROR);
-}
-
-Error_manager Plc_Communicator::write_result_to_plc(struct measure_result result){
-    // std::cout<<" write result 000 "<<result.terminal_id<<std::endl;
-    if(result.terminal_id<=0 || result.terminal_id>PLC_REGION_NUM){
-        Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR, "写plc传入参数错误");
-    }
-    // std::cout<<" write result 111 "<<std::endl;
-    int offset = PLC_SIGNAL_BEGIN_OFFSET + PLC_LASER_STATUS_ADDR + (result.terminal_id-1) * PLC_SIGNAL_NUM_PER_REGION;
-    int result_length = PLC_LASER_WHEELBASE_ADDR - PLC_LASER_STATUS_ADDR + 1;
-    uint16_t result_info_temp[result_length];
-    memset(result_info_temp, 0, result_length * sizeof(uint16_t));
-
-    // 之后设置正确位,先将数据写入,状态写2
-    if(result.correctness){
-        m_plc_region_status[result.terminal_id - 1].current_status = 3;
-        result_info_temp[PLC_LASER_STATUS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(2);
-        result_info_temp[PLC_LASER_X_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(result.x + 0.5f);
-        result_info_temp[PLC_LASER_Y_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(result.y + 0.5f);
-        result_info_temp[PLC_LASER_ANGLE_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(result.angle * 100);
-        result_info_temp[PLC_LASER_LENGTH_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(result.length + 0.5f);
-        result_info_temp[PLC_LASER_WIDTH_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(result.width + 0.5f);
-        result_info_temp[PLC_LASER_HEIGHT_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(result.height + 0.5f);
-        result_info_temp[PLC_LASER_CORRECTNESS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(0);
-        result_info_temp[PLC_LASER_WHEELBASE_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(result.wheel_base + 0.5f);
-    }else{
-        m_plc_region_status[result.terminal_id-1].current_status = 4;
-        result_info_temp[PLC_LASER_STATUS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(2);
-        result_info_temp[PLC_LASER_CORRECTNESS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(0);
-    }
-    if(!m_plc_wrapper.is_connected()){
-        return Error_manager(Error_code::DISCONNECT);
-    }
-    else{
-        // std::cout<<" write result start "<<std::endl;
-        int retry_times = 3;
-        int plc_write_return_code = -1;
-        while(retry_times-->0 && plc_write_return_code<0) {
-		// 更新时间
-		m_plc_region_status[result.terminal_id - 1].last_time_point = std::chrono::steady_clock::now();
-            // 写入数据
-            m_plc_mutex.lock();
-            plc_write_return_code = m_plc_wrapper.write_registers(offset, result_length, result_info_temp);
-            m_plc_mutex.unlock();
-            if(plc_write_return_code<0)
-                continue;
-            usleep(1000* 100);
-            // 写入状态
-            if(result.correctness)
-            {
-                result_info_temp[PLC_LASER_STATUS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(3);
-                result_info_temp[PLC_LASER_CORRECTNESS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(1);
-            }else
-            {
-                result_info_temp[PLC_LASER_STATUS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(4);
-                result_info_temp[PLC_LASER_CORRECTNESS_ADDR - PLC_LASER_STATUS_ADDR] = uint16_t(0);
-            }
-            m_plc_mutex.lock();
-            plc_write_return_code = m_plc_wrapper.write_registers(offset, result_length, result_info_temp);
-            m_plc_mutex.unlock();
-            usleep(1000* 100);
-            // std::cout<<" write result end "<<rc<<std::endl;
-        }
-        if(retry_times <=0 || plc_write_return_code != 0)
-            return Error_manager(Error_code::FAILED);
-        else
-            return Error_manager(Error_code::SUCCESS);
-    }
-}
-/*
- *
- */
-
-void Plc_Communicator::plc_publish_message(Plc_Communicator* plc)
-{
-    return ;
-    /*if(plc==0)
-    {
-        LOG(ERROR)<<"";
-    }
-    while(plc->m_plc_cond_exit.WaitFor(100)==false) {
-        plc_message::plcMsg msg;
-        for(int i=0;i<PLC_SIGNAL_BEGIN_OFFSET;++i)
-        {
-            msg.add_plc_values(0);
-        }
-        for (int i = 0; i < plc->m_plc_data.size(); ++i) {
-            msg.add_plc_values(plc->m_plc_data[i]);
-        }
-        plc_message::plcStatus status;
-        if (plc->mb_plc_is_connected)
-            status = plc_message::ePLCConnected;
-        else
-            status = plc_message::ePLCDisconnected;
-        msg.set_plc_status(status);
-        MeasureTopicPublisher::GetInstance()->Publish(msg.SerializeAsString());
-    }
-*/
-}
-
-// ××××××××××× 更新线程静态函数 ×××××××××××
-void Plc_Communicator::plc_update_thread(Plc_Communicator *plc_communicator)
-{
-    if (plc_communicator == 0)
-        return;
-    while (!plc_communicator->m_plc_cond_exit.WaitFor(100))
-    {
-        // std::cout<<" thread 000 "<<std::endl;
-
-        // 断线重连
-        if (!plc_communicator->mb_plc_is_connected)
-        {
-            Error_manager code=plc_communicator->connect();
-            if(code!=SUCCESS)
-            {
-                LOG(ERROR)<<code.to_string();
-            }
-            usleep(1000 * 200);
-        }
-        else
-        {
-            // std::cout<<" thread 111 "<<std::endl;
-            // 读取所有数据,更新本地并发布消息到UI
-            int plc_length_temp = PLC_REGION_NUM * PLC_SIGNAL_NUM_PER_REGION;
-            uint16_t plc_data_temp[plc_length_temp];
-            int rc = plc_communicator->m_plc_wrapper.read_registers(PLC_SIGNAL_BEGIN_OFFSET, plc_length_temp, plc_data_temp);
-            if(rc <0)
-            {
-                std::cout<<"find plc disconnected while read. try to reconnect."<<std::endl;
-                plc_communicator->mb_plc_is_connected = false;
-                continue;
-            }
-            else if (rc == 0)
-            {
-                plc_communicator->m_plc_mutex.lock();
-                int terminal_id_temp = 0;
-                for (size_t i = 0; i < plc_length_temp; i++)
-                {
-                    terminal_id_temp = i / PLC_SIGNAL_NUM_PER_REGION;
-                    plc_communicator->m_plc_data[i] = plc_data_temp[i];
-                    // 读取后检查是否存在差异, 存在则赋值。调用回调函数启动外部扫描
-                    if (i % PLC_SIGNAL_NUM_PER_REGION == PLC_LASER_START_ADDR && plc_data_temp[i] != plc_communicator->m_plc_region_status[terminal_id_temp].cmd)
-                    {
-                        plc_communicator->m_plc_region_status[terminal_id_temp].cmd = plc_data_temp[i];
-                        bool modified = false;
-                        // 判断指令存在
-                        // std::cout<<" thread 222 "<<std::endl;
-                        if (plc_data_temp[i] == 1)
-                        {
-                            // 判空
-                            if (plc_communicator->m_plc_callback != 0 && plc_communicator->mp_plc_owner != 0)
-                            {
-                                Error_manager ec = plc_communicator->m_plc_callback(terminal_id_temp + 1, plc_communicator->mp_plc_owner);
-                                if (ec.is_equal_error_manager(Error_manager(Error_code::SUCCESS)))
-                                {
-                                    plc_communicator->m_plc_region_status[terminal_id_temp].current_status = 1;
-                                    // 更新时间
-                                    plc_communicator->m_plc_region_status[terminal_id_temp].last_time_point = std::chrono::steady_clock::now();
-                                    modified = true;
-                                }
-                                else{
-                                    LOG(ERROR)<<ec.to_string();
-                                }
-                            }
-                        }
-                        // 指令清空,暂不恢复心跳
-                        else if (plc_data_temp[i] == 0)
-                        {
-                            // int status_temp = plc_communicator->m_plc_region_status[terminal_id_temp].current_status;
-                            // if (status_temp != 254 && status_temp != 255)
-                            // {
-                            //     plc_communicator->m_plc_region_status[terminal_id_temp].current_status = 255;
-                            //     // 更新时间
-                            //     plc_communicator->m_plc_region_status[terminal_id_temp].last_time_point = std::chrono::steady_clock::now();
-                            //     modified = true;
-                            // }
-                        }
-                        // 写入plc
-                        if (modified)
-                        {
-                            int address_temp = PLC_SIGNAL_BEGIN_OFFSET + PLC_SIGNAL_NUM_PER_REGION * terminal_id_temp + PLC_LASER_STATUS_ADDR;
-                            uint16_t value_temp = plc_communicator->m_plc_region_status[terminal_id_temp].current_status;
-                            int rc = plc_communicator->m_plc_wrapper.write_registers(address_temp, 1, &value_temp);
-                            if (rc != 0)
-                                plc_communicator->m_plc_current_error = Error_manager(Error_code::FAILED, Error_level::MINOR_ERROR, "写入状态1失败");
-                        }
-                    }
-                }
-                plc_communicator->m_plc_mutex.unlock();
-            }
-            else
-            {
-                plc_communicator->m_plc_current_error = Error_manager(Error_code::FAILED, Error_level::MINOR_ERROR, "循环读plc失败");
-            }
-            // std::cout<<" thread 333 "<<std::endl;
-
-            // 写入心跳或当前运行状态
-            for (size_t i = 0; i < PLC_REGION_NUM; i++)
-            {
-                int time_interval = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::steady_clock::now() - plc_communicator->m_plc_region_status[i].last_time_point).count();
-                // 判断超时且非心跳,则转回心跳
-                bool modified = false;
-                if (time_interval > plc_communicator->m_plc_status_update_timeout && plc_communicator->m_plc_region_status[i].current_status < 5)
-                {
-                    plc_communicator->m_plc_region_status[i].current_status = 255;
-                    modified = true;
-                }
-                else
-                {
-                    // 状态切换后写入plc
-                    switch (plc_communicator->m_plc_region_status[i].current_status)
-                    {
-                    case 254:
-                        if (time_interval > 1000)
-                        {
-                            plc_communicator->m_plc_region_status[i].current_status = 255;
-                            modified = true;
-                        }
-                        break;
-                    case 255:
-                        if (time_interval > 1000)
-                        {
-                            plc_communicator->m_plc_region_status[i].current_status = 254;
-                            modified = true;
-                        }
-                        break;
-                    case 0:
-                        plc_communicator->m_plc_region_status[i].current_status = 254;
-                        modified = true;
-                        break;
-                    case 1:
-                        if (time_interval > 1000)
-                        {
-                            plc_communicator->m_plc_region_status[i].current_status = 2;
-                            modified = true;
-                        }
-                        break;
-                    case 2:
-                        break;
-                    case 3:
-                        if (time_interval > 3000)
-                        {
-                            plc_communicator->m_plc_region_status[i].current_status = 254;
-                            modified = true;
-                        }
-                        break;
-                    case 4:
-                        if (time_interval > 8000)
-                        {
-                            plc_communicator->m_plc_region_status[i].current_status = 254;
-                            modified = true;
-                        }
-                        break;
-                    case 5:
-                        break;
-                    default:
-                        break;
-                    }
-                }
-                
-                if (modified && plc_communicator->mb_plc_is_connected)
-                {
-                    plc_communicator->m_plc_mutex.lock();
-                    // std::cout<<" thread 444 "<<std::endl;
-                    // 更新时间
-                    plc_communicator->m_plc_region_status[i].last_time_point = std::chrono::steady_clock::now();
-                    // 写入plc
-                    int address_temp = PLC_SIGNAL_BEGIN_OFFSET + PLC_SIGNAL_NUM_PER_REGION * i + PLC_LASER_STATUS_ADDR;
-                    uint16_t value_temp = plc_communicator->m_plc_region_status[i].current_status;
-                    int rc = plc_communicator->m_plc_wrapper.write_registers(address_temp, 1, &value_temp);
-                    if (rc != 0)
-                        plc_communicator->m_plc_current_error = Error_manager(Error_code::FAILED, Error_level::MINOR_ERROR, "写入当前状态失败");
-                    plc_communicator->m_plc_mutex.unlock();
-                    // std::cout<<" thread 555 "<<std::endl;
-                }
-            }
-        }
-
-        usleep(1000 * PLC_SLEEP_IN_MILLISECONDS);
-    }
-}

+ 0 - 134
plc/plc_communicator.h

@@ -1,134 +0,0 @@
-#ifndef PLC_COMMUNICATOR_HH
-#define PLC_COMMUNICATOR_HH
-
-#include <iostream>
-#include <string.h>
-#include <mutex>
-#include <vector>
-#include <thread>
-#include <unistd.h>
-#include <chrono>
-#include <cmath>
-// #include <fstream>
-// #include <stdint.h>
-// #include <unistd.h>
-// #include <sys/types.h>
-// #include <sys/stat.h>
-// #include <fcntl.h>
-
-// #include "../error.h"
-#include "../task/task_command_manager.h"
-#include "../error_code/error_code.h"
-#include "plc_task.h"
-#include "LibmodbusWrapper.h"
-#include "../tool/StdCondition.h"
-#include "plc_module.pb.h"
-#include "plc_message.pb.h"
-
-#include <google/protobuf/io/coded_stream.h>
-#include <google/protobuf/io/zero_copy_stream_impl.h>
-#include <google/protobuf/text_format.h>
-using google::protobuf::io::FileInputStream;
-using google::protobuf::io::FileOutputStream;
-using google::protobuf::io::ZeroCopyInputStream;
-using google::protobuf::io::CodedInputStream;
-using google::protobuf::io::ZeroCopyOutputStream;
-using google::protobuf::io::CodedOutputStream;
-using google::protobuf::Message;
-#include "glog/logging.h"
-
-#include <nnxx/message.h>
-#include <nnxx/message_control.h>
-#include <nnxx/socket.h>
-#include <nnxx/reqrep.h>
-//#include <nnxx/unittest.h>
-#include <nnxx/timeout.h>
-#include <nnxx/error.h>
-#include <cstring>
-#include <nnxx/message.h>
-
-const int PLC_SIGNAL_BEGIN_OFFSET=2;
-const int PLC_REGION_NUM=6;
-const int PLC_SIGNAL_NUM_PER_REGION=12;
-const int PLC_SLEEP_IN_MILLISECONDS=200;
-
-const int PLC_LASER_START_ADDR = 0;
-const int PLC_LASER_STATUS_ADDR = 1;
-const int PLC_LASER_X_ADDR = 2;
-const int PLC_LASER_Y_ADDR = 3;
-const int PLC_LASER_ANGLE_ADDR = 4;
-const int PLC_LASER_LENGTH_ADDR = 5;
-const int PLC_LASER_WIDTH_ADDR = 6;
-const int PLC_LASER_HEIGHT_ADDR = 7;
-const int PLC_LASER_CORRECTNESS_ADDR = 8;
-const int PLC_LASER_WHEELBASE_ADDR = 9;
-
-typedef Error_manager(*Command_Callback)(int terminal_id, void * p_owner);
-
-// plc通信类,modbus通信
-class Plc_Communicator
-{
-    
-public:
-    Plc_Communicator(plc_module::plc_connection_params connection_params);
-    ~Plc_Communicator();
-
-    // get set 方法
-    bool get_initialize_status();
-    bool get_connection();
-    Error_manager get_error();
-
-    // 设置plc检测到指令后外部回调函数
-    Error_manager set_plc_callback(Command_Callback callback, void * p_owner);
-    // 执行任务单
-    Error_manager execute_task(Task_Base* task);
-    // 获取实时数据
-    Error_manager get_plc_data(std::vector<uint16_t> &plc_data,int terminal_id=-1);
-    // 设置plc状态更新超时时间
-    Error_manager set_status_update_timeout(int millisecond);
-
-    struct plc_region_status{
-        std::chrono::steady_clock::time_point last_time_point;
-        int current_status;
-        int cmd;
-    };
-
-private:
-    // 读写线程函数
-    Error_manager ReadProtoParam(std::string path);
-    static void plc_update_thread(Plc_Communicator* plc_communicator);
-    static void plc_publish_message(Plc_Communicator* plc);
-    Error_manager write_result_to_plc(struct measure_result result);
-    // 连接函数
-    Error_manager connect();
-    Error_manager disconnect();
-
-private:
-    bool                mb_plc_is_connected;     // 指示plc连接状态
-    bool                mb_plc_initialized;      // 指示plc是否初始化
-    bool                mb_plc_is_updating;      // 指示plc线程在运行
-    void*               mp_plc_owner;            // 回调函数所有者句柄
-    Command_Callback    m_plc_callback;         // 回调函数
-
-    std::thread*        m_plc_message_thread;           // plc
-    std::thread*        m_plc_thread;           // plc更新线程句柄
-    StdCondition        m_plc_cond_exit;        // plc更新线程退出条件控制变量
-
-    std::mutex          m_plc_mutex;            // plc更新互斥锁,锁住与wrapper相关的所有操作
-    modbus::CLibmodbusWrapper   m_plc_wrapper;  // plc连接与读写封装实例
-
-    std::string         m_plc_ip_str;               // plc连接ip
-    int                 m_plc_port;             // plc连接端口
-    int                 m_plc_slave_id;         // plc连接id
-    int                 m_plc_status_update_timeout;    // plc状态更新超时时间
-
-    std::vector<uint16_t>   m_plc_data;         // 从plc获取的实时数据
-    Error_manager       m_plc_current_error;    // 当前plc出现的错误
-    // 当前系统状态,实时更新到plc。状态254-255每1秒互换,状态1从收到指令开始,紧接着改为状态2,
-    // 之后根据外部传入的task,决定写入3或4,默认3保留3秒,4持续保留直到新指令
-    plc_region_status   m_plc_region_status[PLC_REGION_NUM];   
-
-    // plc_module::plc_connection_params m_connection_params; // 连接参数
-};
-
-#endif // !PLC_COMMUNICATOR_HH

+ 182 - 0
plc/plc_data.cpp

@@ -0,0 +1,182 @@
+//
+// Created by zx on 2019/12/9.
+//
+
+#include "plc_data.h"
+#include <string.h>
+Plc_data *Plc_data::g_ins = 0;
+std::mutex Plc_data::g_lock;
+
+/**
+ * 获取单例句柄
+ * */
+Plc_data *Plc_data::get_instance(std::string ip)
+{
+    if (g_ins == 0)
+    {
+        std::lock_guard<std::mutex> lock(g_lock);
+        if (g_ins == 0)
+        {
+            if (ip != "")
+            {
+                g_ins = new Plc_data(ip);
+                LOG(INFO) << "plc data, handle created";
+            }
+            else
+            {
+                return 0;
+            }
+        }
+    }
+    return g_ins;
+}
+
+// void Plc_data::Release()
+// {
+//     if (g_ins)
+//     {
+//         g_ins->m_cond_exit.Notify(true);
+//         LOG(INFO) << "plc data, try to exit plc send thread";
+//         g_lock.lock();
+//         if (g_ins->p_send_thread)
+//         {
+//             LOG(INFO) << "plc data, try to join plc send thread";
+//             // LOG(INFO) << g_ins->p_send_thread->joinable();
+//             if (g_ins->p_send_thread->joinable())
+//                 g_ins->p_send_thread->join();
+//             LOG(INFO) << "plc data, try to delete plc send thread";
+//             delete g_ins->p_send_thread;
+//             g_ins->p_send_thread = 0;
+//             LOG(INFO) << "plc data, delete data send thread";
+//         }
+//         g_lock.unlock();
+
+//         LOG(INFO) << "plc data, start to exit plc handle";
+//         // if(g_instance->p_plc){
+//         //     LOG(INFO)<<"plc data, try to delete plc handle";
+//         //     delete g_instance->p_plc;
+//         //     g_instance->p_plc = 0;
+//         // }
+//         // LOG(INFO)<<"plc data, delete plc handle";
+//         LOG(INFO) << "plc data, delete instance";
+//         // delete g_ins;
+//         // g_ins = 0;
+//         LOG(INFO) << "plc data, instance deleted";
+//     }
+//     else
+//     {
+//         LOG(WARNING) << "plc data, cannot find the instance";
+//     }
+// }
+
+/**
+ * 更新区域状态
+ * */
+void Plc_data::update_data(int state_code, int border_status, int id)
+{
+//     LOG(INFO) << "plc data 更新数据 id: "<<id<<", code: "<<state_code;
+    if(id<0 || id>=MAX_REGIONS)
+        return ;
+    std::lock_guard<std::mutex> lock(g_lock);
+    m_data[2 * id] = state_code;
+    m_data[2 * id + 1] = border_status;
+}
+
+/**
+ * plc更新线程,将区域状态写入plc
+ * */
+void Plc_data::plc_update_thread(Plc_data *p)
+{
+    if (p == 0)
+    {
+        LOG(ERROR) << "plc update thread null pointer";
+        return;
+    }
+    while (!p->m_cond_exit.wait_for_millisecond(1))
+    {
+
+        // 判断plc状态
+        if (p->m_plc.getConnection() && p->mb_is_ready)
+        {
+
+
+            for (int i = 0; i < ELE_FENCE_COUNT; ++i)
+            {
+
+                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));
+
+                g_lock.unlock();
+                usleep(10 * 1000);
+            }
+
+        }
+        else
+        {
+            // 重连plc
+            LOG(WARNING) << "find plc connection error, trying to reconnect.";
+            g_lock.lock();
+            p->m_plc.disconnect();
+            // LOG(WARNING) << "find plc connection error, diconnect first.";
+            if (p->m_ip_str != "")
+            {
+                p->mb_is_ready = p->m_plc.connect(p->m_ip_str);
+                // LOG(WARNING) << "find plc connection error, trying to connect";
+                if (p->mb_is_ready)
+                {
+                    LOG(INFO) << "successfully reconnect.";
+                }
+                else
+                {
+                    LOG(WARNING) << "failed to connect plc.";
+                }
+            }
+            g_lock.unlock();
+            usleep(p->m_update_interval_milli * 5 * 1000);
+        }
+        usleep(p->m_update_interval_milli * 1000);
+    }
+}
+
+/**
+ * 有参构造
+ * */
+Plc_data::Plc_data(std::string ip) : mp_update_thread(0),
+                                     m_ip_str(""),
+                                     mb_is_ready(0)
+{
+    m_ip_str = ip;
+    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 != "")
+    {
+        if (m_plc.connect(m_ip_str))
+        {
+            mb_is_ready = true;
+        }
+        else
+        {
+            LOG(ERROR) << "Plc_data instance, connect failed";
+        }
+    }
+    else
+    {
+        LOG(ERROR) << "Plc_data instance, empty ip string.";
+    }
+    m_cond_exit.notify_all(false);
+    mp_update_thread = new std::thread(plc_update_thread, this);
+    mp_update_thread->detach();
+}
+
+/**
+ * 获取plc连接状态
+ * */
+bool Plc_data::get_plc_status()
+{
+    return mb_is_ready;
+}

+ 75 - 0
plc/plc_data.h

@@ -0,0 +1,75 @@
+//
+// Created by zx on 2019/12/9.
+//
+
+#ifndef PLC_DATA_H
+#define PLC_DATA_H
+#include <iostream>
+#include <string>
+#include <mutex>
+#include <atomic>
+#include "../tool/thread_condition.h"
+#include <thread>
+#include "../snap7_communication/s7_plc.h"
+#include "unistd.h"
+//#include "define.h"
+#include "glog/logging.h"
+
+#define MAX_REGIONS 6
+#define ELE_FENCE_BOUNDARY_START_ADDR 3
+#define ELE_FENCE_DB_NUM 95
+#define ELE_FENCE_OFFSET 7
+#define ELE_FENCE_COUNT 6
+
+#define CENTRAL_CONTROLLER_DB_NUM 41
+#define DOOR_STATUS_OFFSET 18
+
+
+class Plc_data
+{
+public:
+    // 获取plc通信类单例
+    static Plc_data *get_instance(std::string ip = "");
+    // static void Release();
+    // 更新区域状态数据
+    void update_data(int state_code, int border_status, int id);
+    // plc更新线程
+    static void plc_update_thread(Plc_data *p);
+    // 获取plc实时状态
+    bool get_plc_status();
+
+public:
+    std::atomic<bool> mb_is_ready; // 状态正常与否
+
+private:
+    static Plc_data *g_ins;   // 全局Plc_data实例
+    static std::mutex g_lock; // 全局Plc_data实例访问互斥锁
+
+    Thread_condition m_cond_exit;                // 系统关闭标志
+    std::thread *mp_update_thread;           // plc更新线程
+    S7PLC m_plc;                             // S7协议句柄
+    const int m_update_interval_milli = 100; // plc更新频率
+
+    // 有参构造函数
+    Plc_data(std::string ip);
+
+    // class CGarbo
+    // {
+    // public:
+    // 	~CGarbo() {
+    // 		if (g_ins)
+    // 		{
+    // 			delete g_ins;
+    // 			g_ins = 0;
+    // 		}
+    // 	}
+    // };
+    // static CGarbo Garbo;	//--->1
+
+protected:
+    short m_data[MAX_REGIONS*2];
+    short m_last_data[MAX_REGIONS*2];
+    std::string m_ip_str;
+};
+
+#endif //PLC_DATA_H

+ 0 - 357
plc/plc_message.pb.cc

@@ -1,357 +0,0 @@
-// Generated by the protocol buffer compiler.  DO NOT EDIT!
-// source: plc_message.proto
-
-#include "plc_message.pb.h"
-
-#include <algorithm>
-
-#include <google/protobuf/io/coded_stream.h>
-#include <google/protobuf/extension_set.h>
-#include <google/protobuf/wire_format_lite.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>
-// @@protoc_insertion_point(includes)
-#include <google/protobuf/port_def.inc>
-namespace plc_message {
-class plcMsgDefaultTypeInternal {
- public:
-  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<plcMsg> _instance;
-} _plcMsg_default_instance_;
-}  // namespace plc_message
-static void InitDefaultsscc_info_plcMsg_plc_5fmessage_2eproto() {
-  GOOGLE_PROTOBUF_VERIFY_VERSION;
-
-  {
-    void* ptr = &::plc_message::_plcMsg_default_instance_;
-    new (ptr) ::plc_message::plcMsg();
-    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
-  }
-  ::plc_message::plcMsg::InitAsDefaultInstance();
-}
-
-::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_plcMsg_plc_5fmessage_2eproto =
-    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_plcMsg_plc_5fmessage_2eproto}, {}};
-
-static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_plc_5fmessage_2eproto[1];
-static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_plc_5fmessage_2eproto[1];
-static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_plc_5fmessage_2eproto = nullptr;
-
-const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_plc_5fmessage_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
-  PROTOBUF_FIELD_OFFSET(::plc_message::plcMsg, _has_bits_),
-  PROTOBUF_FIELD_OFFSET(::plc_message::plcMsg, _internal_metadata_),
-  ~0u,  // no _extensions_
-  ~0u,  // no _oneof_case_
-  ~0u,  // no _weak_field_map_
-  PROTOBUF_FIELD_OFFSET(::plc_message::plcMsg, plc_status_),
-  PROTOBUF_FIELD_OFFSET(::plc_message::plcMsg, plc_values_),
-  0,
-  ~0u,
-};
-static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
-  { 0, 7, sizeof(::plc_message::plcMsg)},
-};
-
-static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
-  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::plc_message::_plcMsg_default_instance_),
-};
-
-const char descriptor_table_protodef_plc_5fmessage_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) =
-  "\n\021plc_message.proto\022\013plc_message\"H\n\006plcM"
-  "sg\022*\n\nplc_status\030\001 \001(\0162\026.plc_message.plc"
-  "Status\022\022\n\nplc_values\030\002 \003(\005*V\n\tplcStatus\022"
-  "\021\n\rePLCConnected\020\000\022\024\n\020ePLCDisconnected\020\001"
-  "\022\017\n\013ePLCRefused\020\002\022\017\n\013ePLCUnknown\020\003"
-  ;
-static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_plc_5fmessage_2eproto_deps[1] = {
-};
-static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_plc_5fmessage_2eproto_sccs[1] = {
-  &scc_info_plcMsg_plc_5fmessage_2eproto.base,
-};
-static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_plc_5fmessage_2eproto_once;
-const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_plc_5fmessage_2eproto = {
-  false, false, descriptor_table_protodef_plc_5fmessage_2eproto, "plc_message.proto", 194,
-  &descriptor_table_plc_5fmessage_2eproto_once, descriptor_table_plc_5fmessage_2eproto_sccs, descriptor_table_plc_5fmessage_2eproto_deps, 1, 0,
-  schemas, file_default_instances, TableStruct_plc_5fmessage_2eproto::offsets,
-  file_level_metadata_plc_5fmessage_2eproto, 1, file_level_enum_descriptors_plc_5fmessage_2eproto, file_level_service_descriptors_plc_5fmessage_2eproto,
-};
-
-// Force running AddDescriptors() at dynamic initialization time.
-static bool dynamic_init_dummy_plc_5fmessage_2eproto = (static_cast<void>(::PROTOBUF_NAMESPACE_ID::internal::AddDescriptors(&descriptor_table_plc_5fmessage_2eproto)), true);
-namespace plc_message {
-const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* plcStatus_descriptor() {
-  ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_plc_5fmessage_2eproto);
-  return file_level_enum_descriptors_plc_5fmessage_2eproto[0];
-}
-bool plcStatus_IsValid(int value) {
-  switch (value) {
-    case 0:
-    case 1:
-    case 2:
-    case 3:
-      return true;
-    default:
-      return false;
-  }
-}
-
-
-// ===================================================================
-
-void plcMsg::InitAsDefaultInstance() {
-}
-class plcMsg::_Internal {
- public:
-  using HasBits = decltype(std::declval<plcMsg>()._has_bits_);
-  static void set_has_plc_status(HasBits* has_bits) {
-    (*has_bits)[0] |= 1u;
-  }
-};
-
-plcMsg::plcMsg(::PROTOBUF_NAMESPACE_ID::Arena* arena)
-  : ::PROTOBUF_NAMESPACE_ID::Message(arena),
-  plc_values_(arena) {
-  SharedCtor();
-  RegisterArenaDtor(arena);
-  // @@protoc_insertion_point(arena_constructor:plc_message.plcMsg)
-}
-plcMsg::plcMsg(const plcMsg& from)
-  : ::PROTOBUF_NAMESPACE_ID::Message(),
-      _has_bits_(from._has_bits_),
-      plc_values_(from.plc_values_) {
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  plc_status_ = from.plc_status_;
-  // @@protoc_insertion_point(copy_constructor:plc_message.plcMsg)
-}
-
-void plcMsg::SharedCtor() {
-  plc_status_ = 0;
-}
-
-plcMsg::~plcMsg() {
-  // @@protoc_insertion_point(destructor:plc_message.plcMsg)
-  SharedDtor();
-  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-void plcMsg::SharedDtor() {
-  GOOGLE_DCHECK(GetArena() == nullptr);
-}
-
-void plcMsg::ArenaDtor(void* object) {
-  plcMsg* _this = reinterpret_cast< plcMsg* >(object);
-  (void)_this;
-}
-void plcMsg::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
-}
-void plcMsg::SetCachedSize(int size) const {
-  _cached_size_.Set(size);
-}
-const plcMsg& plcMsg::default_instance() {
-  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_plcMsg_plc_5fmessage_2eproto.base);
-  return *internal_default_instance();
-}
-
-
-void plcMsg::Clear() {
-// @@protoc_insertion_point(message_clear_start:plc_message.plcMsg)
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  // Prevent compiler warnings about cached_has_bits being unused
-  (void) cached_has_bits;
-
-  plc_values_.Clear();
-  plc_status_ = 0;
-  _has_bits_.Clear();
-  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-const char* plcMsg::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) {
-#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure
-  _Internal::HasBits has_bits{};
-  ::PROTOBUF_NAMESPACE_ID::Arena* arena = GetArena(); (void)arena;
-  while (!ctx->Done(&ptr)) {
-    ::PROTOBUF_NAMESPACE_ID::uint32 tag;
-    ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag);
-    CHK_(ptr);
-    switch (tag >> 3) {
-      // optional .plc_message.plcStatus plc_status = 1;
-      case 1:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) {
-          ::PROTOBUF_NAMESPACE_ID::uint64 val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
-          CHK_(ptr);
-          if (PROTOBUF_PREDICT_TRUE(::plc_message::plcStatus_IsValid(val))) {
-            _internal_set_plc_status(static_cast<::plc_message::plcStatus>(val));
-          } else {
-            ::PROTOBUF_NAMESPACE_ID::internal::WriteVarint(1, val, mutable_unknown_fields());
-          }
-        } else goto handle_unusual;
-        continue;
-      // repeated int32 plc_values = 2;
-      case 2:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 16)) {
-          ptr -= 1;
-          do {
-            ptr += 1;
-            _internal_add_plc_values(::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr));
-            CHK_(ptr);
-            if (!ctx->DataAvailable(ptr)) break;
-          } while (::PROTOBUF_NAMESPACE_ID::internal::ExpectTag<16>(ptr));
-        } else if (static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18) {
-          ptr = ::PROTOBUF_NAMESPACE_ID::internal::PackedInt32Parser(_internal_mutable_plc_values(), ptr, ctx);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      default: {
-      handle_unusual:
-        if ((tag & 7) == 4 || tag == 0) {
-          ctx->SetLastTag(tag);
-          goto success;
-        }
-        ptr = UnknownFieldParse(tag,
-            _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(),
-            ptr, ctx);
-        CHK_(ptr != nullptr);
-        continue;
-      }
-    }  // switch
-  }  // while
-success:
-  _has_bits_.Or(has_bits);
-  return ptr;
-failure:
-  ptr = nullptr;
-  goto success;
-#undef CHK_
-}
-
-::PROTOBUF_NAMESPACE_ID::uint8* plcMsg::_InternalSerialize(
-    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
-  // @@protoc_insertion_point(serialize_to_array_start:plc_message.plcMsg)
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  cached_has_bits = _has_bits_[0];
-  // optional .plc_message.plcStatus plc_status = 1;
-  if (cached_has_bits & 0x00000001u) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteEnumToArray(
-      1, this->_internal_plc_status(), target);
-  }
-
-  // repeated int32 plc_values = 2;
-  for (int i = 0, n = this->_internal_plc_values_size(); i < n; i++) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(2, this->_internal_plc_values(i), target);
-  }
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
-        _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
-  }
-  // @@protoc_insertion_point(serialize_to_array_end:plc_message.plcMsg)
-  return target;
-}
-
-size_t plcMsg::ByteSizeLong() const {
-// @@protoc_insertion_point(message_byte_size_start:plc_message.plcMsg)
-  size_t total_size = 0;
-
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  // Prevent compiler warnings about cached_has_bits being unused
-  (void) cached_has_bits;
-
-  // repeated int32 plc_values = 2;
-  {
-    size_t data_size = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      Int32Size(this->plc_values_);
-    total_size += 1 *
-                  ::PROTOBUF_NAMESPACE_ID::internal::FromIntSize(this->_internal_plc_values_size());
-    total_size += data_size;
-  }
-
-  // optional .plc_message.plcStatus plc_status = 1;
-  cached_has_bits = _has_bits_[0];
-  if (cached_has_bits & 0x00000001u) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::EnumSize(this->_internal_plc_status());
-  }
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
-        _internal_metadata_, total_size, &_cached_size_);
-  }
-  int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size);
-  SetCachedSize(cached_size);
-  return total_size;
-}
-
-void plcMsg::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_merge_from_start:plc_message.plcMsg)
-  GOOGLE_DCHECK_NE(&from, this);
-  const plcMsg* source =
-      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<plcMsg>(
-          &from);
-  if (source == nullptr) {
-  // @@protoc_insertion_point(generalized_merge_from_cast_fail:plc_message.plcMsg)
-    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
-  } else {
-  // @@protoc_insertion_point(generalized_merge_from_cast_success:plc_message.plcMsg)
-    MergeFrom(*source);
-  }
-}
-
-void plcMsg::MergeFrom(const plcMsg& from) {
-// @@protoc_insertion_point(class_specific_merge_from_start:plc_message.plcMsg)
-  GOOGLE_DCHECK_NE(&from, this);
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  plc_values_.MergeFrom(from.plc_values_);
-  if (from._internal_has_plc_status()) {
-    _internal_set_plc_status(from._internal_plc_status());
-  }
-}
-
-void plcMsg::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_copy_from_start:plc_message.plcMsg)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-void plcMsg::CopyFrom(const plcMsg& from) {
-// @@protoc_insertion_point(class_specific_copy_from_start:plc_message.plcMsg)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-bool plcMsg::IsInitialized() const {
-  return true;
-}
-
-void plcMsg::InternalSwap(plcMsg* other) {
-  using std::swap;
-  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
-  swap(_has_bits_[0], other->_has_bits_[0]);
-  plc_values_.InternalSwap(&other->plc_values_);
-  swap(plc_status_, other->plc_status_);
-}
-
-::PROTOBUF_NAMESPACE_ID::Metadata plcMsg::GetMetadata() const {
-  return GetMetadataStatic();
-}
-
-
-// @@protoc_insertion_point(namespace_scope)
-}  // namespace plc_message
-PROTOBUF_NAMESPACE_OPEN
-template<> PROTOBUF_NOINLINE ::plc_message::plcMsg* Arena::CreateMaybeMessage< ::plc_message::plcMsg >(Arena* arena) {
-  return Arena::CreateMessageInternal< ::plc_message::plcMsg >(arena);
-}
-PROTOBUF_NAMESPACE_CLOSE
-
-// @@protoc_insertion_point(global_scope)
-#include <google/protobuf/port_undef.inc>

+ 0 - 374
plc/plc_message.pb.h

@@ -1,374 +0,0 @@
-// Generated by the protocol buffer compiler.  DO NOT EDIT!
-// source: plc_message.proto
-
-#ifndef GOOGLE_PROTOBUF_INCLUDED_plc_5fmessage_2eproto
-#define GOOGLE_PROTOBUF_INCLUDED_plc_5fmessage_2eproto
-
-#include <limits>
-#include <string>
-
-#include <google/protobuf/port_def.inc>
-#if PROTOBUF_VERSION < 3013000
-#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 3013000 < 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/port_undef.inc>
-#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/inlined_string_field.h>
-#include <google/protobuf/metadata_lite.h>
-#include <google/protobuf/generated_message_reflection.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/generated_enum_reflection.h>
-#include <google/protobuf/unknown_field_set.h>
-// @@protoc_insertion_point(includes)
-#include <google/protobuf/port_def.inc>
-#define PROTOBUF_INTERNAL_EXPORT_plc_5fmessage_2eproto
-PROTOBUF_NAMESPACE_OPEN
-namespace internal {
-class AnyMetadata;
-}  // namespace internal
-PROTOBUF_NAMESPACE_CLOSE
-
-// Internal implementation detail -- do not use these members.
-struct TableStruct_plc_5fmessage_2eproto {
-  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTableField entries[]
-    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[]
-    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[1]
-    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[];
-  static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[];
-  static const ::PROTOBUF_NAMESPACE_ID::uint32 offsets[];
-};
-extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_plc_5fmessage_2eproto;
-namespace plc_message {
-class plcMsg;
-class plcMsgDefaultTypeInternal;
-extern plcMsgDefaultTypeInternal _plcMsg_default_instance_;
-}  // namespace plc_message
-PROTOBUF_NAMESPACE_OPEN
-template<> ::plc_message::plcMsg* Arena::CreateMaybeMessage<::plc_message::plcMsg>(Arena*);
-PROTOBUF_NAMESPACE_CLOSE
-namespace plc_message {
-
-enum plcStatus : int {
-  ePLCConnected = 0,
-  ePLCDisconnected = 1,
-  ePLCRefused = 2,
-  ePLCUnknown = 3
-};
-bool plcStatus_IsValid(int value);
-constexpr plcStatus plcStatus_MIN = ePLCConnected;
-constexpr plcStatus plcStatus_MAX = ePLCUnknown;
-constexpr int plcStatus_ARRAYSIZE = plcStatus_MAX + 1;
-
-const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* plcStatus_descriptor();
-template<typename T>
-inline const std::string& plcStatus_Name(T enum_t_value) {
-  static_assert(::std::is_same<T, plcStatus>::value ||
-    ::std::is_integral<T>::value,
-    "Incorrect type passed to function plcStatus_Name.");
-  return ::PROTOBUF_NAMESPACE_ID::internal::NameOfEnum(
-    plcStatus_descriptor(), enum_t_value);
-}
-inline bool plcStatus_Parse(
-    ::PROTOBUF_NAMESPACE_ID::ConstStringParam name, plcStatus* value) {
-  return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum<plcStatus>(
-    plcStatus_descriptor(), name, value);
-}
-// ===================================================================
-
-class plcMsg PROTOBUF_FINAL :
-    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:plc_message.plcMsg) */ {
- public:
-  inline plcMsg() : plcMsg(nullptr) {}
-  virtual ~plcMsg();
-
-  plcMsg(const plcMsg& from);
-  plcMsg(plcMsg&& from) noexcept
-    : plcMsg() {
-    *this = ::std::move(from);
-  }
-
-  inline plcMsg& operator=(const plcMsg& from) {
-    CopyFrom(from);
-    return *this;
-  }
-  inline plcMsg& operator=(plcMsg&& from) noexcept {
-    if (GetArena() == from.GetArena()) {
-      if (this != &from) InternalSwap(&from);
-    } else {
-      CopyFrom(from);
-    }
-    return *this;
-  }
-
-  inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const {
-    return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance);
-  }
-  inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() {
-    return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-  }
-
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() {
-    return GetDescriptor();
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() {
-    return GetMetadataStatic().descriptor;
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() {
-    return GetMetadataStatic().reflection;
-  }
-  static const plcMsg& default_instance();
-
-  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
-  static inline const plcMsg* internal_default_instance() {
-    return reinterpret_cast<const plcMsg*>(
-               &_plcMsg_default_instance_);
-  }
-  static constexpr int kIndexInFileMessages =
-    0;
-
-  friend void swap(plcMsg& a, plcMsg& b) {
-    a.Swap(&b);
-  }
-  inline void Swap(plcMsg* other) {
-    if (other == this) return;
-    if (GetArena() == other->GetArena()) {
-      InternalSwap(other);
-    } else {
-      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
-    }
-  }
-  void UnsafeArenaSwap(plcMsg* other) {
-    if (other == this) return;
-    GOOGLE_DCHECK(GetArena() == other->GetArena());
-    InternalSwap(other);
-  }
-
-  // implements Message ----------------------------------------------
-
-  inline plcMsg* New() const final {
-    return CreateMaybeMessage<plcMsg>(nullptr);
-  }
-
-  plcMsg* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
-    return CreateMaybeMessage<plcMsg>(arena);
-  }
-  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void CopyFrom(const plcMsg& from);
-  void MergeFrom(const plcMsg& from);
-  PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final;
-  bool IsInitialized() const final;
-
-  size_t ByteSizeLong() const final;
-  const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final;
-  ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize(
-      ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final;
-  int GetCachedSize() const final { return _cached_size_.Get(); }
-
-  private:
-  inline void SharedCtor();
-  inline void SharedDtor();
-  void SetCachedSize(int size) const final;
-  void InternalSwap(plcMsg* other);
-  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
-  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
-    return "plc_message.plcMsg";
-  }
-  protected:
-  explicit plcMsg(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  private:
-  static void ArenaDtor(void* object);
-  inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  public:
-
-  ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final;
-  private:
-  static ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadataStatic() {
-    ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&::descriptor_table_plc_5fmessage_2eproto);
-    return ::descriptor_table_plc_5fmessage_2eproto.file_level_metadata[kIndexInFileMessages];
-  }
-
-  public:
-
-  // nested types ----------------------------------------------------
-
-  // accessors -------------------------------------------------------
-
-  enum : int {
-    kPlcValuesFieldNumber = 2,
-    kPlcStatusFieldNumber = 1,
-  };
-  // repeated int32 plc_values = 2;
-  int plc_values_size() const;
-  private:
-  int _internal_plc_values_size() const;
-  public:
-  void clear_plc_values();
-  private:
-  ::PROTOBUF_NAMESPACE_ID::int32 _internal_plc_values(int index) const;
-  const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-      _internal_plc_values() const;
-  void _internal_add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value);
-  ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-      _internal_mutable_plc_values();
-  public:
-  ::PROTOBUF_NAMESPACE_ID::int32 plc_values(int index) const;
-  void set_plc_values(int index, ::PROTOBUF_NAMESPACE_ID::int32 value);
-  void add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value);
-  const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-      plc_values() const;
-  ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-      mutable_plc_values();
-
-  // optional .plc_message.plcStatus plc_status = 1;
-  bool has_plc_status() const;
-  private:
-  bool _internal_has_plc_status() const;
-  public:
-  void clear_plc_status();
-  ::plc_message::plcStatus plc_status() const;
-  void set_plc_status(::plc_message::plcStatus value);
-  private:
-  ::plc_message::plcStatus _internal_plc_status() const;
-  void _internal_set_plc_status(::plc_message::plcStatus value);
-  public:
-
-  // @@protoc_insertion_point(class_scope:plc_message.plcMsg)
- private:
-  class _Internal;
-
-  template <typename T> friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper;
-  typedef void InternalArenaConstructable_;
-  typedef void DestructorSkippable_;
-  ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_;
-  mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
-  ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 > plc_values_;
-  int plc_status_;
-  friend struct ::TableStruct_plc_5fmessage_2eproto;
-};
-// ===================================================================
-
-
-// ===================================================================
-
-#ifdef __GNUC__
-  #pragma GCC diagnostic push
-  #pragma GCC diagnostic ignored "-Wstrict-aliasing"
-#endif  // __GNUC__
-// plcMsg
-
-// optional .plc_message.plcStatus plc_status = 1;
-inline bool plcMsg::_internal_has_plc_status() const {
-  bool value = (_has_bits_[0] & 0x00000001u) != 0;
-  return value;
-}
-inline bool plcMsg::has_plc_status() const {
-  return _internal_has_plc_status();
-}
-inline void plcMsg::clear_plc_status() {
-  plc_status_ = 0;
-  _has_bits_[0] &= ~0x00000001u;
-}
-inline ::plc_message::plcStatus plcMsg::_internal_plc_status() const {
-  return static_cast< ::plc_message::plcStatus >(plc_status_);
-}
-inline ::plc_message::plcStatus plcMsg::plc_status() const {
-  // @@protoc_insertion_point(field_get:plc_message.plcMsg.plc_status)
-  return _internal_plc_status();
-}
-inline void plcMsg::_internal_set_plc_status(::plc_message::plcStatus value) {
-  assert(::plc_message::plcStatus_IsValid(value));
-  _has_bits_[0] |= 0x00000001u;
-  plc_status_ = value;
-}
-inline void plcMsg::set_plc_status(::plc_message::plcStatus value) {
-  _internal_set_plc_status(value);
-  // @@protoc_insertion_point(field_set:plc_message.plcMsg.plc_status)
-}
-
-// repeated int32 plc_values = 2;
-inline int plcMsg::_internal_plc_values_size() const {
-  return plc_values_.size();
-}
-inline int plcMsg::plc_values_size() const {
-  return _internal_plc_values_size();
-}
-inline void plcMsg::clear_plc_values() {
-  plc_values_.Clear();
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 plcMsg::_internal_plc_values(int index) const {
-  return plc_values_.Get(index);
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 plcMsg::plc_values(int index) const {
-  // @@protoc_insertion_point(field_get:plc_message.plcMsg.plc_values)
-  return _internal_plc_values(index);
-}
-inline void plcMsg::set_plc_values(int index, ::PROTOBUF_NAMESPACE_ID::int32 value) {
-  plc_values_.Set(index, value);
-  // @@protoc_insertion_point(field_set:plc_message.plcMsg.plc_values)
-}
-inline void plcMsg::_internal_add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  plc_values_.Add(value);
-}
-inline void plcMsg::add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  _internal_add_plc_values(value);
-  // @@protoc_insertion_point(field_add:plc_message.plcMsg.plc_values)
-}
-inline const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-plcMsg::_internal_plc_values() const {
-  return plc_values_;
-}
-inline const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-plcMsg::plc_values() const {
-  // @@protoc_insertion_point(field_list:plc_message.plcMsg.plc_values)
-  return _internal_plc_values();
-}
-inline ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-plcMsg::_internal_mutable_plc_values() {
-  return &plc_values_;
-}
-inline ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-plcMsg::mutable_plc_values() {
-  // @@protoc_insertion_point(field_mutable_list:plc_message.plcMsg.plc_values)
-  return _internal_mutable_plc_values();
-}
-
-#ifdef __GNUC__
-  #pragma GCC diagnostic pop
-#endif  // __GNUC__
-
-// @@protoc_insertion_point(namespace_scope)
-
-}  // namespace plc_message
-
-PROTOBUF_NAMESPACE_OPEN
-
-template <> struct is_proto_enum< ::plc_message::plcStatus> : ::std::true_type {};
-template <>
-inline const EnumDescriptor* GetEnumDescriptor< ::plc_message::plcStatus>() {
-  return ::plc_message::plcStatus_descriptor();
-}
-
-PROTOBUF_NAMESPACE_CLOSE
-
-// @@protoc_insertion_point(global_scope)
-
-#include <google/protobuf/port_undef.inc>
-#endif  // GOOGLE_PROTOBUF_INCLUDED_GOOGLE_PROTOBUF_INCLUDED_plc_5fmessage_2eproto

+ 0 - 16
plc/plc_message.proto

@@ -1,16 +0,0 @@
-syntax = "proto2";
-package plc_message;
-
-enum plcStatus
-{
-    ePLCConnected=0;
-    ePLCDisconnected=1;
-    ePLCRefused=2;
-    ePLCUnknown=3;
-}
-
-message plcMsg
-{
-    optional plcStatus plc_status=1;
-    repeated int32 plc_values=2;
-}

+ 0 - 146
plc/plc_modbus_uml.wsd

@@ -1,146 +0,0 @@
-@startuml
-
-title PLC模块
-
-note top of CLibmodbusWrapper
-    ×PLC底层封装类,非线程安全
-end note
-
-class CLibmodbusWrapper
-{
-    +CLibmodbusWrapper();
-    +virtual ~CLibmodbusWrapper();
-    +int initialize(const char *ip, int port, int slave_id);
-    +void deinitialize();
-    +int read_registers(int addr, int nb, uint16_t *dest);
-    +int write_registers(int addr, int nb, uint16_t *dest);
-    +int read_register(int addr, uint16_t *dest);
-    +int write_register(int addr, uint16_t *dest);
-    +inline bool is_connected() { return (0 == _ctx) ? false : true; };
-    +inline std::string getIP() { return _ip; };
-    +inline int getPort() { return _port; };
-    +inline int getSlave() { return _slave_id; };
-
-    -modbus_t* _ctx;
-    -std::string _ip;
-    -int _port;
-    -int _slave_id;
-}
-
-note right of Plc_Communicator
-    ×PLC通信类,核心模块,线程安全,包括:
-    ×根据plc信号调用回调进行测量
-    *将测量系统实时状态与测量结果写入plc
-end note
-
-class Plc_Communicator
-{
-    +Plc_Communicator(plc_module::plc_connection_params connection_params);
-    +~Plc_Communicator();
-    +bool get_initialize_status();// 获取初始化状态
-    +bool get_connection();// 获取连接状态
-    +Error_manager get_error();// 获取历史错误信息
-    +Error_manager set_plc_callback(Command_Callback callback, void * p_owner);// 设置plc检测到指令后外部回调函数
-    +Error_manager execute_task(Task_Base* task);// 执行任务单
-    +Error_manager get_plc_data(std::vector<uint16_t> &plc_data,int terminal_id=-1);// 获取实时数据
-    +Error_manager set_status_update_timeout(int millisecond);// 设置plc状态更新超时时间
-    +struct plc_region_status // 包含时间戳、指令信息、实时状态
-    {
-        std::chrono::steady_clock::time_point last_time_point;
-        int current_status;
-        int cmd;
-    };
-    -Error_manager ReadProtoParam(std::string path);// 读配置函数
-    -static void plc_update_thread(Plc_Communicator* plc_communicator);// 读PLC各雷达模块信息线程函数
-    -static void plc_publish_message(Plc_Communicator* plc);// 发布读取结果到UI线程函数
-    -Error_manager write_result_to_plc(struct measure_result result);// 写测量数据到PLC函数
-    -Error_manager connect();// 连接函数
-    -Error_manager disconnect();// 断开连接
-
-    -bool mb_plc_is_connected;// 指示plc连接状态
-    -bool mb_plc_initialized; // 指示plc是否初始化
-    -bool mb_plc_is_updating; // 指示plc线程在运行
-    -void* mp_plc_owner;  // 回调函数所有者句柄
-    -Command_Callback    m_plc_callback; // 回调函数
-    -std::thread*   m_plc_message_thread; // plc
-    -std::thread*   m_plc_thread; // plc更新线程句柄
-    -StdCondition   m_plc_cond_exit; // plc更新线程退出条件控制变量
-    -std::mutexm_plc_mutex; // plc更新互斥锁,锁住与wrapper相关的所有操作
-    -modbus::CLibmodbusWrapper  m_plc_wrapper; // plc连接与读写封装实例
-    -std::string    m_plc_ip_str;// plc连接ip
-    -int  m_plc_port; // plc连接端口
-    -int  m_plc_slave_id; // plc连接id
-    -int  m_plc_status_update_timeout; // plc状态更新超时时间
-    -std::vector<uint16_t>   m_plc_data; // 从plc获取的实时数据
-    -Error_manager       m_plc_current_error; // 当前plc出现的错误
-    // 当前系统状态,实时更新到plc。状态254-255每1秒互换,状态1从收到指令开始,紧接着改为状态2,
-    // 之后根据外部传入的task,决定写入3或4,默认3保留3秒,4持续保留直到新指令
-    -plc_region_status   m_plc_region_status[PLC_REGION_NUM];
-}
-
-class plc_message::plcMsg << (M,#00FF77) message>>
-{
-    plcStatus plc_status=1;
-    int32 plc_values=2;
-}
-
-class plc_module::plc_connection_params << (M,#00FF77) message>>
-{
-    string ip=1;
-    int32 port=2;
-    int32 slave_id=3;
-}
-
-class plc_module::Plc_msg << (M,#00FF77) message>>
-{
-    PLC_STATUS status=1;
-    int32 plc_values=2;
-}
-
-class Plc_Task
-{
-    +virtual Error_manager init(); 
-    +Plc_Task();
-    +~Plc_Task();
-    +Error_manager set_result(struct measure_result result);// 将测量结果存入该任务单
-    +Error_manager get_result(struct measure_result &result);// 将测量结果传出
-    +bool get_result_set_flag();// 获取测量结果是否已存入该任务单的指标
-
-    -struct measure_result m_measure_result;// 存放测量结果
-    -bool mb_result_set_flag;// 已获取结果
-    -struct measure_result
-    {
-        int terminal_id;
-        float x;
-        float y;
-        float angle;
-        float length;
-        float width;
-        float height;
-        float wheel_base;
-        bool correctness;
-    };
-}
-
-class Task_Base
-{
-    +Task_Base();
-    +~Task_Base();
-    +virtual Error_manager init();//初始化任务单,初始任务单类型为 UNKONW_TASK
-    +Error_manager update_statu(Task_statu task_statu,std::string statu_information="");更新任务单; task_statu: 任务状态; statu_information:状态说明
-    +Task_type   get_task_type();//获取任务类型
-    +Task_statu  get_statu();//获取任务单状态
-    +std::string get_statu_information();//获取状态说明
-    -Task_type    m_task_type;
-    -Task_statu   m_task_statu;//任务状态
-    -std::string  m_task_statu_information;   //任务状态说明
-}
-
-Task_Base <|-- Plc_Task
-Plc_Communicator <-- Plc_Task
-Plc_Communicator <-- plc_message::plcMsg
-Plc_Communicator <-- plc_module::plc_connection_params
-Plc_Communicator <-- plc_module::Plc_msg
-Plc_Communicator <-- CLibmodbusWrapper
-
-@enduml

+ 0 - 722
plc/plc_module.pb.cc

@@ -1,722 +0,0 @@
-// Generated by the protocol buffer compiler.  DO NOT EDIT!
-// source: plc_module.proto
-
-#include "plc_module.pb.h"
-
-#include <algorithm>
-
-#include <google/protobuf/io/coded_stream.h>
-#include <google/protobuf/extension_set.h>
-#include <google/protobuf/wire_format_lite.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>
-// @@protoc_insertion_point(includes)
-#include <google/protobuf/port_def.inc>
-namespace plc_module {
-class plc_connection_paramsDefaultTypeInternal {
- public:
-  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<plc_connection_params> _instance;
-} _plc_connection_params_default_instance_;
-class Plc_msgDefaultTypeInternal {
- public:
-  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<Plc_msg> _instance;
-} _Plc_msg_default_instance_;
-}  // namespace plc_module
-static void InitDefaultsscc_info_Plc_msg_plc_5fmodule_2eproto() {
-  GOOGLE_PROTOBUF_VERIFY_VERSION;
-
-  {
-    void* ptr = &::plc_module::_Plc_msg_default_instance_;
-    new (ptr) ::plc_module::Plc_msg();
-    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
-  }
-  ::plc_module::Plc_msg::InitAsDefaultInstance();
-}
-
-::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_Plc_msg_plc_5fmodule_2eproto =
-    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_Plc_msg_plc_5fmodule_2eproto}, {}};
-
-static void InitDefaultsscc_info_plc_connection_params_plc_5fmodule_2eproto() {
-  GOOGLE_PROTOBUF_VERIFY_VERSION;
-
-  {
-    void* ptr = &::plc_module::_plc_connection_params_default_instance_;
-    new (ptr) ::plc_module::plc_connection_params();
-    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
-  }
-  ::plc_module::plc_connection_params::InitAsDefaultInstance();
-}
-
-::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_plc_connection_params_plc_5fmodule_2eproto =
-    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_plc_connection_params_plc_5fmodule_2eproto}, {}};
-
-static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_plc_5fmodule_2eproto[2];
-static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_plc_5fmodule_2eproto[1];
-static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_plc_5fmodule_2eproto = nullptr;
-
-const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_plc_5fmodule_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
-  PROTOBUF_FIELD_OFFSET(::plc_module::plc_connection_params, _has_bits_),
-  PROTOBUF_FIELD_OFFSET(::plc_module::plc_connection_params, _internal_metadata_),
-  ~0u,  // no _extensions_
-  ~0u,  // no _oneof_case_
-  ~0u,  // no _weak_field_map_
-  PROTOBUF_FIELD_OFFSET(::plc_module::plc_connection_params, ip_),
-  PROTOBUF_FIELD_OFFSET(::plc_module::plc_connection_params, port_),
-  PROTOBUF_FIELD_OFFSET(::plc_module::plc_connection_params, slave_id_),
-  0,
-  1,
-  2,
-  PROTOBUF_FIELD_OFFSET(::plc_module::Plc_msg, _has_bits_),
-  PROTOBUF_FIELD_OFFSET(::plc_module::Plc_msg, _internal_metadata_),
-  ~0u,  // no _extensions_
-  ~0u,  // no _oneof_case_
-  ~0u,  // no _weak_field_map_
-  PROTOBUF_FIELD_OFFSET(::plc_module::Plc_msg, status_),
-  PROTOBUF_FIELD_OFFSET(::plc_module::Plc_msg, plc_values_),
-  0,
-  ~0u,
-};
-static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
-  { 0, 8, sizeof(::plc_module::plc_connection_params)},
-  { 11, 18, sizeof(::plc_module::Plc_msg)},
-};
-
-static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
-  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::plc_module::_plc_connection_params_default_instance_),
-  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::plc_module::_Plc_msg_default_instance_),
-};
-
-const char descriptor_table_protodef_plc_5fmodule_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) =
-  "\n\020plc_module.proto\022\nplc_module\"C\n\025plc_co"
-  "nnection_params\022\n\n\002ip\030\001 \002(\t\022\014\n\004port\030\002 \002("
-  "\005\022\020\n\010slave_id\030\003 \002(\005\"E\n\007Plc_msg\022&\n\006status"
-  "\030\001 \001(\0162\026.plc_module.PLC_STATUS\022\022\n\nplc_va"
-  "lues\030\002 \003(\005*W\n\nPLC_STATUS\022\021\n\rePLCConnecte"
-  "d\020\000\022\024\n\020ePLCDisconnected\020\001\022\017\n\013ePLCRefused"
-  "\020\002\022\017\n\013ePLCUnknown\020\003"
-  ;
-static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_plc_5fmodule_2eproto_deps[1] = {
-};
-static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_plc_5fmodule_2eproto_sccs[2] = {
-  &scc_info_Plc_msg_plc_5fmodule_2eproto.base,
-  &scc_info_plc_connection_params_plc_5fmodule_2eproto.base,
-};
-static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_plc_5fmodule_2eproto_once;
-const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_plc_5fmodule_2eproto = {
-  false, false, descriptor_table_protodef_plc_5fmodule_2eproto, "plc_module.proto", 259,
-  &descriptor_table_plc_5fmodule_2eproto_once, descriptor_table_plc_5fmodule_2eproto_sccs, descriptor_table_plc_5fmodule_2eproto_deps, 2, 0,
-  schemas, file_default_instances, TableStruct_plc_5fmodule_2eproto::offsets,
-  file_level_metadata_plc_5fmodule_2eproto, 2, file_level_enum_descriptors_plc_5fmodule_2eproto, file_level_service_descriptors_plc_5fmodule_2eproto,
-};
-
-// Force running AddDescriptors() at dynamic initialization time.
-static bool dynamic_init_dummy_plc_5fmodule_2eproto = (static_cast<void>(::PROTOBUF_NAMESPACE_ID::internal::AddDescriptors(&descriptor_table_plc_5fmodule_2eproto)), true);
-namespace plc_module {
-const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* PLC_STATUS_descriptor() {
-  ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_plc_5fmodule_2eproto);
-  return file_level_enum_descriptors_plc_5fmodule_2eproto[0];
-}
-bool PLC_STATUS_IsValid(int value) {
-  switch (value) {
-    case 0:
-    case 1:
-    case 2:
-    case 3:
-      return true;
-    default:
-      return false;
-  }
-}
-
-
-// ===================================================================
-
-void plc_connection_params::InitAsDefaultInstance() {
-}
-class plc_connection_params::_Internal {
- public:
-  using HasBits = decltype(std::declval<plc_connection_params>()._has_bits_);
-  static void set_has_ip(HasBits* has_bits) {
-    (*has_bits)[0] |= 1u;
-  }
-  static void set_has_port(HasBits* has_bits) {
-    (*has_bits)[0] |= 2u;
-  }
-  static void set_has_slave_id(HasBits* has_bits) {
-    (*has_bits)[0] |= 4u;
-  }
-  static bool MissingRequiredFields(const HasBits& has_bits) {
-    return ((has_bits[0] & 0x00000007) ^ 0x00000007) != 0;
-  }
-};
-
-plc_connection_params::plc_connection_params(::PROTOBUF_NAMESPACE_ID::Arena* arena)
-  : ::PROTOBUF_NAMESPACE_ID::Message(arena) {
-  SharedCtor();
-  RegisterArenaDtor(arena);
-  // @@protoc_insertion_point(arena_constructor:plc_module.plc_connection_params)
-}
-plc_connection_params::plc_connection_params(const plc_connection_params& from)
-  : ::PROTOBUF_NAMESPACE_ID::Message(),
-      _has_bits_(from._has_bits_) {
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  ip_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited());
-  if (from._internal_has_ip()) {
-    ip_.Set(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), from._internal_ip(),
-      GetArena());
-  }
-  ::memcpy(&port_, &from.port_,
-    static_cast<size_t>(reinterpret_cast<char*>(&slave_id_) -
-    reinterpret_cast<char*>(&port_)) + sizeof(slave_id_));
-  // @@protoc_insertion_point(copy_constructor:plc_module.plc_connection_params)
-}
-
-void plc_connection_params::SharedCtor() {
-  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&scc_info_plc_connection_params_plc_5fmodule_2eproto.base);
-  ip_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited());
-  ::memset(&port_, 0, static_cast<size_t>(
-      reinterpret_cast<char*>(&slave_id_) -
-      reinterpret_cast<char*>(&port_)) + sizeof(slave_id_));
-}
-
-plc_connection_params::~plc_connection_params() {
-  // @@protoc_insertion_point(destructor:plc_module.plc_connection_params)
-  SharedDtor();
-  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-void plc_connection_params::SharedDtor() {
-  GOOGLE_DCHECK(GetArena() == nullptr);
-  ip_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited());
-}
-
-void plc_connection_params::ArenaDtor(void* object) {
-  plc_connection_params* _this = reinterpret_cast< plc_connection_params* >(object);
-  (void)_this;
-}
-void plc_connection_params::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
-}
-void plc_connection_params::SetCachedSize(int size) const {
-  _cached_size_.Set(size);
-}
-const plc_connection_params& plc_connection_params::default_instance() {
-  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_plc_connection_params_plc_5fmodule_2eproto.base);
-  return *internal_default_instance();
-}
-
-
-void plc_connection_params::Clear() {
-// @@protoc_insertion_point(message_clear_start:plc_module.plc_connection_params)
-  ::PROTOBUF_NAMESPACE_ID::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 & 0x00000001u) {
-    ip_.ClearNonDefaultToEmpty();
-  }
-  if (cached_has_bits & 0x00000006u) {
-    ::memset(&port_, 0, static_cast<size_t>(
-        reinterpret_cast<char*>(&slave_id_) -
-        reinterpret_cast<char*>(&port_)) + sizeof(slave_id_));
-  }
-  _has_bits_.Clear();
-  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-const char* plc_connection_params::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) {
-#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure
-  _Internal::HasBits has_bits{};
-  ::PROTOBUF_NAMESPACE_ID::Arena* arena = GetArena(); (void)arena;
-  while (!ctx->Done(&ptr)) {
-    ::PROTOBUF_NAMESPACE_ID::uint32 tag;
-    ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag);
-    CHK_(ptr);
-    switch (tag >> 3) {
-      // required string ip = 1;
-      case 1:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) {
-          auto str = _internal_mutable_ip();
-          ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx);
-          #ifndef NDEBUG
-          ::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "plc_module.plc_connection_params.ip");
-          #endif  // !NDEBUG
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      // required int32 port = 2;
-      case 2:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 16)) {
-          _Internal::set_has_port(&has_bits);
-          port_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      // required int32 slave_id = 3;
-      case 3:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 24)) {
-          _Internal::set_has_slave_id(&has_bits);
-          slave_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      default: {
-      handle_unusual:
-        if ((tag & 7) == 4 || tag == 0) {
-          ctx->SetLastTag(tag);
-          goto success;
-        }
-        ptr = UnknownFieldParse(tag,
-            _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(),
-            ptr, ctx);
-        CHK_(ptr != nullptr);
-        continue;
-      }
-    }  // switch
-  }  // while
-success:
-  _has_bits_.Or(has_bits);
-  return ptr;
-failure:
-  ptr = nullptr;
-  goto success;
-#undef CHK_
-}
-
-::PROTOBUF_NAMESPACE_ID::uint8* plc_connection_params::_InternalSerialize(
-    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
-  // @@protoc_insertion_point(serialize_to_array_start:plc_module.plc_connection_params)
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  cached_has_bits = _has_bits_[0];
-  // required string ip = 1;
-  if (cached_has_bits & 0x00000001u) {
-    ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::VerifyUTF8StringNamedField(
-      this->_internal_ip().data(), static_cast<int>(this->_internal_ip().length()),
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::SERIALIZE,
-      "plc_module.plc_connection_params.ip");
-    target = stream->WriteStringMaybeAliased(
-        1, this->_internal_ip(), target);
-  }
-
-  // required int32 port = 2;
-  if (cached_has_bits & 0x00000002u) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(2, this->_internal_port(), target);
-  }
-
-  // required int32 slave_id = 3;
-  if (cached_has_bits & 0x00000004u) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(3, this->_internal_slave_id(), target);
-  }
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
-        _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
-  }
-  // @@protoc_insertion_point(serialize_to_array_end:plc_module.plc_connection_params)
-  return target;
-}
-
-size_t plc_connection_params::RequiredFieldsByteSizeFallback() const {
-// @@protoc_insertion_point(required_fields_byte_size_fallback_start:plc_module.plc_connection_params)
-  size_t total_size = 0;
-
-  if (_internal_has_ip()) {
-    // required string ip = 1;
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize(
-        this->_internal_ip());
-  }
-
-  if (_internal_has_port()) {
-    // required int32 port = 2;
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
-        this->_internal_port());
-  }
-
-  if (_internal_has_slave_id()) {
-    // required int32 slave_id = 3;
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
-        this->_internal_slave_id());
-  }
-
-  return total_size;
-}
-size_t plc_connection_params::ByteSizeLong() const {
-// @@protoc_insertion_point(message_byte_size_start:plc_module.plc_connection_params)
-  size_t total_size = 0;
-
-  if (((_has_bits_[0] & 0x00000007) ^ 0x00000007) == 0) {  // All required fields are present.
-    // required string ip = 1;
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize(
-        this->_internal_ip());
-
-    // required int32 port = 2;
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
-        this->_internal_port());
-
-    // required int32 slave_id = 3;
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
-        this->_internal_slave_id());
-
-  } else {
-    total_size += RequiredFieldsByteSizeFallback();
-  }
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  // Prevent compiler warnings about cached_has_bits being unused
-  (void) cached_has_bits;
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
-        _internal_metadata_, total_size, &_cached_size_);
-  }
-  int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size);
-  SetCachedSize(cached_size);
-  return total_size;
-}
-
-void plc_connection_params::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_merge_from_start:plc_module.plc_connection_params)
-  GOOGLE_DCHECK_NE(&from, this);
-  const plc_connection_params* source =
-      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<plc_connection_params>(
-          &from);
-  if (source == nullptr) {
-  // @@protoc_insertion_point(generalized_merge_from_cast_fail:plc_module.plc_connection_params)
-    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
-  } else {
-  // @@protoc_insertion_point(generalized_merge_from_cast_success:plc_module.plc_connection_params)
-    MergeFrom(*source);
-  }
-}
-
-void plc_connection_params::MergeFrom(const plc_connection_params& from) {
-// @@protoc_insertion_point(class_specific_merge_from_start:plc_module.plc_connection_params)
-  GOOGLE_DCHECK_NE(&from, this);
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  cached_has_bits = from._has_bits_[0];
-  if (cached_has_bits & 0x00000007u) {
-    if (cached_has_bits & 0x00000001u) {
-      _internal_set_ip(from._internal_ip());
-    }
-    if (cached_has_bits & 0x00000002u) {
-      port_ = from.port_;
-    }
-    if (cached_has_bits & 0x00000004u) {
-      slave_id_ = from.slave_id_;
-    }
-    _has_bits_[0] |= cached_has_bits;
-  }
-}
-
-void plc_connection_params::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_copy_from_start:plc_module.plc_connection_params)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-void plc_connection_params::CopyFrom(const plc_connection_params& from) {
-// @@protoc_insertion_point(class_specific_copy_from_start:plc_module.plc_connection_params)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-bool plc_connection_params::IsInitialized() const {
-  if (_Internal::MissingRequiredFields(_has_bits_)) return false;
-  return true;
-}
-
-void plc_connection_params::InternalSwap(plc_connection_params* other) {
-  using std::swap;
-  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
-  swap(_has_bits_[0], other->_has_bits_[0]);
-  ip_.Swap(&other->ip_, &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArena());
-  ::PROTOBUF_NAMESPACE_ID::internal::memswap<
-      PROTOBUF_FIELD_OFFSET(plc_connection_params, slave_id_)
-      + sizeof(plc_connection_params::slave_id_)
-      - PROTOBUF_FIELD_OFFSET(plc_connection_params, port_)>(
-          reinterpret_cast<char*>(&port_),
-          reinterpret_cast<char*>(&other->port_));
-}
-
-::PROTOBUF_NAMESPACE_ID::Metadata plc_connection_params::GetMetadata() const {
-  return GetMetadataStatic();
-}
-
-
-// ===================================================================
-
-void Plc_msg::InitAsDefaultInstance() {
-}
-class Plc_msg::_Internal {
- public:
-  using HasBits = decltype(std::declval<Plc_msg>()._has_bits_);
-  static void set_has_status(HasBits* has_bits) {
-    (*has_bits)[0] |= 1u;
-  }
-};
-
-Plc_msg::Plc_msg(::PROTOBUF_NAMESPACE_ID::Arena* arena)
-  : ::PROTOBUF_NAMESPACE_ID::Message(arena),
-  plc_values_(arena) {
-  SharedCtor();
-  RegisterArenaDtor(arena);
-  // @@protoc_insertion_point(arena_constructor:plc_module.Plc_msg)
-}
-Plc_msg::Plc_msg(const Plc_msg& from)
-  : ::PROTOBUF_NAMESPACE_ID::Message(),
-      _has_bits_(from._has_bits_),
-      plc_values_(from.plc_values_) {
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  status_ = from.status_;
-  // @@protoc_insertion_point(copy_constructor:plc_module.Plc_msg)
-}
-
-void Plc_msg::SharedCtor() {
-  status_ = 0;
-}
-
-Plc_msg::~Plc_msg() {
-  // @@protoc_insertion_point(destructor:plc_module.Plc_msg)
-  SharedDtor();
-  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-void Plc_msg::SharedDtor() {
-  GOOGLE_DCHECK(GetArena() == nullptr);
-}
-
-void Plc_msg::ArenaDtor(void* object) {
-  Plc_msg* _this = reinterpret_cast< Plc_msg* >(object);
-  (void)_this;
-}
-void Plc_msg::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
-}
-void Plc_msg::SetCachedSize(int size) const {
-  _cached_size_.Set(size);
-}
-const Plc_msg& Plc_msg::default_instance() {
-  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_Plc_msg_plc_5fmodule_2eproto.base);
-  return *internal_default_instance();
-}
-
-
-void Plc_msg::Clear() {
-// @@protoc_insertion_point(message_clear_start:plc_module.Plc_msg)
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  // Prevent compiler warnings about cached_has_bits being unused
-  (void) cached_has_bits;
-
-  plc_values_.Clear();
-  status_ = 0;
-  _has_bits_.Clear();
-  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-const char* Plc_msg::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) {
-#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure
-  _Internal::HasBits has_bits{};
-  ::PROTOBUF_NAMESPACE_ID::Arena* arena = GetArena(); (void)arena;
-  while (!ctx->Done(&ptr)) {
-    ::PROTOBUF_NAMESPACE_ID::uint32 tag;
-    ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag);
-    CHK_(ptr);
-    switch (tag >> 3) {
-      // optional .plc_module.PLC_STATUS status = 1;
-      case 1:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) {
-          ::PROTOBUF_NAMESPACE_ID::uint64 val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
-          CHK_(ptr);
-          if (PROTOBUF_PREDICT_TRUE(::plc_module::PLC_STATUS_IsValid(val))) {
-            _internal_set_status(static_cast<::plc_module::PLC_STATUS>(val));
-          } else {
-            ::PROTOBUF_NAMESPACE_ID::internal::WriteVarint(1, val, mutable_unknown_fields());
-          }
-        } else goto handle_unusual;
-        continue;
-      // repeated int32 plc_values = 2;
-      case 2:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 16)) {
-          ptr -= 1;
-          do {
-            ptr += 1;
-            _internal_add_plc_values(::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr));
-            CHK_(ptr);
-            if (!ctx->DataAvailable(ptr)) break;
-          } while (::PROTOBUF_NAMESPACE_ID::internal::ExpectTag<16>(ptr));
-        } else if (static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 18) {
-          ptr = ::PROTOBUF_NAMESPACE_ID::internal::PackedInt32Parser(_internal_mutable_plc_values(), ptr, ctx);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      default: {
-      handle_unusual:
-        if ((tag & 7) == 4 || tag == 0) {
-          ctx->SetLastTag(tag);
-          goto success;
-        }
-        ptr = UnknownFieldParse(tag,
-            _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(),
-            ptr, ctx);
-        CHK_(ptr != nullptr);
-        continue;
-      }
-    }  // switch
-  }  // while
-success:
-  _has_bits_.Or(has_bits);
-  return ptr;
-failure:
-  ptr = nullptr;
-  goto success;
-#undef CHK_
-}
-
-::PROTOBUF_NAMESPACE_ID::uint8* Plc_msg::_InternalSerialize(
-    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
-  // @@protoc_insertion_point(serialize_to_array_start:plc_module.Plc_msg)
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  cached_has_bits = _has_bits_[0];
-  // optional .plc_module.PLC_STATUS status = 1;
-  if (cached_has_bits & 0x00000001u) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteEnumToArray(
-      1, this->_internal_status(), target);
-  }
-
-  // repeated int32 plc_values = 2;
-  for (int i = 0, n = this->_internal_plc_values_size(); i < n; i++) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(2, this->_internal_plc_values(i), target);
-  }
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
-        _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
-  }
-  // @@protoc_insertion_point(serialize_to_array_end:plc_module.Plc_msg)
-  return target;
-}
-
-size_t Plc_msg::ByteSizeLong() const {
-// @@protoc_insertion_point(message_byte_size_start:plc_module.Plc_msg)
-  size_t total_size = 0;
-
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  // Prevent compiler warnings about cached_has_bits being unused
-  (void) cached_has_bits;
-
-  // repeated int32 plc_values = 2;
-  {
-    size_t data_size = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      Int32Size(this->plc_values_);
-    total_size += 1 *
-                  ::PROTOBUF_NAMESPACE_ID::internal::FromIntSize(this->_internal_plc_values_size());
-    total_size += data_size;
-  }
-
-  // optional .plc_module.PLC_STATUS status = 1;
-  cached_has_bits = _has_bits_[0];
-  if (cached_has_bits & 0x00000001u) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::EnumSize(this->_internal_status());
-  }
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
-        _internal_metadata_, total_size, &_cached_size_);
-  }
-  int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size);
-  SetCachedSize(cached_size);
-  return total_size;
-}
-
-void Plc_msg::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_merge_from_start:plc_module.Plc_msg)
-  GOOGLE_DCHECK_NE(&from, this);
-  const Plc_msg* source =
-      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<Plc_msg>(
-          &from);
-  if (source == nullptr) {
-  // @@protoc_insertion_point(generalized_merge_from_cast_fail:plc_module.Plc_msg)
-    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
-  } else {
-  // @@protoc_insertion_point(generalized_merge_from_cast_success:plc_module.Plc_msg)
-    MergeFrom(*source);
-  }
-}
-
-void Plc_msg::MergeFrom(const Plc_msg& from) {
-// @@protoc_insertion_point(class_specific_merge_from_start:plc_module.Plc_msg)
-  GOOGLE_DCHECK_NE(&from, this);
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  plc_values_.MergeFrom(from.plc_values_);
-  if (from._internal_has_status()) {
-    _internal_set_status(from._internal_status());
-  }
-}
-
-void Plc_msg::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_copy_from_start:plc_module.Plc_msg)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-void Plc_msg::CopyFrom(const Plc_msg& from) {
-// @@protoc_insertion_point(class_specific_copy_from_start:plc_module.Plc_msg)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-bool Plc_msg::IsInitialized() const {
-  return true;
-}
-
-void Plc_msg::InternalSwap(Plc_msg* other) {
-  using std::swap;
-  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
-  swap(_has_bits_[0], other->_has_bits_[0]);
-  plc_values_.InternalSwap(&other->plc_values_);
-  swap(status_, other->status_);
-}
-
-::PROTOBUF_NAMESPACE_ID::Metadata Plc_msg::GetMetadata() const {
-  return GetMetadataStatic();
-}
-
-
-// @@protoc_insertion_point(namespace_scope)
-}  // namespace plc_module
-PROTOBUF_NAMESPACE_OPEN
-template<> PROTOBUF_NOINLINE ::plc_module::plc_connection_params* Arena::CreateMaybeMessage< ::plc_module::plc_connection_params >(Arena* arena) {
-  return Arena::CreateMessageInternal< ::plc_module::plc_connection_params >(arena);
-}
-template<> PROTOBUF_NOINLINE ::plc_module::Plc_msg* Arena::CreateMaybeMessage< ::plc_module::Plc_msg >(Arena* arena) {
-  return Arena::CreateMessageInternal< ::plc_module::Plc_msg >(arena);
-}
-PROTOBUF_NAMESPACE_CLOSE
-
-// @@protoc_insertion_point(global_scope)
-#include <google/protobuf/port_undef.inc>

+ 0 - 703
plc/plc_module.pb.h

@@ -1,703 +0,0 @@
-// Generated by the protocol buffer compiler.  DO NOT EDIT!
-// source: plc_module.proto
-
-#ifndef GOOGLE_PROTOBUF_INCLUDED_plc_5fmodule_2eproto
-#define GOOGLE_PROTOBUF_INCLUDED_plc_5fmodule_2eproto
-
-#include <limits>
-#include <string>
-
-#include <google/protobuf/port_def.inc>
-#if PROTOBUF_VERSION < 3013000
-#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 3013000 < 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/port_undef.inc>
-#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/inlined_string_field.h>
-#include <google/protobuf/metadata_lite.h>
-#include <google/protobuf/generated_message_reflection.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/generated_enum_reflection.h>
-#include <google/protobuf/unknown_field_set.h>
-// @@protoc_insertion_point(includes)
-#include <google/protobuf/port_def.inc>
-#define PROTOBUF_INTERNAL_EXPORT_plc_5fmodule_2eproto
-PROTOBUF_NAMESPACE_OPEN
-namespace internal {
-class AnyMetadata;
-}  // namespace internal
-PROTOBUF_NAMESPACE_CLOSE
-
-// Internal implementation detail -- do not use these members.
-struct TableStruct_plc_5fmodule_2eproto {
-  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTableField entries[]
-    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[]
-    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[2]
-    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[];
-  static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[];
-  static const ::PROTOBUF_NAMESPACE_ID::uint32 offsets[];
-};
-extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_plc_5fmodule_2eproto;
-namespace plc_module {
-class Plc_msg;
-class Plc_msgDefaultTypeInternal;
-extern Plc_msgDefaultTypeInternal _Plc_msg_default_instance_;
-class plc_connection_params;
-class plc_connection_paramsDefaultTypeInternal;
-extern plc_connection_paramsDefaultTypeInternal _plc_connection_params_default_instance_;
-}  // namespace plc_module
-PROTOBUF_NAMESPACE_OPEN
-template<> ::plc_module::Plc_msg* Arena::CreateMaybeMessage<::plc_module::Plc_msg>(Arena*);
-template<> ::plc_module::plc_connection_params* Arena::CreateMaybeMessage<::plc_module::plc_connection_params>(Arena*);
-PROTOBUF_NAMESPACE_CLOSE
-namespace plc_module {
-
-enum PLC_STATUS : int {
-  ePLCConnected = 0,
-  ePLCDisconnected = 1,
-  ePLCRefused = 2,
-  ePLCUnknown = 3
-};
-bool PLC_STATUS_IsValid(int value);
-constexpr PLC_STATUS PLC_STATUS_MIN = ePLCConnected;
-constexpr PLC_STATUS PLC_STATUS_MAX = ePLCUnknown;
-constexpr int PLC_STATUS_ARRAYSIZE = PLC_STATUS_MAX + 1;
-
-const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* PLC_STATUS_descriptor();
-template<typename T>
-inline const std::string& PLC_STATUS_Name(T enum_t_value) {
-  static_assert(::std::is_same<T, PLC_STATUS>::value ||
-    ::std::is_integral<T>::value,
-    "Incorrect type passed to function PLC_STATUS_Name.");
-  return ::PROTOBUF_NAMESPACE_ID::internal::NameOfEnum(
-    PLC_STATUS_descriptor(), enum_t_value);
-}
-inline bool PLC_STATUS_Parse(
-    ::PROTOBUF_NAMESPACE_ID::ConstStringParam name, PLC_STATUS* value) {
-  return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum<PLC_STATUS>(
-    PLC_STATUS_descriptor(), name, value);
-}
-// ===================================================================
-
-class plc_connection_params PROTOBUF_FINAL :
-    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:plc_module.plc_connection_params) */ {
- public:
-  inline plc_connection_params() : plc_connection_params(nullptr) {}
-  virtual ~plc_connection_params();
-
-  plc_connection_params(const plc_connection_params& from);
-  plc_connection_params(plc_connection_params&& from) noexcept
-    : plc_connection_params() {
-    *this = ::std::move(from);
-  }
-
-  inline plc_connection_params& operator=(const plc_connection_params& from) {
-    CopyFrom(from);
-    return *this;
-  }
-  inline plc_connection_params& operator=(plc_connection_params&& from) noexcept {
-    if (GetArena() == from.GetArena()) {
-      if (this != &from) InternalSwap(&from);
-    } else {
-      CopyFrom(from);
-    }
-    return *this;
-  }
-
-  inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const {
-    return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance);
-  }
-  inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() {
-    return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-  }
-
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() {
-    return GetDescriptor();
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() {
-    return GetMetadataStatic().descriptor;
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() {
-    return GetMetadataStatic().reflection;
-  }
-  static const plc_connection_params& default_instance();
-
-  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
-  static inline const plc_connection_params* internal_default_instance() {
-    return reinterpret_cast<const plc_connection_params*>(
-               &_plc_connection_params_default_instance_);
-  }
-  static constexpr int kIndexInFileMessages =
-    0;
-
-  friend void swap(plc_connection_params& a, plc_connection_params& b) {
-    a.Swap(&b);
-  }
-  inline void Swap(plc_connection_params* other) {
-    if (other == this) return;
-    if (GetArena() == other->GetArena()) {
-      InternalSwap(other);
-    } else {
-      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
-    }
-  }
-  void UnsafeArenaSwap(plc_connection_params* other) {
-    if (other == this) return;
-    GOOGLE_DCHECK(GetArena() == other->GetArena());
-    InternalSwap(other);
-  }
-
-  // implements Message ----------------------------------------------
-
-  inline plc_connection_params* New() const final {
-    return CreateMaybeMessage<plc_connection_params>(nullptr);
-  }
-
-  plc_connection_params* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
-    return CreateMaybeMessage<plc_connection_params>(arena);
-  }
-  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void CopyFrom(const plc_connection_params& from);
-  void MergeFrom(const plc_connection_params& from);
-  PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final;
-  bool IsInitialized() const final;
-
-  size_t ByteSizeLong() const final;
-  const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final;
-  ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize(
-      ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final;
-  int GetCachedSize() const final { return _cached_size_.Get(); }
-
-  private:
-  inline void SharedCtor();
-  inline void SharedDtor();
-  void SetCachedSize(int size) const final;
-  void InternalSwap(plc_connection_params* other);
-  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
-  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
-    return "plc_module.plc_connection_params";
-  }
-  protected:
-  explicit plc_connection_params(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  private:
-  static void ArenaDtor(void* object);
-  inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  public:
-
-  ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final;
-  private:
-  static ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadataStatic() {
-    ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&::descriptor_table_plc_5fmodule_2eproto);
-    return ::descriptor_table_plc_5fmodule_2eproto.file_level_metadata[kIndexInFileMessages];
-  }
-
-  public:
-
-  // nested types ----------------------------------------------------
-
-  // accessors -------------------------------------------------------
-
-  enum : int {
-    kIpFieldNumber = 1,
-    kPortFieldNumber = 2,
-    kSlaveIdFieldNumber = 3,
-  };
-  // required string ip = 1;
-  bool has_ip() const;
-  private:
-  bool _internal_has_ip() const;
-  public:
-  void clear_ip();
-  const std::string& ip() const;
-  void set_ip(const std::string& value);
-  void set_ip(std::string&& value);
-  void set_ip(const char* value);
-  void set_ip(const char* value, size_t size);
-  std::string* mutable_ip();
-  std::string* release_ip();
-  void set_allocated_ip(std::string* ip);
-  private:
-  const std::string& _internal_ip() const;
-  void _internal_set_ip(const std::string& value);
-  std::string* _internal_mutable_ip();
-  public:
-
-  // required int32 port = 2;
-  bool has_port() const;
-  private:
-  bool _internal_has_port() const;
-  public:
-  void clear_port();
-  ::PROTOBUF_NAMESPACE_ID::int32 port() const;
-  void set_port(::PROTOBUF_NAMESPACE_ID::int32 value);
-  private:
-  ::PROTOBUF_NAMESPACE_ID::int32 _internal_port() const;
-  void _internal_set_port(::PROTOBUF_NAMESPACE_ID::int32 value);
-  public:
-
-  // required int32 slave_id = 3;
-  bool has_slave_id() const;
-  private:
-  bool _internal_has_slave_id() const;
-  public:
-  void clear_slave_id();
-  ::PROTOBUF_NAMESPACE_ID::int32 slave_id() const;
-  void set_slave_id(::PROTOBUF_NAMESPACE_ID::int32 value);
-  private:
-  ::PROTOBUF_NAMESPACE_ID::int32 _internal_slave_id() const;
-  void _internal_set_slave_id(::PROTOBUF_NAMESPACE_ID::int32 value);
-  public:
-
-  // @@protoc_insertion_point(class_scope:plc_module.plc_connection_params)
- private:
-  class _Internal;
-
-  // helper for ByteSizeLong()
-  size_t RequiredFieldsByteSizeFallback() const;
-
-  template <typename T> friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper;
-  typedef void InternalArenaConstructable_;
-  typedef void DestructorSkippable_;
-  ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_;
-  mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
-  ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr ip_;
-  ::PROTOBUF_NAMESPACE_ID::int32 port_;
-  ::PROTOBUF_NAMESPACE_ID::int32 slave_id_;
-  friend struct ::TableStruct_plc_5fmodule_2eproto;
-};
-// -------------------------------------------------------------------
-
-class Plc_msg PROTOBUF_FINAL :
-    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:plc_module.Plc_msg) */ {
- public:
-  inline Plc_msg() : Plc_msg(nullptr) {}
-  virtual ~Plc_msg();
-
-  Plc_msg(const Plc_msg& from);
-  Plc_msg(Plc_msg&& from) noexcept
-    : Plc_msg() {
-    *this = ::std::move(from);
-  }
-
-  inline Plc_msg& operator=(const Plc_msg& from) {
-    CopyFrom(from);
-    return *this;
-  }
-  inline Plc_msg& operator=(Plc_msg&& from) noexcept {
-    if (GetArena() == from.GetArena()) {
-      if (this != &from) InternalSwap(&from);
-    } else {
-      CopyFrom(from);
-    }
-    return *this;
-  }
-
-  inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const {
-    return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance);
-  }
-  inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() {
-    return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-  }
-
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() {
-    return GetDescriptor();
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() {
-    return GetMetadataStatic().descriptor;
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() {
-    return GetMetadataStatic().reflection;
-  }
-  static const Plc_msg& default_instance();
-
-  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
-  static inline const Plc_msg* internal_default_instance() {
-    return reinterpret_cast<const Plc_msg*>(
-               &_Plc_msg_default_instance_);
-  }
-  static constexpr int kIndexInFileMessages =
-    1;
-
-  friend void swap(Plc_msg& a, Plc_msg& b) {
-    a.Swap(&b);
-  }
-  inline void Swap(Plc_msg* other) {
-    if (other == this) return;
-    if (GetArena() == other->GetArena()) {
-      InternalSwap(other);
-    } else {
-      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
-    }
-  }
-  void UnsafeArenaSwap(Plc_msg* other) {
-    if (other == this) return;
-    GOOGLE_DCHECK(GetArena() == other->GetArena());
-    InternalSwap(other);
-  }
-
-  // implements Message ----------------------------------------------
-
-  inline Plc_msg* New() const final {
-    return CreateMaybeMessage<Plc_msg>(nullptr);
-  }
-
-  Plc_msg* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
-    return CreateMaybeMessage<Plc_msg>(arena);
-  }
-  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void CopyFrom(const Plc_msg& from);
-  void MergeFrom(const Plc_msg& from);
-  PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final;
-  bool IsInitialized() const final;
-
-  size_t ByteSizeLong() const final;
-  const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final;
-  ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize(
-      ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final;
-  int GetCachedSize() const final { return _cached_size_.Get(); }
-
-  private:
-  inline void SharedCtor();
-  inline void SharedDtor();
-  void SetCachedSize(int size) const final;
-  void InternalSwap(Plc_msg* other);
-  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
-  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
-    return "plc_module.Plc_msg";
-  }
-  protected:
-  explicit Plc_msg(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  private:
-  static void ArenaDtor(void* object);
-  inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  public:
-
-  ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final;
-  private:
-  static ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadataStatic() {
-    ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&::descriptor_table_plc_5fmodule_2eproto);
-    return ::descriptor_table_plc_5fmodule_2eproto.file_level_metadata[kIndexInFileMessages];
-  }
-
-  public:
-
-  // nested types ----------------------------------------------------
-
-  // accessors -------------------------------------------------------
-
-  enum : int {
-    kPlcValuesFieldNumber = 2,
-    kStatusFieldNumber = 1,
-  };
-  // repeated int32 plc_values = 2;
-  int plc_values_size() const;
-  private:
-  int _internal_plc_values_size() const;
-  public:
-  void clear_plc_values();
-  private:
-  ::PROTOBUF_NAMESPACE_ID::int32 _internal_plc_values(int index) const;
-  const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-      _internal_plc_values() const;
-  void _internal_add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value);
-  ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-      _internal_mutable_plc_values();
-  public:
-  ::PROTOBUF_NAMESPACE_ID::int32 plc_values(int index) const;
-  void set_plc_values(int index, ::PROTOBUF_NAMESPACE_ID::int32 value);
-  void add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value);
-  const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-      plc_values() const;
-  ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-      mutable_plc_values();
-
-  // optional .plc_module.PLC_STATUS status = 1;
-  bool has_status() const;
-  private:
-  bool _internal_has_status() const;
-  public:
-  void clear_status();
-  ::plc_module::PLC_STATUS status() const;
-  void set_status(::plc_module::PLC_STATUS value);
-  private:
-  ::plc_module::PLC_STATUS _internal_status() const;
-  void _internal_set_status(::plc_module::PLC_STATUS value);
-  public:
-
-  // @@protoc_insertion_point(class_scope:plc_module.Plc_msg)
- private:
-  class _Internal;
-
-  template <typename T> friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper;
-  typedef void InternalArenaConstructable_;
-  typedef void DestructorSkippable_;
-  ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_;
-  mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
-  ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 > plc_values_;
-  int status_;
-  friend struct ::TableStruct_plc_5fmodule_2eproto;
-};
-// ===================================================================
-
-
-// ===================================================================
-
-#ifdef __GNUC__
-  #pragma GCC diagnostic push
-  #pragma GCC diagnostic ignored "-Wstrict-aliasing"
-#endif  // __GNUC__
-// plc_connection_params
-
-// required string ip = 1;
-inline bool plc_connection_params::_internal_has_ip() const {
-  bool value = (_has_bits_[0] & 0x00000001u) != 0;
-  return value;
-}
-inline bool plc_connection_params::has_ip() const {
-  return _internal_has_ip();
-}
-inline void plc_connection_params::clear_ip() {
-  ip_.ClearToEmpty(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArena());
-  _has_bits_[0] &= ~0x00000001u;
-}
-inline const std::string& plc_connection_params::ip() const {
-  // @@protoc_insertion_point(field_get:plc_module.plc_connection_params.ip)
-  return _internal_ip();
-}
-inline void plc_connection_params::set_ip(const std::string& value) {
-  _internal_set_ip(value);
-  // @@protoc_insertion_point(field_set:plc_module.plc_connection_params.ip)
-}
-inline std::string* plc_connection_params::mutable_ip() {
-  // @@protoc_insertion_point(field_mutable:plc_module.plc_connection_params.ip)
-  return _internal_mutable_ip();
-}
-inline const std::string& plc_connection_params::_internal_ip() const {
-  return ip_.Get();
-}
-inline void plc_connection_params::_internal_set_ip(const std::string& value) {
-  _has_bits_[0] |= 0x00000001u;
-  ip_.Set(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), value, GetArena());
-}
-inline void plc_connection_params::set_ip(std::string&& value) {
-  _has_bits_[0] |= 0x00000001u;
-  ip_.Set(
-    &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), ::std::move(value), GetArena());
-  // @@protoc_insertion_point(field_set_rvalue:plc_module.plc_connection_params.ip)
-}
-inline void plc_connection_params::set_ip(const char* value) {
-  GOOGLE_DCHECK(value != nullptr);
-  _has_bits_[0] |= 0x00000001u;
-  ip_.Set(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), ::std::string(value),
-              GetArena());
-  // @@protoc_insertion_point(field_set_char:plc_module.plc_connection_params.ip)
-}
-inline void plc_connection_params::set_ip(const char* value,
-    size_t size) {
-  _has_bits_[0] |= 0x00000001u;
-  ip_.Set(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), ::std::string(
-      reinterpret_cast<const char*>(value), size), GetArena());
-  // @@protoc_insertion_point(field_set_pointer:plc_module.plc_connection_params.ip)
-}
-inline std::string* plc_connection_params::_internal_mutable_ip() {
-  _has_bits_[0] |= 0x00000001u;
-  return ip_.Mutable(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArena());
-}
-inline std::string* plc_connection_params::release_ip() {
-  // @@protoc_insertion_point(field_release:plc_module.plc_connection_params.ip)
-  if (!_internal_has_ip()) {
-    return nullptr;
-  }
-  _has_bits_[0] &= ~0x00000001u;
-  return ip_.ReleaseNonDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArena());
-}
-inline void plc_connection_params::set_allocated_ip(std::string* ip) {
-  if (ip != nullptr) {
-    _has_bits_[0] |= 0x00000001u;
-  } else {
-    _has_bits_[0] &= ~0x00000001u;
-  }
-  ip_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), ip,
-      GetArena());
-  // @@protoc_insertion_point(field_set_allocated:plc_module.plc_connection_params.ip)
-}
-
-// required int32 port = 2;
-inline bool plc_connection_params::_internal_has_port() const {
-  bool value = (_has_bits_[0] & 0x00000002u) != 0;
-  return value;
-}
-inline bool plc_connection_params::has_port() const {
-  return _internal_has_port();
-}
-inline void plc_connection_params::clear_port() {
-  port_ = 0;
-  _has_bits_[0] &= ~0x00000002u;
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 plc_connection_params::_internal_port() const {
-  return port_;
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 plc_connection_params::port() const {
-  // @@protoc_insertion_point(field_get:plc_module.plc_connection_params.port)
-  return _internal_port();
-}
-inline void plc_connection_params::_internal_set_port(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  _has_bits_[0] |= 0x00000002u;
-  port_ = value;
-}
-inline void plc_connection_params::set_port(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  _internal_set_port(value);
-  // @@protoc_insertion_point(field_set:plc_module.plc_connection_params.port)
-}
-
-// required int32 slave_id = 3;
-inline bool plc_connection_params::_internal_has_slave_id() const {
-  bool value = (_has_bits_[0] & 0x00000004u) != 0;
-  return value;
-}
-inline bool plc_connection_params::has_slave_id() const {
-  return _internal_has_slave_id();
-}
-inline void plc_connection_params::clear_slave_id() {
-  slave_id_ = 0;
-  _has_bits_[0] &= ~0x00000004u;
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 plc_connection_params::_internal_slave_id() const {
-  return slave_id_;
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 plc_connection_params::slave_id() const {
-  // @@protoc_insertion_point(field_get:plc_module.plc_connection_params.slave_id)
-  return _internal_slave_id();
-}
-inline void plc_connection_params::_internal_set_slave_id(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  _has_bits_[0] |= 0x00000004u;
-  slave_id_ = value;
-}
-inline void plc_connection_params::set_slave_id(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  _internal_set_slave_id(value);
-  // @@protoc_insertion_point(field_set:plc_module.plc_connection_params.slave_id)
-}
-
-// -------------------------------------------------------------------
-
-// Plc_msg
-
-// optional .plc_module.PLC_STATUS status = 1;
-inline bool Plc_msg::_internal_has_status() const {
-  bool value = (_has_bits_[0] & 0x00000001u) != 0;
-  return value;
-}
-inline bool Plc_msg::has_status() const {
-  return _internal_has_status();
-}
-inline void Plc_msg::clear_status() {
-  status_ = 0;
-  _has_bits_[0] &= ~0x00000001u;
-}
-inline ::plc_module::PLC_STATUS Plc_msg::_internal_status() const {
-  return static_cast< ::plc_module::PLC_STATUS >(status_);
-}
-inline ::plc_module::PLC_STATUS Plc_msg::status() const {
-  // @@protoc_insertion_point(field_get:plc_module.Plc_msg.status)
-  return _internal_status();
-}
-inline void Plc_msg::_internal_set_status(::plc_module::PLC_STATUS value) {
-  assert(::plc_module::PLC_STATUS_IsValid(value));
-  _has_bits_[0] |= 0x00000001u;
-  status_ = value;
-}
-inline void Plc_msg::set_status(::plc_module::PLC_STATUS value) {
-  _internal_set_status(value);
-  // @@protoc_insertion_point(field_set:plc_module.Plc_msg.status)
-}
-
-// repeated int32 plc_values = 2;
-inline int Plc_msg::_internal_plc_values_size() const {
-  return plc_values_.size();
-}
-inline int Plc_msg::plc_values_size() const {
-  return _internal_plc_values_size();
-}
-inline void Plc_msg::clear_plc_values() {
-  plc_values_.Clear();
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 Plc_msg::_internal_plc_values(int index) const {
-  return plc_values_.Get(index);
-}
-inline ::PROTOBUF_NAMESPACE_ID::int32 Plc_msg::plc_values(int index) const {
-  // @@protoc_insertion_point(field_get:plc_module.Plc_msg.plc_values)
-  return _internal_plc_values(index);
-}
-inline void Plc_msg::set_plc_values(int index, ::PROTOBUF_NAMESPACE_ID::int32 value) {
-  plc_values_.Set(index, value);
-  // @@protoc_insertion_point(field_set:plc_module.Plc_msg.plc_values)
-}
-inline void Plc_msg::_internal_add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  plc_values_.Add(value);
-}
-inline void Plc_msg::add_plc_values(::PROTOBUF_NAMESPACE_ID::int32 value) {
-  _internal_add_plc_values(value);
-  // @@protoc_insertion_point(field_add:plc_module.Plc_msg.plc_values)
-}
-inline const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-Plc_msg::_internal_plc_values() const {
-  return plc_values_;
-}
-inline const ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >&
-Plc_msg::plc_values() const {
-  // @@protoc_insertion_point(field_list:plc_module.Plc_msg.plc_values)
-  return _internal_plc_values();
-}
-inline ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-Plc_msg::_internal_mutable_plc_values() {
-  return &plc_values_;
-}
-inline ::PROTOBUF_NAMESPACE_ID::RepeatedField< ::PROTOBUF_NAMESPACE_ID::int32 >*
-Plc_msg::mutable_plc_values() {
-  // @@protoc_insertion_point(field_mutable_list:plc_module.Plc_msg.plc_values)
-  return _internal_mutable_plc_values();
-}
-
-#ifdef __GNUC__
-  #pragma GCC diagnostic pop
-#endif  // __GNUC__
-// -------------------------------------------------------------------
-
-
-// @@protoc_insertion_point(namespace_scope)
-
-}  // namespace plc_module
-
-PROTOBUF_NAMESPACE_OPEN
-
-template <> struct is_proto_enum< ::plc_module::PLC_STATUS> : ::std::true_type {};
-template <>
-inline const EnumDescriptor* GetEnumDescriptor< ::plc_module::PLC_STATUS>() {
-  return ::plc_module::PLC_STATUS_descriptor();
-}
-
-PROTOBUF_NAMESPACE_CLOSE
-
-// @@protoc_insertion_point(global_scope)
-
-#include <google/protobuf/port_undef.inc>
-#endif  // GOOGLE_PROTOBUF_INCLUDED_GOOGLE_PROTOBUF_INCLUDED_plc_5fmodule_2eproto

+ 0 - 22
plc/plc_module.proto

@@ -1,22 +0,0 @@
-syntax = "proto2";
-package plc_module;
-
-message plc_connection_params{
-    required string ip=1;
-    required int32 port=2;
-    required int32 slave_id=3;
-}
-
-enum PLC_STATUS
-{
-	ePLCConnected=0;
-	ePLCDisconnected=1;
-	ePLCRefused=2;
-	ePLCUnknown=3;
-}
-
-message Plc_msg
-{
-	optional PLC_STATUS status=1;
-	repeated int32 plc_values=2;
-}

+ 0 - 46
plc/plc_task.cpp

@@ -1,46 +0,0 @@
-#include "plc_task.h"
-
-Plc_Task::Plc_Task(){
-    m_task_type = Task_type::PLC_TASK;
-    mb_result_set_flag = false;
-}
-
-Plc_Task::~Plc_Task(){
-
-}
-
-Error_manager Plc_Task::init(){
-    m_measure_result.terminal_id = -1;
-    m_measure_result.correctness = false;
-    m_measure_result.x = 0;
-    m_measure_result.y = 0;
-    m_measure_result.angle = 0;
-    m_measure_result.length = 0;
-    m_measure_result.width = 0;
-    m_measure_result.height = 0;
-    m_measure_result.wheel_base = 0;
-    m_task_statu = Task_statu::TASK_CREATED;
-    return SUCCESS;
-}
-
-Error_manager Plc_Task::get_result(struct measure_result &result){
-    if(mb_result_set_flag)
-    {
-        memcpy(&result, &m_measure_result, sizeof(m_measure_result));
-        return Error_manager(Error_code::SUCCESS, Error_level::NORMAL, "成功获取测量结果");
-    }
-    else
-    {
-        return Error_manager(Error_code::FAILED, Error_level::NEGLIGIBLE_ERROR, "未获得测量结果,或许是由于在set之前被调用");
-    }
-}
-
-Error_manager Plc_Task::set_result(struct measure_result result){
-    memcpy(&m_measure_result, &result, sizeof(result));
-    mb_result_set_flag = true;
-    return Error_manager(Error_code::SUCCESS, Error_level::NORMAL, "设置测量结果成功");
-}
-
-bool Plc_Task::get_result_set_flag(){
-    return mb_result_set_flag;
-}

+ 0 - 41
plc/plc_task.h

@@ -1,41 +0,0 @@
-#ifndef PLC_TASK_HH
-#define PLC_TASK_HH
-#include <string.h>
-
-#include "../task/task_command_manager.h"
-// #include "../error.h"
-#include "../error_code/error_code.h"
-
-struct measure_result
-{
-    int terminal_id;
-    float x;
-    float y;
-    float angle;
-    float length;
-    float width;
-    float height;
-    float wheel_base;
-    bool correctness;
-};
-
-class Plc_Task : public Task_Base
-{
-public:
-    virtual Error_manager init();
-    
-    Plc_Task();
-    ~Plc_Task();
-    // 将测量结果存入该任务单
-    Error_manager set_result(struct measure_result result);
-    // 将测量结果传出
-    Error_manager get_result(struct measure_result &result);
-    // 获取测量结果是否已存入该任务单的指标
-    bool get_result_set_flag();
-
-private:
-struct measure_result   m_measure_result;
-bool                    mb_result_set_flag;
-};
-
-#endif // !PLC_TASK_HH

+ 85 - 0
plc/s7_plc.cpp

@@ -0,0 +1,85 @@
+#include "s7_plc.h"
+
+S7PLC::S7PLC():bConnected_(false)
+{
+}
+S7PLC::~S7PLC()
+{
+    disconnect();
+}
+
+bool S7PLC::getConnection(){
+    return bConnected_;
+}
+
+bool S7PLC::connect(std::string ip)    
+{
+    std::lock_guard<std::mutex> lck (mutex_);
+    int ret=client_.ConnectTo(ip.c_str(),0,1);
+    bConnected_=(ret==0);
+    return bConnected_;
+}
+
+bool S7PLC::ReadShorts(int DBNumber,int start,int size,short* pdata)
+{
+    short* plc_data= (short*)malloc(size*sizeof(short));
+    bool ret=read_dbs(DBNumber,start*sizeof(short),size*sizeof(short),pdata);
+    if(ret)
+    {
+        reverse_byte(pdata,size*sizeof(short),plc_data);
+        for(int i=0;i<size;++i)
+            pdata[i]=plc_data[size-i-1];
+    }
+    free(plc_data);
+    return ret;
+
+}
+    bool S7PLC::WriteShorts(int DBNumber,int start,int size,short* pdata)
+    {
+        short* plc_data=(short*)malloc(size*sizeof(short));
+        memcpy(plc_data,pdata,size*sizeof(short));
+        for(int i=0;i<size;++i)
+            plc_data[i]=HTON(plc_data[i]);
+
+        bool ret=write_dbs(DBNumber,start*sizeof(short),size*sizeof(short),plc_data);
+        free(plc_data);
+        return ret;
+    }
+
+ bool S7PLC::read_dbs(int DBNumber,int start,int size,void* pdata)
+ {
+     std::lock_guard<std::mutex> lck (mutex_);
+     usleep(1000* 50);
+     if(bConnected_==false)
+        return false;
+     
+     int ret=client_.AsDBRead(DBNumber,start,size,pdata);
+
+     return ret == 0;
+ }
+ bool S7PLC::write_dbs(int DBNumber, int start, int size, void *pdata)
+ {
+    std::lock_guard<std::mutex> lck(mutex_);
+    usleep(1000*50);
+     if(bConnected_==false)
+        return false;
+     
+     int ret = client_.AsDBWrite(DBNumber, start, size, pdata);
+
+     return ret == 0;
+ }
+ void S7PLC::disconnect()
+ {
+     std::lock_guard<std::mutex> lck(mutex_);
+     client_.Disconnect();
+ }
+
+ void S7PLC::reverse_byte(void* pdata,int num_byte,void* out)
+ {
+     char* pin=(char*)pdata;
+     char* pout=(char*)out;
+     for(int i=0;i<num_byte;++i)
+     {
+         pout[i]=pin[num_byte-i-1];
+     }
+ }

+ 32 - 0
plc/s7_plc.h

@@ -0,0 +1,32 @@
+#ifndef S7__PLC__H
+#define S7__PLC__H
+
+#include <s7_client.h>
+#include <mutex>
+#include <iostream>
+
+class S7PLC
+{
+public:
+#define HTON(T) ((T) << 8) | ((T) >> 8)
+protected:
+    bool        bConnected_;
+    std::mutex  mutex_;
+    TSnap7Client client_;
+public:
+    S7PLC();
+    ~S7PLC();
+
+    bool connect(std::string ip);
+    bool getConnection();
+    bool ReadShorts(int DBNumber,int start,int size,short* pdata);
+    bool WriteShorts(int DBNumber,int start,int size,short* pdata);
+    void disconnect();
+private:
+    bool read_dbs(int DBNumber,int start,int size,void* pdata);
+    bool write_dbs(int DBNumber,int start,int size,void* pdata);
+    void reverse_byte(void* pdata,int num_byte,void* out);
+
+};
+
+#endif // !S7__PLC__H

+ 236 - 0
plc/snap7_buf.cpp

@@ -0,0 +1,236 @@
+
+
+
+#include "snap7_buf.h"
+#include <string>
+#include <string.h>
+
+Snap7_buf::Snap7_buf()
+{
+	m_id = 0;
+	m_start_index = 0;
+	m_size = 0;
+	mp_buf_obverse = nullptr;
+	mp_buf_reverse = nullptr;
+	m_communication_mode = NO_COMMUNICATION;
+
+}
+Snap7_buf::Snap7_buf(const Snap7_buf& other)
+{
+	m_id = other.m_id;
+	m_start_index = other.m_start_index;
+	m_communication_mode = other.m_communication_mode;
+
+	if ( other.m_size > 0 && other.mp_buf_obverse != nullptr && other.mp_buf_reverse != nullptr)
+	{
+		mp_buf_obverse = (void*)malloc(other.m_size);
+		memcpy(mp_buf_obverse, other.mp_buf_obverse, other.m_size);
+		mp_buf_reverse = (void*)malloc(other.m_size);
+		memcpy(mp_buf_reverse, other.mp_buf_reverse, other.m_size);
+		m_size = other.m_size;
+		m_variable_information_vector=other.m_variable_information_vector;
+	}
+}
+Snap7_buf& Snap7_buf::operator =(const Snap7_buf& other)
+{
+	m_id = other.m_id;
+	m_start_index = other.m_start_index;
+	m_communication_mode = other.m_communication_mode;
+
+	if ( other.m_size > 0 && other.mp_buf_obverse != nullptr && other.mp_buf_reverse != nullptr)
+	{
+		mp_buf_obverse = (void*)malloc(other.m_size);
+		memcpy(mp_buf_obverse, other.mp_buf_obverse, other.m_size);
+		mp_buf_reverse = (void*)malloc(other.m_size);
+		memcpy(mp_buf_reverse, other.mp_buf_reverse, other.m_size);
+		m_size = other.m_size;
+		m_variable_information_vector=other.m_variable_information_vector;
+	}
+	return *this;
+}
+Snap7_buf::~Snap7_buf()
+{
+	if ( mp_buf_obverse )
+	{
+		free(mp_buf_obverse);
+		mp_buf_obverse = NULL;
+	}
+	if ( mp_buf_reverse )
+	{
+		free(mp_buf_reverse);
+		mp_buf_reverse = NULL;
+	}
+}
+
+Snap7_buf::Snap7_buf(int id, int start_index, int size,
+					 std::vector<Snap7_buf::Variable_information>& variable_information_vector,Communication_mode communication_mode)
+{
+	m_id = id;
+	m_start_index = start_index;
+	m_communication_mode = communication_mode;
+
+	if ( size > 0)
+	{
+		mp_buf_obverse = (void*)malloc(size);
+		memset(mp_buf_obverse, 0, size);
+		mp_buf_reverse = (void*)malloc(size);
+		memset(mp_buf_reverse, 0, size);
+		m_size = size;
+		m_variable_information_vector=variable_information_vector;
+	}
+}
+Snap7_buf::Snap7_buf(int id, int start_index, int size, void* p_buf_obverse, void* p_buf_reverse,
+					 std::vector<Snap7_buf::Variable_information>& variable_information_vector, Communication_mode communication_mode)
+{
+	m_id = id;
+	m_start_index = start_index;
+	m_communication_mode = communication_mode;
+
+	if ( size > 0 && p_buf_obverse != nullptr && p_buf_reverse != nullptr)
+	{
+		mp_buf_obverse = (void*)malloc(size);
+		memcpy(mp_buf_obverse, p_buf_obverse, size);
+		mp_buf_reverse = (void*)malloc(size);
+		memcpy(mp_buf_reverse, p_buf_reverse, size);
+		m_size = size;
+		m_variable_information_vector=variable_information_vector;
+	}
+}
+void Snap7_buf::init(int id, int start_index, int size,
+		  std::vector<Snap7_buf::Variable_information>& variable_information_vector,Communication_mode communication_mode)
+{
+	m_id = id;
+	m_start_index = start_index;
+	m_communication_mode = communication_mode;
+
+	if ( mp_buf_obverse )
+	{
+		free(mp_buf_obverse);
+		mp_buf_obverse = NULL;
+	}
+	if ( mp_buf_reverse )
+	{
+		free(mp_buf_reverse);
+		mp_buf_reverse = NULL;
+	}
+
+	if ( size > 0)
+	{
+		mp_buf_obverse = (void*)malloc(size);
+		memset(mp_buf_obverse, 0, size);
+		mp_buf_reverse = (void*)malloc(size);
+		memset(mp_buf_reverse, 0, size);
+		m_size = size;
+		m_variable_information_vector=variable_information_vector;
+	}
+}
+
+void Snap7_buf::init(int id, int start_index, int size, void* p_buf_obverse, void* p_buf_reverse,
+		  std::vector<Snap7_buf::Variable_information>& variable_information_vector, Communication_mode communication_mode)
+{
+	m_id = id;
+	m_start_index = start_index;
+	m_communication_mode = communication_mode;
+
+	if ( mp_buf_obverse )
+	{
+		free(mp_buf_obverse);
+		mp_buf_obverse = NULL;
+	}
+	if ( mp_buf_reverse )
+	{
+		free(mp_buf_reverse);
+		mp_buf_reverse = NULL;
+	}
+
+	if ( size > 0 && p_buf_obverse != nullptr && p_buf_reverse != nullptr)
+	{
+		mp_buf_obverse = (void*)malloc(size);
+		memcpy(mp_buf_obverse, p_buf_obverse, size);
+		mp_buf_reverse = (void*)malloc(size);
+		memcpy(mp_buf_reverse, p_buf_reverse, size);
+		m_size = size;
+		m_variable_information_vector=variable_information_vector;
+	}
+}
+//正序数据 转为 倒序数据
+void Snap7_buf::obverse_to_reverse()
+{
+	char *p_in=(char*)mp_buf_obverse;
+	char *p_out=(char*)mp_buf_reverse;
+
+	for ( auto &iter:m_variable_information_vector)
+	{
+		for (int i = 0; i < iter.m_variable_count; ++i)
+		{
+			for (int j = 0; j < iter.m_variable_size; ++j)
+			{
+				p_out[iter.m_variable_index+iter.m_variable_size*i+j] = p_in[iter.m_variable_index+iter.m_variable_size*(i+1)-j-1];
+			}
+		}
+//		for (int i = 0; i < iter.m_variable_count; ++i)
+//		{
+//			for (int j = iter.m_variable_index*i; j < iter.m_variable_index*i+iter.m_variable_size ; ++j)
+//			{
+//				p_out[j] = p_in[iter.m_variable_index*i+iter.m_variable_size - j -1];
+//			}
+//		}
+	}
+}
+
+//倒序数据 转为 正序数据
+void Snap7_buf::reverse_to_obverse()
+{
+	char *p_in=(char*)mp_buf_reverse;
+	char *p_out=(char*)mp_buf_obverse;
+
+
+	for ( auto &iter:m_variable_information_vector)
+	{
+		for (int i = 0; i < iter.m_variable_count; ++i)
+		{
+			for (int j = 0; j < iter.m_variable_size; ++j)
+			{
+				p_out[iter.m_variable_index+iter.m_variable_size*i+j] = p_in[iter.m_variable_index+iter.m_variable_size*(i+1)-j-1];
+			}
+		}
+
+//		for (int i = 0; i < iter.m_variable_count; ++i)
+//		{
+//			for (int j = iter.m_variable_index*i; j < iter.m_variable_index*i+iter.m_variable_size ; ++j)
+//			{
+//				p_out[j] = p_in[iter.m_variable_index*i+iter.m_variable_size - j -1];
+//			}
+//		}
+	}
+}
+
+int Snap7_buf::get_id()
+{
+	return m_id;
+}
+int Snap7_buf::get_start_index()
+{
+	return m_start_index;
+}
+int Snap7_buf::get_size()
+{
+	return m_size;
+}
+void* Snap7_buf::get_buf_obverse()
+{
+	return mp_buf_obverse;
+}
+void* Snap7_buf::get_buf_reverse()
+{
+	return mp_buf_reverse;
+}
+
+Snap7_buf::Communication_mode Snap7_buf::get_communication_mode()
+{
+	return m_communication_mode;
+}
+void Snap7_buf::set_communication_mode(Communication_mode communication_mode)
+{
+	m_communication_mode = communication_mode;
+}

+ 85 - 0
plc/snap7_buf.h

@@ -0,0 +1,85 @@
+
+
+
+#ifndef NNXX_TESTS_SNAP7_BUF_H
+#define NNXX_TESTS_SNAP7_BUF_H
+
+#include <string>
+#include <map>
+#include <vector>
+#include <iostream>
+
+//Snap7协议的数据结构
+class Snap7_buf
+{
+public:
+	//通信模式
+	enum Communication_mode
+	{
+	    NO_COMMUNICATION               		= 0,    //不通信
+	    ONCE_COMMUNICATION               	= 1,    //一次通信
+	    LOOP_COMMUNICATION					= 2,	//循环通信
+	};
+
+	//变量信息
+	struct Variable_information
+	{
+	    std::string		m_variable_name;		//变量名称
+	    std::string		m_variable_type;		//变量类型, 使用 typeid(a).name() 获取
+	    int 			m_variable_index;		//变量下标, 偏移量
+	    int 			m_variable_size;		//变量类型大小
+		int				m_variable_count;		//变量个数
+	};
+public:
+	Snap7_buf();
+	Snap7_buf(const Snap7_buf& other);
+	Snap7_buf& operator =(const Snap7_buf& other);
+	~Snap7_buf();
+public://API functions
+	Snap7_buf(int id, int start_index, int size,
+			  std::vector<Snap7_buf::Variable_information>& variable_information_vector,Communication_mode communication_mode = NO_COMMUNICATION);
+	Snap7_buf(int id, int start_index, int size, void* p_buf_obverse, void* p_buf_reverse,
+			  std::vector<Snap7_buf::Variable_information>& variable_information_vector, Communication_mode communication_mode = NO_COMMUNICATION);
+
+	void init(int id, int start_index, int size,
+			  std::vector<Snap7_buf::Variable_information>& variable_information_vector,Communication_mode communication_mode = NO_COMMUNICATION);
+	void init(int id, int start_index, int size, void* p_buf_obverse, void* p_buf_reverse,
+		 std::vector<Snap7_buf::Variable_information>& variable_information_vector, Communication_mode communication_mode = NO_COMMUNICATION);
+
+
+	//正序数据 转为 倒序数据
+	void obverse_to_reverse();
+	//倒序数据 转为 正序数据
+	void reverse_to_obverse();
+public://get or set member variable
+	int get_id();
+	int get_start_index();
+	int get_size();
+	void* get_buf_obverse();
+	void* get_buf_reverse();
+	Communication_mode get_communication_mode();
+	void set_communication_mode(Communication_mode communication_mode);
+protected://member functions
+
+public://member variable
+
+	int 		m_id;					//Snap7协议的数据块的编号
+	int 		m_start_index;			//Snap7协议的数据起始位下标
+	int			m_size;					//Snap7协议的数据字节大小
+	void*		mp_buf_obverse;			//Snap7协议的正序数据指针, 和数据结构体进行强转, 内存由本类管理
+	void*		mp_buf_reverse;			//Snap7协议的倒序数据指针, 用作s7通信, 内存由本类管理
+	//注:s7的通信的数据必须要倒序之后才能进行通信,
+
+//	std::map<std::string, Variable_information>			m_variable_information_map;
+	std::vector<Variable_information>		m_variable_information_vector;
+
+	Communication_mode 		m_communication_mode;	//Snap7协议的通信模式
+	//注:s7协议传输很慢, 防止相同的数据重复发送...
+
+
+private:
+
+};
+
+
+#endif //NNXX_TESTS_SNAP7_BUF_H

+ 12 - 0
plc/snap7_communication.proto

@@ -0,0 +1,12 @@
+syntax = "proto2";
+package Snap7_communication_proto;
+
+message Snap7_communication_parameter
+{
+    required string ip_string = 1 [default="192.168.0.1"];
+}
+
+message Snap7_communication_parameter_all
+{
+    required Snap7_communication_parameter        snap7_communication_parameters=1;
+}

+ 337 - 0
plc/snap7_communication_base.cpp

@@ -0,0 +1,337 @@
+//
+// Created by huli on 2020/9/25.
+//
+
+#include "snap7_communication_base.h"
+#include "../tool/proto_tool.h"
+
+Snap7_communication_base::Snap7_communication_base()
+{
+	m_communication_status = SNAP7_COMMUNICATION_UNKNOWN;
+	m_communication_delay_time_ms = SNAP7_COMMUNICATION_DELAY_TIME_MS;
+	mp_communication_thread = NULL;
+}
+
+Snap7_communication_base::~Snap7_communication_base()
+{
+	communication_uninit();
+}
+
+//初始化 通信 模块。如下三选一
+Error_manager Snap7_communication_base::communication_init(std::string ip)
+{
+    m_ip_string=ip;
+    Error_manager t_error = communication_connect(m_ip_string);
+    if ( t_error != Error_code::SUCCESS )
+    {
+        //连接失败, 不要直接返回, 而是改为断连, 后面继续启动线程, (线程内部有重连功能)
+        m_communication_status = SNAP7_COMMUNICATION_DISCONNECT;
+        return t_error;
+    }
+    else
+    {
+        m_communication_status = SNAP7_COMMUNICATION_READY;
+    }
+    return communication_run();
+}
+
+//反初始化 通信 模块。
+Error_manager Snap7_communication_base::communication_uninit()
+{
+	//关闭线程并回收资源
+	if (mp_communication_thread)
+	{
+		m_communication_condition.kill_all();
+	}
+	if (mp_communication_thread)
+	{
+		mp_communication_thread->join();
+		delete mp_communication_thread;
+		mp_communication_thread = NULL;
+	}
+
+	//清空map
+	{
+		std::unique_lock<std::mutex> t_lock(m_receive_buf_lock);
+		m_receive_buf_map.clear();
+	}
+	{
+		std::unique_lock<std::mutex> t_lock(m_send_buf_lock);
+		m_send_buf_map.clear();
+	}
+
+	communication_disconnect();
+	m_communication_status = SNAP7_COMMUNICATION_UNKNOWN;
+
+	return Error_code::SUCCESS;
+}
+
+
+
+//唤醒s7通信线程
+Error_manager Snap7_communication_base::communication_start()
+{
+	m_communication_condition.notify_all(true);
+	return Error_code::SUCCESS;
+}
+//停止s7通信线程
+Error_manager Snap7_communication_base::communication_stop()
+{
+	m_communication_condition.notify_all(false);
+	return Error_code::SUCCESS;
+}
+
+
+
+Snap7_communication_base::Snap7_communication_statu Snap7_communication_base::get_status()
+{
+	return m_communication_status;
+}
+
+//通信连接
+Error_manager Snap7_communication_base::communication_connect(std::string ip_string)
+{
+	std::unique_lock<std::mutex> t_lock(m_communication_lock);
+	int result=m_snap7_client.ConnectTo(ip_string.c_str(),0,1);
+	std::this_thread::sleep_for(std::chrono::milliseconds(m_communication_delay_time_ms));
+	if (result==0)
+	{
+		return Error_code::SUCCESS;
+	}
+	else
+	{
+		return Error_manager(Error_code::SNAP7_CONNECT_ERROR, Error_level::MINOR_ERROR,
+							 " Snap7_communication_base::communication_connect error ");
+	}
+	return Error_code::SUCCESS;
+}
+//启动通信, run thread
+Error_manager Snap7_communication_base::communication_run()
+{
+	//启动4个线程。
+	//接受线程默认循环, 内部的nn_recv进行等待, 超时1ms
+	m_communication_condition.reset(false, false, false);
+	mp_communication_thread = new std::thread(&Snap7_communication_base::communication_thread, this);
+
+	return Error_code::SUCCESS;
+}
+//通信断连
+Error_manager Snap7_communication_base::communication_disconnect()
+{
+	std::unique_lock<std::mutex> t_lock(m_communication_lock);
+	int result=m_snap7_client.Disconnect();
+	std::this_thread::sleep_for(std::chrono::milliseconds(m_communication_delay_time_ms));
+	if (result==0)
+	{
+		return Error_code::SUCCESS;
+	}
+	else
+	{
+		return Error_manager(Error_code::SNAP7_DISCONNECT_ERROR, Error_level::MINOR_ERROR,
+							 " Snap7_communication_base::communication_disconnect error ");
+	}
+	return Error_code::SUCCESS;
+}
+//mp_communication_thread线程的执行函数, 负责进行s7的通信
+void Snap7_communication_base::communication_thread()
+{
+	LOG(INFO) << " ---Snap7_communication_base::communication_thread()--- "<< this;
+Error_manager t_error;
+	while (m_communication_condition.is_alive())
+	{
+		m_communication_condition.wait_for_millisecond(1);
+
+		//s7的通信时间较长, 所以将发送和接受分开
+		//发送多个时, 必须加锁后一起发送, 不允许分段写入, 防止数据错误
+		if ( m_communication_condition.is_alive() )
+		{
+			std::this_thread::sleep_for(std::chrono::milliseconds(m_communication_delay_time_ms));
+			std::this_thread::yield();
+			switch ( m_communication_status )
+			{
+			    case SNAP7_COMMUNICATION_READY:
+				case SNAP7_COMMUNICATION_RECEIVE:
+			    {
+					{
+						std::unique_lock<std::mutex> t_lock(m_receive_buf_lock);
+						auto iter = m_receive_buf_map.begin();
+						for (; iter != m_receive_buf_map.end(); ++iter)
+						{
+							//接受数据, 读取DB块,
+							t_error = read_data_buf(iter->second);
+							if (t_error == Error_code::SNAP7_READ_ERROR)
+							{
+								m_communication_status = SNAP7_COMMUNICATION_DISCONNECT;
+								std::cout << " huli test :::: " << " t_error = " << t_error << std::endl;
+								break;
+							}
+						}
+						if ( iter != m_receive_buf_map.end() )
+						{
+							break;
+						}
+					}
+					//注:数据更新放在锁的外面, 防止重复加锁....
+					updata_receive_buf();
+					m_communication_status = SNAP7_COMMUNICATION_SEND;
+			        break;
+			    }
+			    case SNAP7_COMMUNICATION_SEND:
+			    {
+					//注:数据更新放在锁的外面, 防止重复加锁....
+					updata_send_buf();
+					{
+						std::unique_lock<std::mutex> t_lock(m_send_buf_lock);
+						auto iter = m_send_buf_map.begin();
+						for (; iter != m_send_buf_map.end(); ++iter)
+						{
+							//发送数据, 写入DB块,
+							t_error = write_data_buf(iter->second);
+							if (t_error == Error_code::SNAP7_WRITE_ERROR)
+							{
+								m_communication_status = SNAP7_COMMUNICATION_DISCONNECT;
+								std::cout << " huli test :::: " << " t_error = " << t_error << std::endl;
+								break;
+							}
+						}
+						if ( iter != m_send_buf_map.end() )
+						{
+							break;
+						}
+					}
+					m_communication_status = SNAP7_COMMUNICATION_RECEIVE;
+			        break;
+			    }
+				case SNAP7_COMMUNICATION_DISCONNECT:
+				{
+					//重连
+					LOG(INFO) << "find plc connection error, trying to reconnect.";
+					communication_disconnect();
+					std::this_thread::sleep_for(std::chrono::milliseconds(m_communication_delay_time_ms));
+					t_error = communication_connect(m_ip_string);
+					if ( t_error != Error_code::SUCCESS )
+					{
+						//连接失败, 不要直接返回, 而是改为断连, 后面继续启动线程, (线程内部有重连功能)
+						m_communication_status = SNAP7_COMMUNICATION_DISCONNECT;
+					}
+					else
+					{
+						m_communication_status = SNAP7_COMMUNICATION_READY;
+					}
+					std::this_thread::sleep_for(std::chrono::milliseconds(m_communication_delay_time_ms));
+
+					break;
+				}
+			    default:
+			    {
+
+			        break;
+			    }
+			}
+		}
+	}
+
+	LOG(INFO) << " Communication_socket_base::send_data_thread end "<< this;
+	return;
+}
+
+//接受数据, 读取DB块,
+Error_manager Snap7_communication_base::read_data_buf(Snap7_buf& snap7_buf)
+{
+	Error_manager t_error;
+	if ( snap7_buf.m_communication_mode != Snap7_buf::NO_COMMUNICATION)
+	{
+		if ( snap7_buf.m_communication_mode == Snap7_buf::ONCE_COMMUNICATION )
+		{
+			snap7_buf.m_communication_mode = Snap7_buf::NO_COMMUNICATION;
+		}
+
+
+
+
+		std::unique_lock<std::mutex> lck(m_communication_lock);
+		int result = m_snap7_client.AsDBRead(snap7_buf.m_id, snap7_buf.m_start_index, snap7_buf.m_size, snap7_buf.mp_buf_reverse);
+
+//		std::this_thread::sleep_for(std::chrono::milliseconds(10));
+		if ( result == 0 )
+		{
+			m_snap7_client.WaitAsCompletion(100);
+			//倒序数据 转为 正序数据
+			snap7_buf.reverse_to_obverse();
+		}
+		else
+		{
+			std::cout << " huli test :::: " << " result = " << result << std::endl;
+			return Error_manager(Error_code::SNAP7_READ_ERROR, Error_level::MINOR_ERROR,
+								 " Snap7_communication_base::read_data_buf error ");
+		}
+	}
+
+	return Error_code::SUCCESS;
+}
+//发送数据, 写入DB块,
+Error_manager Snap7_communication_base::write_data_buf(Snap7_buf& snap7_buf)
+{
+	Error_manager t_error;
+	if ( snap7_buf.m_communication_mode != Snap7_buf::NO_COMMUNICATION)
+	{
+		if ( snap7_buf.m_communication_mode == Snap7_buf::ONCE_COMMUNICATION )
+		{
+			snap7_buf.m_communication_mode = Snap7_buf::NO_COMMUNICATION;
+		}
+
+		//正序数据 转为 倒序数据
+		snap7_buf.obverse_to_reverse();
+
+		std::unique_lock<std::mutex> lck(m_communication_lock);
+		int result = m_snap7_client.AsDBWrite(snap7_buf.m_id, snap7_buf.m_start_index, snap7_buf.m_size,
+											  snap7_buf.mp_buf_reverse);
+
+//		std::this_thread::sleep_for(std::chrono::milliseconds(10));
+		if ( result == 0 )
+		{
+			m_snap7_client.WaitAsCompletion(100);
+		}
+		else
+		{
+			return Error_manager(Error_code::SNAP7_WRITE_ERROR, Error_level::MINOR_ERROR,
+								 " Snap7_communication_base::write_data_buf error ");
+		}
+	}
+	return Error_code::SUCCESS;
+}
+
+//数据颠倒
+Error_manager Snap7_communication_base::reverse_byte(void* p_buf_in, void* p_buf_out, int size)
+{
+	if ( p_buf_in == NULL || p_buf_out == NULL )
+	{
+	    return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+	    					"  POINTER IS NULL ");
+	}
+	char* tp_in=(char*)p_buf_in;
+	char* tp_out=(char*)p_buf_out;
+//	for(int i=0;i<size;++i)
+//	{
+//		tp_out[i]=tp_in[size-i-1];
+//	}
+	for(int i=0;i<size;++i)
+	{
+		tp_out[i]=tp_in[i];
+	}
+	return Error_code::SUCCESS;
+}
+
+//更新数据
+Error_manager Snap7_communication_base::updata_receive_buf()
+{
+	return Error_code::SUCCESS;
+}
+Error_manager Snap7_communication_base::updata_send_buf()
+{
+
+	return Error_code::SUCCESS;
+}
+
+
+

+ 105 - 0
plc/snap7_communication_base.h

@@ -0,0 +1,105 @@
+//
+// Created by huli on 2020/9/25.
+//
+
+#ifndef NNXX_TESTS_SNAP7_E_BASE_H
+#define NNXX_TESTS_SNAP7_E_BASE_H
+
+#include <s7_client.h>
+#include <mutex>
+#include <map>
+#include <glog/logging.h>
+
+#include "../error_code/error_code.h"
+#include "../tool/thread_condition.h"
+#include "snap7_buf.h"
+#include "s7_plc.h"
+
+class Snap7_communication_base
+{
+public:
+	//snap7的通信延时, 默认50ms
+#define SNAP7_COMMUNICATION_DELAY_TIME_MS 	10
+//snap7的通信参数路径
+#define SNAP7_COMMUNICATION_PARAMETER_PATH	"../setting/snap7_communication.prototxt"
+	//通信状态
+	enum Snap7_communication_statu
+	{
+		SNAP7_COMMUNICATION_UNKNOWN		=0,	        //通信状态 未知
+		SNAP7_COMMUNICATION_READY			=1,			//通信状态 正常
+
+		SNAP7_COMMUNICATION_RECEIVE		=2, 		//接受
+		SNAP7_COMMUNICATION_SEND			=3, 		//发送
+		SNAP7_COMMUNICATION_DISCONNECT	=4, 		//断连
+
+		SNAP7_COMMUNICATION_FAULT			=10,         //通信状态 错误
+	};
+public:
+	Snap7_communication_base();
+	Snap7_communication_base(const Snap7_communication_base& other)= default;
+	Snap7_communication_base& operator =(const Snap7_communication_base& other)= default;
+	~Snap7_communication_base();
+public://API functions
+	//初始化 通信 模块。如下三选一
+	virtual Error_manager communication_init(std::string ip);
+
+	//反初始化 通信 模块。
+	virtual Error_manager communication_uninit();
+
+	//唤醒s7通信线程
+	virtual Error_manager communication_start();
+	//停止s7通信线程
+	virtual Error_manager communication_stop();
+
+public://get or set member variable
+	Snap7_communication_statu get_status();
+protected://member functions
+	//通信连接
+	Error_manager communication_connect(std::string ip_string);
+    //发送数据, 写入DB块,
+    Error_manager write_data_buf(Snap7_buf& snap7_buf);
+	//启动通信, run thread
+	Error_manager communication_run();
+	//通信断连
+	Error_manager communication_disconnect();
+	//mp_communication_thread线程的执行函数, 负责进行s7的通信
+	void communication_thread();
+
+	//接受数据, 读取DB块,
+	Error_manager read_data_buf(Snap7_buf& snap7_buf);
+
+	//数据颠倒
+	Error_manager reverse_byte(void* p_buf_in, void* p_buf_out, int size);
+
+	//更新数据
+	virtual Error_manager updata_receive_buf();
+	virtual Error_manager updata_send_buf();
+protected://member variable
+public:
+	//状态
+	Snap7_communication_statu				m_communication_status;	//通信状态
+	std::string						m_ip_string;			//通信ip
+
+	//通信模块
+	std::mutex  					m_communication_lock;	//通信锁
+	TSnap7Client 					m_snap7_client;			//通信的客户端
+	int 							m_communication_delay_time_ms;//通信延时, 单位ms
+	//注:s7协议通信很不稳定, 在每次使用 TSnap7Client 之后, 都需要加延时
+
+	//数据
+	std::mutex  					m_receive_buf_lock;		//接受的锁
+	std::map<int, Snap7_buf>		m_receive_buf_map; 		//接受的map容器
+	std::mutex  					m_send_buf_lock;		//发送的锁
+	std::map<int, Snap7_buf>		m_send_buf_map; 		//发送的map容器
+
+	//线程, snap7的通信核心就是对 发送和接受内存的 周期性读写, 所以使用一个线程即可.
+	std::thread*					mp_communication_thread;    		//通信的线程指针
+	Thread_condition				m_communication_condition;			//通信的条件变量
+
+
+private:
+
+};
+
+
+#endif //NNXX_TESTS_SNAP7_E_BASE_H

+ 0 - 1
proto.sh

@@ -1,3 +1,2 @@
 protoc -I=./ setting.proto --cpp_out=./
 
-

+ 100 - 7
safety_excutor.cpp

@@ -3,7 +3,7 @@
 //
 
 #include "safety_excutor.h"
-
+#include <pcl/filters/passthrough.h>
 
 safety_excutor::safety_excutor()
 {
@@ -44,30 +44,123 @@ safety_excutor* safety_excutor::CreateExcutor(const shutter::shutter_param& para
     return excutor;
 }
 
+#if VIEW
 #include <pcl/visualization/pcl_visualizer.h>
-extern pcl::visualization::PCLVisualizer viewer;
-bool safety_excutor::verify()
+pcl::visualization::PCLVisualizer viewer("Cloud");
+#endif
+
+pcl::PointCloud<pcl::PointXYZ>::Ptr  safety_excutor::PassThroughCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
+                                                      const shutter::box_param& box)
+{
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inner(new pcl::PointCloud<pcl::PointXYZ>);
+//限制 x y z
+    pcl::PassThrough<pcl::PointXYZ> passX;
+    pcl::PassThrough<pcl::PointXYZ> passY;
+    pcl::PassThrough<pcl::PointXYZ> passZ;
+    passX.setInputCloud(cloud);
+    passX.setFilterFieldName("x");
+    passX.setFilterLimits(box.minx(), box.maxx());
+    passX.filter(*cloud_inner);
+
+    passY.setInputCloud(cloud_inner);
+    passY.setFilterFieldName("y");
+    passY.setFilterLimits(box.miny(), box.maxy());
+    passY.filter(*cloud_inner);
+
+    passY.setInputCloud(cloud_inner);
+    passY.setFilterFieldName("z");
+    passY.setFilterLimits(box.minz(), box.maxz());
+    passY.filter(*cloud_inner);
+    return cloud_inner;
+
+}
+
+
+bool safety_excutor::verify(tagMeasureData& data)
 {
 
 
     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
+    bool connected=true;
     for(int i=0;i<m_parameter.lidars_size();++i)
     {
+        if(mp_lidars[i].is_connected()==false)
+            connected=false;
         pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_t=mp_lidars[i].GetCloud();
         (*cloud)+=(*cloud_t);
-
-
     }
 
     printf(" shutter  recieve points %d\n",cloud->size());
 
+    shutter::box_param box=m_parameter.box();
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inner=PassThroughCloud(cloud,box);
+
+    shutter::box_param box1=m_parameter.verify_box1();
+    shutter::box_param box2=m_parameter.verify_box2();
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_warnning1=PassThroughCloud(cloud_inner,box1);
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_warnning2=PassThroughCloud(cloud_inner,box2);
+
+    bool safe1=(cloud_warnning1->size()<=5),safe2=((cloud_warnning2->size()<=5));
 
+#if VIEW
     viewer.removeAllPointClouds();
-    pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color2(cloud, 0,255,0); // green
+    viewer.removeShape("cube1");
+    viewer.removeShape("cube2");
+    //绘制矩形
+    Eigen::AngleAxisf rotation = Eigen::AngleAxisf(0, Eigen::Vector3f::UnitZ());
+
+    viewer.addCube(Eigen::Vector3f((box1.minx()+box1.maxx())/2.0,(box1.miny()+box1.maxy())/2.0,(box1.minz()+box1.maxz())/2.0),
+            Eigen::Quaternionf(rotation), box1.maxx()-box1.minx(), box1.maxy()-box1.miny(),box1.maxz()-box1.minz(),"cube1");
+    viewer.addCube(Eigen::Vector3f((box2.minx()+box2.maxx())/2.0,(box2.miny()+box2.maxy())/2.0,(box2.minz()+box2.maxz())/2.0),
+                   Eigen::Quaternionf(rotation), box2.maxx()-box2.minx(), box2.maxy()-box2.miny(),box2.maxz()-box2.minz(),"cube2");
+    viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 0.5, 0, "cube1");
+    viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.3, "cube1");
+
+    viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 0.5, 1, "cube2");
+    viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.3, "cube2");
+
+
+    pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color2(cloud,
+            255*int(!(safe1&safe2&connected)),255*int(safe1&safe2&connected),0);
     viewer.addPointCloud(cloud, single_color2, "cloud");
     viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "cloud");
 
-
     viewer.spinOnce();
+#endif
+
+    data.safety=(unsigned short)(safe1&safe2&connected);
+    data.left_space=0.1;
+    data.right_space=0.1;
+    data.theta=0;
+    data.offset_x=0;
+
+    //保存一帧
+    static bool saved=false;
+    if(saved==false)
+    {
+        FILE* p=fopen("./cloud.txt","w");
+        for(int i=0;i<cloud->size();++i)
+        {
+            fprintf(p,"%f %f %f\n",cloud->points[i].x,cloud->points[i].y,cloud->points[i].z);
+        }
+        fclose(p);
+        saved=true;
+    }
+
 
+
+
+    return safe1&safe2&connected;
+
+}
+
+
+bool safety_excutor::pointInRectangle(pcl::PointXYZ point,const shutter::box_param& box)
+{
+    float x=point.x;
+    float y=point.y;
+    float z=point.z;
+    if(x>box.minx()&&x<box.maxx()&&y>box.miny()&&y<box.maxy()&&z>box.minz()&&z<box.maxz())
+        return true;
+    return false;
 }

+ 14 - 1
safety_excutor.h

@@ -5,19 +5,32 @@
 #ifndef SHUTTER_VERIFY__SAFETY_EXCUTOR_H_
 #define SHUTTER_VERIFY__SAFETY_EXCUTOR_H_
 
+#define VIEW 1
+
 #include "LivoxMid70.h"
 #include "setting.pb.h"
+typedef struct
+{
+    unsigned short  safety;
+    float left_space;
+    float right_space;
+    float theta;
+    float offset_x;
+}tagMeasureData;
 class safety_excutor
 {
  public:
     static safety_excutor* CreateExcutor(const shutter::shutter_param& parameter);
     ~safety_excutor();
-    bool verify();
+    bool verify(tagMeasureData& data);
  private:
     safety_excutor();
     bool init(const shutter::shutter_param& parameter);
 
+    bool pointInRectangle(pcl::PointXYZ point,const shutter::box_param& box);
 
+    pcl::PointCloud<pcl::PointXYZ>::Ptr  PassThroughCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
+                                                          const shutter::box_param& box);
  private:
     shutter::shutter_param          m_parameter;
     livox::LivoxMid70*          mp_lidars;

+ 128 - 18
setting.pb.cc

@@ -124,13 +124,17 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_setting_2eproto::offsets[] PRO
   ~0u,  // no _weak_field_map_
   PROTOBUF_FIELD_OFFSET(::shutter::shutter_param, lidars_),
   PROTOBUF_FIELD_OFFSET(::shutter::shutter_param, box_),
+  PROTOBUF_FIELD_OFFSET(::shutter::shutter_param, verify_box1_),
+  PROTOBUF_FIELD_OFFSET(::shutter::shutter_param, verify_box2_),
   ~0u,
   0,
+  1,
+  2,
 };
 static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
   { 0, 13, sizeof(::shutter::lidar_parameter)},
   { 21, 32, sizeof(::shutter::box_param)},
-  { 38, 45, sizeof(::shutter::shutter_param)},
+  { 38, 47, sizeof(::shutter::shutter_param)},
 };
 
 static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
@@ -146,9 +150,11 @@ const char descriptor_table_protodef_setting_2eproto[] PROTOBUF_SECTION_VARIABLE
   "\002ty\030\006 \001(\001:\0011\022\r\n\002tz\030\007 \001(\001:\0011\022\017\n\003fps\030\010 \001(\001"
   ":\00210\"_\n\tbox_param\022\014\n\004minx\030\001 \001(\001\022\014\n\004maxx\030"
   "\002 \001(\001\022\014\n\004miny\030\003 \001(\001\022\014\n\004maxy\030\004 \001(\001\022\014\n\004min"
-  "z\030\005 \001(\001\022\014\n\004maxz\030\006 \001(\001\"Z\n\rshutter_param\022("
-  "\n\006lidars\030\001 \003(\0132\030.shutter.lidar_parameter"
-  "\022\037\n\003box\030\002 \001(\0132\022.shutter.box_param"
+  "z\030\005 \001(\001\022\014\n\004maxz\030\006 \001(\001\"\254\001\n\rshutter_param\022"
+  "(\n\006lidars\030\001 \003(\0132\030.shutter.lidar_paramete"
+  "r\022\037\n\003box\030\002 \001(\0132\022.shutter.box_param\022\'\n\013ve"
+  "rify_box1\030\003 \001(\0132\022.shutter.box_param\022\'\n\013v"
+  "erify_box2\030\004 \001(\0132\022.shutter.box_param"
   ;
 static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_setting_2eproto_deps[1] = {
 };
@@ -159,7 +165,7 @@ static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_set
 };
 static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_setting_2eproto_once;
 const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_setting_2eproto = {
-  false, false, descriptor_table_protodef_setting_2eproto, "setting.proto", 353,
+  false, false, descriptor_table_protodef_setting_2eproto, "setting.proto", 436,
   &descriptor_table_setting_2eproto_once, descriptor_table_setting_2eproto_sccs, descriptor_table_setting_2eproto_deps, 3, 0,
   schemas, file_default_instances, TableStruct_setting_2eproto::offsets,
   file_level_metadata_setting_2eproto, 3, file_level_enum_descriptors_setting_2eproto, file_level_service_descriptors_setting_2eproto,
@@ -961,6 +967,10 @@ void box_param::InternalSwap(box_param* other) {
 void shutter_param::InitAsDefaultInstance() {
   ::shutter::_shutter_param_default_instance_._instance.get_mutable()->box_ = const_cast< ::shutter::box_param*>(
       ::shutter::box_param::internal_default_instance());
+  ::shutter::_shutter_param_default_instance_._instance.get_mutable()->verify_box1_ = const_cast< ::shutter::box_param*>(
+      ::shutter::box_param::internal_default_instance());
+  ::shutter::_shutter_param_default_instance_._instance.get_mutable()->verify_box2_ = const_cast< ::shutter::box_param*>(
+      ::shutter::box_param::internal_default_instance());
 }
 class shutter_param::_Internal {
  public:
@@ -969,12 +979,28 @@ class shutter_param::_Internal {
   static void set_has_box(HasBits* has_bits) {
     (*has_bits)[0] |= 1u;
   }
+  static const ::shutter::box_param& verify_box1(const shutter_param* msg);
+  static void set_has_verify_box1(HasBits* has_bits) {
+    (*has_bits)[0] |= 2u;
+  }
+  static const ::shutter::box_param& verify_box2(const shutter_param* msg);
+  static void set_has_verify_box2(HasBits* has_bits) {
+    (*has_bits)[0] |= 4u;
+  }
 };
 
 const ::shutter::box_param&
 shutter_param::_Internal::box(const shutter_param* msg) {
   return *msg->box_;
 }
+const ::shutter::box_param&
+shutter_param::_Internal::verify_box1(const shutter_param* msg) {
+  return *msg->verify_box1_;
+}
+const ::shutter::box_param&
+shutter_param::_Internal::verify_box2(const shutter_param* msg) {
+  return *msg->verify_box2_;
+}
 shutter_param::shutter_param(::PROTOBUF_NAMESPACE_ID::Arena* arena)
   : ::PROTOBUF_NAMESPACE_ID::Message(arena),
   lidars_(arena) {
@@ -992,12 +1018,24 @@ shutter_param::shutter_param(const shutter_param& from)
   } else {
     box_ = nullptr;
   }
+  if (from._internal_has_verify_box1()) {
+    verify_box1_ = new ::shutter::box_param(*from.verify_box1_);
+  } else {
+    verify_box1_ = nullptr;
+  }
+  if (from._internal_has_verify_box2()) {
+    verify_box2_ = new ::shutter::box_param(*from.verify_box2_);
+  } else {
+    verify_box2_ = nullptr;
+  }
   // @@protoc_insertion_point(copy_constructor:shutter.shutter_param)
 }
 
 void shutter_param::SharedCtor() {
   ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&scc_info_shutter_param_setting_2eproto.base);
-  box_ = nullptr;
+  ::memset(&box_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&verify_box2_) -
+      reinterpret_cast<char*>(&box_)) + sizeof(verify_box2_));
 }
 
 shutter_param::~shutter_param() {
@@ -1009,6 +1047,8 @@ shutter_param::~shutter_param() {
 void shutter_param::SharedDtor() {
   GOOGLE_DCHECK(GetArena() == nullptr);
   if (this != internal_default_instance()) delete box_;
+  if (this != internal_default_instance()) delete verify_box1_;
+  if (this != internal_default_instance()) delete verify_box2_;
 }
 
 void shutter_param::ArenaDtor(void* object) {
@@ -1034,9 +1074,19 @@ void shutter_param::Clear() {
 
   lidars_.Clear();
   cached_has_bits = _has_bits_[0];
-  if (cached_has_bits & 0x00000001u) {
-    GOOGLE_DCHECK(box_ != nullptr);
-    box_->Clear();
+  if (cached_has_bits & 0x00000007u) {
+    if (cached_has_bits & 0x00000001u) {
+      GOOGLE_DCHECK(box_ != nullptr);
+      box_->Clear();
+    }
+    if (cached_has_bits & 0x00000002u) {
+      GOOGLE_DCHECK(verify_box1_ != nullptr);
+      verify_box1_->Clear();
+    }
+    if (cached_has_bits & 0x00000004u) {
+      GOOGLE_DCHECK(verify_box2_ != nullptr);
+      verify_box2_->Clear();
+    }
   }
   _has_bits_.Clear();
   _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
@@ -1070,6 +1120,20 @@ const char* shutter_param::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_
           CHK_(ptr);
         } else goto handle_unusual;
         continue;
+      // optional .shutter.box_param verify_box1 = 3;
+      case 3:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 26)) {
+          ptr = ctx->ParseMessage(_internal_mutable_verify_box1(), ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional .shutter.box_param verify_box2 = 4;
+      case 4:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 34)) {
+          ptr = ctx->ParseMessage(_internal_mutable_verify_box2(), ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
       default: {
       handle_unusual:
         if ((tag & 7) == 4 || tag == 0) {
@@ -1116,6 +1180,22 @@ failure:
         2, _Internal::box(this), target, stream);
   }
 
+  // optional .shutter.box_param verify_box1 = 3;
+  if (cached_has_bits & 0x00000002u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
+      InternalWriteMessage(
+        3, _Internal::verify_box1(this), target, stream);
+  }
+
+  // optional .shutter.box_param verify_box2 = 4;
+  if (cached_has_bits & 0x00000004u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
+      InternalWriteMessage(
+        4, _Internal::verify_box2(this), target, stream);
+  }
+
   if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
     target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
         _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
@@ -1139,14 +1219,30 @@ size_t shutter_param::ByteSizeLong() const {
       ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(msg);
   }
 
-  // optional .shutter.box_param box = 2;
   cached_has_bits = _has_bits_[0];
-  if (cached_has_bits & 0x00000001u) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
-        *box_);
-  }
+  if (cached_has_bits & 0x00000007u) {
+    // optional .shutter.box_param box = 2;
+    if (cached_has_bits & 0x00000001u) {
+      total_size += 1 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
+          *box_);
+    }
 
+    // optional .shutter.box_param verify_box1 = 3;
+    if (cached_has_bits & 0x00000002u) {
+      total_size += 1 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
+          *verify_box1_);
+    }
+
+    // optional .shutter.box_param verify_box2 = 4;
+    if (cached_has_bits & 0x00000004u) {
+      total_size += 1 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
+          *verify_box2_);
+    }
+
+  }
   if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
     return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
         _internal_metadata_, total_size, &_cached_size_);
@@ -1179,8 +1275,17 @@ void shutter_param::MergeFrom(const shutter_param& from) {
   (void) cached_has_bits;
 
   lidars_.MergeFrom(from.lidars_);
-  if (from._internal_has_box()) {
-    _internal_mutable_box()->::shutter::box_param::MergeFrom(from._internal_box());
+  cached_has_bits = from._has_bits_[0];
+  if (cached_has_bits & 0x00000007u) {
+    if (cached_has_bits & 0x00000001u) {
+      _internal_mutable_box()->::shutter::box_param::MergeFrom(from._internal_box());
+    }
+    if (cached_has_bits & 0x00000002u) {
+      _internal_mutable_verify_box1()->::shutter::box_param::MergeFrom(from._internal_verify_box1());
+    }
+    if (cached_has_bits & 0x00000004u) {
+      _internal_mutable_verify_box2()->::shutter::box_param::MergeFrom(from._internal_verify_box2());
+    }
   }
 }
 
@@ -1207,7 +1312,12 @@ void shutter_param::InternalSwap(shutter_param* other) {
   _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
   swap(_has_bits_[0], other->_has_bits_[0]);
   lidars_.InternalSwap(&other->lidars_);
-  swap(box_, other->box_);
+  ::PROTOBUF_NAMESPACE_ID::internal::memswap<
+      PROTOBUF_FIELD_OFFSET(shutter_param, verify_box2_)
+      + sizeof(shutter_param::verify_box2_)
+      - PROTOBUF_FIELD_OFFSET(shutter_param, box_)>(
+          reinterpret_cast<char*>(&box_),
+          reinterpret_cast<char*>(&other->box_));
 }
 
 ::PROTOBUF_NAMESPACE_ID::Metadata shutter_param::GetMetadata() const {

+ 206 - 0
setting.pb.h

@@ -681,6 +681,8 @@ class shutter_param PROTOBUF_FINAL :
   enum : int {
     kLidarsFieldNumber = 1,
     kBoxFieldNumber = 2,
+    kVerifyBox1FieldNumber = 3,
+    kVerifyBox2FieldNumber = 4,
   };
   // repeated .shutter.lidar_parameter lidars = 1;
   int lidars_size() const;
@@ -718,6 +720,42 @@ class shutter_param PROTOBUF_FINAL :
       ::shutter::box_param* box);
   ::shutter::box_param* unsafe_arena_release_box();
 
+  // optional .shutter.box_param verify_box1 = 3;
+  bool has_verify_box1() const;
+  private:
+  bool _internal_has_verify_box1() const;
+  public:
+  void clear_verify_box1();
+  const ::shutter::box_param& verify_box1() const;
+  ::shutter::box_param* release_verify_box1();
+  ::shutter::box_param* mutable_verify_box1();
+  void set_allocated_verify_box1(::shutter::box_param* verify_box1);
+  private:
+  const ::shutter::box_param& _internal_verify_box1() const;
+  ::shutter::box_param* _internal_mutable_verify_box1();
+  public:
+  void unsafe_arena_set_allocated_verify_box1(
+      ::shutter::box_param* verify_box1);
+  ::shutter::box_param* unsafe_arena_release_verify_box1();
+
+  // optional .shutter.box_param verify_box2 = 4;
+  bool has_verify_box2() const;
+  private:
+  bool _internal_has_verify_box2() const;
+  public:
+  void clear_verify_box2();
+  const ::shutter::box_param& verify_box2() const;
+  ::shutter::box_param* release_verify_box2();
+  ::shutter::box_param* mutable_verify_box2();
+  void set_allocated_verify_box2(::shutter::box_param* verify_box2);
+  private:
+  const ::shutter::box_param& _internal_verify_box2() const;
+  ::shutter::box_param* _internal_mutable_verify_box2();
+  public:
+  void unsafe_arena_set_allocated_verify_box2(
+      ::shutter::box_param* verify_box2);
+  ::shutter::box_param* unsafe_arena_release_verify_box2();
+
   // @@protoc_insertion_point(class_scope:shutter.shutter_param)
  private:
   class _Internal;
@@ -729,6 +767,8 @@ class shutter_param PROTOBUF_FINAL :
   mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
   ::PROTOBUF_NAMESPACE_ID::RepeatedPtrField< ::shutter::lidar_parameter > lidars_;
   ::shutter::box_param* box_;
+  ::shutter::box_param* verify_box1_;
+  ::shutter::box_param* verify_box2_;
   friend struct ::TableStruct_setting_2eproto;
 };
 // ===================================================================
@@ -1310,6 +1350,172 @@ inline void shutter_param::set_allocated_box(::shutter::box_param* box) {
   // @@protoc_insertion_point(field_set_allocated:shutter.shutter_param.box)
 }
 
+// optional .shutter.box_param verify_box1 = 3;
+inline bool shutter_param::_internal_has_verify_box1() const {
+  bool value = (_has_bits_[0] & 0x00000002u) != 0;
+  PROTOBUF_ASSUME(!value || verify_box1_ != nullptr);
+  return value;
+}
+inline bool shutter_param::has_verify_box1() const {
+  return _internal_has_verify_box1();
+}
+inline void shutter_param::clear_verify_box1() {
+  if (verify_box1_ != nullptr) verify_box1_->Clear();
+  _has_bits_[0] &= ~0x00000002u;
+}
+inline const ::shutter::box_param& shutter_param::_internal_verify_box1() const {
+  const ::shutter::box_param* p = verify_box1_;
+  return p != nullptr ? *p : *reinterpret_cast<const ::shutter::box_param*>(
+      &::shutter::_box_param_default_instance_);
+}
+inline const ::shutter::box_param& shutter_param::verify_box1() const {
+  // @@protoc_insertion_point(field_get:shutter.shutter_param.verify_box1)
+  return _internal_verify_box1();
+}
+inline void shutter_param::unsafe_arena_set_allocated_verify_box1(
+    ::shutter::box_param* verify_box1) {
+  if (GetArena() == nullptr) {
+    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(verify_box1_);
+  }
+  verify_box1_ = verify_box1;
+  if (verify_box1) {
+    _has_bits_[0] |= 0x00000002u;
+  } else {
+    _has_bits_[0] &= ~0x00000002u;
+  }
+  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:shutter.shutter_param.verify_box1)
+}
+inline ::shutter::box_param* shutter_param::release_verify_box1() {
+  _has_bits_[0] &= ~0x00000002u;
+  ::shutter::box_param* temp = verify_box1_;
+  verify_box1_ = nullptr;
+  if (GetArena() != nullptr) {
+    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
+  }
+  return temp;
+}
+inline ::shutter::box_param* shutter_param::unsafe_arena_release_verify_box1() {
+  // @@protoc_insertion_point(field_release:shutter.shutter_param.verify_box1)
+  _has_bits_[0] &= ~0x00000002u;
+  ::shutter::box_param* temp = verify_box1_;
+  verify_box1_ = nullptr;
+  return temp;
+}
+inline ::shutter::box_param* shutter_param::_internal_mutable_verify_box1() {
+  _has_bits_[0] |= 0x00000002u;
+  if (verify_box1_ == nullptr) {
+    auto* p = CreateMaybeMessage<::shutter::box_param>(GetArena());
+    verify_box1_ = p;
+  }
+  return verify_box1_;
+}
+inline ::shutter::box_param* shutter_param::mutable_verify_box1() {
+  // @@protoc_insertion_point(field_mutable:shutter.shutter_param.verify_box1)
+  return _internal_mutable_verify_box1();
+}
+inline void shutter_param::set_allocated_verify_box1(::shutter::box_param* verify_box1) {
+  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
+  if (message_arena == nullptr) {
+    delete verify_box1_;
+  }
+  if (verify_box1) {
+    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
+      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(verify_box1);
+    if (message_arena != submessage_arena) {
+      verify_box1 = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
+          message_arena, verify_box1, submessage_arena);
+    }
+    _has_bits_[0] |= 0x00000002u;
+  } else {
+    _has_bits_[0] &= ~0x00000002u;
+  }
+  verify_box1_ = verify_box1;
+  // @@protoc_insertion_point(field_set_allocated:shutter.shutter_param.verify_box1)
+}
+
+// optional .shutter.box_param verify_box2 = 4;
+inline bool shutter_param::_internal_has_verify_box2() const {
+  bool value = (_has_bits_[0] & 0x00000004u) != 0;
+  PROTOBUF_ASSUME(!value || verify_box2_ != nullptr);
+  return value;
+}
+inline bool shutter_param::has_verify_box2() const {
+  return _internal_has_verify_box2();
+}
+inline void shutter_param::clear_verify_box2() {
+  if (verify_box2_ != nullptr) verify_box2_->Clear();
+  _has_bits_[0] &= ~0x00000004u;
+}
+inline const ::shutter::box_param& shutter_param::_internal_verify_box2() const {
+  const ::shutter::box_param* p = verify_box2_;
+  return p != nullptr ? *p : *reinterpret_cast<const ::shutter::box_param*>(
+      &::shutter::_box_param_default_instance_);
+}
+inline const ::shutter::box_param& shutter_param::verify_box2() const {
+  // @@protoc_insertion_point(field_get:shutter.shutter_param.verify_box2)
+  return _internal_verify_box2();
+}
+inline void shutter_param::unsafe_arena_set_allocated_verify_box2(
+    ::shutter::box_param* verify_box2) {
+  if (GetArena() == nullptr) {
+    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(verify_box2_);
+  }
+  verify_box2_ = verify_box2;
+  if (verify_box2) {
+    _has_bits_[0] |= 0x00000004u;
+  } else {
+    _has_bits_[0] &= ~0x00000004u;
+  }
+  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:shutter.shutter_param.verify_box2)
+}
+inline ::shutter::box_param* shutter_param::release_verify_box2() {
+  _has_bits_[0] &= ~0x00000004u;
+  ::shutter::box_param* temp = verify_box2_;
+  verify_box2_ = nullptr;
+  if (GetArena() != nullptr) {
+    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
+  }
+  return temp;
+}
+inline ::shutter::box_param* shutter_param::unsafe_arena_release_verify_box2() {
+  // @@protoc_insertion_point(field_release:shutter.shutter_param.verify_box2)
+  _has_bits_[0] &= ~0x00000004u;
+  ::shutter::box_param* temp = verify_box2_;
+  verify_box2_ = nullptr;
+  return temp;
+}
+inline ::shutter::box_param* shutter_param::_internal_mutable_verify_box2() {
+  _has_bits_[0] |= 0x00000004u;
+  if (verify_box2_ == nullptr) {
+    auto* p = CreateMaybeMessage<::shutter::box_param>(GetArena());
+    verify_box2_ = p;
+  }
+  return verify_box2_;
+}
+inline ::shutter::box_param* shutter_param::mutable_verify_box2() {
+  // @@protoc_insertion_point(field_mutable:shutter.shutter_param.verify_box2)
+  return _internal_mutable_verify_box2();
+}
+inline void shutter_param::set_allocated_verify_box2(::shutter::box_param* verify_box2) {
+  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
+  if (message_arena == nullptr) {
+    delete verify_box2_;
+  }
+  if (verify_box2) {
+    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
+      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(verify_box2);
+    if (message_arena != submessage_arena) {
+      verify_box2 = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
+          message_arena, verify_box2, submessage_arena);
+    }
+    _has_bits_[0] |= 0x00000004u;
+  } else {
+    _has_bits_[0] &= ~0x00000004u;
+  }
+  verify_box2_ = verify_box2;
+  // @@protoc_insertion_point(field_set_allocated:shutter.shutter_param.verify_box2)
+}
+
 #ifdef __GNUC__
   #pragma GCC diagnostic pop
 #endif  // __GNUC__

+ 3 - 1
setting.proto

@@ -24,6 +24,8 @@ message box_param
 
 message shutter_param
 {
-   repeated lidar_parameter   lidars=1;
+   repeated lidar_parameter     lidars=1;
    optional box_param           box=2;
+   optional box_param           verify_box1=3;
+   optional box_param           verify_box2=4;
 }

+ 1 - 1
tool/proto_tool.cpp

@@ -18,7 +18,7 @@ using google::protobuf::Message;
 //读取protobuf 配置文件,转化为protobuf参数形式
 //input:	prototxt_path :prototxt文件路径
 //ouput:	parameter: protobuf参数,这里是消息基类,实际调用时传入对应的子类即可。
-bool proto_tool::read_proto_param(std::string prototxt_path, ::google::protobuf::Message& protobuf_parameter)
+bool proto_tool::read_proto_param(std::string prototxt_path,  ::google::protobuf::Message& protobuf_parameter)
 {
 	int fd = open(prototxt_path.c_str(), O_RDONLY);
 	if (fd == -1) return false;