Browse Source

结果检验

zx 3 years ago
commit
ee44e81ca9
78 changed files with 15276 additions and 0 deletions
  1. 2 0
      .idea/.gitignore
  2. 50 0
      CMakeLists.txt
  3. 534 0
      error_code/error_code.cpp
  4. 458 0
      error_code/error_code.h
  5. 547 0
      laser/Laser.cpp
  6. 198 0
      laser/Laser.h
  7. 298 0
      laser/Laser.puml
  8. 78 0
      laser/LivoxHorizon.cpp
  9. 41 0
      laser/LivoxHorizon.h
  10. 10 0
      laser/LivoxHubLaser.cpp
  11. 19 0
      laser/LivoxHubLaser.h
  12. 450 0
      laser/LivoxLaser.cpp
  13. 96 0
      laser/LivoxLaser.h
  14. 230 0
      laser/LivoxLaser.puml
  15. 213 0
      laser/LivoxMid100Laser.cpp
  16. 46 0
      laser/LivoxMid100Laser.h
  17. 145 0
      laser/LogFiles.cpp
  18. 73 0
      laser/LogFiles.h
  19. 24 0
      laser/Point2D.cpp
  20. 35 0
      laser/Point2D.h
  21. 34 0
      laser/Point3D.cpp
  22. 19 0
      laser/Point3D.h
  23. 323 0
      laser/Sick511FileLaser.cpp
  24. 55 0
      laser/Sick511FileLaser.h
  25. 343 0
      laser/TcpLaser.cpp
  26. 68 0
      laser/TcpLaser.h
  27. 352 0
      laser/UdpLaser.cpp
  28. 61 0
      laser/UdpLaser.h
  29. 432 0
      laser/laser_message.pb.cc
  30. 432 0
      laser/laser_message.pb.h
  31. 17 0
      laser/laser_message.proto
  32. 1434 0
      laser/laser_parameter.pb.cc
  33. 1788 0
      laser/laser_parameter.pb.h
  34. 40 0
      laser/laser_parameter.proto
  35. 189 0
      laser/laser_task_command.cpp
  36. 111 0
      laser/laser_task_command.h
  37. 114 0
      laser/laser_task_command.puml
  38. 271 0
      main.cpp
  39. 116 0
      plc/LibmodbusWrapper.cpp
  40. 37 0
      plc/LibmodbusWrapper.h
  41. 447 0
      plc/plc_communicator.cpp
  42. 134 0
      plc/plc_communicator.h
  43. 357 0
      plc/plc_message.pb.cc
  44. 374 0
      plc/plc_message.pb.h
  45. 16 0
      plc/plc_message.proto
  46. 146 0
      plc/plc_modbus_uml.wsd
  47. 722 0
      plc/plc_module.pb.cc
  48. 703 0
      plc/plc_module.pb.h
  49. 22 0
      plc/plc_module.proto
  50. 46 0
      plc/plc_task.cpp
  51. 41 0
      plc/plc_task.h
  52. 60 0
      task/task_command_manager.cpp
  53. 59 0
      task/task_command_manager.h
  54. 82 0
      task/task_command_manager.puml
  55. 35 0
      tool/StdCondition.cpp
  56. 26 0
      tool/StdCondition.h
  57. 319 0
      tool/binary_buf.cpp
  58. 88 0
      tool/binary_buf.h
  59. 85 0
      tool/binary_buf.puml
  60. 94 0
      tool/pathcreator.cpp
  61. 18 0
      tool/pathcreator.h
  62. 299 0
      tool/point_tool.cpp
  63. 31 0
      tool/point_tool.h
  64. 42 0
      tool/proto_tool.cpp
  65. 56 0
      tool/proto_tool.h
  66. 4 0
      tool/singleton.cpp
  67. 81 0
      tool/singleton.h
  68. 101 0
      tool/threadSafeQueue.h
  69. 144 0
      tool/thread_condition.cpp
  70. 114 0
      tool/thread_condition.h
  71. 96 0
      tool/thread_condition.puml
  72. 34 0
      tool/thread_safe_queue.cpp
  73. 339 0
      tool/thread_safe_queue.h
  74. 108 0
      tool/thread_safe_queue.puml
  75. 19 0
      verifier.cpp
  76. 25 0
      verifier.h
  77. 80 0
      verify/shuttler_verifier.cpp
  78. 46 0
      verify/shuttler_verifier.h

+ 2 - 0
.idea/.gitignore

@@ -0,0 +1,2 @@
+# Default ignored files
+/workspace.xml

+ 50 - 0
CMakeLists.txt

@@ -0,0 +1,50 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(shutter_verify)
+
+## Compile as C++11, supported in ROS Kinetic and newer
+add_compile_options(-std=c++14)
+
+#add_definitions(-std=c++11 -msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2)
+
+FIND_PACKAGE(OpenCV REQUIRED)
+FIND_PACKAGE(PCL REQUIRED)
+FIND_PACKAGE(Protobuf REQUIRED)
+FIND_PACKAGE(Glog REQUIRED)
+FIND_PACKAGE(Ceres REQUIRED)
+set(CMAKE_MODULE_PATH "/usr/local/share/")
+set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wl,--no-as-needed")
+set(CMAKE_CXX_FLAGS "-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2")
+set(CMAKE_BUILD_TYPE "RELEASE")
+
+
+#find_package(Eigen3 REQUIRED)
+
+include_directories(
+		tool
+		error_code
+		verify
+        laser
+        plc
+        /usr/local/include
+        /usr/local/include/modbus
+        /usr/local/include/snap7
+  ${PCL_INCLUDE_DIRS}
+  ${OpenCV_INCLUDE_DIRS}
+        ${CERES_INCLUDE_DIRS}
+)
+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}/task TASK_MANAGER_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/verify VERIFY )
+
+add_executable(shutter_verify  verifier.cpp ./main.cpp ${ERROR_SRC} ${LASER}
+		${PLC_SRC} ${TASK_MANAGER_SRC} ${TOOL_SRC} ${VERIFY})
+target_link_libraries(shutter_verify ${OpenCV_LIBS} ${CERES_LIBRARIES}
+        ${GLOG_LIBRARIES} ${PCL_LIBRARIES} ${PROTOBUF_LIBRARIES}
+        /usr/local/lib/libgflags.a /usr/local/lib/liblivox_sdk_static.a
+		/usr/lib/x86_64-linux-gnu/libmodbus.so)
+
+

+ 534 - 0
error_code/error_code.cpp

@@ -0,0 +1,534 @@
+
+//Error_code是错误码的底层通用模块,
+//功能:用作故障分析和处理。
+
+//用法:所有的功能接口函数return错误管理类,
+//然后上层判断分析错误码,并进行故障处理。
+
+
+
+#include "error_code.h"
+
+/////////////////////////////////////////////
+//构造函数
+Error_manager::Error_manager()
+{
+    m_error_code = SUCCESS;
+    m_error_level = NORMAL;
+    pm_error_description = 0;
+    m_description_length = 0;
+    return ;
+}
+//拷贝构造
+Error_manager::Error_manager(const Error_manager & error_manager)
+{
+    this->m_error_code = error_manager.m_error_code;
+    this->m_error_level = error_manager.m_error_level;
+    pm_error_description = NULL;
+    m_description_length = 0;
+    reallocate_memory_and_copy_string(error_manager.pm_error_description, error_manager.m_description_length);
+    return ;
+}
+//赋值构造
+Error_manager::Error_manager(Error_code error_code, Error_level error_level,
+    const char* p_error_description, int description_length)
+{
+    m_error_code = error_code;
+    m_error_level = error_level;
+    pm_error_description = NULL;
+    m_description_length = 0;
+    reallocate_memory_and_copy_string(p_error_description, description_length);
+    return ;
+}
+//赋值构造
+Error_manager::Error_manager(Error_code error_code, Error_level error_level , std::string & error_aggregate_string)
+{
+    m_error_code = error_code;
+    m_error_level = error_level;
+    pm_error_description = NULL;
+    m_description_length = 0;
+    reallocate_memory_and_copy_string(error_aggregate_string);
+    return ;
+}
+//析构函数
+Error_manager::~Error_manager()
+{
+    free_description();
+}
+
+//初始化
+void Error_manager::error_manager_init()
+{
+    error_manager_clear_all();
+    return;
+}
+//初始化
+void Error_manager::error_manager_init(Error_code error_code, Error_level error_level, const char* p_error_description, int description_length)
+{
+    m_error_code = error_code;
+    m_error_level = error_level;
+    reallocate_memory_and_copy_string(p_error_description, description_length);
+    return ;
+}
+//初始化
+void Error_manager::error_manager_init(Error_code error_code, Error_level error_level , std::string & error_aggregate_string)
+{
+    m_error_code = error_code;
+    m_error_level = error_level;
+    reallocate_memory_and_copy_string(error_aggregate_string);
+    return ;
+}
+//重置
+void Error_manager::error_manager_reset(Error_code error_code, Error_level error_level, const char* p_error_description, int description_length)
+{
+    m_error_code = error_code;
+    m_error_level = error_level;
+    reallocate_memory_and_copy_string(p_error_description, description_length);
+    return ;
+}
+//重置
+void Error_manager::error_manager_reset(Error_code error_code, Error_level error_level , std::string & error_aggregate_string)
+{
+    m_error_code = error_code;
+    m_error_level = error_level;
+    reallocate_memory_and_copy_string(error_aggregate_string);
+    return ;
+}
+//重置
+void Error_manager::error_manager_reset(const Error_manager & error_manager)
+{
+    this->m_error_code = error_manager.m_error_code;
+    this->m_error_level = error_manager.m_error_level;
+    reallocate_memory_and_copy_string(error_manager.pm_error_description, error_manager.m_description_length);
+    return ;
+}
+//清除所有内容
+void Error_manager::error_manager_clear_all()
+{
+    m_error_code = SUCCESS;
+    m_error_level = NORMAL;
+    free_description();
+}
+
+//重载=
+Error_manager& Error_manager::operator=(const Error_manager & error_manager)
+{
+    error_manager_reset(error_manager);
+}
+//重载=,支持Error_manager和Error_code的直接转化,会清空错误等级和描述
+Error_manager& Error_manager::operator=(Error_code error_code)
+{
+    error_manager_clear_all();
+    set_error_code(error_code);
+}
+//重载==
+bool Error_manager::operator==(const Error_manager & error_manager)
+{
+    is_equal_error_manager(error_manager);
+}
+//重载==,支持Error_manager和Error_code的直接比较
+bool Error_manager::operator==(Error_code error_code)
+{
+    if(m_error_code == error_code)
+    {
+        return true;
+    }
+    else
+    {
+        return false;
+    }
+}
+
+//重载!=
+bool Error_manager::operator!=(const Error_manager & error_manager)
+{
+    ! is_equal_error_manager(error_manager);
+}
+//重载!=,支持Error_manager和Error_code的直接比较
+bool Error_manager::operator!=(Error_code error_code)
+{
+    if(m_error_code != error_code)
+    {
+        return true;
+    }
+    else
+    {
+        return false;
+    }
+}
+//重载<<,支持cout<<
+std::ostream & operator<<(std::ostream &out, Error_manager &error_manager)
+{
+	out << error_manager.to_string();
+	return out;
+}
+
+//获取错误码
+Error_code Error_manager::get_error_code()
+{
+    return m_error_code;
+}
+//获取错误等级
+Error_level Error_manager::get_error_level()
+{
+    return m_error_level;
+}
+//获取错误描述的指针,(浅拷贝)
+char* Error_manager::get_error_description()
+{
+    if(pm_error_description== nullptr)
+        return "";
+    return pm_error_description;
+}
+
+//复制错误描述,(深拷贝)
+//output:p_error_description     错误描述的字符串指针,不可以为NULL,必须要有实际的内存
+//output:description_length      错误描述的字符串长度,不可以为0,长度最好足够大,一般256即可。
+void Error_manager::copy_error_description(const char* p_error_description, int description_length)
+{
+    if(p_error_description != NULL && pm_error_description != NULL)
+    {
+        char *pt_source = (char *)p_error_description;
+        char* pt_destination = pm_error_description;
+
+        int t_length_min = m_description_length;
+        if(m_description_length > description_length)
+        {
+            t_length_min = description_length;
+        }
+
+        for(int i=0;i<t_length_min; i++)
+        {
+            *pt_destination = *pt_source;
+            pt_destination++;
+            pt_source++;
+        }
+    }
+
+    return;
+}
+//复制错误描述,(深拷贝)
+//output:error_description_string     错误描述的string
+void Error_manager::copy_error_description(std::string & error_description_string)
+{
+    if( (!error_description_string.empty() ) && pm_error_description != NULL)
+    {
+        error_description_string = pm_error_description;
+    }
+    return;
+}
+
+//设置错误码
+void Error_manager::set_error_code(Error_code error_code)
+{
+    m_error_code = error_code;
+    return;
+}
+//比较错误等级并升级,取高等级的结果
+void Error_manager::set_error_level_up(Error_level error_level)
+{
+    if(m_error_level < error_level)
+    {
+        m_error_level = error_level;
+    }
+    return;
+}
+//比较错误等级并降级,取低等级的结果
+void Error_manager::set_error_level_down(Error_level error_level)
+{
+    if(m_error_level > error_level)
+    {
+        m_error_level = error_level;
+    }
+    return;
+}
+//错误等级,设定到固定值
+void Error_manager::set_error_level_location(Error_level error_level)
+{
+    m_error_level = error_level;
+    return;
+}
+//设置错误描述
+void Error_manager::set_error_description(const char* p_error_description, int description_length)
+{
+    reallocate_memory_and_copy_string(p_error_description, description_length);
+    return ;
+}
+//设置错误描述
+void Error_manager::set_error_description(std::string & error_description_string)
+{
+    reallocate_memory_and_copy_string(error_description_string);
+    return ;
+}
+
+//尾部追加错误描述
+void Error_manager::add_error_description(const char* p_error_description, int description_length)
+{
+    if(p_error_description !=NULL)
+    {
+        char* pt_description_front = pm_error_description;
+        int t_description_front_length = m_description_length;
+        char* pt_description_back = (char *)p_error_description;
+        int t_description_back_length = 0;
+
+        if(description_length == 0)
+        {
+            t_description_back_length = 0;
+            while (*pt_description_back != '\0')
+            {
+                t_description_back_length++;
+                pt_description_back++;
+            }
+            t_description_back_length++;
+            pt_description_back = (char *)p_error_description;
+        }
+        else
+        {
+            t_description_back_length = description_length;
+        }
+
+        int t_description_new_length = t_description_front_length + 5 + t_description_back_length - 1;
+        char* pt_description_new =  (char*) malloc(t_description_new_length );
+
+        sprintf(pt_description_new, "%s ### %s", pt_description_front, pt_description_back);
+        free_description();
+        pm_error_description = pt_description_new;
+        m_description_length = t_description_new_length;
+    }
+    return ;
+}
+//尾部追加错误描述
+void Error_manager::add_error_description(std::string & error_description_string)
+{
+    if( ! error_description_string.empty() )
+    {
+        std::string t_description_string = pm_error_description ;
+        t_description_string += (" ### "+ error_description_string);
+
+        reallocate_memory_and_copy_string(t_description_string);
+    }
+}
+
+//比较错误是否相同,
+// 注:只比较错误码和等级
+bool Error_manager::is_equal_error_manager(const Error_manager & error_manager)
+{
+    if(this->m_error_code == error_manager.m_error_code
+       && this->m_error_level == error_manager.m_error_level)
+    {
+        return true;
+    }
+    else
+    {
+        return false;
+    }
+}
+//比较并覆盖错误,讲低级错误转为字符串存放于描述中,
+//如果错误相同,则保留this的,将输入参数转入描述。
+void Error_manager::compare_and_cover_error(const Error_manager & error_manager)
+{
+    if(this->m_error_code == SUCCESS)
+    {
+        error_manager_reset(error_manager);
+    }
+    else if (error_manager.m_error_code == SUCCESS)
+    {
+		return;
+    }
+    else
+    {
+        Error_manager t_error_manager_new;
+        char* pt_string_inside = NULL;
+        int t_string_inside_length = 0;
+        if(this->m_error_level < error_manager.m_error_level)
+        {
+            t_string_inside_length = ERROR_NAMAGER_TO_STRING_FRONT_LENGTH + this->m_description_length;
+            pt_string_inside = (char*)malloc(t_string_inside_length);
+            translate_error_to_string(pt_string_inside, t_string_inside_length);
+
+            error_manager_reset(error_manager);
+            add_error_description(pt_string_inside,t_string_inside_length);
+        }
+        else
+        {
+            t_string_inside_length = ERROR_NAMAGER_TO_STRING_FRONT_LENGTH + error_manager.m_description_length;
+            pt_string_inside = (char*)malloc(t_string_inside_length);
+			((Error_manager & )error_manager).translate_error_to_string(pt_string_inside, t_string_inside_length);
+
+            add_error_description(pt_string_inside,t_string_inside_length);
+        }
+    }
+}
+//比较并覆盖错误,讲低级错误转为字符串存放于描述中,
+//如果错误相同,则保留this的,将输入参数转入描述。
+void Error_manager::compare_and_cover_error( Error_manager * p_error_manager)
+{
+	if(this->m_error_code == SUCCESS)
+	{
+		error_manager_reset(*p_error_manager);
+	}
+	else if (p_error_manager->m_error_code == SUCCESS)
+	{
+		//
+	}
+	else
+	{
+		Error_manager t_error_manager_new;
+		char* pt_string_inside = NULL;
+		int t_string_inside_length = 0;
+		if(this->m_error_level < p_error_manager->m_error_level)
+		{
+			t_string_inside_length = ERROR_NAMAGER_TO_STRING_FRONT_LENGTH + this->m_description_length;
+			pt_string_inside = (char*)malloc(t_string_inside_length);
+			translate_error_to_string(pt_string_inside, t_string_inside_length);
+
+			error_manager_reset(*p_error_manager);
+			add_error_description(pt_string_inside,t_string_inside_length);
+		}
+		else
+		{
+			t_string_inside_length = ERROR_NAMAGER_TO_STRING_FRONT_LENGTH + p_error_manager->m_description_length;
+			pt_string_inside = (char*)malloc(t_string_inside_length);
+			p_error_manager->translate_error_to_string(pt_string_inside, t_string_inside_length);
+
+			add_error_description(pt_string_inside,t_string_inside_length);
+		}
+	}
+}
+
+//将所有的错误信息,格式化为字符串,用作日志打印。
+//output:p_error_description     错误汇总的字符串指针,不可以为NULL,必须要有实际的内存
+//output:description_length      错误汇总的字符串长度,不可以为0,长度最好足够大,一般256即可。
+void Error_manager::translate_error_to_string(char* p_error_aggregate, int aggregate_length )
+{
+    char t_string_array[ERROR_NAMAGER_TO_STRING_FRONT_LENGTH] = {0};
+    char* pt_index_front = t_string_array;
+    char* pt_index_back = pm_error_description;
+    char* pt_index = p_error_aggregate;
+
+    sprintf(t_string_array, "error_code:0x%08x, error_level:%02d, error_description:", m_error_code , m_error_level );
+
+    int t_length_min = m_description_length + ERROR_NAMAGER_TO_STRING_FRONT_LENGTH -1;
+    if(t_length_min > aggregate_length)
+    {
+        t_length_min = aggregate_length;
+    }
+
+    for(int i=0;i<t_length_min; i++)
+    {
+        if(i < ERROR_NAMAGER_TO_STRING_FRONT_LENGTH -1)
+        {
+            *pt_index = *pt_index_front;
+            pt_index++;
+            pt_index_front++;
+        }
+        else
+        {
+            *pt_index = *pt_index_back;
+            pt_index++;
+            pt_index_back++;
+        }
+    }
+}
+//output:error_description_string     错误汇总的string
+void Error_manager::translate_error_to_string(std::string & error_aggregate_string)
+{
+    char t_string_array[ERROR_NAMAGER_TO_STRING_FRONT_LENGTH] = {0};
+    sprintf(t_string_array, "error_code:0x%08x, error_level:%02d, error_description:", m_error_code , m_error_level );
+
+    error_aggregate_string = t_string_array ;
+    if(pm_error_description != NULL)
+    {
+        error_aggregate_string += pm_error_description;
+    }
+    else
+    {
+        //error_aggregate_string += "NULL";
+    }
+}
+//错误码转字符串的简易版,可支持cout<<
+//return     错误汇总的string
+std::string Error_manager::to_string()
+{
+    std::string t_string;
+    translate_error_to_string(t_string);
+    return t_string;
+}
+
+
+
+
+//释放错误描述的内存,
+void Error_manager::free_description()
+{
+    if(pm_error_description != NULL)
+    {
+        free (pm_error_description);
+        pm_error_description = NULL;
+    }
+    m_description_length = 0;
+}
+
+//重新分配错误描述的内存,并从外部拷贝新的(深拷贝)
+//input:p_error_description     错误描述的字符串指针,可以为NULL,
+//input:description_length      错误描述的字符串长度,如果为0,则从p_error_description里面获取有效的长度
+void Error_manager::reallocate_memory_and_copy_string(const char* p_error_description, int description_length)
+{
+    free_description();
+
+    if(p_error_description != NULL)
+    {
+        char* pt_source = (char *)p_error_description;
+        char* pt_destination = NULL;
+
+        if(description_length == 0)
+        {
+            m_description_length = 0;
+            while (*pt_source != '\0')
+            {
+                m_description_length++;
+                pt_source++;
+            }
+            m_description_length++;
+            pt_source = (char *)p_error_description;
+        }
+        else
+        {
+            m_description_length = description_length;
+        }
+
+        pm_error_description =  (char*) malloc(m_description_length );
+        pt_destination = pm_error_description;
+
+        for(int i=0;i<m_description_length; i++)
+        {
+            *pt_destination = *pt_source;
+            pt_destination++;
+            pt_source++;
+        }
+    }
+
+    return;
+}
+
+
+//重新分配错误描述的内存,并从外部拷贝新的(深拷贝)
+//input:error_aggregate_string     错误描述的string
+void Error_manager::reallocate_memory_and_copy_string(std::string & error_aggregate_string)
+{
+    free_description();
+
+    if( ! error_aggregate_string.empty())
+    {
+        m_description_length = error_aggregate_string.length()+1;
+
+        pm_error_description =  (char*) malloc( m_description_length );
+
+        strcpy(pm_error_description ,   error_aggregate_string.c_str()  );
+    }
+}
+
+
+
+
+

+ 458 - 0
error_code/error_code.h

@@ -0,0 +1,458 @@
+
+//Error_code是错误码的底层通用模块,
+//功能:用作故障分析和处理。
+
+//用法:所有的功能接口函数return错误管理类,
+//然后上层判断分析错误码,并进行故障处理。
+
+
+
+#ifndef TEST_ERROR_ERROR_CODE_H
+#define TEST_ERROR_ERROR_CODE_H
+
+#include <string>
+#include <string.h>
+#include<iostream>
+
+//错误管理类转化为字符串 的前缀,固定长度为58
+//这个是由显示格式来确定的,如果要修改格式或者 Error_code长度超过8位,Error_level长度超过2位,折需要重新计算
+#define ERROR_NAMAGER_TO_STRING_FRONT_LENGTH   58
+
+//进程加锁的状态,
+enum Lock_status
+{
+    UNLOCK      = 0,
+    LOCK        = 1,
+};
+
+//设备使能状态,
+enum Able_status
+{
+    UNABLE      = 0,
+    ENABLE      = 1,
+};
+
+//数据是否为空
+enum Empty_status
+{
+    NON_EMPTY   = 0,
+    EMPTY       = 1,
+};
+
+
+//错误码的枚举,用来做故障分析
+enum Error_code
+{
+    //成功,没有错误,默认值0
+    SUCCESS                         = 0x00000000,
+
+
+    //基本错误码,
+    FAILED                          = 0x00000001,//失败
+    ERROR                           = 0x00000002,//错误
+    WARNING                         = 0x00000003,//警告
+    PARTIAL_SUCCESS                 = 0x00000002,//部分成功
+
+
+    NO_DATA                         = 0x00000010,//没有数据,传入参数容器内部没有数据时,
+	INVALID_MESSAGE					= 0x00000011, //无效的消息,
+    RESPONSE_TIMEOUT                = 0x00000012,
+    PAUSE                           = 0x00000013,   //急停
+    TASK_CANCEL                     = 0x00000014,   //任务取消
+
+    DISCONNECT                      = 0x00000020,   //通讯中断/断开连接
+    UNKNOW_STATU                    = 0x00000021,   //未知状态
+
+    POINTER_IS_NULL                 = 0x00000101,//空指针
+    PARAMETER_ERROR                 = 0x00000102,//参数错误,传入参数不符合规范时,
+    POINTER_MALLOC_FAIL             = 0x00000103,//手动分配内存失败
+
+    CLASS_BASE_FUNCTION_CANNOT_USE  = 0x00000201,//基类函数不允许使用,必须使用子类的
+
+	CONTAINER_IS_TERMINATE			= 0x00000301,//容器被终止
+
+//    错误码的规范,
+//    错误码是int型,32位,十六进制。
+//    例如0x12345678
+//    12表示功能模块,例如:laser雷达模块               	框架制定
+//    34表示文件名称,例如:laser_livox.cpp             框架制定
+//    56表示具体的类,例如:class laser_livox           个人制定
+//    78表示类的函数,例如:laser_livox::start();       个人制定
+//    注:错误码的制定从1开始,不要从0开始,
+//        0用作错误码的基数,用来位运算,来判断错误码的范围。
+
+    LOCATER_MSG_RESPONSE_TYPE_ERROR,                                //测量反馈消息类型错误(致命)
+    LOCATER_MSG_RESPONSE_INFO_ERROR,
+    LOCATER_MSG_REQUEST_CANCELED,
+    LOCATER_MSG_REQUEST_INVALID,
+    LOCATER_MSG_RESPONSE_HAS_NO_REQUEST,
+    LOCATER_MSG_REQUEST_REPEATED,
+
+   /*
+    * parkspace error code
+    */
+    PARKSPACE_REQUEST_MSG_TYPE_ERROR                = 0x04010000,
+    PARKSPACE_ALLOCMSG_RESPONSE_HAS_NO_REQUEST,
+    PARKSPACE_SEARCHMSG_RESPONSE_HAS_NO_REQUEST,
+    PARKSPACE_RELEASEMSG_RESPONSE_HAS_NO_REQUEST,
+    PARKSPACE_ALLOC_REQUEST_INVALID,
+    PARKSPACE_SEARCH_REQUEST_INVALID,
+    PARKSPACE_RELEASE_REQUEST_INVALID,
+
+    PARKSPACE_ALLOC_REQUEST_REPEATED,
+    PARKSPACE_SEARCH_REQUEST_REPEATED,
+    PARKSPACE_RELEASE_REQUEST_REPEATED,
+
+    PARKSPACE_ALLOC_RESPONSE_TYPE_ERROR,
+    PARKSPACE_SEARCH_RESPONSE_TYPE_ERROR,
+    PARKSPACE_RELEASE_RESPONSE_TYPE_ERROR,
+
+    PARKSPACE_ALLOC_RESPONSE_INFO_ERROR,
+    PARKSPACE_SEARCH_RESPONSE_INFO_ERROR,
+    PARKSPACE_RELEASE_RESPONSE_INFO_ERROR,
+
+    PARKSPACE_ALLOC_REQUEST_CANCELED,
+    PARKSPACE_SEARCH_REQUEST_CANCELED,
+    PARKSPACE_RELEASE_REQUEST_CANCELED,
+
+
+	//Communication module, 通信模块
+	COMMUNICATION_BASE_ERROR_BASE					= 0x11010000,
+	COMMUNICATION_READ_PROTOBUF_ERROR,				//模块,读取参数错误
+	COMMUNICATION_BIND_ERROR,
+	COMMUNICATION_CONNECT_ERROR,
+	COMMUNICATION_ANALYSIS_TIME_OUT,									//解析超时,
+	COMMUNICATION_EXCUTER_IS_BUSY,										//处理器正忙, 请稍等
+
+
+
+
+    DISPATCH_ERROR_BASE=	0x13000000,
+    DISPATCH_MANAGER_ERROR_BASE	=0x13010000,
+    DISPATCH_MANAGER_READ_PROTOBUF_ERROR,		//调度管理模块,读取参数错误
+    DISPATCH_MANAGER_STATUS_BUSY,		//调度管理模块,状态正忙
+    DISPATCH_MANAGER_STATUS_ERROR,		//调度管理模块,状态错误
+    DISPATCH_MANAGER_TASK_TYPE_ERROR,		//调度管理模块,任务类型错误
+    DISPATCH_MANAGER_IS_NOT_READY,		//调度管理模块,不在准备状态
+    CARRIER_ERROR_BASE	=0x13020000,
+    CARRIER_READ_PROTOBUF_ERROR	,	//搬运器模块,读取参数错误
+    CARRIER_STATUS_BUSY	,	//搬运器模块,状态正忙
+    CARRIER_STATUS_ERROR,		//搬运器模块,状态错误
+    CARRIER_STATUS_DISCONNECT,		//搬运器模块,状态断连
+    CARRIER_TASK_TYPE_ERROR	,	//搬运器模块,任务类型错误
+    CARRIER_TASK_OVER_TIME	,	//搬运器模块,任务超时
+    CARRIER_IS_NOT_READY	,	//搬运器模块,不在准备状态
+    CARRIER_RESPONS_ERROR	,	//搬运器模块,指令的执行失败
+    CARRIER_TASK_NOTHINGNESS,		//搬运器模块,任务不存在
+    SNAP7_ERROR_BASE	= 0x1401000,
+    SNAP7_READ_PROTOBUF_ERROR	,	//snap7通信模块,读取参数错误
+    SNAP7_CONNECT_ERROR	,	//snap7通信模块,连接错误
+    SNAP7_DISCONNECT_ERROR	,	//snap7通信模块,断连错误
+    SNAP7_READ_ERROR	,	//snap7通信模块,读取错误
+    SNAP7_WRITE_ERROR	,	//snap7通信模块,写入错误
+    SNAP7_ANALYSIS_TIME_OUT	,	//解析超时
+    SNAP7_EXCUTER_IS_BUSY	,	//处理器正忙 请稍等
+
+
+    LASER_ERROR_BASE	=0x01000000,
+    LASER_BASE_ERROR_BASE	=0x01010000,
+    LASER_TASK_PARAMETER_ERROR	=0x01010001,	//雷达基类模块,任务输入参数错误
+    LASER_CONNECT_FAILED,		//雷达基类模块,连接失败
+    LASER_START_FAILED,		//雷达基类模块,开始扫描失败
+    LASER_CHECK_FAILED,		//雷达基类模块,检查失败
+    LASER_STATUS_BUSY,		//雷达基类模块,状态正忙
+    LASER_STATUS_ERROR,		//雷达基类模块,状态错误
+    LASER_TASK_OVER_TIME,		//雷达基类模块,任务超时
+    LASER_QUEUE_ERROR,		//雷达基类模块,数据缓存错误
+    LIVOX_ERROR_BASE	=0x01020000,
+    LIVOX_START_FAILE,		//livox模块,开始扫描失败
+    LIVOX_TASK_TYPE_ERROR,		//livox模块,任务类型错误
+    lIVOX_CANNOT_PUSH_DATA,		//livox模块,不能添加扫描的数据
+    lIVOX_CHECK_FAILED,		//livox模块,检查失败
+    lIVOX_STATUS_BUSY,		//livox模块,状态正忙
+    lIVOX_STATUS_ERROR,		//livox模块,状态错误
+    LASER_MANAGER_ERROR_BASE=	0x01030000,
+    LASER_MANAGER_READ_PROTOBUF_ERROR,		//雷达管理模块,读取参数错误
+    LASER_MANAGER_STATUS_BUSY,		//雷达管理模块,状态正忙
+    LASER_MANAGER_STATUS_ERROR,		//雷达管理模块,状态错误
+    LASER_MANAGER_TASK_TYPE_ERROR,		//雷达管理模块,任务类型错误
+    LASER_MANAGER_IS_NOT_READY,		//雷达管理模块,不在准备状态
+    LASER_MANAGER_TASK_OVER_TIME,		//雷达管理模块,任务超时
+    LASER_MANAGER_LASER_INDEX_ERRPR,		//雷达管理模块,雷达索引错误,编号错误。
+    LASER_MANAGER_LASER_INDEX_REPEAT,		//雷达管理模块,需要扫描的雷达索引重复,可忽略的错误,提示作用
+    LIVOX_DRIVER_ERROR_BASE	=0x01040000,
+    LIVOX_DRIVER_SN_REPEAT,		//livox驱动模块,雷达广播码重复
+    LIVOX_DRIVER_SN_ERROR,		//livox驱动模块,雷达广播码错误
+    LIVOX_SKD_INIT_FAILED,		//livox驱动模块,livox_sdk初始化失败
+    LIVOX_DRIVER_NOT_READY,		//livox驱动模块,livox没有准备好.
+
+    LOCATER_ERROR_BASE	=0x03000000,
+    LOCATER_MANAGER_ERROR_BASE	=0x03010000,
+    LOCATER_MANAGER_READ_PROTOBUF_ERROR,		//定位管理模块,读取参数错误
+    LOCATER_MANAGER_STATUS_BUSY,		//定位管理模块,状态正忙
+    LOCATER_MANAGER_STATUS_ERROR,		//定位管理模块,状态错误
+    LOCATER_MANAGER_TASK_TYPE_ERROR,		//定位管理模块,任务类型错误
+    LOCATER_MANAGER_IS_NOT_READY,		//定位管理模块,不在准备状态
+    LOCATER_MANAGER_CLOUD_MAP_ERROR,		//定位管理模块,任务输入点云map的error
+    LOCATER_MANAGER_TASK_OVER_TIME,		//定位管理模块,任务超时
+    LOCATER_ALGORITHM_ERROR_BASE	=0x03020000,
+    LOCATER_TASK_INIT_CLOUD_EMPTY	,	//定位任务初始化点云为空
+    LOCATER_TASK_ERROR,		//定位任务错误
+    LOCATER_TASK_INPUT_CLOUD_UNINIT,		//定位任务输入点云为空
+    LOCATER_INPUT_CLOUD_EMPTY,		//定位输入点云为空
+    LOCATER_YOLO_UNINIT,		//定位yolo未初始化
+    LOCATER_POINTSIFT_UNINIT,		//定位POINTSIFT未初始化
+    LOCATER_3DCNN_UNINIT,		//定位3DCNN未初始化
+    LOCATER_INPUT_YOLO_CLOUD_EMPTY,		//定位输入yolo点云为空
+    LOCATER_Y_OUT_RANGE_BY_PLC,		//定位超出plc的限制范围
+    LOCATER_MEASURE_HEIGHT_CLOUD_EMPTY,		//定位测量高点云为空
+    LOCATER_SIFT_ERROR_BASE	=0x03020100,
+    LOCATER_SIFT_INIT_FAILED,		//定位过滤模块,初始化失败
+    LOCATER_SIFT_INPUT_CLOUD_UNINIT,		//定位过滤模块,输入点云未初始化
+    LOCATER_SIFT_INPUT_CLOUD_EMPTY,		//定位过滤模块,输入点云为空
+    LOCATER_SIFT_GRID_ERROR,		//定位过滤模块,筛选网格错误
+    LOCATER_SIFT_SELECT_ERROR,		//定位过滤模块,筛选选择错误
+    LOCATER_SIFT_CLOUD_VERY_LITTLE,		//定位过滤模块,筛选点云很少
+    LOCATER_SIFT_CREATE_INPUT_DATA_FAILED,		//定位过滤模块,筛选创建输入数据失败
+    LOCATER_SIFT_PREDICT_FAILED,		//定位过滤模块,预测失败
+    LOCATER_SIFT_PREDICT_TIMEOUT,		//定位过滤模块,预测超时
+    LOCATER_SIFT_PREDICT_NO_WHEEL_POINT,		//定位过滤模块,预测结果没有车轮点云
+    LOCATER_SIFT_PREDICT_NO_CAR_POINT,		//定位过滤模块,预测结果没有车身点云
+    LOCATER_SIFT_FILTE_OBS_FAILED,		//定位过滤模块,过滤OBS失败
+    LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED,		//定位过滤模块,输入范围参数错误
+    LOCATER_3DCNN_ERROR_BASE	=0x03020300,
+    LOCATER_3DCNN_INIT_FAILED,		//定位3DCNN模块,初始化失败
+    LOCATER_3DCNN_INPUT_CLOUD_UNINIT,		//定位3DCNN模块,输入点云未初始化
+    LOCATER_3DCNN_INPUT_CLOUD_EMPTY,		//定位3DCNN模块,输入点云为空
+    LOCATER_3DCNN_INPUT_CLOUD_MAP_ERROR,		//定位3DCNN模块,输入点云的map错误
+    LOCATER_3DCNN_PCA_OUT_ERROR,		//定位3DCNN模块,pca错误
+    LOCATER_3DCNN_EXTRACT_RECT_ERROR,		//定位3DCNN模块,提取矩形错误
+    LOCATER_3DCNN_RECT_SIZE_ERROR,		//定位3DCNN模块,矩形范围错误
+    LOCATER_3DCNN_PREDICT_FAILED,		//定位3DCNN模块,预测失败
+    LOCATER_3DCNN_VERIFY_RECT_FAILED_3,		//定位3DCNN模块,验证矩形失败3
+    LOCATER_3DCNN_VERIFY_RECT_FAILED_4,		//定位3DCNN模块,验证矩形失败4
+    LOCATER_3DCNN_KMEANS_FAILED,		//定位3DCNN模块,k均值失败
+    LOCATER_3DCNN_IIU_FAILED,		//定位3DCNN模块,IIU失败
+    LOCATER_3DCNN_PCA_OUT_CLOUD_EMPTY,		//定位3DCNN模块,pca输出点云为空
+
+    WANJI_LIDAR_DEVICE_ERROR_BASE	=0x06080000,	//万集设备模块,错误基类
+    WANJI_LIDAR_DEVICE_STATUS_BUSY,		//万集设备模块,状态正忙
+    WANJI_LIDAR_DEVICE_STATUS_ERROR,		//万集设备模块,状态错误
+    WANJI_LIDAR_DEVICE_TASK_TYPE_ERROR,		//万集设备模块,任务类型错误
+    WANJI_LIDAR_DEVICE_TASK_OVER_TIME,		//万集设备模块,任务超时
+    WANJI_LIDAR_DEVICE_NO_CLOUD,		//万集设备模块,没有点云
+    WJ_LIDAR_COMMUNICATION_ERROR_BASE	=0x06010000,
+    WJ_LIDAR_COMMUNICATION_UNINITIALIZED,		//万集通信,未初始化
+    WJ_LIDAR_COMMUNICATION_DISCONNECT,		//万集通信,断连
+    WJ_LIDAR_COMMUNICATION_FAULT,		//万集通信,故障
+    WJ_LIDAR_CONNECT_FAILED,		//万集通信,连接失败
+    WJ_LIDAR_UNINITIALIZED,		//万集通信,未初始化
+    WJ_LIDAR_READ_FAILED,		//万集通信,读取失败
+    WJ_LIDAR_WRITE_FAILED,		//万集通信,写入失败
+    WJ_LIDAR_GET_CLOUD_TIMEOUT,		//万集通信,获取点云超时
+    WJ_PROTOCOL_ERROR_BASE	=0x06020000,
+    WJ_PROTOCOL_STATUS_BUSY,		//万集解析,状态正忙
+    WJ_PROTOCOL_STATUS_ERROR,		//万集解析,状态错误
+    WJ_PROTOCOL_INTEGRITY_ERROR,		//万集解析,完整性错误
+    WJ_PROTOCOL_PARSE_FAILED,		//万集解析,解析失败
+    WJ_PROTOCOL_EMPTY_PACKAGE,		//万集解析,空包
+    WJ_PROTOCOL_EXCEED_MAX_SIZE,		//万集解析,超出最大范围
+    WJ_REGION_ERROR_BASE	=0x06030000,
+    WJ_REGION_EMPTY_CLOUD,		//万集测量,空点云
+    WJ_REGION_EMPTY_NO_WHEEL_INFORMATION,		//万集测量,没有车轮信息
+    WJ_REGION_RECTANGLE_ANGLE_ERROR,		//万集测量,矩形旋转角错误
+    WJ_REGION_RECTANGLE_SIZE_ERROR,		//万集测量,矩形大小错误
+    WJ_REGION_RECTANGLE_SYMMETRY_ERROR,		//万集测量,矩形对称错误
+    WJ_REGION_CLUSTER_SIZE_ERROR,		//万集测量,簇大小错误
+    WJ_MANAGER_ERROR_BASE	=0x06040000,
+    WJ_MANAGER_UNINITIALIZED,		//万集管理模块,未初始化
+    WJ_MANAGER_LIDAR_DISCONNECTED,		//万集管理模块,雷达断链
+    WJ_MANAGER_PLC_DISCONNECTED,		//万集管理模块,plc断链
+    WJ_MANAGER_EMPTY_CLOUD,		//万集管理模块,空点云
+    WJ_MANAGER_READ_PROTOBUF_ERROR,		//万集管理模块,读取参数错误
+    WJ_MANAGER_INIT_ERROR,		//万集管理模块,重复初始化
+    WJ_MANAGER_TASK_TYPE_ERROR,		//万集管理模块,任务类型错误
+    WJ_MANAGER_STATUS_BUSY,		//万集管理模块,状态正忙
+    WJ_MANAGER_STATUS_ERROR,		//万集管理模块,状态错误
+    WJ_MANAGER_LASER_INDEX_ERRPR,		//万集管理模块,雷达索引错误,编号错误。
+    WJ_MANAGER_LASER_INDEX_REPEAT,		//万集管理模块,需要扫描的雷达索引重复,可忽略的错误,提示作用
+    WJ_MANAGER_TASK_OVER_TIME,		//万集管理模块,任务超时
+    WJ_LIDAR_TASK_ERROR_BASE	=0x06050000,
+    WJ_LIDAR_TASK_EMPTY_RESULT,		//万集任务模块,空结果
+    WJ_LIDAR_TASK_EMPTY_TASK,		//万集任务模块,空任务
+    WJ_LIDAR_TASK_WRONG_TYPE,		//万集任务模块,错误类型
+    WJ_LIDAR_TASK_INVALID_TASK,		//万集任务模块,无效任务
+    WJ_LIDAR_TASK_MEASURE_FAILED,		//万集任务模块,测量失败
+
+
+};
+
+//错误等级,用来做故障处理
+enum Error_level
+{
+//    正常,没有错误,默认值0
+    NORMAL                = 0,
+
+
+//    轻微故障,可忽略的故障,NEGLIGIBLE_ERROR
+//    提示作用,不做任何处理,不影响代码的流程,
+//    用作一些不重要的事件,即使出错也不会影响到系统功能,
+//    例如:文件保存错误,等
+    NEGLIGIBLE_ERROR      = 1,
+
+
+//    一般故障,MINOR_ERROR
+//    用作底层功能函数的错误返回,表示该功能函数执行失败,
+//    返回给应用层之后,需要做故障分析和处理,
+//    例如:雷达数据传输失败,应用层就需要进行重新扫描,或者重连,或者重置参数等。
+    MINOR_ERROR           = 2,
+
+
+//    严重故障,MAJOR_ERROR
+//    用作应用层的任务事件的结果,表示该功能模块失败。
+//    通常是底层函数返回一般故障之后,应用层无法处理并解决故障,此时就要进行故障升级,
+//    从一般故障升级为严重故障,然后进行回退流程,回退已经执行的操作,最终回到故障待机状态。
+//    需要外部清除故障,并复位至正常待机状态,才能恢复功能的使用。
+//    例如:雷达扫描任务失败,且无法自动恢复。
+    MAJOR_ERROR           = 3,
+
+
+//    致命故障,CRITICAL_ERROR
+//    系统出现致命错误。导致系统无法正常运行,
+//    此时系统应该紧急停机,执行紧急流程,快速停机。
+//    此时不允许再执行任何函数和任务指令,防止系统故障更加严重。
+//    也不需要做任何错误处理了,快速执行紧急流程。
+//    例如:内存错误,进程挂死,关键设备失控,监控设备报警,等
+    CRITICAL_ERROR        = 4,
+};
+
+
+class Error_manager
+{
+public://外部接口函数
+    //构造函数
+    Error_manager();
+    //拷贝构造
+    Error_manager(const Error_manager & error_manager);
+    //赋值构造
+    Error_manager(Error_code error_code, Error_level error_level = NORMAL,
+                  const char* p_error_description = NULL, int description_length = 0);
+    //赋值构造
+    Error_manager(Error_code error_code, Error_level error_level , std::string & error_aggregate_string);
+    //析构函数
+    ~Error_manager();
+
+    //初始化
+    void error_manager_init();
+    //初始化
+    void error_manager_init(Error_code error_code, Error_level error_level = NORMAL,
+                            const char* p_error_description = NULL, int description_length = 0);
+    //初始化
+    void error_manager_init(Error_code error_code, Error_level error_level , std::string & error_aggregate_string);
+    //重置
+    void error_manager_reset(Error_code error_code, Error_level error_level = NORMAL,
+                             const char* p_error_description = NULL, int description_length = 0);
+    //重置
+    void error_manager_reset(Error_code error_code, Error_level error_level , std::string & error_aggregate_string);
+    //重置
+    void error_manager_reset(const Error_manager & error_manager);
+    //清除所有内容
+    void error_manager_clear_all();
+
+    //重载=
+    Error_manager& operator=(const Error_manager & error_manager);
+    //重载=,支持Error_manager和Error_code的直接转化,会清空错误等级和描述
+    Error_manager& operator=(Error_code error_code);
+    //重载==
+    bool operator==(const Error_manager & error_manager);
+    //重载==,支持Error_manager和Error_code的直接比较
+    bool operator==(Error_code error_code);
+    //重载!=
+    bool operator!=(const Error_manager & error_manager);
+    //重载!=,支持Error_manager和Error_code的直接比较
+    bool operator!=(Error_code error_code);
+	//重载<<,支持cout<<
+	friend std::ostream & operator<<(std::ostream &out, Error_manager &error_manager);
+
+
+    //获取错误码
+    Error_code get_error_code();
+    //获取错误等级
+    Error_level get_error_level();
+    //获取错误描述的指针,(浅拷贝)
+    char* get_error_description();
+
+    //复制错误描述,(深拷贝)
+    //output:p_error_description     错误描述的字符串指针,不可以为NULL,必须要有实际的内存
+    //output:description_length      错误描述的字符串长度,不可以为0,长度最好足够大,一般256即可。
+    void copy_error_description(const char* p_error_description, int description_length);
+    //复制错误描述,(深拷贝)
+    //output:error_description_string     错误描述的string
+    void copy_error_description(std::string & error_description_string);
+
+    //设置错误码
+    void set_error_code(Error_code error_code);
+    //比较错误等级并升级,取高等级的结果
+    void set_error_level_up(Error_level error_level);
+    //比较错误等级并降级,取低等级的结果
+    void set_error_level_down(Error_level error_level);
+    //错误等级,设定到固定值
+    void set_error_level_location(Error_level error_level);
+    //设置错误描述
+    void set_error_description(const char* p_error_description, int description_length = 0);
+    //设置错误描述
+    void set_error_description(std::string & error_description_string);
+
+    //尾部追加错误描述
+    void add_error_description(const char* p_error_description, int description_length = 0);
+    //尾部追加错误描述
+    void add_error_description(std::string & error_description_string);
+
+    //比较错误是否相同,
+    // 注:只比较错误码和等级
+	bool is_equal_error_manager(const Error_manager & error_manager);
+	//比较并覆盖错误,讲低级错误转为字符串存放于描述中,
+	//如果错误相同,则保留this的,将输入参数转入描述。
+	void compare_and_cover_error(const Error_manager & error_manager);
+	//比较并覆盖错误,讲低级错误转为字符串存放于描述中,
+	//如果错误相同,则保留this的,将输入参数转入描述。
+	void compare_and_cover_error( Error_manager * p_error_manager);
+
+	//将所有的错误信息,格式化为字符串,用作日志打印。
+    //output:p_error_description     错误汇总的字符串指针,不可以为NULL,必须要有实际的内存
+    //output:description_length      错误汇总的字符串长度,不可以为0,长度最好足够大,一般256即可。
+    void translate_error_to_string(char* p_error_aggregate, int aggregate_length);
+    //output:error_description_string     错误汇总的string
+    void translate_error_to_string(std::string & error_aggregate_string);
+    //错误码转字符串的简易版,可支持cout<<
+    //return     错误汇总的string
+    std::string to_string();
+
+
+
+protected:
+    Error_code              m_error_code;               //错误码
+    Error_level             m_error_level;              //错误等级
+    char*                   pm_error_description;       //错误描述
+    int                     m_description_length;       //错误描述的字符长度
+
+protected://内部功能函数
+public:
+    //释放错误描述的内存,
+    void free_description();
+
+    //重新分配错误描述的内存,并从外部拷贝新的(深拷贝)
+    //input:p_error_description     错误描述的字符串指针,可以为NULL,
+    //input:description_length      错误描述的字符串长度,如果为0,则从p_error_description里面获取有效的长度
+    void reallocate_memory_and_copy_string(const char* p_error_description, int description_length = 0);
+
+    //重新分配错误描述的内存,并从外部拷贝新的(深拷贝)
+    //input:error_aggregate_string     错误描述的string
+    void reallocate_memory_and_copy_string(std::string & error_aggregate_string);
+};
+
+
+
+
+#endif //TEST_ERROR_ERROR_CODE_H
+

+ 547 - 0
laser/Laser.cpp

@@ -0,0 +1,547 @@
+
+
+#include "Laser.h"
+#include "laser_message.pb.h"
+
+Laser_base::Laser_base(int laser_id, Laser_proto::laser_parameter laser_param)
+:m_laser_id(laser_id)
+,m_laser_param(laser_param)
+,m_laser_scan_flag(false)
+,m_laser_statu(LASER_DISCONNECT)
+,m_points_count(0)
+,m_save_flag(false)
+{
+	mp_thread_receive = NULL;
+	mp_thread_transform = NULL;
+	mp_thread_publish = NULL;
+	init_laser_matrix();
+	mp_laser_task = NULL;
+}
+Laser_base::~Laser_base()
+{
+	
+	disconnect_laser();
+	close_save_path();
+}
+
+//雷达链接设备,为3个线程添加线程执行函数。
+Error_manager Laser_base::connect_laser()
+{
+	//检查雷达状态
+	if ( m_laser_statu != LASER_DISCONNECT )
+	{
+	    return Error_manager(Error_code::LASER_STATUS_ERROR, Error_level::MINOR_ERROR,
+	    					" Laser_base::connect_laser  m_laser_statu != LASER_DISCONNECT ");
+	}
+	else
+	{
+		//这里不建议用detach,而是应该在disconnect里面使用join
+		//创建接受缓存的线程,不允许重复创建
+		if (mp_thread_receive != NULL)
+		{
+			return Error_manager(Error_code::LASER_CONNECT_FAILED, Error_level::MINOR_ERROR,
+								 " mp_thread_receive is alive ");
+		}
+		else
+		{
+			//接受缓存的线程,线程存活,暂停运行
+			m_condition_receive.reset(false, false, false);
+			mp_thread_receive = new std::thread(&Laser_base::thread_receive, this);
+		}
+		//转化数据的线程,不允许重复创建
+		if (mp_thread_transform != NULL)
+		{
+			return Error_manager(Error_code::LASER_CONNECT_FAILED, Error_level::MINOR_ERROR,
+								 " mp_thread_transform is alive ");
+		}
+		else
+		{
+			//转化数据的线程,线程存活,暂停运行
+			m_condition_transform.reset(false, false, false);
+			mp_thread_transform = new std::thread(&Laser_base::thread_transform, this);
+		}
+		//发布信息的线程,不允许重复创建
+		if (mp_thread_publish != NULL)
+		{
+			return Error_manager(Error_code::LASER_CONNECT_FAILED, Error_level::MINOR_ERROR,
+								 " mp_thread_publish is alive ");
+		}
+		else
+		{
+			//发布信息的线程,线程存活,循环运行,
+			//注:mp_thread_publish 需要线程持续不断的往上位机发送信息,不受任务的影响。
+			m_condition_publish.reset(false, true, false);
+			mp_thread_publish = new std::thread(&Laser_base::thread_publish, this);
+		}
+
+		LOG(INFO)<<"laser connected success";
+		m_laser_statu = LASER_READY;
+
+	}
+	return Error_code::SUCCESS;
+}
+//雷达断开链接,释放3个线程
+Error_manager Laser_base::disconnect_laser()
+{
+	//终止队列,防止 wait_and_pop 阻塞线程。
+	m_queue_laser_data.termination_queue();
+	//杀死3个线程,强制退出
+	if (mp_thread_receive)
+	{
+		m_condition_receive.kill_all();
+	}
+	if (mp_thread_transform)
+	{
+		m_condition_transform.kill_all();
+	}
+	if (mp_thread_publish)
+	{
+		m_condition_publish.kill_all();
+	}
+	//回收3个线程的资源
+	if (mp_thread_receive)
+	{
+		mp_thread_receive->join();
+		delete mp_thread_receive;
+		mp_thread_receive = NULL;
+	}
+	if (mp_thread_transform)
+	{
+		mp_thread_transform->join();
+		delete mp_thread_transform;
+		mp_thread_transform = 0;
+	}
+	if (mp_thread_publish)
+	{
+		mp_thread_publish->join();
+		delete mp_thread_publish;
+		mp_thread_publish = NULL;
+	}
+	//清空队列
+	m_queue_laser_data.clear_and_delete();
+
+	if ( m_laser_statu != LASER_FAULT  )
+	{
+		m_laser_statu = LASER_DISCONNECT;
+	}
+	return Error_code::SUCCESS;
+}
+
+
+//对外的接口函数,负责接受并处理任务单,
+//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+Error_manager Laser_base::execute_task(Task_Base* p_laser_task)
+{
+	//检查指针
+	if(p_laser_task == NULL)
+	{
+		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+							 "Laser_base::execute_task failed, POINTER_IS_NULL");
+	}
+	else
+	{
+		return Error_manager(Error_code::CLASS_BASE_FUNCTION_CANNOT_USE, Error_level::NEGLIGIBLE_ERROR,
+							 "Laser_base::execute_task cannot use");
+	}
+}
+//检查雷达状态,是否正常运行
+Error_manager Laser_base::check_laser()
+{
+	if ( is_ready() )
+	{
+		return Error_code::SUCCESS;
+	}
+	return Error_manager(Error_code::LASER_CHECK_FAILED, Error_level::MINOR_ERROR,
+						" check_laser failed ");
+}
+//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+Error_manager Laser_base::start_scan()
+{
+	//LOG(INFO) << " Laser_base::start_scan "<< this;
+	if ( is_ready() )
+	{
+		//启动雷达扫描
+		m_laser_scan_flag=true;				//启动雷达扫描
+		m_laser_statu = LASER_BUSY;			//雷达状态 繁忙
+		m_condition_receive.notify_all(true);		//唤醒接受线程
+		m_condition_transform.notify_all(true);	//唤醒转化线程
+		//重置数据
+		m_points_count=0;
+		m_queue_laser_data.clear_and_delete();
+		m_last_data.clear();
+		return Error_code::SUCCESS;
+	}
+	else
+	{
+		return Error_manager(Error_code::LASER_START_FAILED, Error_level::MINOR_ERROR,
+							 "Laser_base::start_scan() is not ready ");
+	}
+}
+//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+Error_manager Laser_base::stop_scan()
+{
+	//LOG(INFO) << " Laser_base::stop_scan "<< this;
+	//stop_scan 只是将 m_laser_scan_flag 改为 stop。
+	//然后多线程内部判断 m_laser_scan_flag,然后自动停止线程
+	m_laser_scan_flag=false;
+	return Error_code::SUCCESS;
+}
+
+//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+Error_manager Laser_base::end_task()
+{
+	//LOG(INFO) << " Laser_base::end_task "<< this;
+	m_laser_scan_flag=false;
+	m_condition_receive.notify_all(false);
+	m_condition_transform.notify_all(false);
+	m_points_count=0;
+	m_queue_laser_data.clear_and_delete();
+	m_last_data.clear();
+
+	close_save_path();
+
+	//在结束任务单时,将雷达任务状态改为 TASK_OVER 已结束
+	if(mp_laser_task !=NULL)
+	{
+		//判断任务单的错误等级,
+		if ( mp_laser_task->get_task_error_manager().get_error_level() <= Error_level::MINOR_ERROR)
+		{
+			if ( m_laser_statu == LASER_BUSY )
+			{
+				//故障等级为 NORMAL NEGLIGIBLE_ERROR MINOR_ERROR,则恢复待机,可以接受下一次的任务单
+				m_laser_statu = LASER_READY;
+			}
+
+		}
+		else
+		{
+			//故障等级为 MAJOR_ERROR CRITICAL_ERROR,则雷达故障,不可以再接受任务单。
+			m_laser_statu = LASER_FAULT;
+		}
+		//强制改为TASK_OVER,不管它当前在做什么。
+		mp_laser_task->set_task_statu(TASK_OVER);
+	}
+	return Error_code::SUCCESS;
+}
+
+
+
+//设置保存文件的路径,并打开文件,
+Error_manager Laser_base::set_open_save_path(std::string save_path,bool is_save)
+{
+	m_save_flag = is_save;
+	m_points_log_tool.close();
+	m_binary_log_tool.close();
+	if (is_save == false)
+	{
+		return Error_code::SUCCESS;
+	}
+	else
+	{
+		m_save_path = save_path;
+		char pts_file[255] = { 0 };
+		sprintf(pts_file, "%s/pts%d.txt", save_path.c_str(), m_laser_id+1);
+		m_points_log_tool.open(pts_file);
+		//std::cout << "huli m_points_log_tool path "<< pts_file << std::endl;
+
+		char bin_file[255] = { 0 };
+		sprintf(bin_file, "%s/laser%d.data", save_path.c_str(), m_laser_id+1);
+		m_binary_log_tool.open(bin_file,true);
+		return Error_code::SUCCESS;
+	}
+}
+//关闭保存文件,推出前一定要执行
+Error_manager Laser_base::close_save_path()
+{
+	m_save_flag = false;
+	m_points_log_tool.close();
+	m_binary_log_tool.close();
+	return Error_code::SUCCESS;
+}
+
+//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+bool Laser_base::is_ready()
+{
+	return ( get_laser_statu() == LASER_READY );
+}
+//获取雷达状态
+Laser_statu Laser_base::get_laser_statu()
+{
+	return m_laser_statu;
+}
+//获取雷达id
+int Laser_base::get_laser_id()
+{
+	return m_laser_id;
+}
+
+//线程执行函数,将二进制消息存入队列缓存,
+void Laser_base::thread_receive()
+{
+	LOG(INFO) << " thread_receive start "<< this;
+	//接受雷达消息,每次循环只接受一个 Binary_buf
+	while (m_condition_receive.is_alive())
+	{
+
+		m_condition_receive.wait();
+		if ( m_condition_receive.is_alive() )
+		{
+			//tp_binaty_buf的内存 需要手动分配,然后存入链表。
+			//m_queue_laser_data的内存由 Laser_base 基类管理。
+			Binary_buf* tp_binaty_buf = new Binary_buf();
+			//获取雷达的通信消息缓存
+			if (this->receive_buf_to_queue(*tp_binaty_buf))
+			{
+				//将缓存 存入队列。
+				//thread_receive存入前要手动分配内存,thread_transform取出后要记得释放。
+				m_queue_laser_data.push(tp_binaty_buf);
+			}
+			else
+			{
+				delete tp_binaty_buf;
+				tp_binaty_buf=NULL;
+
+				//接受线程无法接受到数据的同时,也收到了雷达停止扫描的信息,那么线程停止
+				//如果m_laser_scan_flag停止扫描,但是receive_buf_to_queue仍然能够接受到数据。那么线程继续运行。
+				//m_laser_scan_flag停止的瞬间,可能还有残留的数据,需要继续执行。
+				if ( !m_laser_scan_flag )
+				{
+					//停止线程,m_condition_receive.wait() 函数将会阻塞。
+					m_condition_receive.set_pass_ever(false);
+				}
+			}			
+		}
+	}
+	LOG(INFO) << " thread_receive end :"<<this;
+	return;
+}
+
+
+//线程执行函数,转化并处理三维点云。
+void Laser_base::thread_transform()
+{
+	LOG(INFO) << " thread_transform start "<< this;
+	//转化雷达数据,每次循环只转化一个 Binary_buf,然后得到 t_point3D_cloud.size() 个三维点,
+	while (m_condition_transform.is_alive())
+	{
+		m_condition_transform.wait();
+		if ( m_condition_transform.is_alive() )
+		{
+			//tp_binaty_buf的内存 从链表取出时,就自带内存了。需要手动释放。
+			//m_queue_laser_data的内存由 Laser_base 基类管理。
+			Binary_buf* tp_binaty_buf=NULL;
+			//第1步,从队列中取出缓存。
+			int huli_test = m_queue_laser_data.size();
+			//thread_receive存入前要手动分配内存,thread_transform取出后要记得释放。
+			bool t_pop_flag = m_queue_laser_data.try_pop(tp_binaty_buf);
+			/*if ( t_pop_flag )
+			{
+			    std::cout << "huli m_queue_laser_data.size() last = " << huli_test << std::endl;
+				std::cout << "huli m_queue_laser_data.size() now = " << m_queue_laser_data.size() << std::endl;
+
+			}*/
+
+			//第2步,处理数据,缓存转化缓存为三维点。
+			//如果获取到了 Binary_buf,或者上次有未完成的 m_last_data,那么就执行数据转化。
+			//注注注注注意了,扫描停止后,m_last_data一定要保证清空,不能有垃圾数据残留,这会阻塞线程的暂停
+			if (t_pop_flag || m_last_data.get_length() > 0)
+			{
+				//std::cout << "huli thread_transform " << m_queue_laser_data.size() << std::endl;
+				//std::cout << "huli t_pop_flag = "<< t_pop_flag << std::endl;
+				//缓存类型
+				Buf_type t_buf_type = BUF_UNKNOW;
+				//雷达扫描结果,三维点云(雷达自身坐标系)
+				std::vector<CPoint3D> t_point3D_cloud;
+				//第2.1步,缓存转化为三维点。
+				if (t_pop_flag)
+				{
+					if (tp_binaty_buf == NULL)
+					{
+						//try_pop返回true,但是tp_binaty_buf没有数据,直接跳过。这个一般不可能出现。
+						continue;
+					}
+					else
+					{
+						//保存雷达通信 二进制的源文件。
+						if(m_save_flag)
+						{
+							m_binary_log_tool.write(tp_binaty_buf->get_buf(), tp_binaty_buf->get_length());
+						}
+						//缓存转化为三维点。传入新的缓存,
+						t_buf_type= this->transform_buf_to_points(tp_binaty_buf, t_point3D_cloud);
+					}					
+				}
+				else if(m_last_data.get_length() > 0)
+				{
+					//缓存转化为三维点。没有新消息,就传null,这将处理 m_last_data 上一次遗留的缓存。
+					t_buf_type = this->transform_buf_to_points(NULL, t_point3D_cloud);
+				}
+
+				//第2.2步,判断t_buf_type,处理雷达数据。并存入任务单
+				if (t_buf_type == BUF_UNKNOW || t_buf_type == BUF_READY)
+				{
+					//跳过这次循环。
+					continue;
+				}
+				else if (t_buf_type == BUF_DATA || t_buf_type == BUF_START || t_buf_type == BUF_STOP)
+				{
+					//循环处理雷达数据
+					for (int i = 0; i < t_point3D_cloud.size(); ++i)
+					{
+						//三维点的坐标变换,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+						CPoint3D t_point = transform_by_matrix(t_point3D_cloud[i]);
+						//保存雷达扫描 三维点云的最终结果。
+						if(m_save_flag) {
+							char buf[64] = {0};
+							sprintf(buf, "%f %f %f\n", t_point.x, t_point.y, t_point.z);
+							m_points_log_tool.write(buf, strlen(buf));
+							//std::cout << "huli m_points_log_tool.write" << std::endl;
+						}
+
+						//此时 t_point 为雷达采集数据的结果,转换后的三维点云。
+						//将每个点存入任务单里面的点云容器。
+						if(mp_laser_task!=NULL)
+						{
+							Error_manager t_error= mp_laser_task->task_push_point(pcl::PointXYZ(t_point.x,t_point.y,t_point.z));
+							if ( t_error != Error_code::SUCCESS )
+							{
+								mp_laser_task->get_task_error_manager().compare_and_cover_error(t_error);
+								stop_scan();
+							}
+						}
+					}
+					//统计扫描点个数。
+					m_points_count += t_point3D_cloud.size();
+					//思科雷达停止扫描。
+					if (t_buf_type == BUF_STOP)
+					{
+						//注:这个只是思科的雷达停止处,不同的雷达在不同的地方调用 stop_scan
+						stop_scan();
+					}
+				}
+			}
+			else
+			{
+				//转化线程 不需要数据的同时,也收到了雷达停止扫描的信息并且接受线程已经停止,那么停止转化线程,
+				//注:必须先停止接受线程,再停止转化线程。转化线程停止之后即可结束任务。
+				//如果m_laser_scan_flag停止扫描,接受线程和转化线程还有未完成的数据。那么线程继续运行。
+				//m_laser_scan_flag停止的瞬间,可能还有残留的数据,需要继续执行。防止数据遗留。
+				if ( !m_laser_scan_flag && m_condition_receive.get_pass_ever() == false)
+				{
+					//停止线程,m_condition_transform.wait() 函数将会阻塞。
+					m_condition_transform.set_pass_ever(false);
+
+					//mp_thread_transform 停止时,雷达扫描任务彻底完成,此时结束任务
+					end_task();
+				}
+			}
+
+			//第3步,手动释放缓存
+			if ( tp_binaty_buf != NULL )
+			{
+				delete tp_binaty_buf;
+			}
+		}
+	}
+	LOG(INFO) << " thread_transform end "<< this;
+	return;
+}
+
+Error_manager Laser_base::publish_laser_to_message()
+{
+    return SUCCESS;
+}
+//线程执行函数,公开发布雷达的相关信息,用作上位机的监视。
+void Laser_base::thread_publish(Laser_base *p_laser)
+{
+	LOG(INFO) << " thread_publish start ";
+	if(p_laser==NULL)
+	{
+		return;
+	}
+
+	while (p_laser->m_condition_publish.is_alive())
+	{
+		p_laser->m_condition_publish.wait();
+		if ( p_laser->m_condition_publish.is_alive() )
+		{
+			p_laser->publish_laser_to_message();
+			//每隔300ms,发送一次雷达信息状态。
+			std::this_thread::sleep_for(std::chrono::milliseconds(300));
+		}
+	}
+
+	LOG(INFO) << " thread_publish end ";
+	return;
+}
+
+
+
+//初始化变换矩阵,设置默认值
+Error_manager Laser_base::init_laser_matrix()
+{
+	if ( LASER_MATRIX_ARRAY_SIZE == 12 )
+	{
+		//详见转化的算法transfor。保证转化前后坐标一致。
+		mp_laser_matrix[0] = 1;
+		mp_laser_matrix[1] = 0;
+		mp_laser_matrix[2] = 0;
+		mp_laser_matrix[3] = 0;
+		mp_laser_matrix[4] = 0;
+		mp_laser_matrix[5] = 1;
+		mp_laser_matrix[6] = 0;
+		mp_laser_matrix[7] = 0;
+		mp_laser_matrix[8] = 0;
+		mp_laser_matrix[9] = 0;
+		mp_laser_matrix[10] = 1;
+		mp_laser_matrix[11] = 0;
+	}
+	else
+	{
+		for (int i = 0; i < LASER_MATRIX_ARRAY_SIZE; ++i)
+		{
+			//设为0之后,变换之后,新的点坐标全部为0
+			mp_laser_matrix[i] = 0;
+		}
+	}
+	return Error_code::SUCCESS;
+}
+//设置变换矩阵,用作三维点的坐标变换,
+Error_manager Laser_base::set_laser_matrix(double* p_matrix, int size)
+{
+	if ( p_matrix == NULL )
+	{
+		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+							 " set_laser_matrix p_matrix IS_NULL ");
+	}
+	else if ( size != LASER_MATRIX_ARRAY_SIZE )
+	{
+	    return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
+	    					" set_laser_matrix  size is not Match");
+	}
+	else
+	{
+	    if(m_laser_id==5)
+	        std::cout<<"----------------------   horizon matrix";
+		memcpy(mp_laser_matrix, p_matrix, LASER_MATRIX_ARRAY_SIZE * sizeof(double));
+		return Error_code::SUCCESS;
+	}
+}
+//三维点的坐标变换的功能函数,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+CPoint3D Laser_base::transform_by_matrix(CPoint3D point)
+{
+	CPoint3D result;
+	double x = point.x;
+	double y = point.y;
+	double z = point.z;
+	result.x = x * mp_laser_matrix[0] + y*mp_laser_matrix[1] + z*mp_laser_matrix[2] + mp_laser_matrix[3];
+	result.y = x * mp_laser_matrix[4] + y*mp_laser_matrix[5] + z*mp_laser_matrix[6] + mp_laser_matrix[7];
+	result.z = x * mp_laser_matrix[8] + y*mp_laser_matrix[9] + z*mp_laser_matrix[10] + mp_laser_matrix[11];
+	return result;
+}
+
+
+
+

+ 198 - 0
laser/Laser.h

@@ -0,0 +1,198 @@
+
+/*
+ * laser雷达核心模块,主要是负责管理所有的雷达设备,按需采集三维点。
+ * 由上层下发任务单,雷达模块按照任务指示,进行相应的雷达扫描。
+ * 转换和拼接为标准参考系的三维坐标点云。
+ * 然后通过任务单返回上层。
+ */
+
+#ifndef __LASER__HH__
+#define __LASER__HH__
+#include "Point2D.h"
+#include "Point3D.h"
+#include "LogFiles.h"
+
+#include <glog/logging.h>
+
+#include "laser_parameter.pb.h"
+#include "laser_task_command.h"
+
+#include "../error_code/error_code.h"
+#include "../tool/binary_buf.h"
+#include "../tool/thread_safe_queue.h"
+#include "../tool/thread_condition.h"
+
+
+
+
+//雷达工作状态,基类三线程的状态
+//connect_laser 和  disconnect_laser  	中要切换状态 LASER_DISCONNECT <===> LASER_READY
+//start_scan 和 stop_scan 和 end_task	中要切换状态 LASER_READY <===> LASER_BUSY
+enum Laser_statu
+{
+	//默认值 LASER_DISCONNECT	=0
+	LASER_DISCONNECT	=0,	        //雷达断连
+	LASER_READY			=1,			//雷达正常待机,空闲
+	LASER_BUSY			=2,	        //雷达正在工作,正忙
+	LASER_FAULT			=3,         //雷达错误
+};
+
+//雷达变换矩阵的数组长度,默认为12个参数, size = 3 * ( 3 + 1 ) ,旋转加平移,没有缩放
+#define LASER_MATRIX_ARRAY_SIZE 12
+
+//雷达的基类,不能直接使用,必须子类继承
+class Laser_base
+{
+public:
+	Laser_base() = delete;
+	Laser_base(const Laser_base& other) = delete;
+	//唯一的构造函数,按照设备名称和雷达参数来创建实例。
+	//input:id: 雷达设备的id,(唯一索引)
+	//input:laser_param:雷达的参数,
+	//注:利用protobuf创建 laser_parameter 类,然后从文件读取参数
+	Laser_base(int laser_id,Laser_proto::laser_parameter laser_param);
+	//析构函数
+	~Laser_base();
+
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+
+public:
+	//设置保存文件的路径,并打开文件,
+	Error_manager set_open_save_path(std::string save_path,bool is_save=true);
+	//关闭保存文件,推出前一定要执行
+	Error_manager close_save_path();
+	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+	virtual bool is_ready();
+
+	//获取雷达id
+	int get_laser_id();
+
+
+protected:
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	// 纯虚函数,必须由子类重载,
+	virtual bool receive_buf_to_queue(Binary_buf& binary_buf) = 0;
+	//线程执行函数,将二进制消息存入队列缓存,
+	void thread_receive();
+
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud)=0;
+	//线程执行函数,转化并处理三维点云。
+	void thread_transform();
+
+	//公开发布雷达信息的功能函数,
+	virtual Error_manager publish_laser_to_message();
+	//线程执行函数,公开发布雷达的相关信息,用作上位机的监视。
+	static void thread_publish(Laser_base* p_laser);
+
+	//获取雷达状态
+	Laser_statu get_laser_statu();
+protected:
+	//初始化变换矩阵,设置默认值
+	Error_manager init_laser_matrix();
+	//设置变换矩阵,用作三维点的坐标变换,
+	Error_manager set_laser_matrix(double* p_matrix, int size);
+
+	//三维点的坐标变换的功能函数,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+	virtual CPoint3D transform_by_matrix(CPoint3D point);
+
+
+protected:
+	//为了保证多线程的数据安全,修改共享数据必须加锁。  atomic 和 安全队列 可以不加锁进行读写
+	//建议:判断标志位使用 atomic, 容器要封装并使用 安全容器,
+	std::mutex          				m_laser_lock;            	//雷达数据锁
+
+	std::atomic<int>					m_laser_id;                 //雷达设备id
+	Laser_proto::laser_parameter  		m_laser_param;				//雷达的配置参数
+	//雷达变换矩阵,三维点的坐标变换的矩阵,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+	//必须在set_laser_matrix之后,才能使用。(connect时,从雷达的配置参数导入)
+	double								mp_laser_matrix[LASER_MATRIX_ARRAY_SIZE];	//雷达变换矩阵
+	//雷达扫描事件的标志位,受start和stop控制,然后其他线程判断m_scan_flag标准位,来进行启停。
+	std::atomic<bool>                	m_laser_scan_flag;          //雷达扫描的使能标志位
+	//雷达状态和任务状态同步,m_scan_flag停止之后,还要等任务执行完成,才会切回 ready。
+	std::atomic<Laser_statu>			m_laser_statu;             	//雷达工作状态,基类三线程的状态
+	//注:m_laser_statu是基类的三线程的状态,和livox sdk后台线程状态没有任何关系。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+
+	std::atomic<int>            		m_points_count;         	//雷达采集点的计数
+	Thread_safe_queue<Binary_buf*>		m_queue_laser_data;         //二进制缓存的队列容器
+	Binary_buf							m_last_data;			    //上一个二进制缓存,用作数据拼接
+
+
+	std::atomic<bool> 					m_save_flag;           		//雷达保存文件的使能标志位
+	std::string							m_save_path;            	//雷达保存文件的保存路径
+	CLogFile							m_binary_log_tool;          //二进制缓存的日志工具
+	CLogFile							m_points_log_tool;          //三维点云的日志工具
+
+
+	//线程指针的内存管理,由Connect和Disconnect进行分配和释放。
+	std::thread*						mp_thread_receive;    		//接受缓存的线程指针
+	Thread_condition					m_condition_receive;		//接受缓存的条件变量
+	std::thread*						mp_thread_transform;   		//转化数据的线程指针
+	Thread_condition					m_condition_transform;		//转化数据的条件变量
+	std::thread*        				mp_thread_publish;   		//发布信息的线程指针
+	Thread_condition					m_condition_publish;		//发布信息的条件变量
+
+	//任务单的指针,实际内存由应用层管理,
+	//接受任务后,指向新的任务单
+	Laser_task *  						mp_laser_task;        		//任务单的指针
+
+};
+
+
+//雷达的注册类,
+//雷达模块可能有多个不同的雷达,这些雷达需要制定不同的子类,从laser基类继承。
+//使用类的多态,从基类操作不同的子类。
+//雷达的注册器为单例模式,没有任何成员变量。
+//里面定义了 static std::map<std::string, CreateLaserFunc>* g_map  注册表,作为永久的内存。
+//然后提供了注册函数和访问函数,来操作这段静态变量(唯一,永久)
+class LaserRegistory
+{
+	typedef Laser_base*  (*CreateLaserFunc)(int id, Laser_proto::laser_parameter laser_param);
+public:
+	LaserRegistory(std::string name, CreateLaserFunc pFun) {
+		AddCreator(name, pFun);
+	}
+	static Laser_base* CreateLaser(std::string name, int id,Laser_proto::laser_parameter laser_param) {
+		if (GetFuncMap().count(name) == 0)
+			return 0;
+		return GetFuncMap()[name](id,laser_param);
+	}
+private:
+	static std::map<std::string, CreateLaserFunc>& GetFuncMap() {
+		static std::map<std::string, CreateLaserFunc>* g_map = new std::map<std::string, CreateLaserFunc>;
+
+		return *g_map;
+	}
+	void AddCreator(std::string name, CreateLaserFunc pFun) {
+		GetFuncMap()[name] = pFun;
+	}
+};
+
+
+#define RegisterLaser(NAME) \
+	static Laser_base* Create_##NAME##_Laser(int id, Laser_proto::laser_parameter param)	\
+	{																\
+		return new C##NAME##Laser(id,param);							\
+	}																\
+	LaserRegistory g_##NAME##_Laser(#NAME,Create_##NAME##_Laser);
+
+
+#endif

+ 298 - 0
laser/Laser.puml

@@ -0,0 +1,298 @@
+@startuml
+skinparam classAttributeIconSize 0
+
+title  Laser_base  雷达的基类
+
+enum Laser_statu
+{
+//雷达工作状态,基类三线程的状态
+//connect_laser 和  disconnect_laser  	中要切换状态 LASER_DISCONNECT <===> LASER_READY
+//start_scan 和 stop_scan 和 end_task	中要切换状态 LASER_READY <===> LASER_BUSY
+//默认值 LASER_DISCONNECT	=0
+	LASER_DISCONNECT	=0,	        //雷达断连
+	LASER_READY			=1,			//雷达正常待机,空闲
+	LASER_BUSY			=2,	        //雷达正在工作,正忙
+	LASER_FAULT			=3,         //雷达错误
+}
+
+
+
+class Laser_base
+{
+//雷达的基类,不能直接使用,必须子类继承
+==public:==
+	Laser_base() = delete;
+	Laser_base(const Laser_base& other) = delete;
+..
+	//唯一的构造函数,按照设备名称和雷达参数来创建实例。
+	//input:id: 雷达设备的id,(唯一索引)
+	//input:laser_param:雷达的参数,
+	//注:利用protobuf创建 laser_parameter 类,然后从文件读取参数
+	Laser_base(int laser_id,Laser_proto::laser_parameter laser_param);
+	//析构函数
+	~Laser_base();
+..
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+==public:==
+	//设置保存文件的路径,并打开文件,
+	Error_manager set_open_save_path(std::string save_path,bool is_save=true);
+	//关闭保存文件,推出前一定要执行
+	Error_manager close_save_path();
+	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+	virtual bool is_ready();
+	//获取雷达id
+	int get_laser_id();
+==protected:==
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	// 纯虚函数,必须由子类重载,
+	virtual bool receive_buf_to_queue(Binary_buf& binary_buf) = 0;
+	//线程执行函数,将二进制消息存入队列缓存,
+	void thread_receive();
+..
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud)=0;
+	//线程执行函数,转化并处理三维点云。
+	void thread_transform();
+..
+	//公开发布雷达信息的功能函数,
+	Error_manager publish_laser_to_message();
+	//线程执行函数,公开发布雷达的相关信息,用作上位机的监视。
+	static void thread_publish(Laser_base* p_laser);
+..
+	//获取雷达状态
+	Laser_statu get_laser_statu();
+==protected:==
+	//初始化变换矩阵,设置默认值
+	Error_manager init_laser_matrix();
+	//设置变换矩阵,用作三维点的坐标变换,
+	Error_manager set_laser_matrix(double* p_matrix, int size);
+..
+	//三维点的坐标变换的功能函数,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+	virtual CPoint3D transform_by_matrix(CPoint3D point);
+==protected:==
+	//为了保证多线程的数据安全,修改共享数据必须加锁。  atomic 和 安全队列 可以不加锁进行读写
+	//建议:判断标志位使用 atomic, 容器要封装并使用 安全容器,
+	std::mutex          				m_laser_lock;            	//雷达数据锁
+..
+	std::atomic<int>					m_laser_id;                 //雷达设备id
+	Laser_proto::laser_parameter  		m_laser_param;				//雷达的配置参数
+	//雷达变换矩阵,三维点的坐标变换的矩阵,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+	//必须在set_laser_matrix之后,才能使用。(connect时,从雷达的配置参数导入)
+	double								mp_laser_matrix[LASER_MATRIX_ARRAY_SIZE];	//雷达变换矩阵
+	//雷达扫描事件的标志位,受start和stop控制,然后其他线程判断m_scan_flag标准位,来进行启停。
+	std::atomic<bool>                	m_laser_scan_flag;          //雷达扫描的使能标志位
+	//雷达状态和任务状态同步,m_scan_flag停止之后,还要等任务执行完成,才会切回 ready。
+	std::atomic<Laser_statu>			m_laser_statu;             	//雷达工作状态,基类三线程的状态
+	//注:m_laser_statu是基类的三线程的状态,和livox sdk后台线程状态没有任何关系。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+..
+	std::atomic<int>            		m_points_count;         	//雷达采集点的计数
+	Thread_safe_queue<Binary_buf*>		m_queue_laser_data;         //二进制缓存的队列容器
+	Binary_buf							m_last_data;			    //上一个二进制缓存,用作数据拼接
+..
+	std::atomic<bool> 					m_save_flag;           		//雷达保存文件的使能标志位
+	std::string							m_save_path;            	//雷达保存文件的保存路径
+	CLogFile							m_binary_log_tool;          //二进制缓存的日志工具
+	CLogFile							m_points_log_tool;          //三维点云的日志工具
+..
+	//线程指针的内存管理,由Connect和Disconnect进行分配和释放。
+	std::thread*						mp_thread_receive;    		//接受缓存的线程指针
+	Thread_condition					m_condition_receive;		//接受缓存的条件变量
+	std::thread*						mp_thread_transform;   		//转化数据的线程指针
+	Thread_condition					m_condition_transform;		//转化数据的条件变量
+	std::thread*        				mp_thread_publish;   		//发布信息的线程指针
+	Thread_condition					m_condition_publish;		//发布信息的条件变量
+..
+	//任务单的指针,实际内存由应用层管理,
+	//接受任务后,指向新的任务单
+	Laser_task *  						mp_laser_task;        		//任务单的指针
+}
+
+
+class CPoint3D
+{
+//三维点
+	double x, y, z;
+}
+
+class CLogFile
+{
+//日志文件
+	void open(const char *_Filename, bool binary = false);
+	void write(const char *_Str, streamsize _Count);
+	void close();
+	fstream m_file;
+    std::mutex m_lock;
+}
+
+class laser_parameter
+{
+//雷达参数
+}
+
+
+class Laser_task
+{
+//雷达模块的任务指令,从Task_Base继承,
+//补充了雷达专属的数据输入和输出
+==public:==
+    //初始化任务单,必须初始化之后才可以使用,(必选参数)
+    Error_manager task_init(Task_statu task_statu,
+                            pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
+..
+    //初始化任务单,必须初始化之后才可以使用,(可选参数)
+    Error_manager task_init(Task_statu task_statu,
+                            std::string & task_statu_information,
+                            unsigned int task_frame_maxnum,
+                            pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
+..
+    //push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
+    Error_manager task_push_point(pcl::PointXYZ point_xyz);
+==protected:==
+    //点云的采集帧数最大值,任务输入
+    unsigned int                    m_task_frame_maxnum;
+    //点云保存文件的路径,任务输入
+    std::string                     m_task_save_path;
+    //三维点云的数据保护锁,任务输入
+    std::mutex*                     mp_task_cloud_lock;
+    //采集结果,三维点云容器的智能指针,任务输出
+    //这里只是指针,实际内存由应用层管理,初始化时必须保证内存有效。
+    pcl::PointCloud<pcl::PointXYZ>::Ptr        mp_task_point_cloud;
+}
+
+
+class Task_Base
+{
+//任务单基类
+==public:==
+    //初始化任务单,初始任务单类型为 UNKONW_TASK
+    virtual Error_manager init();
+    //更新任务单
+    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
+    //获取任务类型
+    Task_type   get_task_type();
+==protected:==
+    Task_type                   m_task_type;                    //任务类型
+    Task_statu                  m_task_statu;                   //任务状态
+    std::string                 m_task_statu_information;       //任务状态说明
+	Error_manager               m_task_error_manager;//错误码,任务故障信息,任务输出
+}
+
+Laser_task <-- Task_Base : inherit
+
+class Error_manager
+{
+//错误码管理
+}
+
+
+class Binary_buf
+{
+//二进制缓存,
+	//比较前面部分的buf是否相等,使用 other.m_length 为标准
+	bool is_equal_front(const Binary_buf& other);
+	//比较前面部分的buf是否相等,len为0时,使用strlen(buf)为标准,不比较结束符'\0'
+	bool is_equal_front(const char* p_buf, int len = 0);
+..
+	char* get_buf()const;
+	int	get_length()const;
+--
+	char*		mp_buf;				//二进制缓存指针
+	int			m_length;			//二进制缓存长度
+}
+
+
+class Thread_condition
+{
+	bool wait();
+	//等待一定的时间(默认时间单位:毫秒ms),由 is_pass_wait 决定是否阻塞。
+	bool wait_for_millisecond(unsigned int millisecond);
+	//唤醒已经阻塞的线程,唤醒一个线程
+	void notify_one(bool pass_ever, bool pass_once = false);
+	//唤醒已经阻塞的线程,唤醒全部线程
+	void notify_all(bool pass_ever, bool pass_once = false);
+	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
+	void kill_all();
+	//判断是否或者,return !m_kill_flag
+	bool is_alive();
+==protected:==
+	static bool is_pass_wait(Thread_condition * other);
+..
+	std::atomic<bool> 		m_kill_flag;			//是否杀死线程,让线程强制退出,
+	std::atomic<bool> 		m_pass_ever;			//线程能否直接通过等待,对后面的线程也生效。
+	std::atomic<bool> 		m_pass_once;			//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
+	std::mutex 				m_mutex;				//线程的锁
+	std::condition_variable m_condition_variable;	//线程的条件变量
+}
+
+
+class Thread_safe_queue <<    template<class T>    >>
+{
+	//等待并弹出数据,成功弹出则返回true
+	bool wait_and_pop(T& value);
+	//尝试弹出数据,成功弹出则返回true
+	bool try_pop(T& value);
+	//等待并弹出数据,成功弹出则返回true
+	std::shared_ptr<T> wait_and_pop();
+	//尝试弹出数据,成功弹出则返回true
+	std::shared_ptr<T> try_pop();
+	//插入一项,并唤醒一个线程,
+	bool push(T new_value);
+	//清除队列,只是将队列的实例抛出。T是实例内存,系统自动回收的。
+	bool clear();
+	//清除队列,抛出之后还要delete指针。T是动态内存,需要手动回收的。
+	bool clear_and_delete();
+==public:==
+	//判空
+	bool empty();
+	//获取队列大小
+	size_t size();
+	//设置队列为退出状态。并唤醒所有的线程,使其通过wait
+	void termination_queue();
+	//唤醒队列,恢复所有的功能函数。wait_and_pop会继续阻塞。
+	void wake_queue();
+	//获取退出状态
+	bool get_termination_flag();
+	//判断是否可以直接通过wait,  m_data_queue不为空或者m_termination终止时都可以通过等待。
+	bool is_pass();
+==protected:==
+	std::mutex 						m_mutex;				//队列的锁
+	std::queue<std::shared_ptr<T>> 	m_data_queue;			//队列数据,使用智能指针shared_ptr
+	std::condition_variable 		m_data_cond;			//条件变量
+	std::atomic<bool> 				m_termination_flag;		//终止标志位
+}
+
+
+
+Laser_base <-- Laser_statu : include
+Laser_base <-- CPoint3D : include
+Laser_base <-- CLogFile : include
+Laser_base <-- laser_parameter : include
+Laser_base <-- Laser_task : include
+Laser_base <-- Error_manager : include
+Laser_base <-- Binary_buf : include
+Laser_base <-- Thread_condition : include
+Laser_base <-- Thread_safe_queue : include
+
+
+
+@enduml

+ 78 - 0
laser/LivoxHorizon.cpp

@@ -0,0 +1,78 @@
+
+
+#include "LivoxHorizon.h"
+
+RegisterLaser(Horizon)
+
+
+
+CHorizonLaser::CHorizonLaser(int id, Laser_proto::laser_parameter laser_param)
+:CLivoxLaser(id, laser_param)
+{
+
+        //设备livox扫描最大帧数
+        m_frame_maxnum = laser_param.frame_num();
+        //判断参数类型,
+        if(laser_param.type()=="Horizon")
+        {
+            //填充雷达设备的广播码
+            g_sn_laser.insert(std::make_pair(laser_param.sn(), this));
+            //初始化livox
+            InitLivox();
+        }
+
+
+}
+
+CHorizonLaser::~CHorizonLaser()
+{
+
+}
+//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+Error_manager CHorizonLaser::start_scan()
+{
+    //LOG(INFO) << " Horizon start :"<<this;
+    return CLivoxLaser::start_scan();
+}
+//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+// 纯虚函数,必须由子类重载,
+Buf_type CHorizonLaser::transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud)
+{
+    static int count=0;
+
+    if ( p_binary_buf ==NULL )
+    {
+        return BUF_UNKNOW;
+    }
+    else
+    {
+        //livox的二进制数据格式就是三维点坐标。直接强行转化指针类型即可
+        LivoxExtendRawPoint *tp_Livox_data = (LivoxExtendRawPoint *)p_binary_buf->get_buf();
+        //计算这一帧数据有多少个三维点。
+        int t_count = p_binary_buf->get_length() / (sizeof(LivoxExtendRawPoint));
+
+        if (t_count <= 0)
+        {
+            return BUF_UNKNOW;
+        }
+        else
+        {
+            //转变三维点格式,并存入vector。
+            for (int i = 0; i < t_count; ++i)
+            {
+                //LivoxExtendRawPoint 转为 CPoint3D
+                //int32_t 转 double。不要信号强度
+                LivoxExtendRawPoint t_livox_point = tp_Livox_data[i];
+                CPoint3D t_point3D;
+                t_point3D.x = t_livox_point.x/1000.0;
+                t_point3D.y = t_livox_point.y/1000.0;
+                t_point3D.z = t_livox_point.z/1000.0;
+                point3D_cloud.push_back(t_point3D);
+//				std::cout << "huli points:" << t_point3D.x << " : " << t_point3D.y << " : " << t_point3D.z<< std::endl;
+            }
+            return BUF_DATA;
+        }
+    }
+
+}
+

+ 41 - 0
laser/LivoxHorizon.h

@@ -0,0 +1,41 @@
+#ifndef __LIVOX_HORIZON__H
+#define __LIVOX_HORIZON__H
+
+#include "Laser.h"
+#include "livox_def.h"
+#include "livox_sdk.h"
+#include <map>
+#include "LivoxLaser.h"
+
+
+
+
+//大疆livox雷达,从Laser_base继承。
+class CHorizonLaser :public CLivoxLaser
+{
+
+public:
+	CHorizonLaser() = delete;
+	CHorizonLaser(const CHorizonLaser& other) = delete;
+	//唯一的构造函数,按照设备名称和雷达参数来创建实例。
+	//input:id: 雷达设备的id,(唯一索引)
+	//input:laser_param:雷达的参数,
+	//注:利用protobuf创建 laser_parameter 类,然后从文件读取参数
+	CHorizonLaser(int id, Laser_proto::laser_parameter laser_param);
+	~CHorizonLaser();
+    //雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+    virtual Error_manager start_scan();
+
+	//将二进制消息转化为三维点云的功能函数,并将其存入 任务单 , 每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud);
+};
+
+
+
+
+
+
+
+
+#endif

+ 10 - 0
laser/LivoxHubLaser.cpp

@@ -0,0 +1,10 @@
+#include "LivoxHubLaser.h"
+
+CLivoxHubLaser::CLivoxHubLaser()
+{
+
+}
+CLivoxHubLaser::~CLivoxHubLaser()
+{
+
+}

+ 19 - 0
laser/LivoxHubLaser.h

@@ -0,0 +1,19 @@
+#ifndef LIVOXHUBLASER_H
+#define LIVOXHUBLASER_H
+
+
+class CLivoxHubLaser
+{
+public:
+    CLivoxHubLaser();
+    ~CLivoxHubLaser();
+protected:
+    /*static void InitLivoxHub();
+    static void LidarDataCallbackHub(uint8_t handle, LivoxEthPacket *data, uint32_t data_num, void *laser);
+    static void OnDeviceChangeHub(const DeviceInfo *info, DeviceEvent type);
+    static void OnDeviceBroadcastHub(const BroadcastDeviceInfo *info);
+    static void OnSampleCallbackHub(uint8_t status, uint8_t handle, uint8_t response, void *data);*/
+
+};
+
+#endif // LIVOXHUBLASER_H

+ 450 - 0
laser/LivoxLaser.cpp

@@ -0,0 +1,450 @@
+
+#include "LivoxLaser.h"
+
+RegisterLaser(Livox)
+
+CLivoxLaser::DeviceItem CLivoxLaser::g_devices[kMaxLidarCount] = { 0 };
+
+std::map<uint8_t, std::string>	CLivoxLaser::g_handle_sn= std::map<uint8_t, std::string>();
+std::map<std::string, uint8_t>	CLivoxLaser::g_sn_handle = std::map<std::string, uint8_t>();
+std::map<std::string, CLivoxLaser*> CLivoxLaser::g_sn_laser= std::map<std::string, CLivoxLaser*>();
+CLivoxLaser*						CLivoxLaser::g_all_laser[kMaxLidarCount] = { 0 };
+unsigned int  CLivoxLaser::g_count[kMaxLidarCount] = { 0 };
+
+
+
+
+
+CLivoxLaser::CLivoxLaser(int id, Laser_proto::laser_parameter laser_param)
+:Laser_base(id, laser_param)
+{
+	//设备livox扫描最大帧数
+	m_frame_maxnum = laser_param.frame_num();
+	//判断参数类型,
+	if(laser_param.type()=="Livox")
+	{
+		//填充雷达设备的广播码
+		g_sn_laser.insert(std::make_pair(laser_param.sn(), this));
+		//初始化livox
+		InitLivox();
+	}
+}
+
+CLivoxLaser::~CLivoxLaser()
+{
+
+}
+
+//雷达链接设备,为3个线程添加线程执行函数。
+Error_manager CLivoxLaser::connect_laser()
+{
+    Error_manager t_error;
+    //设置点云变换矩阵
+    double matrix[12]={0};
+    matrix[0]=m_laser_param.mat_r00();
+    matrix[1]=m_laser_param.mat_r01();
+    matrix[2]=m_laser_param.mat_r02();
+    matrix[3]=m_laser_param.mat_r03();
+
+    matrix[4]=m_laser_param.mat_r10();
+    matrix[5]=m_laser_param.mat_r11();
+    matrix[6]=m_laser_param.mat_r12();
+    matrix[7]=m_laser_param.mat_r13();
+
+    matrix[8]=m_laser_param.mat_r20();
+    matrix[9]=m_laser_param.mat_r21();
+    matrix[10]=m_laser_param.mat_r22();
+    matrix[11]=m_laser_param.mat_r23();
+    t_error = set_laser_matrix(matrix, 12);
+    if ( t_error != Error_code::SUCCESS )
+    {
+        return t_error;
+    }
+	return Laser_base::connect_laser();
+}
+//雷达断开链接,释放3个线程
+Error_manager CLivoxLaser::disconnect_laser()
+{
+	return Laser_base::disconnect_laser();
+}
+//对外的接口函数,负责接受并处理任务单,
+//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+Error_manager CLivoxLaser::execute_task(Task_Base* p_laser_task)
+{
+	//LOG(INFO) << " CLivoxLaser::execute_task start  "<< this;
+	Error_manager t_error;
+	Error_manager t_result;
+
+	//检查指针
+	if (p_laser_task == NULL) {
+		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+							 "Laser_base::porform_task failed, POINTER_IS_NULL");
+	}
+	//检查任务类型,
+	if (p_laser_task->get_task_type() != LASER_TASK)
+	{
+		return Error_manager(Error_code::LIVOX_TASK_TYPE_ERROR, Error_level::MINOR_ERROR,
+							 "laser task type error != LASER_TASK");
+	}
+
+	//接受任务,并将任务的状态改为TASK_SIGNED已签收
+	mp_laser_task = (Laser_task *) p_laser_task;
+	mp_laser_task->set_task_statu(TASK_SIGNED);
+
+	//检查消息内容是否正确,
+	//检查三维点云指针
+	if (mp_laser_task->get_task_point_cloud()== NULL)
+	{
+		t_result.error_manager_reset(Error_code::POINTER_IS_NULL,
+											Error_level::MINOR_ERROR,
+											"execute_task mp_task_point_cloud is null");
+		//将任务的状态改为 TASK_OVER 结束任务
+		mp_laser_task->set_task_statu(TASK_OVER);
+		//返回错误码
+		mp_laser_task->set_task_error_manager(t_result);
+		return t_result;
+	}
+	else
+	{
+		m_frame_maxnum=mp_laser_task->get_task_frame_maxnum();
+
+
+		//设置保存文件的路径
+		std::string save_path = mp_laser_task->get_save_path();
+		t_error = set_open_save_path(save_path,m_laser_param.is_save_txt());
+		if ( t_error != Error_code::SUCCESS )
+		{
+			//文件保存文件的路径的设置 允许失败。继续后面的动作
+			t_result.compare_and_cover_error(t_error);
+		}
+		//启动雷达扫描
+		t_error = start_scan();
+		if ( t_error != Error_code::SUCCESS )
+		{
+			t_result.compare_and_cover_error(t_error);
+
+			//将任务的状态改为 TASK_OVER 结束任务
+			mp_laser_task->set_task_statu(TASK_OVER);
+			//返回错误码
+			mp_laser_task->set_task_error_manager(t_result);
+			return t_result;
+		}
+		else
+		{
+			//将任务的状态改为 TASK_WORKING 处理中
+			mp_laser_task->set_task_statu(TASK_WORKING);
+		}
+	}
+	//返回错误码
+	if (t_result != Error_code::SUCCESS)
+	{
+		mp_laser_task->set_task_error_manager(t_result);
+	}
+	return t_result;
+}
+
+//检查雷达状态,是否正常运行
+Error_manager CLivoxLaser::check_laser()
+{
+	return Laser_base::check_laser();
+}
+//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+Error_manager CLivoxLaser::start_scan()
+{
+	//LOG(INFO) << " livox start :"<<this;
+	//清空livox子类的队列,
+	m_queue_livox_data.clear_and_delete();
+	g_count[m_handle] = 0;
+	return Laser_base::start_scan();
+}
+//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+Error_manager CLivoxLaser::stop_scan()
+{
+	return Laser_base::stop_scan();
+}
+//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+Error_manager CLivoxLaser::end_task()
+{
+	return Laser_base::end_task();
+}
+
+//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+bool CLivoxLaser::is_ready()
+{
+
+	//livox雷达设备的状态,livox sdk后台线程的状态
+	if ( m_laser_statu == LASER_READY &&
+		 g_devices[m_handle].device_state != kDeviceStateDisconnect  )
+	{
+		return true;
+	}
+	else
+	{
+	    return false;
+	}
+}
+
+//接受二进制消息的功能函数,每次只接受一个CBinaryData
+// 纯虚函数,必须由子类重载,
+bool CLivoxLaser::receive_buf_to_queue(Binary_buf& binary_buf)
+{
+	Binary_buf* tp_livox_buf;
+	if (m_queue_livox_data.try_pop(tp_livox_buf))
+	{
+		binary_buf = *tp_livox_buf;
+		delete tp_livox_buf;
+		//std::cout << "huli m_queue_livox_data.try_pop" << std::endl;
+		return true;
+	}
+	return false;
+}
+//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+// 纯虚函数,必须由子类重载,
+Buf_type CLivoxLaser::transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud)
+{
+	if ( p_binary_buf ==NULL )
+	{
+		return BUF_UNKNOW;
+	}
+	else
+	{
+		//livox的二进制数据格式就是三维点坐标。直接强行转化指针类型即可
+		LivoxRawPoint *tp_Livox_data = (LivoxRawPoint *)p_binary_buf->get_buf();
+		//计算这一帧数据有多少个三维点。
+		int t_count = p_binary_buf->get_length() / (sizeof(LivoxRawPoint));
+
+		if (t_count <= 0)
+		{
+			return BUF_UNKNOW;
+		}
+		else
+		{
+			//转变三维点格式,并存入vector。
+			for (int i = 0; i < t_count; ++i)
+			{
+				//LivoxRawPoint 转为 CPoint3D
+				//int32_t 转 double。不要信号强度
+				LivoxRawPoint t_livox_point = tp_Livox_data[i];
+				CPoint3D t_point3D;
+				t_point3D.x = t_livox_point.x;
+				t_point3D.y = t_livox_point.y;
+				t_point3D.z = t_livox_point.z;
+				point3D_cloud.push_back(t_point3D);
+//				std::cout << "huli points:" << t_point3D.x << " : " << t_point3D.y << " : " << t_point3D.z<< std::endl;
+			}
+			return BUF_DATA;
+		}
+	}
+
+}
+
+
+
+void CLivoxLaser::InitLivox()
+{
+	static bool g_init = false;
+	if (g_init == false)
+	{
+		if (!Init()) {
+			LOG(INFO) << "livox sdk init failed...";
+		}
+		else
+		{
+			LivoxSdkVersion _sdkversion;
+			GetLivoxSdkVersion(&_sdkversion);
+			char buf[255] = { 0 };
+			sprintf(buf, "Livox SDK version %d.%d.%d .\n", _sdkversion.major, _sdkversion.minor, _sdkversion.patch);
+			LOG(INFO) << buf;
+			SetBroadcastCallback(OnDeviceBroadcast);
+			SetDeviceStateUpdateCallback(OnDeviceChange);
+			g_init = true;
+		}
+	}
+}
+
+bool CLivoxLaser::IsScanComplete()
+{
+	//雷达的采集帧数判断,直接比较任务单里面的帧数最大值
+	if(mp_laser_task!=NULL)
+		return g_count[m_handle] >= mp_laser_task->get_task_frame_maxnum();
+	else
+		return false;
+}
+
+void CLivoxLaser::UpdataHandle()
+{
+	std::string sn = m_laser_param.sn();
+	if (g_sn_handle.find(sn) != g_sn_handle.end())
+	{
+		m_handle = g_sn_handle[sn];
+	}
+}
+
+void CLivoxLaser::OnSampleCallback(livox_status status, uint8_t handle, uint8_t response, void *data) {
+	CLivoxLaser* laser = (CLivoxLaser*)data;
+    LOG(INFO)<<"122333-------------------------------";
+	if (status == kStatusSuccess) {
+		if (response != 0) {
+			g_devices[handle].device_state = kDeviceStateConnect;
+		}
+	}
+	else if (status == kStatusTimeout) {
+		g_devices[handle].device_state = kDeviceStateConnect;
+	}
+}
+
+void CLivoxLaser::OnDeviceChange(const DeviceInfo *info, DeviceEvent type)
+{
+
+	if (info == NULL) {
+		return;
+	}
+
+	uint8_t handle = info->handle;
+	if (handle >= kMaxLidarCount) {
+		return;
+	}
+	/*std::cout<<"-----------------------------------------------------------------"<<std::endl;
+    std::cout<<" OnDeviceChange  handle :   "<<info->broadcast_code<<"  type : "<<type <<"  device_state : "
+                <<g_devices[handle].device_state<<std::endl;*/
+
+	if (type == kEventConnect) {
+		//QueryDeviceInformation(handle, OnDeviceInformation, NULL);
+		if (g_devices[handle].device_state == kDeviceStateDisconnect)
+		{
+			g_devices[handle].device_state = kDeviceStateConnect;
+			g_devices[handle].info = *info;
+		}
+	}
+	else if (type == kEventDisconnect) {
+		g_devices[handle].device_state = kDeviceStateDisconnect;
+	}
+	else if (type == kEventStateChange) {
+		g_devices[handle].info = *info;
+	}
+
+	if (g_devices[handle].device_state == kDeviceStateConnect)
+	{
+
+		if (g_devices[handle].info.state == kLidarStateNormal)
+		{
+			if (g_devices[handle].info.type == kDeviceTypeHub)
+			{
+				HubStartSampling(OnSampleCallback, NULL);
+			}
+			else
+			{
+				LidarStartSampling(handle, OnSampleCallback, NULL);
+			}
+			g_devices[handle].device_state = kDeviceStateSampling;
+		}
+	}
+}
+void CLivoxLaser::OnDeviceBroadcast(const BroadcastDeviceInfo *info)
+{
+	if (info == NULL) {
+		return;
+	}
+
+	//printf("Receive Broadcast Code %s\n", info->broadcast_code);
+	LOG(INFO) << " broadcast  sn : " << info->broadcast_code;
+	bool result = false;
+	uint8_t handle = 0;
+	result = AddLidarToConnect(info->broadcast_code, &handle);
+
+	if (result == kStatusSuccess) {
+		/** Set the point cloud data for a specific Livox LiDAR. */
+		SetDataCallback(handle, LidarDataCallback, NULL);
+		g_devices[handle].handle = handle;
+		g_devices[handle].device_state = kDeviceStateDisconnect;
+
+		std::string sn = info->broadcast_code;
+		if (g_handle_sn.find(handle) != g_handle_sn.end())
+			g_handle_sn[handle] = sn;
+		else
+			g_handle_sn.insert(std::make_pair(handle,sn));
+
+		if (g_sn_handle.find(sn) != g_sn_handle.end())
+			g_sn_handle[sn] = handle;
+		else
+			g_sn_handle.insert(std::make_pair(sn,handle));
+
+	}
+
+}
+
+void CLivoxLaser::LidarDataCallback(uint8_t handle, LivoxEthPacket *data, uint32_t data_num, void *client_data)
+{
+//	std::cout << "huli LidarDataCallback" << std::endl;
+
+	CLivoxLaser* livox = g_all_laser[handle];
+	if (livox == NULL)
+	{
+		if (g_handle_sn.find(handle) != g_handle_sn.end())
+		{
+			std::string sn = g_handle_sn[handle];
+			if (g_sn_laser.find(sn) != g_sn_laser.end())
+			{
+				livox = g_sn_laser[sn];
+				g_all_laser[handle] = livox;
+				if (livox)
+					livox->UpdataHandle();
+			}
+		}
+	}
+//	std::cout << "huli LidarDataCallback " << std::endl;
+
+
+	if (data && livox)
+	{
+//		std::cout << "huli m_laser_scan_flag = " << livox->m_laser_scan_flag << std::endl;
+
+		//判断雷达扫描标志位
+		if (livox->m_laser_scan_flag)
+		{
+			if (livox->IsScanComplete())
+			{
+				//std::cout << "huli qwe point count = " << livox->g_count[livox->m_handle] << std::endl;
+				livox->stop_scan();
+				return;
+			}
+			/*else
+			{
+				//std::cout << "huli asd point count = " << livox->g_count[livox->m_handle] << std::endl;
+
+			}*/
+//			std::cout << "huli LidarDataCallback " << std::endl;
+
+			if (g_count[handle] >= livox->m_frame_maxnum)
+				return;
+			uint64_t cur_timestamp = *((uint64_t *)(data->timestamp));
+            if(data ->data_type == kCartesian)
+            {
+                LivoxRawPoint *p_point_data = (LivoxRawPoint *)data->data;
+                Binary_buf* data_bin = new Binary_buf((char*)p_point_data, data_num * sizeof(LivoxRawPoint));
+                livox->m_queue_livox_data.push(data_bin);
+            }
+            else if(data ->data_type == kExtendCartesian)
+            {
+                LivoxExtendRawPoint *p_point_data = (LivoxExtendRawPoint *)data->data;
+                Binary_buf* data_bin = new Binary_buf((char*)p_point_data, data_num * sizeof(LivoxExtendRawPoint));
+                livox->m_queue_livox_data.push(data_bin);
+            }
+            else
+            {
+                return;
+            }
+
+			g_count[handle]++;
+
+		}
+        livox->m_laser_statu = LASER_READY;
+	}
+	/*else
+	{
+		//std::cout << "huli 2z error " << "data = "<< data  << std::endl;
+		//std::cout << "huli 2z error " << "livox = "<< livox  << std::endl;
+	}*/
+}

+ 96 - 0
laser/LivoxLaser.h

@@ -0,0 +1,96 @@
+#ifndef __LIVOX_MID_40_LIDAR__H
+#define __LIVOX_MID_40_LIDAR__H
+#include "Laser.h"
+#include "livox_def.h"
+#include "livox_sdk.h"
+#include <map>
+
+//大疆livox雷达,从Laser_base继承。
+class CLivoxLaser :public Laser_base
+{
+protected:
+	//雷达设备状态,livox管理底层sdk,后台线程的工作状态
+	typedef enum
+	{
+		kDeviceStateDisconnect = 0,		//雷达设备状态	断开连接
+		kDeviceStateConnect = 1,		//雷达设备状态	连接正常
+		kDeviceStateSampling = 2,		//雷达设备状态	正在扫描
+	} DeviceState;
+
+	//雷达设备信息,
+	typedef struct
+	{
+		uint8_t handle;					//雷达控制句柄
+		DeviceState device_state;		//雷达设备状态
+		DeviceInfo info;				//雷达基本信息
+	} DeviceItem;
+
+
+public:
+	CLivoxLaser() = delete;
+	CLivoxLaser(const CLivoxLaser& other) = delete;
+	//唯一的构造函数,按照设备名称和雷达参数来创建实例。
+	//input:id: 雷达设备的id,(唯一索引)
+	//input:laser_param:雷达的参数,
+	//注:利用protobuf创建 laser_parameter 类,然后从文件读取参数
+	CLivoxLaser(int id, Laser_proto::laser_parameter laser_param);
+	~CLivoxLaser();
+
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+
+	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+	virtual bool is_ready();
+
+protected:
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	// 纯虚函数,必须由子类重载,
+	virtual bool receive_buf_to_queue(Binary_buf& binary_buf);
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud);
+
+
+
+protected:
+	static void InitLivox();
+	virtual bool IsScanComplete();
+	virtual void UpdataHandle();
+	static void LidarDataCallback(uint8_t handle, LivoxEthPacket *data, uint32_t data_num, void *laser);
+	static void OnDeviceChange(const DeviceInfo *info, DeviceEvent type);
+	static void OnDeviceBroadcast(const BroadcastDeviceInfo *info);
+	static void OnSampleCallback(livox_status status, uint8_t handle, uint8_t response, void *data);
+
+protected:
+	uint8_t									m_handle;
+	unsigned int							m_frame_maxnum;
+	Thread_safe_queue<Binary_buf*>			m_queue_livox_data;
+
+	static DeviceItem						g_devices[kMaxLidarCount];
+	
+	static std::map<uint8_t,std::string>	g_handle_sn;
+	static std::map<std::string, uint8_t>	g_sn_handle;
+	static std::map<std::string, CLivoxLaser*> g_sn_laser;
+	static CLivoxLaser*						g_all_laser[kMaxLidarCount];
+	static unsigned int						g_count[kMaxLidarCount];
+
+
+};
+
+#endif
+

+ 230 - 0
laser/LivoxLaser.puml

@@ -0,0 +1,230 @@
+@startuml
+skinparam classAttributeIconSize 0
+
+<<<<<<< HEAD
+title  CLivoxLaser 大疆livox雷达
+=======
+title  CLivoxLaser
+>>>>>>> origin/hl
+
+
+
+
+class CLivoxLaser
+{
+//大疆livox雷达,从Laser_base继承。
+==protected:==
+	//雷达设备状态,livox管理底层sdk,后台线程的工作状态
+	typedef enum
+	{
+		kDeviceStateDisconnect = 0,		//雷达设备状态	断开连接
+		kDeviceStateConnect = 1,		//雷达设备状态	连接正常
+		kDeviceStateSampling = 2,		//雷达设备状态	正在扫描
+	} DeviceState;
+..
+	//雷达设备信息,
+	typedef struct
+	{
+		uint8_t handle;					//雷达控制句柄
+		DeviceState device_state;		//雷达设备状态
+		DeviceInfo info;				//雷达基本信息
+	} DeviceItem;
+==public:==
+	CLivoxLaser() = delete;
+	CLivoxLaser(const CLivoxLaser& other) = delete;
+	//唯一的构造函数,按照设备名称和雷达参数来创建实例。
+	CLivoxLaser(int id, Laser_proto::laser_parameter laser_param);
+	~CLivoxLaser();
+..
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+..
+	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+	virtual bool is_ready();
+==protected:==
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	virtual bool receive_buf_to_queue(Binary_buf& binary_buf);
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	virtual Buf_type transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud);
+==protected:==
+	static void InitLivox();
+	virtual bool IsScanComplete();
+	virtual void UpdataHandle();
+	static void LidarDataCallback(uint8_t handle, LivoxEthPacket *data, uint32_t data_num, void *laser);
+	static void OnDeviceChange(const DeviceInfo *info, DeviceEvent type);
+	static void OnDeviceBroadcast(const BroadcastDeviceInfo *info);
+	static void OnSampleCallback(uint8_t status, uint8_t handle, uint8_t response, void *data);
+==protected:==
+	uint8_t									m_handle;
+	unsigned int							m_frame_maxnum;
+	Thread_safe_queue<Binary_buf*>			m_queue_livox_data;
+	static DeviceItem						g_devices[kMaxLidarCount];
+	static std::map<uint8_t,std::string>	g_handle_sn;
+	static std::map<std::string, uint8_t>	g_sn_handle;
+	static std::map<std::string, CLivoxLaser*> g_sn_laser;
+	static CLivoxLaser*						g_all_laser[kMaxLidarCount];
+	static unsigned int						g_count[kMaxLidarCount];
+}
+
+
+class Laser_base
+{
+//雷达的基类,不能直接使用,必须子类继承
+==public:==
+	Laser_base() = delete;
+	Laser_base(const Laser_base& other) = delete;
+..
+	//唯一的构造函数,按照设备名称和雷达参数来创建实例。
+	//input:id: 雷达设备的id,(唯一索引)
+	//input:laser_param:雷达的参数,
+	//注:利用protobuf创建 laser_parameter 类,然后从文件读取参数
+	Laser_base(int laser_id,Laser_proto::laser_parameter laser_param);
+	//析构函数
+	~Laser_base();
+..
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+==public:==
+	//设置保存文件的路径,并打开文件,
+	Error_manager set_open_save_path(std::string save_path,bool is_save=true);
+	//关闭保存文件,推出前一定要执行
+	Error_manager close_save_path();
+	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+	virtual bool is_ready();
+	//获取雷达id
+	int get_laser_id();
+==protected:==
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	// 纯虚函数,必须由子类重载,
+	virtual bool receive_buf_to_queue(Binary_buf& binary_buf) = 0;
+	//线程执行函数,将二进制消息存入队列缓存,
+	void thread_receive();
+..
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* p_binary_buf, std::vector<CPoint3D>& point3D_cloud)=0;
+	//线程执行函数,转化并处理三维点云。
+	void thread_transform();
+..
+	//公开发布雷达信息的功能函数,
+	Error_manager publish_laser_to_message();
+	//线程执行函数,公开发布雷达的相关信息,用作上位机的监视。
+	static void thread_publish(Laser_base* p_laser);
+..
+	//获取雷达状态
+	Laser_statu get_laser_statu();
+==protected:==
+	//初始化变换矩阵,设置默认值
+	Error_manager init_laser_matrix();
+	//设置变换矩阵,用作三维点的坐标变换,
+	Error_manager set_laser_matrix(double* p_matrix, int size);
+..
+	//三维点的坐标变换的功能函数,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+	virtual CPoint3D transform_by_matrix(CPoint3D point);
+==protected:==
+	//为了保证多线程的数据安全,修改共享数据必须加锁。  atomic 和 安全队列 可以不加锁进行读写
+	//建议:判断标志位使用 atomic, 容器要封装并使用 安全容器,
+	std::mutex          				m_laser_lock;            	//雷达数据锁
+..
+	std::atomic<int>					m_laser_id;                 //雷达设备id
+	Laser_proto::laser_parameter  		m_laser_param;				//雷达的配置参数
+	//雷达变换矩阵,三维点的坐标变换的矩阵,从雷达自己的坐标系,转化到公共坐标系,(目前以plc为公共坐标系)
+	//必须在set_laser_matrix之后,才能使用。(connect时,从雷达的配置参数导入)
+	double								mp_laser_matrix[LASER_MATRIX_ARRAY_SIZE];	//雷达变换矩阵
+	//雷达扫描事件的标志位,受start和stop控制,然后其他线程判断m_scan_flag标准位,来进行启停。
+	std::atomic<bool>                	m_laser_scan_flag;          //雷达扫描的使能标志位
+	//雷达状态和任务状态同步,m_scan_flag停止之后,还要等任务执行完成,才会切回 ready。
+	std::atomic<Laser_statu>			m_laser_statu;             	//雷达工作状态,基类三线程的状态
+	//注:m_laser_statu是基类的三线程的状态,和livox sdk后台线程状态没有任何关系。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+..
+	std::atomic<int>            		m_points_count;         	//雷达采集点的计数
+	Thread_safe_queue<Binary_buf*>		m_queue_laser_data;         //二进制缓存的队列容器
+	Binary_buf							m_last_data;			    //上一个二进制缓存,用作数据拼接
+..
+	std::atomic<bool> 					m_save_flag;           		//雷达保存文件的使能标志位
+	std::string							m_save_path;            	//雷达保存文件的保存路径
+	CLogFile							m_binary_log_tool;          //二进制缓存的日志工具
+	CLogFile							m_points_log_tool;          //三维点云的日志工具
+..
+	//线程指针的内存管理,由Connect和Disconnect进行分配和释放。
+	std::thread*						mp_thread_receive;    		//接受缓存的线程指针
+	Thread_condition					m_condition_receive;		//接受缓存的条件变量
+	std::thread*						mp_thread_transform;   		//转化数据的线程指针
+	Thread_condition					m_condition_transform;		//转化数据的条件变量
+	std::thread*        				mp_thread_publish;   		//发布信息的线程指针
+	Thread_condition					m_condition_publish;		//发布信息的条件变量
+..
+	//任务单的指针,实际内存由应用层管理,
+	//接受任务后,指向新的任务单
+	Laser_task *  						mp_laser_task;        		//任务单的指针
+}
+
+class CLivoxMid100Laser
+{
+==public:==
+	CLivoxMid100Laser(int id, Laser_proto::laser_parameter laser_param);
+	~CLivoxMid100Laser();
+..
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+..
+	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+	virtual bool is_ready();
+==protected:==
+	virtual bool IsScanComplete();
+	virtual void UpdataHandle();
+==protected:==
+	uint8_t		m_handle1;
+	uint8_t		m_handle2;
+	uint8_t		m_handle3;
+}
+
+Laser_base -> CLivoxLaser : inherit
+CLivoxLaser -> CLivoxMid100Laser : inherit
+
+
+@enduml

+ 213 - 0
laser/LivoxMid100Laser.cpp

@@ -0,0 +1,213 @@
+
+#include "LivoxMid100Laser.h"
+#include <glog/logging.h>
+RegisterLaser(LivoxMid100)
+
+
+CLivoxMid100Laser::CLivoxMid100Laser(int id, Laser_proto::laser_parameter laser_param)
+:CLivoxLaser(id, laser_param)
+{
+	//设备livox扫描最大帧数
+    m_frame_maxnum = laser_param.frame_num();
+	//判断参数类型,
+    if (laser_param.type() == "LivoxMid100")
+    {
+        std::string sn = laser_param.sn();
+        std::string sn1 = sn, sn2 = sn, sn3 = sn;
+        sn1 += "1";
+        sn2 += "2";
+        sn3 += "3";
+        g_sn_laser.insert(std::make_pair(sn1, this));
+        g_sn_laser.insert(std::make_pair(sn2, this));
+        g_sn_laser.insert(std::make_pair(sn3, this));
+		//初始化livox
+		InitLivox();
+    }
+}
+CLivoxMid100Laser::~CLivoxMid100Laser()
+{
+
+}
+
+//雷达链接设备,为3个线程添加线程执行函数。
+Error_manager CLivoxMid100Laser::connect_laser()
+{
+
+	return CLivoxLaser::connect_laser();
+}
+//雷达断开链接,释放3个线程
+Error_manager CLivoxMid100Laser::disconnect_laser()
+{
+	return CLivoxLaser::disconnect_laser();
+}
+
+
+
+//对外的接口函数,负责接受并处理任务单,
+//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+Error_manager CLivoxMid100Laser::execute_task(Task_Base* p_laser_task)
+{
+	LOG(INFO) << " CLivoxMid100Laser::execute_task start  "<< this;
+	Error_manager t_error;
+	Error_manager t_result;
+
+	//检查指针
+	if (p_laser_task == NULL) {
+		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+							 "Laser_base::porform_task failed, POINTER_IS_NULL");
+	}
+	//检查任务类型,
+	if (p_laser_task->get_task_type() != LASER_TASK)
+	{
+		return Error_manager(Error_code::LIVOX_TASK_TYPE_ERROR, Error_level::MINOR_ERROR,
+							 "laser task type error != LASER_TASK");
+	}
+    //检查当前状态
+    t_error=check_laser();
+	if(t_error!=SUCCESS)
+    {
+	    return t_error;
+    }
+	//接受任务,并将任务的状态改为TASK_SIGNED已签收
+	mp_laser_task = (Laser_task *) p_laser_task;
+	mp_laser_task->set_task_statu(TASK_SIGNED);
+
+	//检查消息内容是否正确,
+	//检查三维点云指针
+	if (mp_laser_task->get_task_point_cloud() == NULL)
+	{
+		t_result.error_manager_reset(Error_code::POINTER_IS_NULL,
+									 Error_level::MINOR_ERROR,
+									 "execute_task mp_task_point_cloud is null");
+		//将任务的状态改为 TASK_OVER 结束任务
+		mp_laser_task->set_task_statu(TASK_OVER);
+		//返回错误码
+		mp_laser_task->set_task_error_manager(t_result);
+		return t_result;
+	}
+	else
+	{
+		m_frame_maxnum=mp_laser_task->get_task_frame_maxnum();
+
+
+		//设置保存文件的路径
+		std::string save_path = mp_laser_task->get_save_path();
+
+		t_error = set_open_save_path(save_path,m_laser_param.is_save_txt());
+		if ( t_error != Error_code::SUCCESS )
+		{
+			//文件保存文件的路径的设置 允许失败。继续后面的动作
+			t_result.compare_and_cover_error(t_error);
+		}
+		//启动雷达扫描
+		t_error = start_scan();
+		if ( t_error != Error_code::SUCCESS )
+		{
+			t_result.compare_and_cover_error(t_error);
+
+			//将任务的状态改为 TASK_OVER 结束任务
+			mp_laser_task->set_task_statu(TASK_OVER);
+			//返回错误码
+			mp_laser_task->set_task_error_manager(t_result);
+			return t_result;
+		}
+		else
+		{
+			//将任务的状态改为 TASK_WORKING 处理中
+			mp_laser_task->set_task_statu(TASK_WORKING);
+		}
+	}
+	//返回错误码
+	if (t_result != Error_code::SUCCESS)
+	{
+		mp_laser_task->set_task_error_manager(t_result);
+	}
+	return t_result;
+}
+
+//检查雷达状态,是否正常运行
+Error_manager CLivoxMid100Laser::check_laser()
+{
+	return CLivoxLaser::check_laser();
+}
+
+//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+Error_manager CLivoxMid100Laser::start_scan()
+{
+	LOG(INFO) << " livoxMid100 start :" << m_laser_param.sn();
+	//清空livox子类的队列,
+	m_queue_livox_data.clear_and_delete();
+	g_count[m_handle1] = 0;
+	g_count[m_handle2] = 0;
+	g_count[m_handle3] = 0;
+	return CLivoxLaser::start_scan();
+}
+//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+Error_manager CLivoxMid100Laser::stop_scan()
+{
+	LOG(INFO)<<" livoxmid100 stoped !!!"<<m_laser_param.sn();
+	return CLivoxLaser::stop_scan();
+}
+//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+Error_manager CLivoxMid100Laser::end_task()
+{
+	return CLivoxLaser::end_task();
+}
+//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+bool CLivoxMid100Laser::is_ready()
+{
+	//3个livox雷达设备的状态,livox sdk后台线程的状态
+	bool cond1=g_devices[m_handle1].device_state == kDeviceStateConnect ||
+			   g_devices[m_handle1].device_state == kDeviceStateSampling;
+	bool cond2=g_devices[m_handle2].device_state == kDeviceStateConnect ||
+			   g_devices[m_handle2].device_state == kDeviceStateSampling;
+	bool cond3=g_devices[m_handle3].device_state == kDeviceStateConnect ||
+			   g_devices[m_handle3].device_state == kDeviceStateSampling;
+
+	if ( cond1 && cond2 && cond3 && m_laser_statu == LASER_READY )
+	{
+		true;
+	}
+	else
+	{
+		false;
+	}
+}
+
+
+void CLivoxMid100Laser::UpdataHandle()
+{
+	std::string sn = m_laser_param.sn();
+	std::string sn1 = sn, sn2 = sn, sn3 = sn;
+	sn1 += "1";
+	sn2 += "2";
+	sn3 += "3";
+	if (g_sn_handle.find(sn1) != g_sn_handle.end())
+	{
+		m_handle1 = g_sn_handle[sn1];
+	}
+	if (g_sn_handle.find(sn2) != g_sn_handle.end())
+	{
+		m_handle2 = g_sn_handle[sn2];
+	}
+	if (g_sn_handle.find(sn3) != g_sn_handle.end())
+	{
+		m_handle3 = g_sn_handle[sn3];
+	}
+}
+bool CLivoxMid100Laser::IsScanComplete()
+{
+	//雷达的采集帧数判断,直接比较任务单里面的帧数最大值
+	if(mp_laser_task==NULL)
+	{
+		return false;
+	}
+	else
+	{
+		int frame_count=mp_laser_task->get_task_frame_maxnum();
+		return g_count[m_handle1] >= frame_count && g_count[m_handle2] >= frame_count
+			   && g_count[m_handle2] >= frame_count;
+	}
+}

+ 46 - 0
laser/LivoxMid100Laser.h

@@ -0,0 +1,46 @@
+#pragma once
+#include "LivoxLaser.h"
+#include "livox_def.h"
+#include "livox_sdk.h"
+#include <map>
+class CLivoxMid100Laser : public CLivoxLaser
+{
+
+public:
+	CLivoxMid100Laser(int id, Laser_proto::laser_parameter laser_param);
+	~CLivoxMid100Laser();
+
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+
+	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
+	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
+	virtual bool is_ready();
+
+
+protected:
+	virtual bool IsScanComplete();
+	virtual void UpdataHandle();
+
+
+protected:
+	uint8_t		m_handle1;
+	uint8_t		m_handle2;
+	uint8_t		m_handle3;
+};
+
+

+ 145 - 0
laser/LogFiles.cpp

@@ -0,0 +1,145 @@
+
+#include "LogFiles.h"
+#include <string.h>
+
+const string CLogFiles::m_strFileNameLoglaserBinary1 = "laser1.data";
+const string CLogFiles::m_strFileNameLoglaserValue1 = "laser1.txt";
+const string CLogFiles::m_strFileNameLogPoints1 = "points1.txt";
+
+const string CLogFiles::m_strFileNameLoglaserBinary2 = "laser2.data";
+const string CLogFiles::m_strFileNameLoglaserValue2 = "laser2.txt";
+const string CLogFiles::m_strFileNameLogPoints2 = "points2.txt";
+
+
+
+CLogFile::CLogFile()
+{
+
+}
+
+
+CLogFile::~CLogFile()
+{
+	if (m_file)
+	{
+        m_lock.lock();
+		m_file.close();
+        m_lock.unlock();
+	}
+}
+
+void CLogFile::open(const char *_Filename, bool binary /* = false */)
+{
+	if (!m_file.is_open())
+	{
+        m_lock.lock();
+		if (binary)
+			m_file.open(_Filename, ios_base::out | ios_base::binary);
+		else
+			m_file.open(_Filename, ios_base::out);
+        m_lock.unlock();
+	}
+}
+
+void CLogFile::write(const char *_Str,	streamsize _Count)
+{
+	if (m_file.is_open())
+	{
+        m_lock.lock();
+		m_file.write(_Str, _Count);
+        m_lock.unlock();
+	}
+}
+
+void CLogFile::write_double(double val)
+{
+	char buffer[512] = { 0 };
+	if (m_file.is_open())
+	{
+        m_lock.lock();
+        sprintf(buffer, "%f ", val);
+		m_file.write(buffer, strlen(buffer));
+        m_lock.unlock();
+	}
+}
+
+void CLogFile::write_int(int val)
+{
+	char buffer[512] = { 0 };
+	if (m_file.is_open())
+	{
+        m_lock.lock();
+        sprintf(buffer, "%d ", val);
+		m_file.write(buffer, strlen(buffer));
+        m_lock.unlock();
+	}
+}
+
+void CLogFile::close()
+{
+	if (m_file.is_open())
+	{
+        m_lock.lock();
+		m_file.close();
+        m_lock.unlock();
+	}
+}
+
+/****************************************************************************/
+
+CLogFiles::CLogFiles()
+	: m_bBinary(true)
+	, m_bValue(true)
+	, m_bPoints(true)
+{
+
+}
+
+CLogFiles::~CLogFiles()
+{
+	close_project();
+}
+
+void CLogFiles::close_project()
+{
+	m_logLaserBinary1.close();
+	m_logLaserValue1.close();
+	m_logPoints1.close();
+
+	m_logLaserBinary2.close();
+	m_logLaserValue2.close();
+	m_logPoints2.close();
+}
+
+void CLogFiles::new_project(const char * path)
+{
+	close_project();
+
+	if (m_bBinary) 
+	{
+		string filepath1 = string(path) + m_strFileNameLoglaserBinary1;
+		m_logLaserBinary1.open(filepath1.c_str(), true);
+
+		string filepath3 = string(path) + m_strFileNameLoglaserBinary2;
+		m_logLaserBinary2.open(filepath3.c_str(), true);
+	}
+
+	if (m_bValue)
+	{
+		string filepath1 = string(path) + m_strFileNameLoglaserValue1;
+		m_logLaserValue1.open(filepath1.c_str(), true);
+
+		string filepath3 = string(path) + m_strFileNameLoglaserValue2;
+		m_logLaserValue2.open(filepath3.c_str(), true);
+	}
+
+	if (m_bPoints)
+	{
+		string filepath2 = string(path) + m_strFileNameLogPoints1;
+		m_logPoints1.open(filepath2.c_str(), true);
+
+		string filepath4 = string(path) + m_strFileNameLogPoints2;
+		m_logPoints2.open(filepath4.c_str(), true);
+	}
+	
+}

+ 73 - 0
laser/LogFiles.h

@@ -0,0 +1,73 @@
+#ifndef __LOG__FILE__HH
+#define __LOG__FILE__HH
+#include <string>
+#include <fstream>
+#include <mutex>
+
+using namespace std;
+
+class CLogFile
+{
+public:
+	CLogFile();
+	~CLogFile();
+
+	void open(const char *_Filename, bool binary = false);
+	void write(const char *_Str, streamsize _Count);
+	void close();
+	inline bool is_open() const { return m_file.is_open(); };
+
+	void write_double(double val);
+	void write_int(int val);
+
+public:
+	fstream m_file;
+
+public:
+    std::mutex m_lock;
+};
+
+
+class CLogFiles
+{
+public:
+	CLogFiles();
+	~CLogFiles();
+
+	void set_config(bool binary = true, bool value = true, bool points = true)
+	{
+		m_bBinary = binary;
+		m_bValue = value;
+		m_bPoints = points;
+	}
+
+	void new_project(const char * path);
+	void close_project();
+
+private:
+	bool m_bBinary;
+	bool m_bValue;
+	bool m_bPoints;
+
+
+public:		  
+	CLogFile m_logLaserBinary1;
+	CLogFile m_logLaserValue1;
+	CLogFile m_logPoints1;
+		
+	CLogFile m_logLaserBinary2;
+	CLogFile m_logLaserValue2;
+	CLogFile m_logPoints2;
+
+
+public:
+	static const string m_strFileNameLoglaserBinary1;
+	static const string m_strFileNameLoglaserValue1;
+	static const string m_strFileNameLogPoints1;
+
+	static const string m_strFileNameLoglaserBinary2;
+	static const string m_strFileNameLoglaserValue2;
+	static const string m_strFileNameLogPoints2;
+};
+
+#endif

+ 24 - 0
laser/Point2D.cpp

@@ -0,0 +1,24 @@
+
+#include "Point2D.h"
+
+
+CPoint2D::CPoint2D(double x, double y)
+{
+	this->x = x;
+	this->y = y;
+}
+
+
+CPoint2D::~CPoint2D()
+{
+}
+
+double CPoint2D::GetDistance(CPoint2D &pt1, CPoint2D &pt2)
+{
+	return sqrt((pt1.x - pt2.x)*(pt1.x - pt2.x) + (pt1.y - pt2.y)*(pt1.y - pt2.y));
+}
+
+double CPoint2D::GetDistance(CPoint2D &pt)
+{
+	return sqrt((x - pt.x)*(x - pt.x) + (y - pt.y)*(y - pt.y));
+}

+ 35 - 0
laser/Point2D.h

@@ -0,0 +1,35 @@
+#ifndef POINT_2D__HH__
+#define POINT_2D__HH__
+#include <math.h>
+
+#ifndef PI
+#define PI 3.141592653589793238462643383279502f   
+#endif
+
+#ifndef DEGREES
+#define DEGREES 0.01745329251994329576923690768489f                           
+#endif
+
+class CPoint2D
+{
+public:
+	double x, y;
+
+public:
+	CPoint2D(double x = 0, double y = 0);
+	virtual ~CPoint2D();
+	
+	inline double GetDistance(CPoint2D &pt);
+	static double GetDistance(CPoint2D &pt1, CPoint2D &pt2);
+};
+
+class CPointPolar2D
+{
+public:
+	double dist, theta;
+
+public:
+	CPointPolar2D(double d = 0, double t = 0) : dist(.0), theta(.0) { dist = d; theta = t; };
+	virtual ~CPointPolar2D() {};
+};
+#endif

+ 34 - 0
laser/Point3D.cpp

@@ -0,0 +1,34 @@
+
+#include "Point3D.h"
+
+
+CPoint3D::CPoint3D()
+{
+	x = y = z = 0;
+}
+
+
+CPoint3D::~CPoint3D()
+{
+
+}
+
+CPoint3D::CPoint3D(double c1, double c2, double c3)
+{
+    x = c1;      y = c2;      z = c3;
+}
+
+
+
+CPoint3D &CPoint3D::operator=(const CPoint3D& pt) //ÖØÔØµÈºÅ
+{
+	x = pt.x;   z = pt.z;   y = pt.y;
+    return *this;
+}
+
+void CPoint3D::Translate(double cx, double cy, double cz) //ת»¯
+{
+    x += cx;
+    y += cy;
+    z += cz;
+}

+ 19 - 0
laser/Point3D.h

@@ -0,0 +1,19 @@
+#ifndef __POINT_3D__HH
+#define __POINT_3D__HH
+class CPoint3D
+{
+public:
+	double x, y, z;
+
+	CPoint3D();
+	~CPoint3D();
+    CPoint3D(double c1, double c2, double c3);
+    CPoint3D& operator=(const CPoint3D& pt);
+	CPoint3D(const CPoint3D& pt)
+	{
+		*this = pt;
+	}
+    void Translate(double cx, double cy, double cz); //ת��
+};
+
+#endif

+ 323 - 0
laser/Sick511FileLaser.cpp

@@ -0,0 +1,323 @@
+
+#include "Sick511FileLaser.h"
+#include <unistd.h>
+
+RegisterLaser(Sick511File);
+CSick511FileLaser::CSick511FileLaser(int id, Laser_proto::laser_parameter laser_param)
+:Laser_base(id, laser_param)
+,m_start_read(false)
+{
+}
+
+CSick511FileLaser::~CSick511FileLaser()
+{
+	if (m_stream_read.is_open())
+		m_stream_read.close();
+}
+
+
+
+//雷达链接设备,为3个线程添加线程执行函数。
+Error_manager CSick511FileLaser::connect_laser()
+{
+	std::string ip = m_laser_param.laser_ip();
+	char file[255] = { 0 };
+	sprintf(file, "%s/laser%d.data", ip.c_str(), m_laser_id + 1);
+	if (m_stream_read.is_open())
+	{
+		m_stream_read.close();
+	}
+	m_stream_read.open(file, ios::in | ios::binary);
+	if (!m_stream_read.good())
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							 "m_stream_read.open error ");
+	m_laser_statu = LASER_READY;
+	m_file = file;
+	return Laser_base::connect_laser();
+}
+//雷达断开链接,释放3个线程
+Error_manager CSick511FileLaser::disconnect_laser()
+{
+	if(m_stream_read.is_open())
+		m_stream_read.close();
+	return Laser_base::disconnect_laser();
+}
+//对外的接口函数,负责接受并处理任务单,
+//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+Error_manager CSick511FileLaser::execute_task(Task_Base* p_laser_task)
+{
+
+}
+//检查雷达状态,是否正常运行
+Error_manager CSick511FileLaser::check_laser()
+{
+
+}
+//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+Error_manager CSick511FileLaser::start_scan()
+{
+	std::lock_guard<std::mutex> lk(m_mutex);
+
+	if (!this->is_ready())
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							" is_ready error ");
+
+	m_start_read = true;
+	return Laser_base::start_scan();
+
+}
+//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+Error_manager CSick511FileLaser::stop_scan()
+{
+	std::lock_guard<std::mutex> lk(m_mutex);
+	m_start_read = false;
+	return Error_code::SUCCESS;
+}
+//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+Error_manager CSick511FileLaser::end_task()
+{
+
+}
+
+
+
+Buf_type CSick511FileLaser::transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points)
+{
+	////ƴ���ϴ�δ�������
+
+	Buf_type type = BUF_UNKNOW;
+	Binary_buf frame;
+
+	if (m_last_data.get_length() > 0)
+	{
+		if (pData)
+			frame = m_last_data + (*pData);
+		else
+			frame = m_last_data;
+		m_last_data = Binary_buf();
+	}
+	else if(pData)
+	{
+		frame = (*pData);
+	}
+	else
+	{
+		return type;
+	}
+
+	int head = FindHead(frame.get_buf(), frame.get_length());
+	int tail = FindTail(frame.get_buf(), frame.get_length());
+
+	if (tail >= 0)
+	{
+		if (tail < frame.get_length() - 1)		//���������
+		{
+			m_last_data = Binary_buf(frame.get_buf() + tail + 1, frame.get_length() - tail - 1);
+		}
+		if (head >= 0 && head < tail)
+		{
+			////���
+			Binary_buf data(frame.get_buf() + head, tail - head + 1);
+			if (data.is_equal_front( "$SLSSTP"))
+				type = BUF_STOP;
+			else if (data.is_equal_front( "$SLSSTA"))
+				type = BUF_START;
+			else if (data.is_equal_front( "$SCLRDY"))
+				type = BUF_READY;
+			else if (data.is_equal_front( "$SHWERR"))
+				type = BUF_ERROR;
+			else if (data.is_equal_front( "$N"))
+				type = BUF_DATA;
+
+			if (type == BUF_DATA)
+			{
+				////��������
+				points.clear();
+				if (data.get_length() <= 29)
+					return type;
+
+				////����
+				unsigned char angle_1 = 0;
+				unsigned char angle_2 = 0;
+				memcpy(&angle_1, (data.get_buf())+26, 1);
+				memcpy(&angle_2, (data.get_buf())+27, 1);
+				float beta_a = float(angle_1 * 256 + angle_2)*0.01;
+				float start_angle = 0.0;
+				float freq = 0.0;
+
+				std::vector<float> distance;
+				if (GetData(&data, distance, freq, start_angle))
+				{
+					float beta = (beta_a)*DEGREES;
+					float sin_beta = sin(beta);
+					float cos_beta = cos(beta);
+					for (int i = 0; i < distance.size(); ++i)
+					{
+						if (distance[i] < 0.001)
+							continue;
+
+						float alpha = (start_angle + i*freq - 90.0) * DEGREES;
+						float sin_alpha = sin(alpha);
+						float cos_alpha = cos(alpha);
+
+						float x = distance[i] * sin_alpha;
+						float y = distance[i] * cos_alpha * sin_beta;
+						float z = distance[i] * cos_alpha * cos_beta;
+
+						points.push_back(CPoint3D(x, y, z));
+					}
+					//points.push_back(CPoint3D(double(distance.size()), start_angle, freq));
+				}
+
+			}
+			else if (type == BUF_STOP)
+			{
+				m_laser_statu = LASER_READY;
+			}
+		}
+	}
+	else if (head >= 0)
+	{
+		m_last_data = Binary_buf(frame.get_buf() + head, frame.get_length() - head);
+	}
+
+	return type;
+}
+
+bool CSick511FileLaser::receive_buf_to_queue(Binary_buf& data)
+{
+	if (m_start_read == false)
+		return false;
+	if (!m_stream_read.is_open())
+		return false;
+
+	if (m_stream_read.eof())
+	{
+		stop_scan();
+		m_stream_read.close();
+		usleep(100*1000);
+		m_stream_read.open(m_file.c_str(), ios::in | ios::binary);
+	}
+
+	char buf[512] = { 0 };
+	m_stream_read.read(buf, 512);
+	int count = m_stream_read.gcount();
+	if (count > 0)
+	{
+		Binary_buf bin_data(buf, count);
+		data = bin_data;
+		return true;
+	}
+	return false;
+}
+
+int CSick511FileLaser::FindHead(char* buf, int b_len)
+{
+	int i = 0;
+	if (b_len < 2)
+		return 0;
+	for (i = 0; i <= b_len; i++)
+	{
+		if (b_len > 10)
+		{
+			if (buf[i] == '$'&& buf[i + 1] == 'N' && buf[i + 7] == 'S'
+				&&buf[i + 8] == '5'&&buf[i + 9] == '1'&&buf[i + 10] == '1')
+				return i;
+		}
+		if (b_len > 7)
+		{
+			if (buf[i] == '$'&& buf[i + 1] == 'S'&&buf[i + 7] == '*')
+				return i;
+		}
+	}
+	return -1;
+}
+
+int CSick511FileLaser::FindTail(char* buf, int b_len)
+{
+	int i = 0;
+
+	for (i = 0; i <= b_len; i++)
+	{
+		if (b_len >= i + 5)
+		{
+			if (buf[i] == '*' && buf[i + 3] == '\r'&&buf[i + 4] == '\n')
+				return i + 4;
+		}
+	}
+	return -9999999;
+}
+
+bool CSick511FileLaser::GetData(Binary_buf* pData, std::vector<float>& distance,
+								float& freq, float& start_angle)
+{
+	struct stData
+	{
+		const char* data;
+		int length;
+	};
+	std::vector<struct stData> strDatas;
+	int start = 0;
+	int end = 0;
+	int LMDscandata_index = -1;
+	for (int i = 0; i < pData->get_length(); ++i)
+	{
+		if ((*pData)[i] == ' ')
+		{
+			end = i;
+			if (end > start)
+			{
+				struct stData strData;
+//				strData.data = (*pData + start);
+				strData.data = ( pData->get_buf() + start);
+				strData.length = end - start;
+
+				strDatas.push_back(strData);
+				if (strncmp(strData.data, "LMDscandata", 11) == 0)
+					LMDscandata_index = strDatas.size() - 1;
+			}
+			end = i + 1;
+			start = end;
+		}
+	}
+
+	if (strDatas.size() > 26 + LMDscandata_index - 1)
+	{
+		struct stData start_angle_str = strDatas[23 + LMDscandata_index - 1];
+		long start_angle_l = Str0x2Long(start_angle_str.data, start_angle_str.length);
+		start_angle = float(start_angle_l)*0.01;
+
+		struct stData freq_str = strDatas[24 + LMDscandata_index - 1];
+		long freq_l = Str0x2Long(freq_str.data, freq_str.length);
+		freq = float(freq_l)*0.0001;
+
+		struct stData count_str = strDatas[25 + LMDscandata_index - 1];
+		long count = Str0x2Long(count_str.data, count_str.length);
+		if (strDatas.size() >= 26 + LMDscandata_index - 1 + count)
+		{
+			for (int i = 26 + LMDscandata_index - 1; i < 26 + LMDscandata_index - 1 + count; ++i)
+			{
+				float dis = float(Str0x2Long(strDatas[i].data, strDatas[i].length));
+				distance.push_back(dis);
+			}
+			return true;
+		}
+	}
+	return false;
+}
+long CSick511FileLaser::Str0x2Long(const char* data, int len)
+{
+	long sum = 0;
+	for (int i = 0; i < len; ++i)
+	{
+		char c = data[i];
+		int n = 0;
+		if (c >= 48 && c <= 57)
+			n = c - 48;
+		else if (c >= 65 && c <= 70)
+			n = c - 65 + 10;
+		sum += n*pow(16, len - i - 1);
+	}
+	return sum;
+}

+ 55 - 0
laser/Sick511FileLaser.h

@@ -0,0 +1,55 @@
+/*************************
+sick 511 �״� �ļ����ݽ���
+*************************/
+#ifndef __SICK_511_LASER_FILE__HH
+#define __SICK_511_LASER_FILE__HH
+#include "Laser.h"
+#include <fstream>
+class CSick511FileLaser :
+	public Laser_base
+{
+public:
+	CSick511FileLaser(int id, Laser_proto::laser_parameter laser_param);
+	virtual ~CSick511FileLaser();
+
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+
+protected:
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	// 纯虚函数,必须由子类重载,
+	virtual bool receive_buf_to_queue(Binary_buf& data);
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points);
+
+
+protected:
+	int FindHead(char* buf, int b_len);
+	int FindTail(char* buf, int b_len);
+protected:
+	virtual bool GetData(Binary_buf* pData, std::vector<float>& distance,
+		float& freq, float& start_angle);
+	long Str0x2Long(const char* data, int len);
+
+protected:
+	std::ifstream	m_stream_read;
+	std::string		m_file;
+	bool			m_start_read;
+	std::mutex		m_mutex;
+};
+#endif

+ 343 - 0
laser/TcpLaser.cpp

@@ -0,0 +1,343 @@
+#include "TcpLaser.h"
+#include <stdlib.h>
+#include <unistd.h>
+
+RegisterLaser(Tcp);
+CTcpLaser::CTcpLaser(int id, Laser_proto::laser_parameter laser_param)
+	:Laser_base(id,laser_param)
+{
+}
+
+CTcpLaser::~CTcpLaser()
+{
+}
+
+
+
+
+//雷达链接设备,为3个线程添加线程执行函数。
+Error_manager CTcpLaser::connect_laser()
+{
+	std::string ip = m_laser_param.laser_ip();
+	int			port = m_laser_param.laser_port();
+	int			remoteport = m_laser_param.laser_port_remote();
+	if (ip == "" || port < 0)
+		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
+							" m_laser_param PARAMRTER ERROR ");
+
+	//��ʼ��Socket
+	//WSAStartup(MAKEWORD(1, 1), &m_wsd);
+	//����Socket����
+	m_socket = socket(AF_INET, SOCK_STREAM, 0);
+	if (m_socket <= 0)
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							 " m_laser_param PARAMRTER ERROR ");
+
+	m_send_addr.sin_family = AF_INET;
+	m_send_addr.sin_addr.s_addr = inet_addr(ip.c_str());
+	m_send_addr.sin_port = htons(remoteport);
+
+	if (0 != ::connect(m_socket, (struct sockaddr *)&m_send_addr, sizeof(struct sockaddr)))
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							 " connect m_socket ERROR ");
+	m_last_data_time = clock();
+	return Laser_base::connect_laser();
+}
+//雷达断开链接,释放3个线程
+Error_manager CTcpLaser::disconnect_laser()
+{
+	if (m_socket > 0)
+	{
+		close(m_socket);
+		//	WSACleanup();
+		m_socket = -1;
+	}
+	return Laser_base::disconnect_laser();
+}
+//对外的接口函数,负责接受并处理任务单,
+//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+Error_manager CTcpLaser::execute_task(Task_Base* p_laser_task)
+{
+
+}
+//检查雷达状态,是否正常运行
+Error_manager CTcpLaser::check_laser()
+{
+
+}
+//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+Error_manager CTcpLaser::start_scan()
+{
+	std::lock_guard<std::mutex> lk(m_mutex);
+	if (!this->is_ready())
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							"  is_ready ERROR ");
+
+	const char* sendMsg = "$SLSSTA*0A\r\n";
+	if (Send(sendMsg, strlen(sendMsg)))
+	{
+		return Laser_base::start_scan();
+	}
+	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+						" Send error ");
+}
+//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+Error_manager CTcpLaser::stop_scan()
+{
+	char sendMsg[] = "$SLSSTP*1B\r\n";
+	std::lock_guard<std::mutex> lk(m_mutex);
+	if (Send(sendMsg, strlen(sendMsg)))
+		return Error_code::SUCCESS;
+	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+						" error ");
+}
+//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+Error_manager CTcpLaser::end_task()
+{
+
+}
+
+
+Buf_type CTcpLaser::transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points)
+{
+	////ƴ���ϴ�δ�������
+
+	Buf_type type = BUF_UNKNOW;
+	Binary_buf frame;
+
+	if (m_last_data.get_length() > 0)
+	{
+		if (pData)
+			frame = m_last_data + (*pData);
+		else
+			frame = m_last_data;
+		m_last_data = Binary_buf();
+	}
+	else if (pData)
+	{
+		frame = (*pData);
+	}
+	else
+	{
+		return type;
+	}
+
+	int head = FindHead(frame.get_buf(), frame.get_length());
+	int tail = FindTail(frame.get_buf(), frame.get_length());
+
+	if (tail >= 0)
+	{
+		if (tail < frame.get_length() - 1)		//���������
+		{
+			m_last_data = Binary_buf(frame.get_buf() + tail + 1, frame.get_length() - tail - 1);
+		}
+		if (head >= 0 && head < tail)
+		{
+			////���
+			Binary_buf data(frame.get_buf() + head, tail - head + 1);
+			if (data.is_equal_front("$SLSSTP") )
+				type = BUF_STOP;
+			else if (data.is_equal_front( "$SLSSTA"))
+				type = BUF_START;
+			else if (data.is_equal_front( "$SCLRDY"))
+				type = BUF_READY;
+			else if (data.is_equal_front( "$SHWERR"))
+				type = BUF_ERROR;
+			else if (data.is_equal_front( "$N"))
+				type = BUF_DATA;
+
+			if (type == BUF_DATA)
+			{
+				////��������
+				points.clear();
+				if (data.get_length() <= 29)
+					return type;
+
+				////����
+				unsigned char angle_1 = 0;
+				unsigned char angle_2 = 0;
+				memcpy(&angle_1, (data.get_buf())+26, 1);
+				memcpy(&angle_2, (data.get_buf())+27, 1);
+				float beta_a = float(angle_1 * 256 + angle_2)*0.01;
+				float start_angle = 0.0;
+				float freq = 0.0;
+
+				std::vector<float> distance;
+				if (GetData(&data, distance, freq, start_angle))
+				{
+					float beta = (beta_a)*DEGREES;
+					float sin_beta = sin(beta);
+					float cos_beta = cos(beta);
+					for (int i = 0; i < distance.size(); ++i)
+					{
+						if (distance[i] < 0.001)
+							continue;
+
+						float alpha = (start_angle + i*freq - 90.0) * DEGREES;
+						float sin_alpha = sin(alpha);
+						float cos_alpha = cos(alpha);
+
+						float x = distance[i] * sin_alpha;
+						float y = distance[i] * cos_alpha * sin_beta;
+						float z = distance[i] * cos_alpha * cos_beta;
+
+						points.push_back(CPoint3D(x, y, z));
+					}
+					//points.push_back(CPoint3D(double(distance.size()), start_angle, freq));
+				}
+
+			}
+		}
+	}
+	else if (head >= 0)
+	{
+		m_last_data = Binary_buf(frame.get_buf() + head, frame.get_length() - head);
+	}
+
+	return type;
+}
+
+bool CTcpLaser::receive_buf_to_queue(Binary_buf& data)
+{
+	char buf[4096] = { 0 };
+	int bytesRead = Recv(buf, 4096);
+	if (bytesRead > 0)
+	{
+		Binary_buf bin_data(buf, bytesRead);
+		data = bin_data;
+		m_last_data_time = clock();
+		return true;
+	}
+	return false;
+}
+
+int CTcpLaser::FindHead(char* buf, int b_len)
+{
+	int i = 0;
+	if (b_len < 2)
+		return 0;
+	for (i = 0; i <= b_len; i++)
+	{
+		if (b_len > 10)
+		{
+			if (buf[i] == '$'&& buf[i + 1] == 'N' && buf[i + 7] == 'S'
+				&&buf[i + 8] == '5'&&buf[i + 9] == '1'&&buf[i + 10] == '1')
+				return i;
+		}
+		if (b_len > 7)
+		{
+			if (buf[i] == '$'&& buf[i + 1] == 'S'&&buf[i + 7] == '*')
+				return i;
+		}
+	}
+	return -1;
+}
+
+int CTcpLaser::FindTail(char* buf, int b_len)
+{
+	int i = 0;
+
+	for (i = 0; i <= b_len; i++)
+	{
+		if (b_len >= i + 5)
+		{
+			if (buf[i] == '*' && buf[i + 3] == '\r'&&buf[i + 4] == '\n')
+				return i + 4;
+		}
+	}
+	return -9999999;
+}
+
+bool CTcpLaser::Send(const char* sendbuf, int len)
+{
+	int ret = 0;
+	do
+	{
+        ret = send(m_socket, sendbuf, strlen(sendbuf), 0);
+	} while (ret < 0);
+	return ret == len;
+}
+int CTcpLaser::Recv(char* recvbuf, int len)
+{
+	struct sockaddr_in sddr_from;
+	int ret = 0;
+	do
+	{
+        ret = recv(m_socket, recvbuf, 4096, 0);
+	} while (ret < 0);
+	return ret;
+}
+
+bool CTcpLaser::GetData(Binary_buf* pData, std::vector<float>& distance,
+	float& freq, float& start_angle)
+{
+	struct stData
+	{
+		const char* data;
+		int length;
+	};
+	std::vector<struct stData> strDatas;
+	int start = 0;
+	int end = 0;
+	int LMDscandata_index = -1;
+	for (int i = 0; i < pData->get_length(); ++i)
+	{
+		if ((*pData)[i] == ' ')
+		{
+			end = i;
+			if (end > start)
+			{
+				struct stData strData;
+//				strData.data = (*pData + start);
+				strData.data = (pData->get_buf() + start);
+				strData.length = end - start;
+
+				strDatas.push_back(strData);
+				if (strncmp(strData.data, "LMDscandata", 11) == 0)
+					LMDscandata_index = strDatas.size() - 1;
+			}
+			end = i + 1;
+			start = end;
+		}
+	}
+
+	if (strDatas.size() > 26 + LMDscandata_index - 1)
+	{
+		struct stData start_angle_str = strDatas[23 + LMDscandata_index - 1];
+		long start_angle_l = Str0x2Long(start_angle_str.data, start_angle_str.length);
+		start_angle = float(start_angle_l)*0.01;
+
+		struct stData freq_str = strDatas[24 + LMDscandata_index - 1];
+		long freq_l = Str0x2Long(freq_str.data, freq_str.length);
+		freq = float(freq_l)*0.0001;
+
+		struct stData count_str = strDatas[25 + LMDscandata_index - 1];
+		long count = Str0x2Long(count_str.data, count_str.length);
+		if (strDatas.size() >= 26 + LMDscandata_index - 1 + count)
+		{
+			for (int i = 26 + LMDscandata_index - 1; i < 26 + LMDscandata_index - 1 + count; ++i)
+			{
+				float dis = float(Str0x2Long(strDatas[i].data, strDatas[i].length));
+				distance.push_back(dis);
+			}
+			return true;
+		}
+	}
+	return false;
+}
+long CTcpLaser::Str0x2Long(const char* data, int len)
+{
+	long sum = 0;
+	for (int i = 0; i < len; ++i)
+	{
+		char c = data[i];
+		int n = 0;
+		if (c >= 48 && c <= 57)
+			n = c - 48;
+		else if (c >= 65 && c <= 70)
+			n = c - 65 + 10;
+		sum += n*pow(16, len - i - 1);
+	}
+	return sum;
+}

+ 68 - 0
laser/TcpLaser.h

@@ -0,0 +1,68 @@
+/*************************
+sick 511 �״� tcpЭ�����ӿ��ư�
+*************************/
+
+#pragma once
+#include "Laser.h"
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <mutex>
+
+#define LASER_DATA_TIME_OUT		10000
+
+class CTcpLaser :
+	public Laser_base
+{
+public:
+	CTcpLaser(int id, Laser_proto::laser_parameter laser_param);
+	~CTcpLaser();
+
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+
+protected:
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	// 纯虚函数,必须由子类重载,
+	virtual bool receive_buf_to_queue(Binary_buf& data);
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points);
+
+
+private:
+	bool	Send(const char* sendbuf, int len);                          // ����ָ��
+	int		Recv(char* recvbuf, int len);                           // ��������
+	static int FindHead(char* buf, int b_len);
+	static int FindTail(char* buf, int b_len);
+private:
+	bool GetData(Binary_buf* pData, std::vector<float>& distance,
+		float& freq, float& start_angle);
+	long Str0x2Long(const char* data, int len);
+
+private:
+#pragma region udp��ر���
+	int				m_socket;
+    //WSADATA			m_wsd;
+	struct sockaddr_in m_send_addr;	
+	std::mutex		m_mutex;
+	clock_t			m_last_data_time;
+#pragma endregion
+
+};
+

+ 352 - 0
laser/UdpLaser.cpp

@@ -0,0 +1,352 @@
+
+#include "UdpLaser.h"
+#include <stdlib.h>
+#include <unistd.h>
+
+RegisterLaser(Udp);
+CUdpLaser::CUdpLaser(int id, Laser_proto::laser_parameter laser_param)
+	:Laser_base(id,laser_param)
+{
+}
+
+
+CUdpLaser::~CUdpLaser()
+{
+}
+
+
+
+//雷达链接设备,为3个线程添加线程执行函数。
+Error_manager CUdpLaser::connect_laser()
+{
+	std::string ip = m_laser_param.laser_ip();
+	int			port = m_laser_param.laser_port();
+	int			remoteport = m_laser_param.laser_port_remote();
+	if (ip == "" || port < 0)
+		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
+							" m_laser_param PARAMRTER_ERROR ");
+
+	//��ʼ��Socket
+	//WSAStartup(MAKEWORD(1, 1), &m_wsd);
+	//����Socket����
+	m_socket = socket(AF_INET, SOCK_DGRAM, 0);
+	if (m_socket <= 0)
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							" m_socket PARAMRTER_ERROR ");
+
+	struct sockaddr_in sddr_udp;
+	sddr_udp.sin_family = AF_INET;
+	sddr_udp.sin_addr.s_addr = htons(INADDR_ANY);
+	sddr_udp.sin_port = htons(port);
+
+	m_send_addr.sin_family = AF_INET;
+	m_send_addr.sin_addr.s_addr = inet_addr(ip.c_str());
+	m_send_addr.sin_port = htons(remoteport);
+
+	if(-1==bind(m_socket, (struct sockaddr *)&sddr_udp, sizeof(struct sockaddr)))
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							" bind m_socket  ERROR ");
+
+	return Laser_base::connect_laser();
+}
+//雷达断开链接,释放3个线程
+Error_manager CUdpLaser::disconnect_laser()
+{
+	if (m_socket > 0)
+	{
+
+		close(m_socket);
+		//WSACleanup();
+		m_socket = -1;
+	}
+	return Laser_base::disconnect_laser();
+}
+//对外的接口函数,负责接受并处理任务单,
+//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+Error_manager CUdpLaser::execute_task(Task_Base* p_laser_task)
+{
+
+}
+//检查雷达状态,是否正常运行
+Error_manager CUdpLaser::check_laser()
+{
+
+}
+//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+Error_manager CUdpLaser::start_scan()
+{
+	std::lock_guard<std::mutex> lk(m_mutex);
+	if (!this->is_ready())
+		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+							"is_ready error ");
+
+	const char* sendMsg = (char*)"$SLSSTA*0A\r\n";
+	if (Send(sendMsg, strlen(sendMsg)))
+	{
+		m_laser_statu = LASER_BUSY;
+
+		return Laser_base::start_scan();
+	}
+	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+						" Send error ");
+}
+//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+Error_manager CUdpLaser::stop_scan()
+{
+	const char sendMsg[] = "$SLSSTP*1B\r\n";
+	std::lock_guard<std::mutex> lk(m_mutex);
+	if (Send(sendMsg, strlen(sendMsg)))
+		return Error_code::SUCCESS;
+	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
+						" Send error ");
+}
+//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+Error_manager CUdpLaser::end_task()
+{
+
+}
+
+
+Buf_type CUdpLaser::transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points)
+{
+	////ƴ���ϴ�δ�������
+
+	Buf_type type = BUF_UNKNOW;
+	Binary_buf frame;
+
+	if (m_last_data.get_length() > 0)
+	{
+		if (pData)
+			frame = m_last_data + (*pData);
+		else
+			frame = m_last_data;
+		m_last_data = Binary_buf();
+	}
+	else if (pData)
+	{
+		frame = (*pData);
+	}
+	else
+	{
+		return type;
+	}
+
+	int head = FindHead(frame.get_buf(), frame.get_length());
+	int tail = FindTail(frame.get_buf(), frame.get_length());
+	if (tail >= 0)
+	{
+		if (tail < frame.get_length() - 1)		//���������
+		{
+			m_last_data = Binary_buf(frame.get_buf() + tail + 1, frame.get_length() - tail - 1);
+		}
+		if (head >= 0 && head < tail)
+		{
+			////���
+			Binary_buf data(frame.get_buf() + head, tail - head + 1);
+			if (data.is_equal_front( "$SLSSTP"))
+				type = BUF_STOP;
+			else if (data.is_equal_front( "$SLSSTA"))
+				type = BUF_START;
+			else if (data.is_equal_front( "$SCLRDY"))
+				type = BUF_READY;
+			else if (data.is_equal_front( "$SHWERR"))
+				type = BUF_ERROR;
+			else if (data.is_equal_front( "$N"))
+				type = BUF_DATA;
+
+			if (type == BUF_DATA)
+			{
+				////��������
+				points.clear();
+				if (data.get_length() <= 29)
+					return type;
+
+				////����
+				unsigned char angle_1 = 0;
+				unsigned char angle_2 = 0;
+				memcpy(&angle_1, (data.get_buf())+26, 1);
+				memcpy(&angle_2, (data.get_buf())+27, 1);
+				float beta_a = float(angle_1 * 256 + angle_2)*0.01;
+				float start_angle = 0.0;
+				float freq = 0.0;
+
+				std::vector<float> distance;
+				if (GetData(&data, distance, freq, start_angle))
+				{
+					
+					float beta = (beta_a)*DEGREES;
+					float sin_beta = sin(beta);
+					float cos_beta = cos(beta);
+					for (int i = 0; i < distance.size(); ++i)
+					{
+						if (distance[i] < 0.001)
+							continue;
+
+						float alpha = (start_angle + i*freq - 90.0) * DEGREES;
+						float sin_alpha = sin(alpha);
+						float cos_alpha = cos(alpha);
+
+						float x = distance[i] * sin_alpha;
+						float y = distance[i] * cos_alpha * sin_beta;
+						float z = distance[i] * cos_alpha * cos_beta;
+
+						points.push_back(CPoint3D(x, y, z));
+					}
+					//points.push_back(CPoint3D(double(distance.size()), start_angle, freq));
+				}
+
+			}
+		}
+	}
+	else if (head >= 0)
+	{
+		m_last_data = Binary_buf(frame.get_buf() + head, frame.get_length() - head);
+	}
+	
+	return type;
+}
+
+bool CUdpLaser::receive_buf_to_queue(Binary_buf& data)
+{
+	char buf[4096 * 10] = { 0 };
+    int bytesRead = Recv(buf, 4096);
+	if (bytesRead > 0)
+	{
+		Binary_buf bin_data(buf, bytesRead);
+		data = bin_data;
+		return true;
+	}
+	return false;
+}
+
+int CUdpLaser::FindHead(char* buf, int b_len)
+{
+	int i = 0;
+	if (b_len < 2)
+		return 0;
+	for (i = 0; i <= b_len; i++)
+	{
+		if (b_len > 10)
+		{
+			if (buf[i] == '$'&& buf[i + 1] == 'N' && buf[i + 7] == 'S'
+				&&buf[i + 8] == '5'&&buf[i + 9] == '1'&&buf[i + 10] == '1')
+				return i;
+		}
+		if (b_len >7)
+		{
+			if (buf[i] == '$'&& buf[i + 1] == 'S'&&buf[i + 7]=='*')
+				return i;
+		}
+	}
+	return -1;
+}
+
+int CUdpLaser::FindTail(char* buf, int b_len)
+{
+	int i = 0;
+	
+	for (i = 0; i <= b_len; i++)
+	{
+		if (b_len >=i+ 5)
+		{
+			if (buf[i] == '*' && buf[i + 3] == '\r'&&buf[i + 4] == '\n')
+				return i+4;
+		}
+	}
+	return -9999999;
+}
+
+bool CUdpLaser::Send(const char* sendbuf, int len)
+{
+	int ret = 0;
+	do 
+	{
+        ret = sendto(m_socket, sendbuf, strlen(sendbuf), 0, (struct sockaddr*)&m_send_addr, sizeof(struct sockaddr));
+	} while (ret < 0);
+	return ret == len;
+}
+int CUdpLaser::Recv(char* recvbuf, int len)
+{
+	struct sockaddr_in sddr_from;
+    socklen_t clientLen = sizeof(sddr_from);
+	int ret = 0;
+	do
+	{
+        ret = recvfrom(m_socket, recvbuf, 4096, 0, (struct sockaddr*)&sddr_from, &clientLen);
+	} while (ret < 0);
+	return ret;
+}
+
+bool CUdpLaser::GetData(Binary_buf* pData, std::vector<float>& distance,
+	float& freq, float& start_angle)
+{
+	struct stData
+	{
+		const char* data;
+		int length;
+	};
+	std::vector<struct stData> strDatas;
+	int start = 0;
+	int end = 0;
+	int LMDscandata_index = -1;
+	for (int i = 0; i < pData->get_length(); ++i)
+	{
+		if ((*pData)[i] == ' ')
+		{
+			end = i;
+			if (end > start)
+			{
+				struct stData strData;
+//				strData.data = (*pData + start);
+				strData.data = (pData->get_buf() + start);
+				strData.length = end - start;
+				
+				strDatas.push_back(strData);
+				if (strncmp(strData.data, "LMDscandata", 11) == 0)
+					LMDscandata_index = strDatas.size() - 1;
+			}
+			end = i + 1;
+			start = end;
+		}
+	}
+
+	if (strDatas.size() > 26 + LMDscandata_index - 1)
+	{
+		struct stData start_angle_str = strDatas[23 + LMDscandata_index - 1];
+		long start_angle_l = Str0x2Long(start_angle_str.data, start_angle_str.length);
+		start_angle = float(start_angle_l)*0.01;
+
+		struct stData freq_str = strDatas[24 + LMDscandata_index - 1];
+		long freq_l = Str0x2Long(freq_str.data, freq_str.length);
+		freq = float(freq_l)*0.0001;
+
+		struct stData count_str = strDatas[25 + LMDscandata_index - 1];
+		long count = Str0x2Long(count_str.data, count_str.length);
+		if (strDatas.size() >= 26 + LMDscandata_index - 1 + count)
+		{
+			for (int i = 26 + LMDscandata_index - 1; i < 26 + LMDscandata_index - 1 + count; ++i)
+			{
+				float dis = float(Str0x2Long(strDatas[i].data, strDatas[i].length));
+				distance.push_back(dis);
+			}
+			return true;
+		}
+	}
+	return false;
+}
+long CUdpLaser::Str0x2Long(const char* data, int len)
+{
+	long sum = 0;
+	for (int i = 0; i < len; ++i)
+	{
+		char c = data[i];
+		int n = 0;
+		if (c >= 48 && c <= 57)
+			n = c - 48;
+		else if (c >= 65 && c <= 70)
+			n = c - 65 + 10;
+		sum += n*pow(16, len - i - 1);
+	}
+	return sum;
+}

+ 61 - 0
laser/UdpLaser.h

@@ -0,0 +1,61 @@
+/*************************
+sick 511 �״� updЭ�����ӿ��ư�
+*************************/
+#pragma once
+#include "Laser.h"
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <mutex>
+class CUdpLaser : public Laser_base
+{
+public:
+	CUdpLaser(int id, Laser_proto::laser_parameter laser_param);
+	virtual ~CUdpLaser();
+
+	//雷达链接设备,为3个线程添加线程执行函数。
+	virtual Error_manager connect_laser();
+	//雷达断开链接,释放3个线程
+	virtual Error_manager disconnect_laser();
+	//对外的接口函数,负责接受并处理任务单,
+	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
+	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
+	virtual Error_manager execute_task(Task_Base* p_laser_task);
+	//检查雷达状态,是否正常运行
+	virtual Error_manager check_laser();
+	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
+	virtual Error_manager start_scan();
+	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
+	virtual Error_manager stop_scan();
+	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
+	virtual Error_manager end_task();
+
+protected:
+	//接受二进制消息的功能函数,每次只接受一个CBinaryData
+	// 纯虚函数,必须由子类重载,
+	virtual bool receive_buf_to_queue(Binary_buf& data);
+	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
+	// 纯虚函数,必须由子类重载,
+	virtual Buf_type transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points);
+	
+
+private:
+	bool Send(const char* sendbuf, int len);                          // ����ָ��
+	int Recv(char* recvbuf, int len);                           // ��������
+	static int FindHead(char* buf, int b_len);
+	static int FindTail(char* buf, int b_len);
+private:
+	bool GetData(Binary_buf* pData, std::vector<float>& distance,
+		float& freq, float& start_angle);
+	long Str0x2Long(const char* data, int len);
+
+protected:
+#pragma region udp��ر���
+	int				m_socket;
+//	WSADATA			m_wsd;
+	struct sockaddr_in m_send_addr;
+	std::mutex		m_mutex;
+#pragma endregion
+};
+

+ 432 - 0
laser/laser_message.pb.cc

@@ -0,0 +1,432 @@
+// Generated by the protocol buffer compiler.  DO NOT EDIT!
+// source: laser_message.proto
+
+#include "laser_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 laser_message {
+class laserMsgDefaultTypeInternal {
+ public:
+  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<laserMsg> _instance;
+} _laserMsg_default_instance_;
+}  // namespace laser_message
+static void InitDefaultsscc_info_laserMsg_laser_5fmessage_2eproto() {
+  GOOGLE_PROTOBUF_VERIFY_VERSION;
+
+  {
+    void* ptr = &::laser_message::_laserMsg_default_instance_;
+    new (ptr) ::laser_message::laserMsg();
+    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
+  }
+  ::laser_message::laserMsg::InitAsDefaultInstance();
+}
+
+::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_laserMsg_laser_5fmessage_2eproto =
+    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_laserMsg_laser_5fmessage_2eproto}, {}};
+
+static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_laser_5fmessage_2eproto[1];
+static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_laser_5fmessage_2eproto[1];
+static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_laser_5fmessage_2eproto = nullptr;
+
+const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_laser_5fmessage_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
+  PROTOBUF_FIELD_OFFSET(::laser_message::laserMsg, _has_bits_),
+  PROTOBUF_FIELD_OFFSET(::laser_message::laserMsg, _internal_metadata_),
+  ~0u,  // no _extensions_
+  ~0u,  // no _oneof_case_
+  ~0u,  // no _weak_field_map_
+  PROTOBUF_FIELD_OFFSET(::laser_message::laserMsg, laser_status_),
+  PROTOBUF_FIELD_OFFSET(::laser_message::laserMsg, queue_data_count_),
+  PROTOBUF_FIELD_OFFSET(::laser_message::laserMsg, cloud_count_),
+  PROTOBUF_FIELD_OFFSET(::laser_message::laserMsg, id_),
+  0,
+  1,
+  2,
+  3,
+};
+static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
+  { 0, 9, sizeof(::laser_message::laserMsg)},
+};
+
+static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
+  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::laser_message::_laserMsg_default_instance_),
+};
+
+const char descriptor_table_protodef_laser_5fmessage_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) =
+  "\n\023laser_message.proto\022\rlaser_message\"w\n\010"
+  "laserMsg\0220\n\014laser_status\030\001 \001(\0162\032.laser_m"
+  "essage.laserStatus\022\030\n\020queue_data_count\030\002"
+  " \001(\005\022\023\n\013cloud_count\030\003 \001(\005\022\n\n\002id\030\004 \002(\005*]\n"
+  "\013laserStatus\022\023\n\017eLaserConnected\020\000\022\026\n\022eLa"
+  "serDisconnected\020\001\022\016\n\neLaserBusy\020\002\022\021\n\reLa"
+  "serUnknown\020\003"
+  ;
+static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_laser_5fmessage_2eproto_deps[1] = {
+};
+static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_laser_5fmessage_2eproto_sccs[1] = {
+  &scc_info_laserMsg_laser_5fmessage_2eproto.base,
+};
+static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_laser_5fmessage_2eproto_once;
+const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_laser_5fmessage_2eproto = {
+  false, false, descriptor_table_protodef_laser_5fmessage_2eproto, "laser_message.proto", 252,
+  &descriptor_table_laser_5fmessage_2eproto_once, descriptor_table_laser_5fmessage_2eproto_sccs, descriptor_table_laser_5fmessage_2eproto_deps, 1, 0,
+  schemas, file_default_instances, TableStruct_laser_5fmessage_2eproto::offsets,
+  file_level_metadata_laser_5fmessage_2eproto, 1, file_level_enum_descriptors_laser_5fmessage_2eproto, file_level_service_descriptors_laser_5fmessage_2eproto,
+};
+
+// Force running AddDescriptors() at dynamic initialization time.
+static bool dynamic_init_dummy_laser_5fmessage_2eproto = (static_cast<void>(::PROTOBUF_NAMESPACE_ID::internal::AddDescriptors(&descriptor_table_laser_5fmessage_2eproto)), true);
+namespace laser_message {
+const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* laserStatus_descriptor() {
+  ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_laser_5fmessage_2eproto);
+  return file_level_enum_descriptors_laser_5fmessage_2eproto[0];
+}
+bool laserStatus_IsValid(int value) {
+  switch (value) {
+    case 0:
+    case 1:
+    case 2:
+    case 3:
+      return true;
+    default:
+      return false;
+  }
+}
+
+
+// ===================================================================
+
+void laserMsg::InitAsDefaultInstance() {
+}
+class laserMsg::_Internal {
+ public:
+  using HasBits = decltype(std::declval<laserMsg>()._has_bits_);
+  static void set_has_laser_status(HasBits* has_bits) {
+    (*has_bits)[0] |= 1u;
+  }
+  static void set_has_queue_data_count(HasBits* has_bits) {
+    (*has_bits)[0] |= 2u;
+  }
+  static void set_has_cloud_count(HasBits* has_bits) {
+    (*has_bits)[0] |= 4u;
+  }
+  static void set_has_id(HasBits* has_bits) {
+    (*has_bits)[0] |= 8u;
+  }
+  static bool MissingRequiredFields(const HasBits& has_bits) {
+    return ((has_bits[0] & 0x00000008) ^ 0x00000008) != 0;
+  }
+};
+
+laserMsg::laserMsg(::PROTOBUF_NAMESPACE_ID::Arena* arena)
+  : ::PROTOBUF_NAMESPACE_ID::Message(arena) {
+  SharedCtor();
+  RegisterArenaDtor(arena);
+  // @@protoc_insertion_point(arena_constructor:laser_message.laserMsg)
+}
+laserMsg::laserMsg(const laserMsg& from)
+  : ::PROTOBUF_NAMESPACE_ID::Message(),
+      _has_bits_(from._has_bits_) {
+  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
+  ::memcpy(&laser_status_, &from.laser_status_,
+    static_cast<size_t>(reinterpret_cast<char*>(&id_) -
+    reinterpret_cast<char*>(&laser_status_)) + sizeof(id_));
+  // @@protoc_insertion_point(copy_constructor:laser_message.laserMsg)
+}
+
+void laserMsg::SharedCtor() {
+  ::memset(&laser_status_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&id_) -
+      reinterpret_cast<char*>(&laser_status_)) + sizeof(id_));
+}
+
+laserMsg::~laserMsg() {
+  // @@protoc_insertion_point(destructor:laser_message.laserMsg)
+  SharedDtor();
+  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+void laserMsg::SharedDtor() {
+  GOOGLE_DCHECK(GetArena() == nullptr);
+}
+
+void laserMsg::ArenaDtor(void* object) {
+  laserMsg* _this = reinterpret_cast< laserMsg* >(object);
+  (void)_this;
+}
+void laserMsg::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
+}
+void laserMsg::SetCachedSize(int size) const {
+  _cached_size_.Set(size);
+}
+const laserMsg& laserMsg::default_instance() {
+  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_laserMsg_laser_5fmessage_2eproto.base);
+  return *internal_default_instance();
+}
+
+
+void laserMsg::Clear() {
+// @@protoc_insertion_point(message_clear_start:laser_message.laserMsg)
+  ::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 & 0x0000000fu) {
+    ::memset(&laser_status_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&id_) -
+        reinterpret_cast<char*>(&laser_status_)) + sizeof(id_));
+  }
+  _has_bits_.Clear();
+  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+const char* laserMsg::_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 .laser_message.laserStatus laser_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(::laser_message::laserStatus_IsValid(val))) {
+            _internal_set_laser_status(static_cast<::laser_message::laserStatus>(val));
+          } else {
+            ::PROTOBUF_NAMESPACE_ID::internal::WriteVarint(1, val, mutable_unknown_fields());
+          }
+        } else goto handle_unusual;
+        continue;
+      // optional int32 queue_data_count = 2;
+      case 2:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 16)) {
+          _Internal::set_has_queue_data_count(&has_bits);
+          queue_data_count_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 cloud_count = 3;
+      case 3:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 24)) {
+          _Internal::set_has_cloud_count(&has_bits);
+          cloud_count_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // required int32 id = 4;
+      case 4:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 32)) {
+          _Internal::set_has_id(&has_bits);
+          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* laserMsg::_InternalSerialize(
+    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
+  // @@protoc_insertion_point(serialize_to_array_start:laser_message.laserMsg)
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  cached_has_bits = _has_bits_[0];
+  // optional .laser_message.laserStatus laser_status = 1;
+  if (cached_has_bits & 0x00000001u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteEnumToArray(
+      1, this->_internal_laser_status(), target);
+  }
+
+  // optional int32 queue_data_count = 2;
+  if (cached_has_bits & 0x00000002u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(2, this->_internal_queue_data_count(), target);
+  }
+
+  // optional int32 cloud_count = 3;
+  if (cached_has_bits & 0x00000004u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(3, this->_internal_cloud_count(), target);
+  }
+
+  // required int32 id = 4;
+  if (cached_has_bits & 0x00000008u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(4, this->_internal_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:laser_message.laserMsg)
+  return target;
+}
+
+size_t laserMsg::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:laser_message.laserMsg)
+  size_t total_size = 0;
+
+  // required int32 id = 4;
+  if (_internal_has_id()) {
+    total_size += 1 +
+      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+        this->_internal_id());
+  }
+  ::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 & 0x00000007u) {
+    // optional .laser_message.laserStatus laser_status = 1;
+    if (cached_has_bits & 0x00000001u) {
+      total_size += 1 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::EnumSize(this->_internal_laser_status());
+    }
+
+    // optional int32 queue_data_count = 2;
+    if (cached_has_bits & 0x00000002u) {
+      total_size += 1 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_queue_data_count());
+    }
+
+    // optional int32 cloud_count = 3;
+    if (cached_has_bits & 0x00000004u) {
+      total_size += 1 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_cloud_count());
+    }
+
+  }
+  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 laserMsg::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_merge_from_start:laser_message.laserMsg)
+  GOOGLE_DCHECK_NE(&from, this);
+  const laserMsg* source =
+      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<laserMsg>(
+          &from);
+  if (source == nullptr) {
+  // @@protoc_insertion_point(generalized_merge_from_cast_fail:laser_message.laserMsg)
+    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
+  } else {
+  // @@protoc_insertion_point(generalized_merge_from_cast_success:laser_message.laserMsg)
+    MergeFrom(*source);
+  }
+}
+
+void laserMsg::MergeFrom(const laserMsg& from) {
+// @@protoc_insertion_point(class_specific_merge_from_start:laser_message.laserMsg)
+  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 & 0x0000000fu) {
+    if (cached_has_bits & 0x00000001u) {
+      laser_status_ = from.laser_status_;
+    }
+    if (cached_has_bits & 0x00000002u) {
+      queue_data_count_ = from.queue_data_count_;
+    }
+    if (cached_has_bits & 0x00000004u) {
+      cloud_count_ = from.cloud_count_;
+    }
+    if (cached_has_bits & 0x00000008u) {
+      id_ = from.id_;
+    }
+    _has_bits_[0] |= cached_has_bits;
+  }
+}
+
+void laserMsg::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:laser_message.laserMsg)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+void laserMsg::CopyFrom(const laserMsg& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:laser_message.laserMsg)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+bool laserMsg::IsInitialized() const {
+  if (_Internal::MissingRequiredFields(_has_bits_)) return false;
+  return true;
+}
+
+void laserMsg::InternalSwap(laserMsg* other) {
+  using std::swap;
+  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
+  swap(_has_bits_[0], other->_has_bits_[0]);
+  ::PROTOBUF_NAMESPACE_ID::internal::memswap<
+      PROTOBUF_FIELD_OFFSET(laserMsg, id_)
+      + sizeof(laserMsg::id_)
+      - PROTOBUF_FIELD_OFFSET(laserMsg, laser_status_)>(
+          reinterpret_cast<char*>(&laser_status_),
+          reinterpret_cast<char*>(&other->laser_status_));
+}
+
+::PROTOBUF_NAMESPACE_ID::Metadata laserMsg::GetMetadata() const {
+  return GetMetadataStatic();
+}
+
+
+// @@protoc_insertion_point(namespace_scope)
+}  // namespace laser_message
+PROTOBUF_NAMESPACE_OPEN
+template<> PROTOBUF_NOINLINE ::laser_message::laserMsg* Arena::CreateMaybeMessage< ::laser_message::laserMsg >(Arena* arena) {
+  return Arena::CreateMessageInternal< ::laser_message::laserMsg >(arena);
+}
+PROTOBUF_NAMESPACE_CLOSE
+
+// @@protoc_insertion_point(global_scope)
+#include <google/protobuf/port_undef.inc>

+ 432 - 0
laser/laser_message.pb.h

@@ -0,0 +1,432 @@
+// Generated by the protocol buffer compiler.  DO NOT EDIT!
+// source: laser_message.proto
+
+#ifndef GOOGLE_PROTOBUF_INCLUDED_laser_5fmessage_2eproto
+#define GOOGLE_PROTOBUF_INCLUDED_laser_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_laser_5fmessage_2eproto
+PROTOBUF_NAMESPACE_OPEN
+namespace internal {
+class AnyMetadata;
+}  // namespace internal
+PROTOBUF_NAMESPACE_CLOSE
+
+// Internal implementation detail -- do not use these members.
+struct TableStruct_laser_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_laser_5fmessage_2eproto;
+namespace laser_message {
+class laserMsg;
+class laserMsgDefaultTypeInternal;
+extern laserMsgDefaultTypeInternal _laserMsg_default_instance_;
+}  // namespace laser_message
+PROTOBUF_NAMESPACE_OPEN
+template<> ::laser_message::laserMsg* Arena::CreateMaybeMessage<::laser_message::laserMsg>(Arena*);
+PROTOBUF_NAMESPACE_CLOSE
+namespace laser_message {
+
+enum laserStatus : int {
+  eLaserConnected = 0,
+  eLaserDisconnected = 1,
+  eLaserBusy = 2,
+  eLaserUnknown = 3
+};
+bool laserStatus_IsValid(int value);
+constexpr laserStatus laserStatus_MIN = eLaserConnected;
+constexpr laserStatus laserStatus_MAX = eLaserUnknown;
+constexpr int laserStatus_ARRAYSIZE = laserStatus_MAX + 1;
+
+const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* laserStatus_descriptor();
+template<typename T>
+inline const std::string& laserStatus_Name(T enum_t_value) {
+  static_assert(::std::is_same<T, laserStatus>::value ||
+    ::std::is_integral<T>::value,
+    "Incorrect type passed to function laserStatus_Name.");
+  return ::PROTOBUF_NAMESPACE_ID::internal::NameOfEnum(
+    laserStatus_descriptor(), enum_t_value);
+}
+inline bool laserStatus_Parse(
+    ::PROTOBUF_NAMESPACE_ID::ConstStringParam name, laserStatus* value) {
+  return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum<laserStatus>(
+    laserStatus_descriptor(), name, value);
+}
+// ===================================================================
+
+class laserMsg PROTOBUF_FINAL :
+    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:laser_message.laserMsg) */ {
+ public:
+  inline laserMsg() : laserMsg(nullptr) {}
+  virtual ~laserMsg();
+
+  laserMsg(const laserMsg& from);
+  laserMsg(laserMsg&& from) noexcept
+    : laserMsg() {
+    *this = ::std::move(from);
+  }
+
+  inline laserMsg& operator=(const laserMsg& from) {
+    CopyFrom(from);
+    return *this;
+  }
+  inline laserMsg& operator=(laserMsg&& 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 laserMsg& default_instance();
+
+  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
+  static inline const laserMsg* internal_default_instance() {
+    return reinterpret_cast<const laserMsg*>(
+               &_laserMsg_default_instance_);
+  }
+  static constexpr int kIndexInFileMessages =
+    0;
+
+  friend void swap(laserMsg& a, laserMsg& b) {
+    a.Swap(&b);
+  }
+  inline void Swap(laserMsg* other) {
+    if (other == this) return;
+    if (GetArena() == other->GetArena()) {
+      InternalSwap(other);
+    } else {
+      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
+    }
+  }
+  void UnsafeArenaSwap(laserMsg* other) {
+    if (other == this) return;
+    GOOGLE_DCHECK(GetArena() == other->GetArena());
+    InternalSwap(other);
+  }
+
+  // implements Message ----------------------------------------------
+
+  inline laserMsg* New() const final {
+    return CreateMaybeMessage<laserMsg>(nullptr);
+  }
+
+  laserMsg* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
+    return CreateMaybeMessage<laserMsg>(arena);
+  }
+  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void CopyFrom(const laserMsg& from);
+  void MergeFrom(const laserMsg& 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(laserMsg* other);
+  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
+  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
+    return "laser_message.laserMsg";
+  }
+  protected:
+  explicit laserMsg(::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_laser_5fmessage_2eproto);
+    return ::descriptor_table_laser_5fmessage_2eproto.file_level_metadata[kIndexInFileMessages];
+  }
+
+  public:
+
+  // nested types ----------------------------------------------------
+
+  // accessors -------------------------------------------------------
+
+  enum : int {
+    kLaserStatusFieldNumber = 1,
+    kQueueDataCountFieldNumber = 2,
+    kCloudCountFieldNumber = 3,
+    kIdFieldNumber = 4,
+  };
+  // optional .laser_message.laserStatus laser_status = 1;
+  bool has_laser_status() const;
+  private:
+  bool _internal_has_laser_status() const;
+  public:
+  void clear_laser_status();
+  ::laser_message::laserStatus laser_status() const;
+  void set_laser_status(::laser_message::laserStatus value);
+  private:
+  ::laser_message::laserStatus _internal_laser_status() const;
+  void _internal_set_laser_status(::laser_message::laserStatus value);
+  public:
+
+  // optional int32 queue_data_count = 2;
+  bool has_queue_data_count() const;
+  private:
+  bool _internal_has_queue_data_count() const;
+  public:
+  void clear_queue_data_count();
+  ::PROTOBUF_NAMESPACE_ID::int32 queue_data_count() const;
+  void set_queue_data_count(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_queue_data_count() const;
+  void _internal_set_queue_data_count(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional int32 cloud_count = 3;
+  bool has_cloud_count() const;
+  private:
+  bool _internal_has_cloud_count() const;
+  public:
+  void clear_cloud_count();
+  ::PROTOBUF_NAMESPACE_ID::int32 cloud_count() const;
+  void set_cloud_count(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_cloud_count() const;
+  void _internal_set_cloud_count(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // required int32 id = 4;
+  bool has_id() const;
+  private:
+  bool _internal_has_id() const;
+  public:
+  void clear_id();
+  ::PROTOBUF_NAMESPACE_ID::int32 id() const;
+  void set_id(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_id() const;
+  void _internal_set_id(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // @@protoc_insertion_point(class_scope:laser_message.laserMsg)
+ 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_;
+  int laser_status_;
+  ::PROTOBUF_NAMESPACE_ID::int32 queue_data_count_;
+  ::PROTOBUF_NAMESPACE_ID::int32 cloud_count_;
+  ::PROTOBUF_NAMESPACE_ID::int32 id_;
+  friend struct ::TableStruct_laser_5fmessage_2eproto;
+};
+// ===================================================================
+
+
+// ===================================================================
+
+#ifdef __GNUC__
+  #pragma GCC diagnostic push
+  #pragma GCC diagnostic ignored "-Wstrict-aliasing"
+#endif  // __GNUC__
+// laserMsg
+
+// optional .laser_message.laserStatus laser_status = 1;
+inline bool laserMsg::_internal_has_laser_status() const {
+  bool value = (_has_bits_[0] & 0x00000001u) != 0;
+  return value;
+}
+inline bool laserMsg::has_laser_status() const {
+  return _internal_has_laser_status();
+}
+inline void laserMsg::clear_laser_status() {
+  laser_status_ = 0;
+  _has_bits_[0] &= ~0x00000001u;
+}
+inline ::laser_message::laserStatus laserMsg::_internal_laser_status() const {
+  return static_cast< ::laser_message::laserStatus >(laser_status_);
+}
+inline ::laser_message::laserStatus laserMsg::laser_status() const {
+  // @@protoc_insertion_point(field_get:laser_message.laserMsg.laser_status)
+  return _internal_laser_status();
+}
+inline void laserMsg::_internal_set_laser_status(::laser_message::laserStatus value) {
+  assert(::laser_message::laserStatus_IsValid(value));
+  _has_bits_[0] |= 0x00000001u;
+  laser_status_ = value;
+}
+inline void laserMsg::set_laser_status(::laser_message::laserStatus value) {
+  _internal_set_laser_status(value);
+  // @@protoc_insertion_point(field_set:laser_message.laserMsg.laser_status)
+}
+
+// optional int32 queue_data_count = 2;
+inline bool laserMsg::_internal_has_queue_data_count() const {
+  bool value = (_has_bits_[0] & 0x00000002u) != 0;
+  return value;
+}
+inline bool laserMsg::has_queue_data_count() const {
+  return _internal_has_queue_data_count();
+}
+inline void laserMsg::clear_queue_data_count() {
+  queue_data_count_ = 0;
+  _has_bits_[0] &= ~0x00000002u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 laserMsg::_internal_queue_data_count() const {
+  return queue_data_count_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 laserMsg::queue_data_count() const {
+  // @@protoc_insertion_point(field_get:laser_message.laserMsg.queue_data_count)
+  return _internal_queue_data_count();
+}
+inline void laserMsg::_internal_set_queue_data_count(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00000002u;
+  queue_data_count_ = value;
+}
+inline void laserMsg::set_queue_data_count(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_queue_data_count(value);
+  // @@protoc_insertion_point(field_set:laser_message.laserMsg.queue_data_count)
+}
+
+// optional int32 cloud_count = 3;
+inline bool laserMsg::_internal_has_cloud_count() const {
+  bool value = (_has_bits_[0] & 0x00000004u) != 0;
+  return value;
+}
+inline bool laserMsg::has_cloud_count() const {
+  return _internal_has_cloud_count();
+}
+inline void laserMsg::clear_cloud_count() {
+  cloud_count_ = 0;
+  _has_bits_[0] &= ~0x00000004u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 laserMsg::_internal_cloud_count() const {
+  return cloud_count_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 laserMsg::cloud_count() const {
+  // @@protoc_insertion_point(field_get:laser_message.laserMsg.cloud_count)
+  return _internal_cloud_count();
+}
+inline void laserMsg::_internal_set_cloud_count(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00000004u;
+  cloud_count_ = value;
+}
+inline void laserMsg::set_cloud_count(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_cloud_count(value);
+  // @@protoc_insertion_point(field_set:laser_message.laserMsg.cloud_count)
+}
+
+// required int32 id = 4;
+inline bool laserMsg::_internal_has_id() const {
+  bool value = (_has_bits_[0] & 0x00000008u) != 0;
+  return value;
+}
+inline bool laserMsg::has_id() const {
+  return _internal_has_id();
+}
+inline void laserMsg::clear_id() {
+  id_ = 0;
+  _has_bits_[0] &= ~0x00000008u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 laserMsg::_internal_id() const {
+  return id_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 laserMsg::id() const {
+  // @@protoc_insertion_point(field_get:laser_message.laserMsg.id)
+  return _internal_id();
+}
+inline void laserMsg::_internal_set_id(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00000008u;
+  id_ = value;
+}
+inline void laserMsg::set_id(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_id(value);
+  // @@protoc_insertion_point(field_set:laser_message.laserMsg.id)
+}
+
+#ifdef __GNUC__
+  #pragma GCC diagnostic pop
+#endif  // __GNUC__
+
+// @@protoc_insertion_point(namespace_scope)
+
+}  // namespace laser_message
+
+PROTOBUF_NAMESPACE_OPEN
+
+template <> struct is_proto_enum< ::laser_message::laserStatus> : ::std::true_type {};
+template <>
+inline const EnumDescriptor* GetEnumDescriptor< ::laser_message::laserStatus>() {
+  return ::laser_message::laserStatus_descriptor();
+}
+
+PROTOBUF_NAMESPACE_CLOSE
+
+// @@protoc_insertion_point(global_scope)
+
+#include <google/protobuf/port_undef.inc>
+#endif  // GOOGLE_PROTOBUF_INCLUDED_GOOGLE_PROTOBUF_INCLUDED_laser_5fmessage_2eproto

+ 17 - 0
laser/laser_message.proto

@@ -0,0 +1,17 @@
+syntax = "proto2";
+package laser_message;
+
+enum laserStatus
+{
+    eLaserConnected=0;
+    eLaserDisconnected=1;
+    eLaserBusy=2;
+    eLaserUnknown=3;
+}
+message laserMsg
+{
+    optional laserStatus laser_status=1;
+    optional int32 queue_data_count=2;
+    optional int32 cloud_count=3;
+    required int32 id=4;
+}

File diff suppressed because it is too large
+ 1434 - 0
laser/laser_parameter.pb.cc


File diff suppressed because it is too large
+ 1788 - 0
laser/laser_parameter.pb.h


+ 40 - 0
laser/laser_parameter.proto

@@ -0,0 +1,40 @@
+syntax = "proto2";
+package Laser_proto;
+
+message laser_parameter {
+    optional string laser_ip = 1;
+    optional int64 laser_port = 2;
+    optional int64 laser_port_remote = 3;
+    optional double mat_r00 = 4 [default = 1.0];
+    optional double mat_r01 = 5 [default = 1.0];
+    optional double mat_r02 = 6 [default = 1.0];
+    optional double mat_r03 = 7 [default = 1.0];
+    optional double mat_r10 = 8 [default = 1.0];
+    optional double mat_r11 = 9 [default = 1.0];
+    optional double mat_r12 = 10 [default = 1.0];
+    optional double mat_r13 = 11 [default = 1.0];
+    optional double mat_r20 = 12 [default = 1.0];
+    optional double mat_r21 = 13 [default = 1.0];
+    optional double mat_r22 = 14 [default = 1.0];
+    optional double mat_r23 = 15 [default = 1.0];
+    optional double axis_x_theta = 16;
+    optional double axis_y_theta = 17;
+    optional double axis_z_theta = 18;
+    optional double translation_x = 19;
+    optional double translation_y = 20;
+    optional double translation_z = 21;
+
+    optional double install_angle = 22 [default = 0.0];
+    optional bool scan_direction = 23 [default = true];
+    optional string sn = 24;
+    optional int64 frame_num = 25 [default = 3000];
+    optional string type = 26 [default = ""];
+    optional bool is_save_banary=27 [default=false];
+    optional bool is_save_txt=28 [default=true];
+
+}
+
+message Laser_parameter_all
+{
+    repeated laser_parameter        laser_parameters=1;
+}

+ 189 - 0
laser/laser_task_command.cpp

@@ -0,0 +1,189 @@
+
+//laser_task_command,是雷达任务指令的相关功能
+//功能:用作应用层向laser模块传输任务,的指令消息
+
+//用法:应用层直接调用laser的接口函数,并将Laser_task类作为参数传递
+//CLaser类则按照Laser_task的功能码和指定的参数,执行相应的功能
+//并将结果填充到Laser_task,返回给应用层
+
+#include "laser_task_command.h"
+//构造函数,构造函数锁定任务类型为LASER_TASK,后续不允许更改
+Laser_task::Laser_task()
+{
+    //构造函数锁定任务类型为LASER_TASK,后续不允许更改
+    m_task_type = LASER_TASK;
+    m_task_statu = TASK_CREATED;
+    //m_task_statu_information默认为空
+
+    m_task_frame_maxnum = 0;
+    mp_task_point_cloud = NULL;
+    //m_task_error_manager 默认为空
+    mp_task_cloud_lock=NULL;
+}
+//析构函数
+Laser_task::~Laser_task()
+{
+
+}
+
+//初始化任务单,必须初始化之后才可以使用,(必选参数)
+// input:task_statu 任务状态
+// output:p_task_point_cloud 三维点云容器的智能指针
+// input:p_task_cloud_lock 三维点云的数据保护锁
+//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+Error_manager Laser_task::task_init(Task_statu task_statu,
+                                    pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud,
+                                    std::mutex* p_task_cloud_lock)
+{
+    if(p_task_point_cloud == NULL)
+    {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "Laser_task::task_init p_task_point_cloud is null");
+    }
+    if(p_task_cloud_lock==NULL)
+    {
+        return Error_manager(POINTER_IS_NULL,MINOR_ERROR,"laser task input lock is null");
+    }
+
+    m_task_statu = task_statu;
+    m_task_statu_information.clear();
+
+    m_task_frame_maxnum = TASK_FRAME_MAXNUM_DEFAULT;
+    mp_task_cloud_lock=p_task_cloud_lock;
+    mp_task_point_cloud = p_task_point_cloud;
+    m_task_error_manager.error_manager_clear_all();
+
+    return Error_code::SUCCESS;
+}
+
+//初始化任务单,必须初始化之后才可以使用,(可选参数)
+//    input:task_statu任务状态
+//    input:task_statu_information状态说明
+//    input:task_frame_maxnum点云的采集帧数最大值
+//    output:p_task_point_cloud三维点云容器的智能指针
+// input:p_task_cloud_lock 三维点云的数据保护锁
+//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+Error_manager Laser_task::task_init(Task_statu task_statu,
+                                    std::string & task_statu_information,
+                                    unsigned int task_frame_maxnum,
+                                    pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud,
+                                    std::mutex* p_task_cloud_lock)
+{
+    if(p_task_point_cloud == NULL)
+    {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "Laser_task::task_init p_task_point_cloud is null");
+    }
+    if(p_task_cloud_lock==NULL)
+    {
+        return Error_manager(POINTER_IS_NULL,MINOR_ERROR,"laser task input lock is null");
+    }
+
+    m_task_statu = task_statu;
+    m_task_statu_information = task_statu_information;
+
+    if(task_frame_maxnum == 0)
+    {
+        m_task_frame_maxnum = TASK_FRAME_MAXNUM_DEFAULT;
+    }
+    else
+    {
+        m_task_frame_maxnum = task_frame_maxnum;
+    }
+    mp_task_cloud_lock=p_task_cloud_lock;
+    mp_task_point_cloud = p_task_point_cloud;
+    m_task_error_manager.error_manager_clear_all();
+
+    return Error_code::SUCCESS;
+}
+
+//push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
+Error_manager Laser_task::task_push_point(pcl::PointXYZ point_xyz)
+{
+    if(mp_task_cloud_lock==NULL)
+    {
+        return Error_manager(POINTER_IS_NULL,MINOR_ERROR,
+                             "push_point laser task input lock is null");
+    }
+    if(mp_task_point_cloud==NULL)
+    {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "Laser_task::task_push_point p_task_point_cloud is null");
+    }
+    //加锁,并添加三维点。
+    mp_task_cloud_lock->lock();
+    mp_task_point_cloud->push_back(point_xyz);
+    mp_task_cloud_lock->unlock();
+    return SUCCESS;
+}
+
+
+
+
+//获取 点云的采集帧数最大值
+unsigned int Laser_task::get_task_frame_maxnum()
+{
+    return m_task_frame_maxnum;
+}
+//获取采集的点云保存路径
+std::string Laser_task::get_task_save_path()
+{
+    return m_task_save_path;
+}
+//获取 三维点云容器的智能指针
+pcl::PointCloud<pcl::PointXYZ>* Laser_task::get_task_point_cloud()
+{
+    return mp_task_point_cloud;
+}
+
+
+
+
+//设置 任务状态
+void Laser_task::set_task_statu(Task_statu task_statu)
+{
+    m_task_statu = task_statu;
+}
+//设置 任务状态说明
+void Laser_task::set_task_statu_information(std::string & task_statu_information)
+{
+    m_task_statu_information = task_statu_information;
+}
+//设置 点云的采集帧数最大值
+void Laser_task::set_task_frame_maxnum(unsigned int task_frame_maxnum)
+{
+    m_task_frame_maxnum = task_frame_maxnum;
+
+}
+//设置采集的点云保存路径
+void Laser_task::set_task_save_path(std::string task_save_path)
+{
+    m_task_save_path=task_save_path;
+}
+//设置 三维点云容器的智能指针
+void Laser_task::set_task_point_cloud(pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud)
+{
+    mp_task_point_cloud = p_task_point_cloud;
+}
+//设置 错误码
+void Laser_task::set_task_error_manager(Error_manager & error_manager)
+{
+    m_task_error_manager = error_manager;
+}
+
+//获取采集的点云保存路径
+std::string Laser_task::get_save_path()
+{
+    return m_save_path;
+}
+//设置采集的点云保存路径
+void Laser_task::set_save_path(std::string save_path)
+{
+    m_save_path=save_path;
+}
+
+
+
+
+
+

+ 111 - 0
laser/laser_task_command.h

@@ -0,0 +1,111 @@
+
+//laser_task_command,是雷达任务指令的相关功能
+//功能:用作应用层向laser模块传输任务,的指令消息
+
+//用法:应用层直接调用laser的接口函数,并将Laser_task类作为参数传递
+//CLaser类则按照Laser_task的功能码和指定的参数,执行相应的功能
+//并将结果填充到Laser_task,返回给应用层
+
+
+#ifndef __LASER_TASK_COMMAND__HH__
+#define __LASER_TASK_COMMAND__HH__
+#include "Point2D.h"
+#include "Point3D.h"
+#include <pcl/point_types.h>
+#include <pcl/common/common.h>
+#include "../error_code/error_code.h"
+
+#include <vector>
+#include <mutex>
+
+#include "../task/task_command_manager.h"
+
+//任务点云的采集帧数最大值,默认值1000
+#define TASK_FRAME_MAXNUM_DEFAULT               1000
+
+//雷达模块的任务指令,从Task_Base继承,
+//补充了雷达专属的数据输入和输出
+class Laser_task:public Task_Base
+{
+public:
+    //构造函数,构造函数锁定任务类型为LASER_TASK,后续不允许更改
+    Laser_task();
+    //析构函数
+    virtual ~Laser_task();
+
+    //初始化任务单,必须初始化之后才可以使用,(必选参数)
+    // input:task_statu 任务状态
+    // output:p_task_point_cloud 三维点云容器的智能指针
+    // input:p_task_cloud_lock 三维点云的数据保护锁
+    //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+    Error_manager task_init(Task_statu task_statu,
+                            pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
+
+    //初始化任务单,必须初始化之后才可以使用,(可选参数)
+    //    input:task_statu任务状态
+    //    input:task_statu_information状态说明
+    //    input:task_frame_maxnum点云的采集帧数最大值
+    //    output:p_task_point_cloud 三维点云容器的智能指针
+    // input:p_task_cloud_lock 三维点云的数据保护锁
+    //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+    Error_manager task_init(Task_statu task_statu,
+                            std::string & task_statu_information,
+                            unsigned int task_frame_maxnum,
+                            pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
+
+    //push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
+    Error_manager task_push_point(pcl::PointXYZ point_xyz);
+
+
+public:
+    //获取 点云的采集帧数最大值
+    unsigned int get_task_frame_maxnum();
+    //获取采集的点云保存路径
+    std::string get_task_save_path();
+    //获取 三维点云容器的智能指针
+    pcl::PointCloud<pcl::PointXYZ>* get_task_point_cloud();
+
+
+
+
+    //设置 任务状态
+    void set_task_statu(Task_statu task_statu);
+    //设置 任务状态说明
+    void set_task_statu_information(std::string & task_statu_information);
+    //设置 点云的采集帧数最大值
+    void set_task_frame_maxnum(unsigned int task_frame_maxnum);
+    //设置采集的点云保存路径
+    void set_task_save_path(std::string task_save_path);
+    //设置 三维点云容器的智能指针
+    void set_task_point_cloud(pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud);
+    //设置 错误码
+    void set_task_error_manager(Error_manager & error_manager);
+
+    //获取采集的点云保存路径
+    std::string get_save_path();
+    //设置采集的点云保存路径
+    void set_save_path(std::string save_path);
+
+protected:
+    //点云的采集帧数最大值,任务输入
+    unsigned int                    m_task_frame_maxnum;
+
+    std::string                     m_save_path;
+
+    //点云保存文件的路径,任务输入
+    std::string                     m_task_save_path;
+
+    //三维点云的数据保护锁,任务输入
+    std::mutex*                     mp_task_cloud_lock;
+    //采集结果,三维点云容器的智能指针,任务输出
+    //这里只是指针,实际内存由应用层管理,初始化时必须保证内存有效。
+    pcl::PointCloud<pcl::PointXYZ>*        mp_task_point_cloud;
+
+
+};
+
+
+#endif //__LASER_TASK_COMMAND__HH__
+

+ 114 - 0
laser/laser_task_command.puml

@@ -0,0 +1,114 @@
+@startuml
+skinparam classAttributeIconSize 0
+
+<<<<<<< HEAD
+title  Laser_task 雷达模块的任务指令
+=======
+title  binary_buf是二进制缓存
+>>>>>>> origin/hl
+
+note left of Laser_task
+//laser_task_command,是雷达任务指令的相关功能
+//功能:用作应用层向laser模块传输任务,的指令消息
+
+//用法:应用层直接调用laser的接口函数,并将Laser_task类作为参数传递
+//CLaser类则按照Laser_task的功能码和指定的参数,执行相应的功能
+//并将结果填充到Laser_task,返回给应用层
+end note
+
+
+class Laser_task
+{
+//雷达模块的任务指令,从Task_Base继承,
+//补充了雷达专属的数据输入和输出
+==public:==
+    //构造函数,构造函数锁定任务类型为LASER_TASK,后续不允许更改
+    Laser_task();
+    //析构函数
+    ~Laser_task();
+..
+    //初始化任务单,必须初始化之后才可以使用,(必选参数)
+    // input:task_statu 任务状态
+    // output:p_task_point_cloud 三维点云容器的智能指针
+    // input:p_task_cloud_lock 三维点云的数据保护锁
+    //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+    Error_manager task_init(Task_statu task_statu,
+                            pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
+..
+    //初始化任务单,必须初始化之后才可以使用,(可选参数)
+    //    input:task_statu任务状态
+    //    input:task_statu_information状态说明
+    //    input:task_frame_maxnum点云的采集帧数最大值
+    //    output:p_task_point_cloud 三维点云容器的智能指针
+    // input:p_task_cloud_lock 三维点云的数据保护锁
+    //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+    Error_manager task_init(Task_statu task_statu,
+                            std::string & task_statu_information,
+                            unsigned int task_frame_maxnum,
+                            pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
+..
+    //push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
+    Error_manager task_push_point(pcl::PointXYZ point_xyz);
+==public:==
+    //获取 点云的采集帧数最大值
+    unsigned int get_task_frame_maxnum();
+    //获取采集的点云保存路径
+    std::string get_task_save_path();
+    //获取 三维点云容器的智能指针
+    pcl::PointCloud<pcl::PointXYZ>::Ptr get_task_point_cloud();
+..
+    //设置 任务状态
+    void set_task_statu(Task_statu task_statu);
+    //设置 任务状态说明
+    void set_task_statu_information(std::string & task_statu_information);
+    //设置 点云的采集帧数最大值
+    void set_task_frame_maxnum(unsigned int task_frame_maxnum);
+    //设置采集的点云保存路径
+    void set_task_save_path(std::string task_save_path);
+    //设置 三维点云容器的智能指针
+    void set_task_point_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud);
+    //设置 错误码
+    void set_task_error_manager(Error_manager & error_manager);
+==protected:==
+    //点云的采集帧数最大值,任务输入
+    unsigned int                    m_task_frame_maxnum;
+    //点云保存文件的路径,任务输入
+    std::string                     m_task_save_path;
+    //三维点云的数据保护锁,任务输入
+    std::mutex*                     mp_task_cloud_lock;
+    //采集结果,三维点云容器的智能指针,任务输出
+    //这里只是指针,实际内存由应用层管理,初始化时必须保证内存有效。
+    pcl::PointCloud<pcl::PointXYZ>::Ptr        mp_task_point_cloud;
+}
+
+
+class Task_Base
+{
+//任务单基类
+==public:==
+    //初始化任务单,初始任务单类型为 UNKONW_TASK
+    virtual Error_manager init();
+..
+    //更新任务单
+    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
+..
+    //获取任务类型
+    Task_type   get_task_type();
+..
+    //获取任务单状态
+    Task_statu  get_statu();
+..
+    //获取状态说明
+    std::string get_statu_information();
+==protected:==
+    Task_type                   m_task_type;                    //任务类型
+    Task_statu                  m_task_statu;                   //任务状态
+    std::string                 m_task_statu_information;       //任务状态说明
+	Error_manager               m_task_error_manager;//错误码,任务故障信息,任务输出
+}
+
+Laser_task <-- Task_Base : inherit
+
+@enduml

+ 271 - 0
main.cpp

@@ -0,0 +1,271 @@
+//
+// 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 <livox_sdk.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;
+GOOGLE_GLOG_DLL_DECL void shut_down_logging(const char* data, int size)
+{
+    time_t tt;
+    time( &tt );
+    tt = tt + 8*3600;  // transform the time zone
+    tm* t= gmtime( &tt );
+    char buf[255]={0};
+    sprintf(buf,"./%d%02d%02d-%02d%02d%02d-dump.txt",
+            t->tm_year + 1900,
+            t->tm_mon + 1,
+            t->tm_mday,
+            t->tm_hour,
+            t->tm_min,
+            t->tm_sec);
+
+    FILE* tp_file=fopen(buf,"w");
+    fprintf(tp_file,data,strlen(data));
+    fclose(tp_file);
+
+}
+
+void init_glog()
+{
+    time_t tt = time(0);//时间cuo
+    struct tm* t = localtime(&tt);
+
+    char strYear[255]={0};
+    char strMonth[255]={0};
+    char strDay[255]={0};
+
+    sprintf(strYear,"%04d", t->tm_year+1900);
+    sprintf(strMonth,"%02d", t->tm_mon+1);
+    sprintf(strDay,"%02d", t->tm_mday);
+
+    char buf[255]={0};
+    getcwd(buf,255);
+    char strdir[255]={0};
+    sprintf(strdir,"%s/log/%s/%s/%s", buf,strYear,strMonth,strDay);
+    PathCreator creator;
+    creator.Mkdir(strdir);
+
+    char logPath[255] = { 0 };
+    sprintf(logPath, "%s/", strdir);
+    FLAGS_max_log_size = 100;
+    FLAGS_logbufsecs = 0;
+    google::InitGoogleLogging("shutter_verify");
+    google::SetStderrLogging(google::INFO);
+    google::SetLogDestination(0, logPath);
+    google::SetLogFilenameExtension("zxlog");
+    google::InstallFailureSignalHandler();
+    google::InstallFailureWriter(&shut_down_logging);
+    FLAGS_colorlogtostderr = true;        // Set log color
+    FLAGS_logbufsecs = 0;                // Set log output speed(s)
+    FLAGS_max_log_size = 1024;            // Set max log file size(GB)
+    FLAGS_stop_logging_if_full_disk = true;
+}
+
+std::mutex   mut;
+pcl::visualization::PCLVisualizer viewer("Cloud");
+
+int Working()
+{
+    Error_manager code;
+
+    Eigen::Vector4f plane,plane1;
+    plane[0]=0;
+    plane[1]=1;
+    plane[2]=0.2;
+    plane[3]=2;
+
+    plane1[0]=0;
+    plane1[1]=1;
+    plane1[2]=-0.2;
+    plane1[3]=-1.3;
+    float maxd=0.02,mind=-0.08,maxd1=-0.02,mind1=-0.12;
+
+    shuttler_verifier left_shutter;
+    shuttler_verifier right_shutter;
+    left_shutter.set_condition(plane1,maxd1,mind1);
+    right_shutter.set_condition(plane,maxd,mind);
+
+    verifier shutter(left_shutter,right_shutter);
+    mut.lock();
+    left_shutter.create_plane(viewer);
+    right_shutter.create_plane(viewer);
+    mut.unlock();
+
+    //创建雷达  循环采集
+    //读laser配置
+    Laser_proto::Laser_parameter_all laser_parameters;
+    if(!proto_tool::read_proto_param("./setting/laser.prototxt",laser_parameters))
+    {
+        LOG(ERROR)<<"read laser parameter failed";
+        return -1;
+    }
+
+    int laser_cout=laser_parameters.laser_parameters_size();
+    if(laser_cout==0)
+    {
+        LOG(ERROR)<<" no lidars ";
+        return 0;
+    }
+    std::vector<Laser_base*>  plasers;
+    plasers.resize(laser_cout);
+    for(int i=0;i<laser_parameters.laser_parameters_size();++i)
+    {
+        plasers[i] = LaserRegistory::CreateLaser(laser_parameters.laser_parameters(i).type(), i,
+                                                 laser_parameters.laser_parameters(i));
+        if (plasers[i] != NULL)
+        {
+            if (plasers[i]->connect_laser() != SUCCESS)
+            {
+                char description[255] = {0};
+                sprintf(description, "Laser %d connect failed...", i);
+                LOG(ERROR)<<description;
+            }
+        }
+    }
+    for (int i = 0; i < laser_parameters.laser_parameters_size(); ++i)
+    {
+        std::string type = laser_parameters.laser_parameters(i).type();
+        if (type.find("Livox") != type.npos ||type.find("Horizon") != type.npos)
+        {
+            if (Start() == false)
+            {
+                Uninit();
+                LOG(ERROR)<<"Livox laser init failed...";
+                return -2;
+            }
+            break;
+        }
+    }
+
+    usleep(3000*1000);
+
+    LOG(INFO)<<"init ok...";
+
+    //采集
+    int frames=0;
+    while(1)
+    {
+        auto t_start_point = std::chrono::system_clock::now();
+
+        pcl::PointCloud<pcl::PointXYZ> scan_cloud;
+        std::mutex cloud_lock;
+        std::vector<Laser_task *> laser_task_vector;
+        for (int i = 0; i < plasers.size(); ++i)
+        {
+            int frame_count = laser_parameters.laser_parameters(i).frame_num();
+            if (plasers[i] != nullptr)
+            {
+
+                //创建扫描任务,
+                Laser_task *laser_task = new Laser_task();
+                //
+                laser_task->task_init(TASK_CREATED, &scan_cloud, &cloud_lock);
+                laser_task->set_task_frame_maxnum(frame_count);
+                laser_task_vector.push_back(laser_task);
+                //发送任务单给雷达
+                code = plasers[i]->execute_task(laser_task);
+                if (code != SUCCESS)
+                {
+                    LOG(ERROR) << " capture failed :" << code.get_error_description();
+                    return -3;
+                }
+            }
+
+        }
+
+
+        //等待雷达完成任务单
+        double second=0.0;
+        while (1)
+        {
+            //判断是否强制退出
+            //判断雷达任务单是否全部完成
+            bool tb_laser_complete = true;
+            for (int i = 0; i < laser_task_vector.size(); ++i)
+            {
+                tb_laser_complete &= (TASK_OVER == laser_task_vector[i]->get_statu());
+            }
+            if (tb_laser_complete)
+            {
+                break;
+            }
+            //计算扫描时间,若超时,并且没有点,则返回错误.
+            auto t_end_point = std::chrono::system_clock::now();
+            auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(t_end_point - t_start_point);
+            second = double(duration.count()) *
+                    std::chrono::milliseconds::period::num / std::chrono::milliseconds::period::den;
+            if (second > 0.5)
+            {
+                LOG(WARNING)<<"capture time out";
+                break;
+            }
+            usleep(1000*10);
+        }
+        //检查雷达任务完成情况,是否是正常完成
+
+        //释放扫描任务单
+        for (int i = 0; i < laser_task_vector.size(); ++i) {
+            if (laser_task_vector[i] != 0) {
+                delete laser_task_vector[i];
+                laser_task_vector[i] = NULL;
+            }
+        }
+        LOG(INFO) << " frame :"<<++frames<<",laser scanning over cloud size:" << scan_cloud.size()
+                  <<" , time:"<<second;
+
+
+        //处理点云--------------------------------------------------------------------------
+        int color[3]={0,255,0};
+        if(shutter.verify(scan_cloud.makeShared())!=SUCCESS)
+        {
+            color[0]=255;
+            color[1]=0;
+            color[2]=0;
+        }
+
+        mut.lock();
+        viewer.removeAllPointClouds();
+        pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color(scan_cloud.makeShared(), color[0],color[1],color[2]); // green
+        viewer.addPointCloud(scan_cloud.makeShared(), single_color, "livox");
+        viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "livox");
+        mut.unlock();
+        usleep(10*1000);
+    }
+
+
+}
+
+int main(int argc,char* argv[])
+{
+    //初始化日志
+    init_glog();
+    viewer.addCoordinateSystem(2.0,0,0,0,"car_center");
+
+    usleep(500*1000);
+    std::thread* thread=new std::thread(Working);
+
+    while(1)
+    {
+        mut.lock();
+        viewer.spinOnce();
+        mut.unlock();
+        usleep(33*1000);
+    }
+
+    return 0;
+}

+ 116 - 0
plc/LibmodbusWrapper.cpp

@@ -0,0 +1,116 @@
+
+#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;
+    }
+}

+ 37 - 0
plc/LibmodbusWrapper.h

@@ -0,0 +1,37 @@
+#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;
+    };
+};

+ 447 - 0
plc/plc_communicator.cpp

@@ -0,0 +1,447 @@
+#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);
+    }
+}

+ 134 - 0
plc/plc_communicator.h

@@ -0,0 +1,134 @@
+#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

+ 357 - 0
plc/plc_message.pb.cc

@@ -0,0 +1,357 @@
+// 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>

+ 374 - 0
plc/plc_message.pb.h

@@ -0,0 +1,374 @@
+// 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

+ 16 - 0
plc/plc_message.proto

@@ -0,0 +1,16 @@
+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;
+}

+ 146 - 0
plc/plc_modbus_uml.wsd

@@ -0,0 +1,146 @@
+@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

+ 722 - 0
plc/plc_module.pb.cc

@@ -0,0 +1,722 @@
+// 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>

+ 703 - 0
plc/plc_module.pb.h

@@ -0,0 +1,703 @@
+// 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

+ 22 - 0
plc/plc_module.proto

@@ -0,0 +1,22 @@
+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;
+}

+ 46 - 0
plc/plc_task.cpp

@@ -0,0 +1,46 @@
+#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;
+}

+ 41 - 0
plc/plc_task.h

@@ -0,0 +1,41 @@
+#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

+ 60 - 0
task/task_command_manager.cpp

@@ -0,0 +1,60 @@
+//
+// Created by zx on 2019/12/28.
+//
+
+#include "task_command_manager.h"
+#include "../error.h"
+
+Task_Base::Task_Base()
+{
+    m_task_type=UNKNOW_TASK;
+}
+Task_Base::~Task_Base()
+{
+
+}
+//初始化任务单,初始任务单类型为 UNKONW_TASK
+Error_manager Task_Base::init()
+{
+    m_task_type=UNKNOW_TASK;
+    return SUCCESS;
+}
+//更新任务单
+//task_statu: 任务状态
+//statu_information:状态说明
+Error_manager Task_Base::update_statu(Task_statu task_statu,std::string statu_information)
+{
+    m_task_statu=task_statu;
+    m_task_statu_information=statu_information;
+    return SUCCESS;
+}
+//获取任务类型
+Task_type Task_Base::get_task_type()
+{
+    return m_task_type;
+}
+//获取任务单状态
+Task_statu  Task_Base::get_statu()
+{
+    return m_task_statu;
+}
+//获取状态说明
+std::string Task_Base::get_statu_information()
+{
+    return m_task_statu_information;
+}
+
+//获取 错误码
+Error_manager& Task_Base::get_task_error_manager()
+{
+	return m_task_error_manager;
+}
+//设置 错误码
+void Task_Base::set_task_error_manager(Error_manager & error_manager)
+{
+	m_task_error_manager = error_manager;
+}
+
+
+
+

+ 59 - 0
task/task_command_manager.h

@@ -0,0 +1,59 @@
+//
+// Created by zx on 2019/12/28.
+//
+
+#ifndef TASK_COMAND_MANAGER_H
+#define TASK_COMAND_MANAGER_H
+#include <string>
+#include "../error_code/error_code.h"
+
+//任务类型
+enum Task_type
+{
+    LASER_TASK=0,           //雷达扫描任务
+    LOCATE_TASK,            //测量任务
+    PLC_TASK,                //上传PLC任务
+    WJ_TASK,
+    UNKNOW_TASK             //未知任务单/初始化
+};
+//任务状态,如果任务故障,任务状态改为TASK_OVER,然后在m_task_error_manager 补充错误码。
+enum Task_statu
+{
+    TASK_CREATED            =0,             //创建状态,默认值
+    TASK_SIGNED             =1,             //已签收
+    TASK_WORKING            =2,             //处理中
+    TASK_OVER               =3,             //已结束
+};
+
+//任务单基类
+class Task_Base
+{
+public:
+    virtual ~Task_Base();
+    //初始化任务单,初始任务单类型为 UNKONW_TASK
+    virtual Error_manager init();
+    //更新任务单
+    //task_statu: 任务状态
+    //statu_information:状态说明
+    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
+    //获取任务类型
+    Task_type   get_task_type();
+    //获取任务单状态
+    Task_statu  get_statu();
+    //获取状态说明
+    std::string get_statu_information();
+	//获取 错误码
+	Error_manager& get_task_error_manager();
+	//设置 错误码
+	void set_task_error_manager(Error_manager & error_manager);
+protected:
+    Task_Base();
+protected:
+    Task_type                   m_task_type;					//任务类型
+    Task_statu                  m_task_statu;					//任务状态
+    std::string					m_task_statu_information;		//任务状态说明
+	//错误码,任务故障信息,任务输出
+	Error_manager               m_task_error_manager;
+};
+
+#endif //TASK_COMAND_MANAGER_H

+ 82 - 0
task/task_command_manager.puml

@@ -0,0 +1,82 @@
+@startuml
+@startuml
+skinparam classAttributeIconSize 0
+
+<<<<<<< HEAD
+title  Task_Base 任务单基类
+=======
+title  binary_buf是二进制缓存
+>>>>>>> origin/hl
+
+
+
+enum Task_type
+{
+//任务类型
+	UNKNOW_TASK             =0,				//未知任务单//初始化,默认值
+	LASER_TASK              =1,             //雷达扫描任务,
+    LOCATE_TASK             =2,             //测量任务
+    PLC_TASK                =3,             //上传PLC任务
+}
+
+
+enum Task_statu
+{
+//任务状态,如果任务故障,任务状态改为TASK_OVER,然后在m_task_error_manager 补充错误码。
+    TASK_CREATED            =0,             //创建状态,默认值
+    TASK_SIGNED             =1,             //已签收
+    TASK_WORKING            =2,             //处理中
+    TASK_OVER               =3,             //已结束
+}
+
+
+
+
+class Task_Base
+{
+//任务单基类
+==public:==
+    ~Task_Base();
+..
+    //初始化任务单,初始任务单类型为 UNKONW_TASK
+    virtual Error_manager init();
+..
+    //更新任务单
+    //task_statu: 任务状态
+    //statu_information:状态说明
+    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
+..
+    //获取任务类型
+    Task_type   get_task_type();
+..
+    //获取任务单状态
+    Task_statu  get_statu();
+..
+    //获取状态说明
+    std::string get_statu_information();
+..
+	//获取 错误码
+	Error_manager& get_task_error_manager();
+..
+	//设置 错误码
+	void set_task_error_manager(Error_manager & error_manager);
+==protected:==
+    Task_Base();
+==protected:==
+    Task_type                   m_task_type;                    //任务类型
+    Task_statu                  m_task_statu;                   //任务状态
+    std::string                 m_task_statu_information;       //任务状态说明
+	//错误码,任务故障信息,任务输出
+	Error_manager               m_task_error_manager;
+}
+
+class Error_manager
+{
+//错误码管理
+}
+Task_Base <-- Error_manager : include
+
+
+Task_Base <-- Task_type : include
+Task_Base <-- Task_statu : include
+@enduml

+ 35 - 0
tool/StdCondition.cpp

@@ -0,0 +1,35 @@
+#include "StdCondition.h"
+
+StdCondition::StdCondition():m_value(false)
+{
+}
+
+StdCondition::StdCondition(bool init):m_value(init)
+{
+}
+
+StdCondition::~StdCondition()
+{
+}
+bool StdCondition::isTrue(StdCondition* scd)
+{
+	if (scd == 0)return false;
+	return scd->m_value;
+}
+
+void StdCondition::Wait()
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_cv.wait(loc,std::bind(isTrue,this));
+}
+bool StdCondition::WaitFor(unsigned int millisecond)
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	return m_cv.wait_for(loc, std::chrono::milliseconds(millisecond), std::bind(isTrue, this));
+}
+void StdCondition::Notify(bool istrue)
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_value = istrue;
+	m_cv.notify_all();
+}

+ 26 - 0
tool/StdCondition.h

@@ -0,0 +1,26 @@
+#pragma once
+
+#include <thread>  
+#include <mutex>  
+#include <chrono>  
+#include <condition_variable>
+#include <functional>
+
+class StdCondition
+{
+public:
+	StdCondition();
+	StdCondition(bool init);
+	~StdCondition();
+	void Wait();
+	bool WaitFor(unsigned int millisecond);
+	void Notify(bool istrue);
+
+protected:
+	static bool isTrue(StdCondition* scd);
+protected:
+	bool m_value;
+	std::mutex m_mutex;
+	std::condition_variable m_cv;
+};
+

+ 319 - 0
tool/binary_buf.cpp

@@ -0,0 +1,319 @@
+
+/*
+ * binary_buf是二进制缓存
+ * 这里用字符串,来存储雷达的通信消息的原始数据
+ * Binary_buf 的内容格式:消息类型 + 消息数据
+ *
+ * 例如思科的雷达的消息类型
+ * ready->ready->start->data->data->data->stop->ready->ready
+ *
+ * 提供了 is_equal 系列的函数,来进行判断前面的消息类型
+ * 
+ * 注意了:m_buf是中间可以允许有‘\0’的,不是单纯的字符串格式
+ * 			末尾也不一定是‘\0’
+ */
+
+#include "binary_buf.h"
+
+#include <string>
+#include <string.h>
+
+Binary_buf::Binary_buf()
+{
+	mp_buf = NULL;
+	m_length = 0;
+}
+
+Binary_buf::Binary_buf(const Binary_buf& other)
+{
+	mp_buf = NULL;
+	m_length = 0;
+
+	if ( other.m_length > 0 && other.mp_buf != NULL)
+	{
+		mp_buf = (char*)malloc(other.m_length);
+		memcpy(mp_buf, other.mp_buf, other.m_length);
+		m_length = other.m_length;
+	}
+}
+
+Binary_buf::~Binary_buf()
+{
+	if ( mp_buf )
+	{
+		free(mp_buf);
+		mp_buf = NULL;
+	}
+	m_length = 0;
+}
+
+
+//使用参数构造,深拷贝,len为0时,使用strlen(buf),不存储结束符'\0'
+Binary_buf::Binary_buf(const char* p_buf, int len)
+{
+	mp_buf = NULL;
+	m_length = 0;
+
+	if ( p_buf != NULL)
+	{
+		if (len <= 0)
+		{
+			len = strlen(p_buf);
+		}
+
+		mp_buf = (char*)malloc(len);
+		memcpy(mp_buf, p_buf, len);
+		m_length = len;
+	}
+}
+
+//重载=,深拷贝,
+Binary_buf& Binary_buf::operator=(const Binary_buf& other)
+{
+	clear();
+
+	if ( other.m_length > 0 && other.mp_buf != NULL)
+	{
+		mp_buf = (char*)malloc(other.m_length);
+		memcpy(mp_buf, other.mp_buf, other.m_length);
+		m_length = other.m_length;
+	}
+	return *this;
+}
+
+//重载=,深拷贝,使用strlen(buf),不存储结束符'\0'
+Binary_buf& Binary_buf::operator=(const char* p_buf)
+{
+	clear();
+
+	if ( p_buf != NULL)
+	{
+		int len = strlen(p_buf);
+		mp_buf = (char*)malloc(len);
+		memcpy(mp_buf, p_buf, len);
+		m_length = len;
+	}
+	return *this;
+}
+
+//重载+,other追加在this的后面,
+Binary_buf& Binary_buf::operator+(Binary_buf& other)
+{
+	if (other.mp_buf != NULL && other.m_length > 0)
+	{
+		int t_length_total = m_length + other.m_length;
+		char* tp_buf_total = (char*)malloc(t_length_total);
+		memcpy(tp_buf_total, mp_buf, m_length);
+		memcpy(tp_buf_total + m_length, other.mp_buf, other.m_length);
+		free(mp_buf);
+		mp_buf = tp_buf_total;
+		m_length = t_length_total;
+	}
+	return *this;
+}
+
+//重载+,追加在this的后面,使用strlen(buf),不存储结束符'\0'
+Binary_buf& Binary_buf::operator+(const char* p_buf)
+{
+	if (p_buf != NULL )
+	{
+		int t_length_back = strlen(p_buf);
+		int t_length_total = m_length + t_length_back;
+		char* tp_buf_total = (char*)malloc(t_length_total);
+		memcpy(tp_buf_total, mp_buf, m_length);
+		memcpy(tp_buf_total + m_length, p_buf, t_length_back);
+		free(mp_buf);
+		mp_buf = tp_buf_total;
+		m_length = t_length_total;
+	}
+	return *this;
+}
+
+//重载[],允许直接使用数组的形式,直接访问buf的内存。注意,n值必须在0~m_length之间,
+char& Binary_buf::operator[](int n)
+{
+	if (n >= 0 && n < m_length)
+	{
+		return mp_buf[n];
+	}
+	else
+	{
+		throw (n);
+	}
+}
+
+
+//判空
+bool Binary_buf::is_empty()
+{
+	if ( mp_buf != NULL && m_length > 0 )
+	{
+		return false;
+	}
+	else
+	{
+		return true;
+	}
+}
+
+//清空
+void Binary_buf::clear()
+{
+	if ( mp_buf )
+	{
+		free(mp_buf);
+		mp_buf = NULL;
+	}
+	m_length = 0;
+}
+
+
+//比较前面部分的buf是否相等,使用 other.m_length 为标准
+bool Binary_buf::is_equal_front(const Binary_buf& other)
+{
+	if ( other.mp_buf == NULL || other.m_length <= 0 )
+	{
+		if ( mp_buf == NULL || m_length <= 0 )
+		{
+			return true;
+		}
+		else
+		{
+			return false;
+		}
+	}
+	else
+	{
+		if ( mp_buf != NULL && m_length > 0 )
+		{
+			if ( other.m_length > m_length )
+			{
+				return false;
+			}
+			return  (strncmp((const char*)mp_buf, other.mp_buf, other.m_length) == 0);
+		}
+		else
+		{
+			return false;
+		}
+
+	}
+}
+
+//比较前面部分的buf是否相等,len为0时,使用strlen(buf)为标准,不比较结束符'\0'
+bool Binary_buf::is_equal_front(const char* p_buf, int len)
+{
+	if ( p_buf == NULL )
+	{
+		if ( mp_buf == NULL || m_length <= 0 )
+		{
+			return true;
+		}
+		else
+		{
+			return false;
+		}
+	}
+	else
+	{
+		if ( mp_buf != NULL && m_length > 0 )
+		{
+			if ( len == 0 )
+			{
+				len = strlen(p_buf);
+			}
+			if ( len > m_length )
+			{
+				return false;
+			}
+			return  (strncmp((const char*)mp_buf, p_buf, len) == 0);
+		}
+		else
+		{
+			return false;
+		}
+
+	}
+}
+
+//比较的buf是否全部相等,
+bool Binary_buf::is_equal_all(const Binary_buf& other)
+{
+	if ( other.mp_buf == NULL || other.m_length <= 0 )
+	{
+		if ( mp_buf == NULL || m_length <= 0 )
+		{
+			return true;
+		}
+		else
+		{
+			return false;
+		}
+	}
+	else
+	{
+		if ( mp_buf != NULL && m_length > 0 )
+		{
+			if ( other.m_length != m_length )
+			{
+				return false;
+			}
+			return  (strncmp((const char*)mp_buf, other.mp_buf, other.m_length) == 0);
+		}
+		else
+		{
+			return false;
+		}
+
+	}
+}
+//比较的buf是否全部相等,不比较结束符'\0'
+bool Binary_buf::is_equal_all(const char* p_buf)
+{
+	if ( p_buf == NULL )
+	{
+		if ( mp_buf == NULL || m_length <= 0 )
+		{
+			return true;
+		}
+		else
+		{
+			return false;
+		}
+	}
+	else
+	{
+		if ( mp_buf != NULL && m_length > 0 )
+		{
+			int	len = strlen(p_buf);
+			if ( len != m_length )
+			{
+				return false;
+			}
+			return  (strncmp((const char*)mp_buf, p_buf, len) == 0);
+		}
+		else
+		{
+			return false;
+		}
+
+	}
+}
+
+
+
+
+char*	Binary_buf::get_buf()const
+{
+	return mp_buf;
+}
+
+int		Binary_buf::get_length()const
+{
+	return m_length;
+}
+
+
+
+
+

+ 88 - 0
tool/binary_buf.h

@@ -0,0 +1,88 @@
+
+/*
+ * binary_buf是二进制缓存
+ * 这里用字符串,来存储雷达的通信消息的原始数据
+ * Binary_buf 的内容格式:消息类型 + 消息数据
+ *
+ * 例如思科的雷达的消息类型
+ * ready->ready->start->data->data->data->stop->ready->ready
+ *
+ * 提供了 is_equal 系列的函数,来进行判断前面的消息类型
+ *
+ * 注意了:m_buf是中间可以允许有‘\0’的,不是单纯的字符串格式
+ * 			末尾也不一定是‘\0’
+ */
+
+#ifndef LIDARMEASURE_BINARY_BUF_H
+#define LIDARMEASURE_BINARY_BUF_H
+
+
+//雷达消息的类型
+//在通信消息的前面一部分字符串,表示这条消息的类型。
+//在解析消息的时候,先解析前面的消息类型,来判断这条消息的功用
+enum Buf_type
+{
+	//默认值 BUF_UNKNOW = 0
+	BUF_UNKNOW   		=0,	//未知消息
+	BUF_READY  			=1,	//待机消息
+	BUF_START 			=2,	//开始消息
+	BUF_DATA   			=3,	//数据消息
+	BUF_STOP  			=4,	//结束消息
+	BUF_ERROR   		=5,	//错误消息
+};
+
+
+//二进制缓存,
+class Binary_buf
+{
+public:
+	Binary_buf();
+	Binary_buf(const Binary_buf& other);
+	~Binary_buf();
+
+	//使用参数构造,深拷贝,len为0时,使用strlen(buf),不存储结束符'\0'
+	Binary_buf(const char* p_buf, int len = 0);
+	//重载=,深拷贝,
+	Binary_buf& operator=(const Binary_buf& other);
+	//重载=,深拷贝,使用strlen(buf),不存储结束符'\0'
+	Binary_buf& operator=(const char* p_buf);
+	//重载+,other追加在this的后面,
+	Binary_buf& operator+(Binary_buf& other);
+	//重载+,追加在this的后面,使用strlen(buf),不存储结束符'\0'
+	Binary_buf& operator+(const char* p_buf);
+	//重载[],允许直接使用数组的形式,直接访问buf的内存。注意,n值必须在0~m_length之间,
+	char& operator[](int n);
+
+	//判空
+	bool is_empty();
+	//清空
+	void clear();
+
+	//比较前面部分的buf是否相等,使用 other.m_length 为标准
+	bool is_equal_front(const Binary_buf& other);
+	//比较前面部分的buf是否相等,len为0时,使用strlen(buf)为标准,不比较结束符'\0'
+	bool is_equal_front(const char* p_buf, int len = 0);
+
+	//比较的buf是否全部相等,
+	bool is_equal_all(const Binary_buf& other);
+	//比较的buf是否全部相等,不比较结束符'\0'
+	bool is_equal_all(const char* p_buf);
+
+
+
+public:
+	char* get_buf()const;
+	int	get_length()const;
+
+protected:
+	char*		mp_buf;				//二进制缓存指针
+	int			m_length;			//二进制缓存长度
+
+private:
+
+};
+
+
+
+
+#endif //LIDARMEASURE_BINARY_BUF_H

+ 85 - 0
tool/binary_buf.puml

@@ -0,0 +1,85 @@
+@startuml
+skinparam classAttributeIconSize 0
+
+title  binary_buf是二进制缓存
+
+note left of Binary_buf
+/*
+ * binary_buf是二进制缓存
+ * 这里用字符串,来存储雷达的通信消息的原始数据
+ * Binary_buf 的内容格式:消息类型 + 消息数据
+ *
+ * 例如思科的雷达的消息类型
+ * ready->ready->start->data->data->data->stop->ready->ready
+ *
+ * 提供了 is_equal 系列的函数,来进行判断前面的消息类型
+ *
+ * 注意了:m_buf是中间可以允许有‘\0’的,不是单纯的字符串格式
+ * 			末尾也不一定是‘\0’
+ */
+end note
+
+
+
+enum Buf_type
+{
+//雷达消息的类型
+//在通信消息的前面一部分字符串,表示这条消息的类型。
+//在解析消息的时候,先解析前面的消息类型,来判断这条消息的功用
+	//默认值 BUF_UNKNOW = 0
+	BUF_UNKNOW   		=0,	//未知消息
+	BUF_READY  			=1,	//待机消息
+	BUF_START 			=2,	//开始消息
+	BUF_DATA   			=3,	//数据消息
+	BUF_STOP  			=4,	//结束消息
+	BUF_ERROR   		=5,	//错误消息
+}
+
+
+
+class Binary_buf
+{
+//二进制缓存,
+==public:==
+	Binary_buf();
+	Binary_buf(const Binary_buf& other);
+	~Binary_buf();
+..
+	//使用参数构造,深拷贝,len为0时,使用strlen(buf),不存储结束符'\0'
+	Binary_buf(const char* p_buf, int len = 0);
+	//重载=,深拷贝,
+	Binary_buf& operator=(const Binary_buf& other);
+	//重载=,深拷贝,使用strlen(buf),不存储结束符'\0'
+	Binary_buf& operator=(const char* p_buf);
+	//重载+,other追加在this的后面,
+	Binary_buf& operator+(Binary_buf& other);
+	//重载+,追加在this的后面,使用strlen(buf),不存储结束符'\0'
+	Binary_buf& operator+(const char* p_buf);
+	//重载[],允许直接使用数组的形式,直接访问buf的内存。注意,n值必须在0~m_length之间,
+	char& operator[](int n);
+..
+	//判空
+	bool is_empty();
+	//清空
+	void clear();
+..
+	//比较前面部分的buf是否相等,使用 other.m_length 为标准
+	bool is_equal_front(const Binary_buf& other);
+	//比较前面部分的buf是否相等,len为0时,使用strlen(buf)为标准,不比较结束符'\0'
+	bool is_equal_front(const char* p_buf, int len = 0);
+
+	//比较的buf是否全部相等,
+	bool is_equal_all(const Binary_buf& other);
+	//比较的buf是否全部相等,不比较结束符'\0'
+	bool is_equal_all(const char* p_buf);
+==public:==
+	char* get_buf()const;
+	int	get_length()const;
+==protected:==
+	char*		mp_buf;				//二进制缓存指针
+	int			m_length;			//二进制缓存长度
+==private:==
+}
+
+
+@enduml

+ 94 - 0
tool/pathcreator.cpp

@@ -0,0 +1,94 @@
+#include "pathcreator.h"
+
+#include <unistd.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <time.h>
+#include <stdint.h>
+#include <stdio.h>
+
+PathCreator::PathCreator()
+{
+
+}
+
+PathCreator::~PathCreator()
+{
+
+}
+
+std::string PathCreator::GetCurPath()
+{
+    return m_current_path;
+}
+bool PathCreator::Mkdir(std::string dirName)
+{
+    uint32_t beginCmpPath = 0;
+    uint32_t endCmpPath = 0;
+    std::string fullPath = "";
+
+    if('/' != dirName[0])
+    {
+        fullPath = getcwd(nullptr, 0);
+        beginCmpPath = fullPath.size();
+        fullPath = fullPath + "/" + dirName;
+    }
+    else
+    {
+        //Absolute path
+        fullPath = dirName;
+        beginCmpPath = 1;
+    }
+    if (fullPath[fullPath.size() - 1] != '/')
+    {
+        fullPath += "/";
+    }
+    endCmpPath = fullPath.size();
+
+    //create dirs;
+    for(uint32_t i = beginCmpPath; i < endCmpPath ; i++ )
+    {
+        if('/' == fullPath[i])
+        {
+            std::string curPath = fullPath.substr(0, i);
+            if(access(curPath.c_str(), F_OK) != 0)
+            {
+                if(mkdir(curPath.c_str(), /*S_IRUSR|S_IRGRP|S_IROTH|S_IWUSR|S_IWGRP|S_IWOTH*/0777) == -1)
+                {
+                    printf("mkdir(%s) failed\n", curPath.c_str());
+                    return false;
+                }
+            }
+        }
+    }
+    m_current_path=fullPath;
+    return true;
+
+}
+
+bool PathCreator::CreateDatePath(std::string root, bool add_time)
+{
+    time_t tt;
+    time( &tt );
+    tt = tt + 8*3600;  // transform the time zone
+    tm* t= gmtime( &tt );
+    char buf[255]={0};
+    if (add_time)
+    {
+        sprintf(buf, "%s/%d%02d%02d-%02d%02d%02d", root.c_str(),
+                t->tm_year + 1900,
+                t->tm_mon + 1,
+                t->tm_mday,
+                t->tm_hour,
+                t->tm_min,
+                t->tm_sec);
+    }
+    else
+    {
+        sprintf(buf, "%s/%d%02d%02d", root.c_str(),
+                t->tm_year + 1900,
+                t->tm_mon + 1,
+                t->tm_mday);
+    }
+    return Mkdir(buf);
+}

+ 18 - 0
tool/pathcreator.h

@@ -0,0 +1,18 @@
+#ifndef PATHCREATOR_H
+#define PATHCREATOR_H
+#include <string>
+
+class PathCreator
+{
+public:
+    PathCreator();
+    ~PathCreator();
+    std::string GetCurPath();
+    bool Mkdir(std::string dir);
+    bool CreateDatePath(std::string root, bool add_time = true);
+protected:
+    std::string m_current_path;
+};
+
+
+#endif // PATHCREATOR_H

+ 299 - 0
tool/point_tool.cpp

@@ -0,0 +1,299 @@
+//
+// Created by zx on 2021/5/11.
+//
+
+#include "point_tool.h"
+
+void rotation_matrix_to_rpy()
+{
+    //2#  92.0084   112.664  179.263
+    //3#  85.2597  73.8993  -1.70915
+    //4#  91.93   112.146   -179.65
+    //5#  32.9435  67.8446  -52.9897
+    //6#  124.098  119.42  -150.147
+    //8#  37.3443  111.887  130.948
+
+    /*
+    mat_r00:0.0229183
+    mat_r01:-0.9985044
+    mat_r02:0.0496393
+    mat_r03:5287.829
+    mat_r10:0.2763783
+    mat_r11:0.0540452
+    mat_r12:0.9595283
+    mat_r13:-2399.535
+    mat_r20:-0.9607757
+    mat_r21:-0.0082715
+    mat_r22:0.2772034
+    mat_r23:6674.29500*/
+    Eigen::Matrix3d mat;
+    mat<<0.0229183,
+            -0.9985044,
+    0.0496393,
+            0.2763783,
+    0.0540452,
+    0.9595283,
+            -0.9607757,
+                    -0.0082715,
+    0.2772034;
+    Eigen::Vector3d euler_angles = mat.eulerAngles(2, 1, 0);
+    std::cout<<euler_angles*180.0/M_PI<<std::endl;
+}
+
+void rpy_to_rotation_matrix()
+{
+    //
+    float ea[3]={-172,105.42,99.38};
+    Eigen::Matrix3d rotation_matrix3;
+    rotation_matrix3 = Eigen::AngleAxisd(ea[2]*M_PI/180.0, Eigen::Vector3d::UnitZ()) *
+            Eigen::AngleAxisd(ea[1]*M_PI/180.0, Eigen::Vector3d::UnitY()) *
+            Eigen::AngleAxisd(ea[0]*M_PI/180.0, Eigen::Vector3d::UnitX());
+    std::cout << "rotation matrix3 =\n" << rotation_matrix3 << std::endl;
+}
+
+void reverse_test(){
+    Eigen::Matrix3d mat;
+    mat<<-0.2963634,0.9547403,-0.0252988,-0.2261306,-0.0958803,-0.9693665,-0.9279189,-0.2815638,0.2443113;
+    Eigen::Vector3d euler_angles = mat.eulerAngles(2, 1, 0);
+    std::cout<<euler_angles*180.0/M_PI<<std::endl;
+    Eigen::Matrix3d rotation_matrix3;
+    rotation_matrix3 = Eigen::AngleAxisd(euler_angles[0], Eigen::Vector3d::UnitZ()) *
+            Eigen::AngleAxisd(euler_angles[1], Eigen::Vector3d::UnitY()) *
+            Eigen::AngleAxisd(euler_angles[2], Eigen::Vector3d::UnitX());
+    std::cout << "origin matrix3 =\n" << mat << std::endl;
+    std::cout << "rotation matrix3 =\n" << rotation_matrix3 << std::endl;
+}
+
+bool string2point(std::string str,pcl::PointXYZ& point)
+{
+    std::istringstream iss;
+    iss.str(str);
+    float value;
+    float data[3]={0};
+    for(int i=0;i<3;++i)
+    {
+        if(iss>>value)
+        {
+            data[i]=value;
+        }
+        else
+        {
+            return false;
+        }
+    }
+    point.x=data[0];
+    point.y=data[1];
+    point.z=data[2];
+    return true;
+}
+
+pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
+{
+    std::ifstream fin(file.c_str());
+    const int line_length=64;
+    char str[line_length]={0};
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
+    while(fin.getline(str,line_length))
+    {
+        pcl::PointXYZ point;
+        if(string2point(str,point))
+        {
+            cloud->push_back(point);
+        }
+    }
+    return cloud;
+}
+
+
+void save_cloud_txt(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,std::string file)
+{
+    FILE* pf=fopen(file.c_str(),"w");
+    for(int i=0;i<cloud->size();++i)
+    {
+        pcl::PointXYZ point=cloud->points[i];
+        fprintf(pf,"%.3f %.3f %.3f\n",point.x,point.y,point.z);
+    }
+    fclose(pf);
+}
+
+void save_cloud_txt(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,std::string file)
+{
+    FILE* pf=fopen(file.c_str(),"w");
+    for(int i=0;i<cloud->size();++i)
+    {
+        pcl::PointXYZRGB point=cloud->points[i];
+        fprintf(pf,"%.3f %.3f %.3f %d %d %d\n",point.x,point.y,point.z,point.r,point.g,point.b);
+    }
+    fclose(pf);
+}
+
+//欧式聚类*******************************************************
+std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
+{
+    std::vector<pcl::PointIndices> ece_inlier;
+    pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
+    pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
+    ece.setInputCloud(sor_cloud);
+    ece.setClusterTolerance(0.2);
+    ece.setMinClusterSize(20);
+    ece.setMaxClusterSize(20000);
+    ece.setSearchMethod(tree);
+    ece.extract(ece_inlier);
+
+    std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>  segmentation_clouds;
+    for (int i = 0; i < ece_inlier.size(); i++)
+    {
+        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
+        std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
+        copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy);//按照索引提取点云数据
+        segmentation_clouds.push_back(cloud_copy);
+    }
+    return segmentation_clouds;
+}
+
+double distance(cv::Point2f p1, cv::Point2f p2)
+{
+    return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
+}
+
+
+bool isRect(std::vector<cv::Point2f>& points)
+{
+    if (points.size() == 4)
+    {
+        double L[3] = {0.0};
+        L[0] = distance(points[0], points[1]);
+        L[1] = distance(points[1], points[2]);
+        L[2] = distance(points[0], points[2]);
+        double max_l = L[0];
+        double l1 = L[1];
+        double l2 = L[2];
+        cv::Point2f ps = points[0], pt = points[1];
+        cv::Point2f pc = points[2];
+        for (int i = 1; i < 3; ++i) {
+            if (L[i] > max_l)
+            {
+                max_l = L[i];
+                l1 = L[abs(i + 1) % 3];
+                l2 = L[abs(i + 2) % 3];
+                ps = points[i % 3];
+                pt = points[(i + 1) % 3];
+                pc = points[(i + 2) % 3];
+            }
+        }
+
+        //直角边与坐标轴的夹角 <20°
+        float thresh=20.0*M_PI/180.0;
+        cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
+        float angle=atan2(vct.y,vct.x);
+        if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
+        {
+            //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
+            return false;
+        }
+
+        double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
+        if (fabs(cosa) >= 0.15) {
+            /*char description[255]={0};
+            sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
+            std::cout<<description<<std::endl;*/
+            return false;
+        }
+
+        float width=std::min(l1,l2);
+        float length=std::max(l1,l2);
+        if(width<1.400 || width >1.900 || length >3.300 ||length < 2.200)
+        {
+            /*char description[255]={0};
+            sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
+            std::cout<<description<<std::endl;*/
+            return false;
+        }
+
+        double d = distance(pc, points[3]);
+        cv::Point2f center1 = (ps + pt) * 0.5;
+        cv::Point2f center2 = (pc + points[3]) * 0.5;
+        if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150) {
+            /*std::cout << "d:" << d << " maxl:" << max_l << "  center1:" << center1 << "  center2:" << center2<<std::endl;
+            char description[255]={0};
+            sprintf(description,"Verify failed-4  fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
+            std::cout<<description<<std::endl;*/
+            return false;
+        }
+        //std::cout << "d:" << d << " maxl:" << max_l << "  center1:" << center1 << "  center2:" << center2<<std::endl;
+
+
+        return true;
+    }
+    else if(points.size()==3)
+    {
+        double L[3] = {0.0};
+        L[0] = distance(points[0], points[1]);
+        L[1] = distance(points[1], points[2]);
+        L[2] = distance(points[0], points[2]);
+        double max_l = L[0];
+        double l1 = L[1];
+        double l2 = L[2];
+        int max_index = 0;
+        cv::Point2f ps = points[0], pt = points[1];
+        cv::Point2f pc = points[2];
+        for (int i = 1; i < 3; ++i) {
+            if (L[i] > max_l) {
+                max_index = i;
+                max_l = L[i];
+                l1 = L[abs(i + 1) % 3];
+                l2 = L[abs(i + 2) % 3];
+                ps = points[i % 3];
+                pt = points[(i + 1) % 3];
+                pc = points[(i + 2) % 3];
+            }
+        }
+
+        //直角边与坐标轴的夹角 <20°
+        float thresh=20.0*M_PI/180.0;
+        cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
+        float angle=atan2(vct.y,vct.x);
+        if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
+        {
+            //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
+            return false;
+        }
+
+        double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
+        if (fabs(cosa) >= 0.15) {
+            /*char description[255]={0};
+            sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
+            std::cout<<description<<std::endl;*/
+            return false;
+        }
+
+        double l=std::max(l1,l2);
+        double w=std::min(l1,l2);
+        if(l>2.100 && l<3.300 && w>1.400 && w<2.100)
+        {
+            //生成第四个点
+            cv::Point2f vec1=ps-pc;
+            cv::Point2f vec2=pt-pc;
+            cv::Point2f point4=(vec1+vec2)+pc;
+            points.push_back(point4);
+
+            /*char description[255]={0};
+            sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
+            std::cout<<description<<std::endl;*/
+            return true;
+        }
+        else
+        {
+
+            /*char description[255]={0};
+            sprintf(description,"3 wheels rectangle verify Failed  cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
+            std::cout<<description<<std::endl;*/
+            return false;
+        }
+
+    }
+    //std::cout<<" default false"<<std::endl;
+    return false;
+
+}
+

+ 31 - 0
tool/point_tool.h

@@ -0,0 +1,31 @@
+//
+// Created by zx on 2021/5/11.
+//
+
+#ifndef ROBOT_CONTROL_FEATURE_EXTRA_SRC_POINT_TOOL_HPP_
+#define ROBOT_CONTROL_FEATURE_EXTRA_SRC_POINT_TOOL_HPP_
+#include <iostream>
+#include <pcl/point_types.h>
+#include <pcl/point_cloud.h>
+#include <pcl/io/pcd_io.h>
+#include <pcl/segmentation/sac_segmentation.h>
+#include <pcl/ModelCoefficients.h>
+#include <pcl/filters/extract_indices.h>
+#include <pcl/segmentation/extract_clusters.h>
+#include <opencv2/opencv.hpp>
+
+bool string2point(std::string str,pcl::PointXYZ& point);
+pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file);
+
+void save_cloud_txt(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,std::string file);
+void save_cloud_txt(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,std::string file);
+
+double distance(cv::Point2f p1, cv::Point2f p2);
+bool isRect(std::vector<cv::Point2f>& points);
+std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud);
+
+
+void rpy_to_rotation_matrix();
+void rotation_matrix_to_rpy();
+void reverse_test();
+#endif //ROBOT_CONTROL_FEATURE_EXTRA_SRC_POINT_TOOL_HPP_

+ 42 - 0
tool/proto_tool.cpp

@@ -0,0 +1,42 @@
+
+
+
+#include "proto_tool.h"
+#include <fcntl.h>
+#include<unistd.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;
+
+
+//读取protobuf 配置文件,转化为protobuf参数形式
+//input:	prototxt_path :prototxt文件路径
+//ouput:	parameter: protobuf参数,这里是消息基类,实际调用时传入对应的子类即可。
+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;
+	FileInputStream* input = new FileInputStream(fd);
+	bool success = google::protobuf::TextFormat::Parse(input, &protobuf_parameter);
+	delete input;
+	close(fd);
+	return success;
+}
+
+
+
+
+
+
+
+
+
+
+
+

+ 56 - 0
tool/proto_tool.h

@@ -0,0 +1,56 @@
+
+
+
+
+
+#ifndef __PROTO_TOOL_H
+#define __PROTO_TOOL_H
+
+#include "singleton.h"
+#include <istream>
+#include <google/protobuf/message.h>
+
+class proto_tool:public Singleton<proto_tool>
+{
+	// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
+	friend class Singleton<proto_tool>;
+public:
+	// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
+	proto_tool(const proto_tool&)=delete;
+	proto_tool& operator =(const proto_tool&)= delete;
+	~proto_tool()=default;
+private:
+	// 父类的构造函数必须保护,子类的构造函数必须私有。
+	proto_tool()=default;
+
+
+public:
+	//读取protobuf 配置文件,转化为protobuf参数形式
+	//input:	prototxt_path :prototxt文件路径
+	//ouput:	parameter: protobuf参数,这里是消息基类,实际调用时传入对应的子类即可。
+	static bool read_proto_param(std::string prototxt_path, ::google::protobuf::Message& protobuf_parameter);
+};
+
+
+
+
+#endif //__PROTO_TOOL_H
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+

+ 4 - 0
tool/singleton.cpp

@@ -0,0 +1,4 @@
+
+#include "singleton.h"
+
+

+ 81 - 0
tool/singleton.h

@@ -0,0 +1,81 @@
+
+/* Singleton 是单例类的模板。
+ * https://www.cnblogs.com/sunchaothu/p/10389842.html
+ * 单例 Singleton 是设计模式的一种,其特点是只提供唯一一个类的实例,具有全局变量的特点,在任何位置都可以通过接口获取到那个唯一实例;
+ * 全局只有一个实例:static 特性,同时禁止用户自己声明并定义实例(把构造函数设为 private 或者 protected)
+ * Singleton 模板类对这种方法进行了一层封装。
+ * 单例类需要从Singleton继承。
+ * 子类需要将自己作为模板参数T 传递给 Singleton<T> 模板;
+ * 同时需要将基类声明为友元,这样Singleton才能调用子类的私有构造函数。
+// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
+// 父类的构造函数必须保护,子类的构造函数必须私有。
+// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来操作 唯一的实例。
+ * */
+
+#ifndef __SINGLIETON_H
+#define __SINGLIETON_H
+
+//#include <iostream>
+
+template<typename T>
+class Singleton
+{
+public:
+	//获取单例的引用
+	static T& get_instance_references()
+	{
+		static T instance;
+		return instance;
+	}
+	//获取单例的指针
+	static T* get_instance_pointer()
+	{
+		return &(get_instance_references());
+	}
+
+	virtual ~Singleton()
+	{
+//		std::cout<<"destructor called!"<<std::endl;
+	}
+
+	Singleton(const Singleton&)=delete;					//关闭拷贝构造函数
+	Singleton& operator =(const Singleton&)=delete;		//关闭赋值函数
+
+protected:
+	//构造函数需要是 protected,这样子类才能继承;
+	Singleton()
+	{
+//		std::cout<<"constructor called!"<<std::endl;
+	}
+
+};
+
+/*
+// 如下是 使用样例:
+// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
+// 父类的构造函数必须保护,子类的构造函数必须私有。
+// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
+
+class DerivedSingle:public Singleton<DerivedSingle>
+{
+ // 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
+	friend class Singleton<DerivedSingle>;
+public:
+ // 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
+	DerivedSingle(const DerivedSingle&)=delete;
+	DerivedSingle& operator =(const DerivedSingle&)= delete;
+ 	~DerivedSingle()=default;
+private:
+ // 父类的构造函数必须保护,子类的构造函数必须私有。
+	DerivedSingle()=default;
+};
+
+int main(int argc, char* argv[]){
+	DerivedSingle& instance1 = DerivedSingle::get_instance_references();
+	DerivedSingle* p_instance2 = DerivedSingle::get_instance_pointer();
+	return 0;
+}
+
+ */
+
+#endif

+ 101 - 0
tool/threadSafeQueue.h

@@ -0,0 +1,101 @@
+//
+// Created by zx on 2019/12/17.
+//
+
+#ifndef SRC_THREADSAFEQUEUE_H
+#define SRC_THREADSAFEQUEUE_H
+
+
+#include <queue>
+#include <memory>
+#include <mutex>
+#include <condition_variable>
+template<typename T>
+class threadsafe_queue
+{
+private:
+    mutable std::mutex mut;
+    std::queue<T> data_queue;
+    std::condition_variable data_cond;
+public:
+    threadsafe_queue() {}
+    threadsafe_queue(threadsafe_queue const& other)
+    {
+        std::lock_guard<std::mutex> lk(other.mut);
+        data_queue = other.data_queue;
+    }
+    ~threadsafe_queue()
+    {
+        while (!empty())
+        {
+            try_pop();
+        }
+    }
+    size_t size()
+    {
+        return data_queue.size();
+    }
+    void push(T new_value)//��Ӳ���
+    {
+        std::lock_guard<std::mutex> lk(mut);
+        data_queue.push(new_value);
+        data_cond.notify_one();
+    }
+    void wait_and_pop(T& value)//ֱ����Ԫ�ؿ���ɾ��Ϊֹ
+    {
+        std::unique_lock<std::mutex> lk(mut);
+        data_cond.wait(lk, [this] {return !data_queue.empty(); });
+        value = data_queue.front();
+        data_queue.pop();
+    }
+    std::shared_ptr<T> wait_and_pop()
+    {
+        std::unique_lock<std::mutex> lk(mut);
+        data_cond.wait(lk, [this] {return !data_queue.empty(); });
+        std::shared_ptr<T> res(std::make_shared<T>(data_queue.front()));
+        data_queue.pop();
+        return res;
+    }
+    //ֻ���� �� pop
+    bool front(T& value)
+    {
+        std::lock_guard<std::mutex> lk(mut);
+        if (data_queue.empty())
+            return false;
+        value = data_queue.front();
+        return true;
+    }
+
+    bool try_pop(T& value)//������û�ж���Ԫ��ֱ�ӷ���
+    {
+        if (data_queue.empty())
+            return false;
+        std::lock_guard<std::mutex> lk(mut);
+        value = data_queue.front();
+        data_queue.pop();
+        return true;
+    }
+    std::shared_ptr<T> try_pop()
+    {
+        std::lock_guard<std::mutex> lk(mut);
+        if (data_queue.empty())
+            return std::shared_ptr<T>();
+        std::shared_ptr<T> res(std::make_shared<T>(data_queue.front()));
+        data_queue.pop();
+        return res;
+    }
+    bool empty() const
+    {
+        std::lock_guard<std::mutex> lk(mut);
+        return data_queue.empty();
+    }
+    void clear()
+    {
+        while (!empty()) {
+            try_pop();
+        }
+    }
+};
+
+
+#endif //SRC_THREADSAFEQUEUE_H

+ 144 - 0
tool/thread_condition.cpp

@@ -0,0 +1,144 @@
+
+
+/* Thread_condition 是多线程的条件控制类,主要是控制线程的启停和退出
+ * 线程创建后,一般是循环运行,
+ * 为了防止线程暂满整个cpu,那么需要线程在不工作的是否进入等待状态。
+ * Thread_condition 就可以控制线程的运行状态。
+ *
+	std::atomic<bool> m_pass_ever		//线程能否直接通过等待,对后面的线程也生效。
+	std::atomic<bool> m_pass_once		//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
+ * 外部调用notify系列的函数,唤醒等待的线程,让线程执行功能函数。
+ * 如果需要线程循环多次执行功能函数,那么就使用 notify_all(true),后面的线程可以直接通过等待了。
+ * 再使用 notify_all(false) ,即可停止线程,让其继续等待。
+ * 如果只想要线程执行一次,那就使用 notify_all(false, true)
+ * 注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
+ *
+ * m_kill_flag //是否杀死线程,让线程强制退出,
+ * 外部调用 kill_all() 函数,可以直接通知线程自动退出。
+	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
+	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
+	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
+	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
+
+ 注:notify唤醒线程之后,wait里面的判断函数会重新判断。
+ */
+
+#include "thread_condition.h"
+
+Thread_condition::Thread_condition()
+{
+	m_kill_flag = false;
+	m_pass_ever = false;
+	m_pass_once = false;
+}
+Thread_condition::~Thread_condition()
+{
+	kill_all();
+}
+
+//无限等待,由 is_pass_wait 决定是否阻塞。
+//返回m_pass,
+bool Thread_condition::wait()
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_condition_variable.wait(loc,std::bind(is_pass_wait,this));
+	bool t_pass = is_pass_wait(this);
+	m_pass_once = false;
+	return t_pass;
+}
+//等待一定的时间(默认时间单位:毫秒ms),由 is_pass_wait 决定是否阻塞。
+//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
+//注意了:线程阻塞期间,是不会return的。
+bool Thread_condition::wait_for_millisecond(unsigned int millisecond)
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_condition_variable.wait_for(loc, std::chrono::milliseconds(millisecond), std::bind(is_pass_wait, this));
+	bool t_pass = is_pass_wait(this);
+	m_pass_once = false;
+	return t_pass;
+}
+
+
+//唤醒已经阻塞的线程,唤醒一个线程
+//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
+void Thread_condition::notify_one(bool pass_ever, bool pass_once)
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_pass_ever = pass_ever;
+	m_pass_once = pass_once;
+	m_condition_variable.notify_one();
+}
+//唤醒已经阻塞的线程,唤醒全部线程
+//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
+void Thread_condition::notify_all(bool pass_ever, bool pass_once)
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_pass_ever = pass_ever;
+	m_pass_once = pass_once;
+	m_condition_variable.notify_all();
+}
+//注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
+
+
+//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
+//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
+// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
+//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
+void Thread_condition::kill_all()
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_kill_flag = true;
+	m_condition_variable.notify_all();
+}
+
+//判断是否或者,return !m_kill_flag
+bool Thread_condition::is_alive()
+{
+	return !m_kill_flag;
+}
+
+
+bool Thread_condition::get_kill_flag()
+{
+	return m_kill_flag;
+}
+bool Thread_condition::get_pass_ever()
+{
+	return m_pass_ever;
+}
+bool Thread_condition::get_pass_once()
+{
+	return m_pass_once;
+}
+void Thread_condition::set_kill_flag(bool kill)
+{
+	m_kill_flag = kill;
+}
+void Thread_condition::set_pass_ever(bool pass_ever)
+{
+	m_pass_ever = pass_ever;
+}
+void Thread_condition::set_pass_once(bool pass_once)
+{
+	m_pass_once = pass_once;
+}
+void Thread_condition::reset(bool kill, bool pass_ever, bool pass_once)
+{
+	m_kill_flag = kill;
+	m_pass_ever = pass_ever;
+	m_pass_once = pass_once;
+}
+
+
+//判断线程是否可以通过等待,wait系列函数的判断标志
+//注:m_kill或者m_pass为真时,return true
+bool Thread_condition::is_pass_wait(Thread_condition * other)
+{
+	if ( other == NULL )
+	{
+		throw (other);
+		return false;
+	}
+	return (other->m_kill_flag || other->m_pass_ever || other->m_pass_once);
+}
+

+ 114 - 0
tool/thread_condition.h

@@ -0,0 +1,114 @@
+
+
+/* Thread_condition 是多线程的条件控制类,主要是控制线程的启停和退出
+ * 线程创建后,一般是循环运行,
+ * 为了防止线程暂满整个cpu,那么需要线程在不工作的是否进入等待状态。
+ * Thread_condition 就可以控制线程的运行状态。
+ *
+	std::atomic<bool> m_pass_ever		//线程能否直接通过等待,对后面的线程也生效。
+	std::atomic<bool> m_pass_once		//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
+ * 外部调用notify系列的函数,唤醒等待的线程,让线程执行功能函数。
+ * 如果需要线程循环多次执行功能函数,那么就使用 notify_all(true),后面的线程可以直接通过等待了。
+ * 再使用 notify_all(false) ,即可停止线程,让其继续等待。
+ * 如果只想要线程执行一次,那就使用 notify_all(false, true)
+ * 注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
+ *
+ * m_kill_flag //是否杀死线程,让线程强制退出,
+ * 外部调用 kill_all() 函数,可以直接通知线程自动退出。
+	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
+	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
+	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
+	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
+
+ 注:notify唤醒线程之后,wait里面的判断函数会重新判断。
+ */
+
+#ifndef LIDARMEASURE_THREAD_CONDITION_H
+#define LIDARMEASURE_THREAD_CONDITION_H
+
+#include <ratio>
+#include <chrono>
+#include <thread>
+#include <atomic>
+#include <mutex>
+#include <condition_variable>
+#include <functional>
+
+class Thread_condition
+{
+public:
+	Thread_condition();
+	Thread_condition(const Thread_condition& other) = delete;
+	~Thread_condition();
+
+	//无限等待,由 is_pass_wait 决定是否阻塞。
+	//返回m_pass,
+	bool wait();
+	//等待一定的时间(默认时间单位:毫秒ms),由 is_pass_wait 决定是否阻塞。
+	//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
+	//注意了:线程阻塞期间,是不会return的。
+	bool wait_for_millisecond(unsigned int millisecond);
+
+	//等待一定的时间(时间单位可调),由 is_pass_wait 决定是否阻塞。
+	//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
+	//注意了:线程阻塞期间,是不会return的。
+	template<typename _Rep, typename _Period>
+	bool wait_for_ex(const std::chrono::duration<_Rep, _Period>& time_duration);
+
+	//唤醒已经阻塞的线程,唤醒一个线程
+	//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
+	void notify_one(bool pass_ever, bool pass_once = false);
+	//唤醒已经阻塞的线程,唤醒全部线程
+	//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
+	void notify_all(bool pass_ever, bool pass_once = false);
+	//注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
+
+	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
+	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
+	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
+	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
+	void kill_all();
+
+	//判断是否或者,return !m_kill_flag
+	bool is_alive();
+
+public:
+
+	bool get_kill_flag();
+	bool get_pass_ever();
+	bool get_pass_once();
+	void set_kill_flag(bool kill);
+	void set_pass_ever(bool pass_ever);
+	void set_pass_once(bool pass_once);
+	void reset(bool kill = false, bool pass_ever = false, bool pass_once = false);
+
+protected:
+	//判断线程是否可以通过等待,wait系列函数的判断标志
+	//注:m_kill或者m_pass为真时,return true
+	static bool is_pass_wait(Thread_condition * other);
+
+	std::atomic<bool> 		m_kill_flag;			//是否杀死线程,让线程强制退出,
+	std::atomic<bool> 		m_pass_ever;			//线程能否直接通过等待,对后面的线程也生效。
+	std::atomic<bool> 		m_pass_once;			//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
+
+	std::mutex 				m_mutex;				//线程的锁
+	std::condition_variable m_condition_variable;	//线程的条件变量
+
+private:
+
+};
+
+//等待一定的时间(时间单位可调),由 is_pass_wait 决定是否阻塞。
+//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
+//注意了:线程阻塞期间,是不会return的。
+template<typename _Rep, typename _Period>
+bool Thread_condition::wait_for_ex(const std::chrono::duration<_Rep, _Period>& time_duration)
+{
+	std::unique_lock<std::mutex> loc(m_mutex);
+	m_condition_variable.wait_for(loc, std::chrono::duration<_Rep, _Period>(time_duration), std::bind(is_pass_wait, this));
+	bool t_pass = is_pass_wait(this);
+	m_pass_once = false;
+	return t_pass;
+}
+
+#endif //LIDARMEASURE_THREAD_CONDITION_H

+ 96 - 0
tool/thread_condition.puml

@@ -0,0 +1,96 @@
+@startuml
+skinparam classAttributeIconSize 0
+
+title  Thread_condition 是多线程的条件控制类,主要是控制线程的启停和退出
+note left of Thread_condition
+/* Thread_condition 是多线程的条件控制类,主要是控制线程的启停和退出
+ * 线程创建后,一般是循环运行,
+ * 为了防止线程暂满整个cpu,那么需要线程在不工作的是否进入等待状态。
+ * Thread_condition 就可以控制线程的运行状态。
+ *
+	std::atomic<bool> m_pass_ever		//线程能否直接通过等待,对后面的线程也生效。
+	std::atomic<bool> m_pass_once		//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
+ * 外部调用notify系列的函数,唤醒等待的线程,让线程执行功能函数。
+ * 如果需要线程循环多次执行功能函数,那么就使用 notify_all(true),后面的线程可以直接通过等待了。
+ * 再使用 notify_all(false) ,即可停止线程,让其继续等待。
+ * 如果只想要线程执行一次,那就使用 notify_all(false, true)
+ * 注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
+ *
+ * m_kill_flag //是否杀死线程,让线程强制退出,
+ * 外部调用 kill_all() 函数,可以直接通知线程自动退出。
+	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
+	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
+	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
+	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
+
+ 注:notify唤醒线程之后,wait里面的判断函数会重新判断。
+ */
+end note
+
+
+
+class Thread_condition
+{
+==public:==
+	Thread_condition();
+	Thread_condition(const Thread_condition& other) = delete;
+	~Thread_condition();
+..
+	//无限等待,由 is_pass_wait 决定是否阻塞。
+	//返回m_pass,
+	bool wait();
+..
+	//等待一定的时间(默认时间单位:毫秒ms),由 is_pass_wait 决定是否阻塞。
+	//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
+	//注意了:线程阻塞期间,是不会return的。
+	bool wait_for_millisecond(unsigned int millisecond);
+..
+	//等待一定的时间(时间单位可调),由 is_pass_wait 决定是否阻塞。
+	//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
+	//注意了:线程阻塞期间,是不会return的。
+	template<typename _Rep, typename _Period>
+	bool wait_for_ex(const std::chrono::duration<_Rep, _Period>& time_duration);
+..
+	//唤醒已经阻塞的线程,唤醒一个线程
+	//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
+	void notify_one(bool pass_ever, bool pass_once = false);
+..
+	//唤醒已经阻塞的线程,唤醒全部线程
+	//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
+	void notify_all(bool pass_ever, bool pass_once = false);
+	//注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
+..
+	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
+	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
+	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
+	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
+	void kill_all();
+..
+	//判断是否或者,return !m_kill_flag
+	bool is_alive();
+==public:==
+	bool get_kill_flag();
+	bool get_pass_ever();
+	bool get_pass_once();
+	void set_kill_flag(bool kill);
+	void set_pass_ever(bool pass_ever);
+	void set_pass_once(bool pass_once);
+	void reset(bool kill = false, bool pass_ever = false, bool pass_once = false);
+==protected:==
+	//判断线程是否可以通过等待,wait系列函数的判断标志
+	//注:m_kill或者m_pass为真时,return true
+	static bool is_pass_wait(Thread_condition * other);
+
+	std::atomic<bool> 		m_kill_flag;			//是否杀死线程,让线程强制退出,
+	std::atomic<bool> 		m_pass_ever;			//线程能否直接通过等待,对后面的线程也生效。
+	std::atomic<bool> 		m_pass_once;			//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
+
+	std::mutex 				m_mutex;				//线程的锁
+	std::condition_variable m_condition_variable;	//线程的条件变量
+
+==private:==
+
+}
+
+
+@enduml

+ 34 - 0
tool/thread_safe_queue.cpp

@@ -0,0 +1,34 @@
+
+
+/*
+ * (1)这个实现要求构建工具支持C++11的atomic std::mutex condition_veriable功能。这是C++11的基础特性,一般2011年以后的C++编译器都能支持。 例如,visual studio 2012以上。
+
+(2)这个类的实现中有两处使用了unique_lock而不是lock_guard,这是data_cond.wait所需要的,unique_lock是lock_guard的增强版。
+
+通过std::move的使用(前提是我们实现的类型T定义了移动构造函数和移动赋值函数),能利用移动语义带来的性能优势。
+
+使用shared_ptr<T>返回元素,用户无需释放元素的内存。
+
+
+原文链接:https://blog.csdn.net/weixin_41855721/article/details/81703818
+引用了他的思路,增加了一些功能函数, 补充了注释说明
+
+ termination_queue
+ 	// 在退出状态下,所有的功能函数不可用,返回false或者null。
+	// wait_and_pop不会阻塞。让其直接通过,通过后直接return,不允许做其他的。
+
+ pop系列函数
+	//(1)没有调用termination时,每调用一次出队一个元素,直到队列为空本方法阻塞线程。
+	//(2)在调用了termination后,本方法永不阻塞,如果原本已经处于阻塞状态,解除阻塞状态。
+	//(3)返回true时,value值有效。返回false时,value值无效。调用了termination且队列为空时返回false.
+
+注注注注注意了:模板类不支持分离编译。 模板类的实现必须放在头文件
+ 为了方便阅读和编程规范,依然将声明和实现分开,就像是把cpp文件的代码复制到h文件的尾部。
+
+ 如果将实现放到cpp里面,那么就要为cpp文件加 ifndef define endif
+ 然后在调用方include包含cpp文件,但是这样不好。
+ * */
+
+#include "thread_safe_queue.h"
+
+

+ 339 - 0
tool/thread_safe_queue.h

@@ -0,0 +1,339 @@
+
+
+/*
+ * (1)这个实现要求构建工具支持C++11的atomic mutex condition_veriable功能。这是C++11的基础特性,一般2011年以后的C++编译器都能支持。 例如,visual studio 2012以上。
+
+(2)这个类的实现中有两处使用了unique_lock而不是lock_guard,这是data_cond.wait所需要的,unique_lock是lock_guard的增强版。
+
+通过std::move的使用(前提是我们实现的类型T定义了移动构造函数和移动赋值函数),能利用移动语义带来的性能优势。
+
+使用shared_ptr<T>返回元素,用户无需释放元素的内存。
+
+
+原文链接:https://blog.csdn.net/weixin_41855721/article/details/81703818
+ 增加了一些功能函数,
+ 补充了注释说明
+
+ termination_queue
+ 	// 在退出状态下,所有的功能函数不可用,返回false或者null。
+	// wait_and_pop不会阻塞。让其直接通过,通过后直接return,不允许做其他的。
+
+ pop系列函数
+	//(1)没有调用termination时,每调用一次出队一个元素,直到队列为空本方法阻塞线程。
+	//(2)在调用了termination后,本方法永不阻塞,如果原本已经处于阻塞状态,解除阻塞状态。
+	//(3)返回true时,value值有效。返回false时,value值无效。调用了termination且队列为空时返回false.
+
+注注注注注意了:模板类不支持分离编译。 模板类的实现必须放在头文件
+ 为了方便阅读和编程规范,依然将声明和实现分开,就像是把cpp文件的代码复制到h文件的尾部。
+
+ 如果将实现放到cpp里面,那么就要为cpp文件加 ifndef define endif 防止重定义。
+ 然后在调用方include包含cpp文件,但是这样不好。
+
+
+ * */
+
+#ifndef LIDARMEASURE_THREAD_SAFE_QUEUE_H
+#define LIDARMEASURE_THREAD_SAFE_QUEUE_H
+
+#include <queue>
+
+#include <atomic>
+#include <mutex>
+#include <condition_variable>
+
+
+template<class T>
+class Thread_safe_queue
+{
+public:
+	Thread_safe_queue();
+	Thread_safe_queue(const Thread_safe_queue& other);
+	~Thread_safe_queue();
+
+	//(1)没有调用termination时,每调用一次出队一个元素,直到队列为空本方法阻塞线程。
+	//(2)在调用了termination后,本方法永不阻塞,如果原本已经处于阻塞状态,解除阻塞状态。
+	//(3)返回true时,value值有效。返回false时,value值无效。调用了termination且队列为空时返回false.
+
+	//等待并弹出数据,成功弹出则返回true
+	// 队列为空则无限等待,termination终止队列,则返回false
+	bool wait_and_pop(T& value);
+	//尝试弹出数据,成功弹出则返回true
+	//队列为空 或者 termination终止队列,返回false
+	bool try_pop(T& value);
+	//等待并弹出数据,成功弹出则返回true
+	// 队列为空则无限等待,termination终止队列,则返回false
+	std::shared_ptr<T> wait_and_pop();
+	//尝试弹出数据,成功弹出则返回true
+	//队列为空 或者 termination终止队列,返回false
+	std::shared_ptr<T> try_pop();
+	//插入一项,并唤醒一个线程,
+	//如果成功插入,则返回true,  失败则返回false
+	//注:只能唤醒一个线程,防止多线程误判empty()
+	bool push(T new_value);
+	//清除队列,只是将队列的实例抛出。T是实例内存,系统自动回收的。
+	bool clear();
+	//清除队列,抛出之后还要delete指针。T是动态内存,需要手动回收的。
+	bool clear_and_delete();
+
+public:
+	//判空
+	bool empty();
+	//获取队列大小
+	size_t size();
+	//设置队列为退出状态。并唤醒所有的线程,使其通过wait
+	// 在退出状态下,所有的功能函数不可用,必须直接返回false或者null。
+	// wait_and_pop不会阻塞。让其直接通过,通过后直接return,不允许做其他的。
+	void termination_queue();
+	//唤醒队列,恢复所有的功能函数。wait_and_pop会继续阻塞。
+	void wake_queue();
+	//获取退出状态
+	bool get_termination_flag();
+	//判断是否可以直接通过wait,  m_data_queue不为空或者m_termination终止时都可以通过等待。
+	bool is_pass();
+
+protected:
+	std::mutex 						m_mutex;				//队列的锁
+	std::queue<std::shared_ptr<T>> 	m_data_queue;			//队列数据,使用智能指针shared_ptr
+	std::condition_variable 		m_data_cond;			//条件变量
+	std::atomic<bool> 				m_termination_flag;		//终止标志位
+
+private:
+
+
+};
+
+
+
+
+
+
+
+
+template<class T>
+Thread_safe_queue<T>::Thread_safe_queue()
+{
+	m_termination_flag = false;
+}
+template<class T>
+Thread_safe_queue<T>::Thread_safe_queue(const Thread_safe_queue& other)
+{
+	std::unique_lock<std::mutex> lock_this(m_mutex);
+	std::unique_lock<std::mutex> lock_other(other.m_mutex);
+	m_data_queue = other.data_queue;
+	m_termination_flag = other.m_termination_flag;
+}
+template<class T>
+Thread_safe_queue<T>::~Thread_safe_queue()
+{
+	//析构时,终止队列,让线程通过等待,方便线程推出。
+	termination_queue();
+}
+
+//(1)没有调用termination时,每调用一次出队一个元素,直到队列为空本方法阻塞线程。
+//(2)在调用了termination后,本方法永不阻塞,如果原本已经处于阻塞状态,解除阻塞状态。
+//(3)返回true时,value值有效。返回false时,value值无效。调用了termination且队列为空时返回false.
+
+//等待并弹出数据,成功弹出则返回true
+// 队列为空则无限等待,termination终止队列,则返回false
+template<class T>
+bool Thread_safe_queue<T>::wait_and_pop(T& value)
+{
+	if ( m_termination_flag )
+	{
+		return false;
+	}
+	else
+	{
+		std::unique_lock<std::mutex> lk(m_mutex);
+		//无限等待,一直阻塞,除非有新的数据加入或者终止队列
+		m_data_cond.wait(lk, [this]
+		{ return ((!m_data_queue.empty()) || m_termination_flag); });
+		if (m_termination_flag)
+		{
+			return false;
+		}
+		else
+		{
+			value = move(*m_data_queue.front());
+			m_data_queue.pop();
+			return true;
+		}
+	}
+}
+//尝试弹出数据,成功弹出则返回true
+//队列为空 或者 termination终止队列,返回false
+template<class T>
+bool Thread_safe_queue<T>::try_pop(T& value)
+{
+	if ( m_termination_flag )
+	{
+		return false;
+	}
+	else
+	{
+		std::unique_lock<std::mutex> lk(m_mutex);
+		if (m_data_queue.empty())
+		{
+			return false;
+		}
+		else
+		{
+			value = move(*m_data_queue.front());
+			m_data_queue.pop();
+			return true;
+		}
+	}
+}
+//等待并弹出数据,成功弹出则返回true
+// 队列为空则无限等待,termination终止队列,则返回false
+template<class T>
+std::shared_ptr<T> Thread_safe_queue<T>::wait_and_pop()
+{
+	if ( m_termination_flag )
+	{
+		return NULL;
+	}
+	else
+	{
+		std::unique_lock<std::mutex> lk(m_mutex);
+		//无限等待,一直阻塞,除非有新的数据加入或者终止队列
+		m_data_cond.wait(lk, [this]
+		{ return ((!m_data_queue.empty()) || m_termination_flag); });
+		if (m_termination_flag)
+		{
+			return NULL;
+		}
+		else
+		{
+			std::shared_ptr<T> res = m_data_queue.front();
+			m_data_queue.pop();
+			return res;
+		}
+	}
+}
+//尝试弹出数据,成功弹出则返回true
+//队列为空 或者 termination终止队列,返回false
+template<class T>
+std::shared_ptr<T> Thread_safe_queue<T>::try_pop()
+{
+	if ( m_termination_flag )
+	{
+		return NULL;
+	}
+	else
+	{
+		std::unique_lock<std::mutex> lk(m_mutex);
+		if (m_data_queue.empty())
+		{
+			return NULL;
+		}
+		else
+		{
+			std::shared_ptr<T> res = m_data_queue.front();
+			m_data_queue.pop();
+			return res;
+		}
+	}
+}
+//插入一项,并唤醒一个线程,
+//如果成功插入,则返回true,  失败则返回false
+//注:只能唤醒一个线程,防止多线程误判empty()
+template<class T>
+bool Thread_safe_queue<T>::push(T new_value)
+{
+	if (m_termination_flag)
+	{
+		return false;
+	}
+	else
+	{
+		std::shared_ptr<T> data(std::make_shared<T>(move(new_value)));
+		std::unique_lock<std::mutex> lk(m_mutex);
+		m_data_queue.push(data);
+		m_data_cond.notify_one();
+		return true;
+	}
+}
+//清除队列,只是将队列的实例抛出。T是实例内存,系统自动回收的。
+template<class T>
+bool Thread_safe_queue<T>::clear()
+{
+		std::unique_lock<std::mutex> lk(m_mutex);
+		while (!m_data_queue.empty())
+		{
+			m_data_queue.pop();
+		}
+		return true;
+
+}
+//清除队列,抛出之后还要delete指针。T是动态内存,需要手动回收的。
+template<class T>
+bool Thread_safe_queue<T>::clear_and_delete()
+{
+		std::unique_lock<std::mutex> lk(m_mutex);
+		while (!m_data_queue.empty())
+		{
+			T res = NULL;
+			res = move(*m_data_queue.front());
+			m_data_queue.pop();
+			if(res != NULL)
+			{
+				delete(res);
+
+			}
+		}
+	return true;
+
+}
+
+//判空
+template<class T>
+bool Thread_safe_queue<T>::empty()
+{
+	std::unique_lock<std::mutex> lk(m_mutex);
+	return m_data_queue.empty();
+}
+//获取队列大小
+template<class T>
+size_t Thread_safe_queue<T>::size()
+{
+	std::unique_lock<std::mutex> lk(m_mutex);
+	return m_data_queue.size();
+}
+//设置队列为退出状态。并唤醒所有的线程,使其通过wait
+// 在退出状态下,所有的功能函数不可用,必须直接返回false或者null。
+// wait_and_pop不会阻塞。让其直接通过,通过后直接return,不允许做其他的。
+template<class T>
+void Thread_safe_queue<T>::termination_queue()
+{
+	std::unique_lock<std::mutex> lk(m_mutex);
+	m_termination_flag = true;
+	m_data_cond.notify_all();
+}
+//唤醒队列,恢复所有的功能函数。wait_and_pop会继续阻塞。
+template<class T>
+void Thread_safe_queue<T>::wake_queue()
+{
+	std::unique_lock<std::mutex> lk(m_mutex);
+	m_termination_flag = false;
+	m_data_cond.notify_all();
+}
+//获取退出状态
+template<class T>
+bool Thread_safe_queue<T>::get_termination_flag()
+{
+	return m_termination_flag;
+}
+//判断是否可以直接通过wait,  m_data_queue不为空或者m_termination终止时都可以通过等待。
+template<class T>
+bool Thread_safe_queue<T>::is_pass()
+{
+	return (!m_data_queue.empty() || m_termination_flag);
+}
+
+
+
+
+
+
+#endif //LIDARMEASURE_THREAD_SAFE_QUEUE_H

+ 108 - 0
tool/thread_safe_queue.puml

@@ -0,0 +1,108 @@
+@startuml
+skinparam classAttributeIconSize 0
+
+title  Thread_safe_queue 安全线程队列
+
+note left of Thread_safe_queue
+
+/*
+ * (1)这个实现要求构建工具支持C++11的atomic mutex condition_veriable功能。这是C++11的基础特性,一般2011年以后的C++编译器都能支持。 例如,visual studio 2012以上。
+
+(2)这个类的实现中有两处使用了unique_lock而不是lock_guard,这是data_cond.wait所需要的,unique_lock是lock_guard的增强版。
+
+通过std::move的使用(前提是我们实现的类型T定义了移动构造函数和移动赋值函数),能利用移动语义带来的性能优势。
+
+使用shared_ptr<T>返回元素,用户无需释放元素的内存。
+
+
+原文链接:https://blog.csdn.net/weixin_41855721/article/details/81703818
+ 增加了一些功能函数,
+ 补充了注释说明
+
+ termination_queue
+ 	// 在退出状态下,所有的功能函数不可用,返回false或者null。
+	// wait_and_pop不会阻塞。让其直接通过,通过后直接return,不允许做其他的。
+
+ pop系列函数
+	//(1)没有调用termination时,每调用一次出队一个元素,直到队列为空本方法阻塞线程。
+	//(2)在调用了termination后,本方法永不阻塞,如果原本已经处于阻塞状态,解除阻塞状态。
+	//(3)返回true时,value值有效。返回false时,value值无效。调用了termination且队列为空时返回false.
+
+注注注注注意了:模板类不支持分离编译。 模板类的实现必须放在头文件
+ 为了方便阅读和编程规范,依然将声明和实现分开,就像是把cpp文件的代码复制到h文件的尾部。
+
+ 如果将实现放到cpp里面,那么就要为cpp文件加 ifndef define endif 防止重定义。
+ 然后在调用方include包含cpp文件,但是这样不好。
+
+
+ * */
+end note
+
+
+
+class Thread_safe_queue <<    template<class T>    >>
+{
+==public:==
+	Thread_safe_queue();
+	Thread_safe_queue(const Thread_safe_queue& other);
+	~Thread_safe_queue();
+..
+	//(1)没有调用termination时,每调用一次出队一个元素,直到队列为空本方法阻塞线程。
+	//(2)在调用了termination后,本方法永不阻塞,如果原本已经处于阻塞状态,解除阻塞状态。
+	//(3)返回true时,value值有效。返回false时,value值无效。调用了termination且队列为空时返回false.
+	//等待并弹出数据,成功弹出则返回true
+	// 队列为空则无限等待,termination终止队列,则返回false
+	bool wait_and_pop(T& value);
+..
+	//尝试弹出数据,成功弹出则返回true
+	//队列为空 或者 termination终止队列,返回false
+	bool try_pop(T& value);
+..
+	//等待并弹出数据,成功弹出则返回true
+	// 队列为空则无限等待,termination终止队列,则返回false
+	std::shared_ptr<T> wait_and_pop();
+..
+	//尝试弹出数据,成功弹出则返回true
+	//队列为空 或者 termination终止队列,返回false
+	std::shared_ptr<T> try_pop();
+..
+	//插入一项,并唤醒一个线程,
+	//如果成功插入,则返回true,  失败则返回false
+	//注:只能唤醒一个线程,防止多线程误判empty()
+	bool push(T new_value);
+..
+	//清除队列,只是将队列的实例抛出。T是实例内存,系统自动回收的。
+	bool clear();
+..
+	//清除队列,抛出之后还要delete指针。T是动态内存,需要手动回收的。
+	bool clear_and_delete();
+==public:==
+	//判空
+	bool empty();
+..
+	//获取队列大小
+	size_t size();
+..
+	//设置队列为退出状态。并唤醒所有的线程,使其通过wait
+	// 在退出状态下,所有的功能函数不可用,必须直接返回false或者null。
+	// wait_and_pop不会阻塞。让其直接通过,通过后直接return,不允许做其他的。
+	void termination_queue();
+..
+	//唤醒队列,恢复所有的功能函数。wait_and_pop会继续阻塞。
+	void wake_queue();
+..
+	//获取退出状态
+	bool get_termination_flag();
+..
+	//判断是否可以直接通过wait,  m_data_queue不为空或者m_termination终止时都可以通过等待。
+	bool is_pass();
+==protected:==
+	std::mutex 						m_mutex;				//队列的锁
+	std::queue<std::shared_ptr<T>> 	m_data_queue;			//队列数据,使用智能指针shared_ptr
+	std::condition_variable 		m_data_cond;			//条件变量
+	std::atomic<bool> 				m_termination_flag;		//终止标志位
+==private:==
+}
+
+
+@enduml

+ 19 - 0
verifier.cpp

@@ -0,0 +1,19 @@
+//
+// Created by zx on 2021/8/10.
+//
+
+#include "verifier.h"
+verifier::verifier(const shuttler_verifier& left,const shuttler_verifier& right)
+{
+    m_left_shutter_verifier=left;
+    m_right_shutter_verifier=right;
+}
+
+Error_manager verifier::verify(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
+{
+    Error_manager code=m_left_shutter_verifier.verify(cloud);
+    if(code!=SUCCESS)
+        return code;
+    code=m_right_shutter_verifier.verify(cloud);
+    return code;
+}

+ 25 - 0
verifier.h

@@ -0,0 +1,25 @@
+//
+// Created by zx on 2021/8/10.
+//
+
+#ifndef SHUTTER_VERIFY__VERIFIER_H_
+#define SHUTTER_VERIFY__VERIFIER_H_
+
+#include "shuttler_verifier.h"
+
+class verifier
+{
+ public:
+    verifier(const shuttler_verifier& left,const shuttler_verifier& right);
+
+    Error_manager verify(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
+
+
+ protected:
+    shuttler_verifier       m_left_shutter_verifier;
+    shuttler_verifier       m_right_shutter_verifier;
+
+};
+
+
+#endif //SHUTTER_VERIFY__VERIFIER_H_

+ 80 - 0
verify/shuttler_verifier.cpp

@@ -0,0 +1,80 @@
+//
+// Created by zx on 2021/8/6.
+//
+
+#include "shuttler_verifier.h"
+
+shuttler_verifier::shuttler_verifier()
+{
+
+}
+shuttler_verifier::~shuttler_verifier()
+{
+
+}
+
+shuttler_verifier& shuttler_verifier::operator=(const shuttler_verifier& shutter)
+{
+    m_plane=shutter.m_plane;
+    m_maxd=shutter.m_maxd;
+    m_mind=shutter.m_mind;
+
+}
+void shuttler_verifier::set_condition(Eigen::Vector4f plane, float maxd, float mind)
+{
+    m_plane=plane;
+    m_maxd=maxd;
+    m_mind=mind;
+
+}
+
+Error_manager shuttler_verifier::verify(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
+{
+    for(int i=0;i<cloud->size();++i)
+    {
+        if(pointInRectangle(cloud->points[i]))
+            return FAILED;
+    }
+    return SUCCESS;
+}
+
+bool shuttler_verifier::pointInRectangle(pcl::PointXYZ point)
+{
+
+    float a=m_plane[0];
+    float b=m_plane[1];
+    float c=m_plane[2];
+    float d=m_plane[3];
+    //计算点到该平面的距离
+
+    float D=(a*point.x+b*point.y+c*point.z+d)/sqrt(a*a+b*b+c*c);
+    if(D>m_mind && D<m_maxd)
+        return true;
+
+    return false;
+}
+
+void shuttler_verifier::create_plane(pcl::visualization::PCLVisualizer& viewer)
+{
+    static int count=0;
+    char name[64]={0};
+    sprintf(name,"plane_%d",count++);
+
+    float a=m_plane[0],b=m_plane[1],c=m_plane[2],d=m_plane[3];
+    float x=3,z=0.5;
+    float y=(-d-a*x-c*z)/b;
+    float rz=atan2(a,b);
+    float ry=atan2(a,c);
+    float rx=atan2(c,b);
+    Eigen::Vector3f center(x,y,z);
+    float ea[] = {rx,ry,rz};
+    Eigen::Quaternionf quaternion = Eigen::AngleAxisf(ea[0], Eigen::Vector3f::UnitX()) *
+            Eigen::AngleAxisf(ea[1], Eigen::Vector3f::UnitY()) *
+            Eigen::AngleAxisf(ea[2], Eigen::Vector3f::UnitZ());
+
+    viewer.addCube(center, quaternion, 6, 0.04, 1, name);
+    viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 0.5, 0, name);
+    viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.3, name);
+
+
+}

+ 46 - 0
verify/shuttler_verifier.h

@@ -0,0 +1,46 @@
+//
+// Created by zx on 2021/8/6.
+//
+
+#ifndef ROBOT_CONTROL_FEATURE_EXTRA_SRC_SHUTTLER_VERIFIER_H_
+#define ROBOT_CONTROL_FEATURE_EXTRA_SRC_SHUTTLER_VERIFIER_H_
+
+#include <iostream>
+#include <pcl/point_types.h>
+#include <pcl/point_cloud.h>
+#include <pcl/io/pcd_io.h>
+#include <opencv2/opencv.hpp>
+#include <mutex>
+#include "error_code.h"
+#include <pcl/visualization/pcl_visualizer.h>
+
+class shuttler_verifier
+{
+
+ public:
+    shuttler_verifier();
+    ~shuttler_verifier();
+    shuttler_verifier(const shuttler_verifier& shutter)= default;
+    shuttler_verifier& operator=(const shuttler_verifier& shutter);
+
+    void set_condition(Eigen::Vector4f plane,float maxd,float mind);
+
+    Error_manager verify(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
+
+    void create_plane(pcl::visualization::PCLVisualizer& viewer);
+
+ protected:
+    bool pointInRectangle(pcl::PointXYZ point);
+ private:
+
+    std::mutex              m_mutex;
+
+    float                   m_maxd;
+    float                   m_mind;
+
+    Eigen::Vector4f         m_plane;    //平面法向量
+
+};
+
+
+#endif //ROBOT_CONTROL_FEATURE_EXTRA_SRC_SHUTTLER_VERIFIER_H_