浏览代码

合并huli到zzw_sift, 未测试

zx 5 年之前
父节点
当前提交
e6b387d877

+ 4 - 0
CMakeLists.txt

@@ -43,6 +43,10 @@ aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/system_manager SYS_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/wj_lidar WJLIDAR_SRC )
 
 
+# plc test module
+add_executable(plc_test  ./test/plc_test.cpp ${PLC_SRC} ${TASK_MANAGER_SRC} ${TOOL_SRC} ${ERROR_CODE_SRC})
+target_link_libraries(plc_test ${OpenCV_LIBS}
+        ${GLOG_LIBRARIES} ${PCL_LIBRARIES} ${PROTOBUF_LIBRARIES} ipopt modbus libnanomsg.so libnnxx.a libglog.a libgflags.a)
 add_executable(fence_debug  test/plc_s7.cpp wj_lidar/wj_lidar_msg.pb.cc)
 target_link_libraries(fence_debug ${GLOG_LIBRARIES} ${PROTOBUF_LIBRARIES} /usr/local/lib/libglog.a
         /usr/local/lib/libgflags.a nnxx nanomsg)

+ 1 - 0
plc/plc_communicator.h

@@ -36,6 +36,7 @@ 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>

+ 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

+ 3 - 1
test/plc_test.cpp

@@ -37,7 +37,7 @@ public:
             Error_manager ec = t->mp_pc->execute_task(&t->m_task);
             std::cout << "thread execute task " << ec.to_string() << std::endl;
 
-            int count = 2;
+            int count = 1;
             while (count-- > 0)
             {
                 std::cout << "---------- "<<count<<" --------" << std::endl;
@@ -74,6 +74,7 @@ private:
 
 int main(int argc,char* argv[])
 {
+    google::InitGoogleLogging("plc");
     plc_module::plc_connection_params params;
     params.set_ip("192.168.2.131");
     params.set_port(502);
@@ -92,5 +93,6 @@ int main(int argc,char* argv[])
     // std::cout<<"test "<<ec.to_string()<<std::endl;
 
     getchar();
+    google::ShutdownGoogleLogging();
     return 0;
 }

+ 2 - 2
wj_lidar/fence_controller.cpp

@@ -57,7 +57,7 @@ Error_manager Fence_controller::initialize(wj::wjManagerParams params)
         PathCreator path_creator;
         path_creator.Mkdir(m_wj_manager_param.fence_data_path());
     }
-    mp_plc_data = Plc_data::get_instance("192.168.0.1");
+    mp_plc_data = Plc_data::get_instance(m_wj_manager_param.plc_ip_address());
     if (mp_plc_data != 0 && mp_plc_data->get_plc_status())
     {
         LOG(INFO) << "created plc data handler" << mp_plc_data;
@@ -235,7 +235,7 @@ Error_manager Fence_controller::get_current_status()
         else if (!m_lidars_vector[i]->get_connection_status())
         {
             LOG(ERROR) << i << "号雷达检测到连接断开";
-            sprintf(buf, "%d ", i);
+            sprintf(buf+strlen(buf), "%d ", i);
             disconnected_lidar_exist = true;
         }
     }

+ 85 - 0
wj_lidar/globalmsg.proto

@@ -0,0 +1,85 @@
+syntax = "proto2";
+package globalmsg;
+
+message msg
+{
+	required type msg_type=1;
+	optional laserMsg laser_msg=2;
+	optional plcMsg plc_msg=3;
+	optional algMsg alg_msg=4;
+	optional SysMsg sys_msg=5;
+}
+
+enum type
+{
+	ePLC=0;
+	eLaser=1;
+	eAlg=2;
+	eLog=3;
+}
+
+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;
+}
+
+enum plcStatus
+{
+	ePLCConnected=0;
+	ePLCDisconnected=1;
+	ePLCRefused=2;
+	ePLCUnknown=3;
+}
+message plcMsg
+{
+	optional plcStatus plc_status=1;
+	repeated int32 plc_values=2;
+}
+
+message resultInfo
+{
+	required string time=1 [default=""];
+	required bool correctness=2;
+	optional int32 park_space_id=3;
+	optional int32 laser_ids=4;
+	
+	optional double x=5;
+	optional double y=6;
+	optional double c=7;
+	optional double wheel_base=8;
+	optional double length=9;
+	optional double width=10;
+	optional double height=11;
+	optional string error=12 [default=""];
+}
+message algMsg
+{
+
+	repeated resultInfo result=1;
+	optional int32 thread_queue_size=2;
+	optional string log_path=3 [default=""];
+}
+
+enum logLevel
+{
+	eSysInfo=0;
+	eSysLog=1;
+	eSysWarning=2;
+	eSysError=3;
+}
+
+message SysMsg
+{
+	required string log=1 [default=""];
+	optional logLevel level=2 [default=eSysInfo];
+}

+ 96 - 28
wj_lidar/wj_lidar_conf.pb.cc

@@ -62,6 +62,10 @@ void InitDefaultswjManagerParamsImpl() {
 #endif  // GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS
   protobuf_wj_5flidar_5fconf_2eproto::InitDefaultswjLidarParams();
   protobuf_wj_5flidar_5fconf_2eproto::InitDefaultsRegion();
+  ::wj::wjManagerParams::_default_plc_ip_address_.DefaultConstruct();
+  *::wj::wjManagerParams::_default_plc_ip_address_.get_mutable() = ::std::string("192.168.0.1", 11);
+  ::google::protobuf::internal::OnShutdownDestroyString(
+      ::wj::wjManagerParams::_default_plc_ip_address_.get_mutable());
   {
     void* ptr = &::wj::_wjManagerParams_default_instance_;
     new (ptr) ::wj::wjManagerParams();
@@ -195,10 +199,12 @@ const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUT
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj::wjManagerParams, regions_),
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj::wjManagerParams, fence_data_path_),
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj::wjManagerParams, fence_log_path_),
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj::wjManagerParams, plc_ip_address_),
   ~0u,
   ~0u,
   0,
   1,
+  2,
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj::Region, _has_bits_),
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::wj::Region, _internal_metadata_),
   ~0u,  // no _extensions_
@@ -278,12 +284,12 @@ const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUT
   0,
 };
 static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = {
-  { 0, 9, sizeof(::wj::wjManagerParams)},
-  { 13, 22, sizeof(::wj::Region)},
-  { 26, 40, sizeof(::wj::wjLidarParams)},
-  { 49, 56, sizeof(::wj::netConfig)},
-  { 58, 69, sizeof(::wj::Transform2d)},
-  { 75, 85, sizeof(::wj::scanLimit)},
+  { 0, 10, sizeof(::wj::wjManagerParams)},
+  { 15, 24, sizeof(::wj::Region)},
+  { 28, 42, sizeof(::wj::wjLidarParams)},
+  { 51, 58, sizeof(::wj::netConfig)},
+  { 60, 71, sizeof(::wj::Transform2d)},
+  { 77, 87, sizeof(::wj::scanLimit)},
 };
 
 static ::google::protobuf::Message const * const file_default_instances[] = {
@@ -317,30 +323,31 @@ void protobuf_RegisterTypes(const ::std::string&) {
 void AddDescriptorsImpl() {
   InitDefaults();
   static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = {
-      "\n\023wj_lidar_conf.proto\022\002wj\"\210\001\n\017wjManagerP"
+      "\n\023wj_lidar_conf.proto\022\002wj\"\255\001\n\017wjManagerP"
       "arams\022#\n\010wj_lidar\030\001 \003(\0132\021.wj.wjLidarPara"
       "ms\022\033\n\007regions\030\002 \003(\0132\n.wj.Region\022\031\n\017fence"
       "_data_path\030\003 \001(\t:\000\022\030\n\016fence_log_path\030\004 \001"
-      "(\t:\000\"@\n\006Region\022\014\n\004minx\030\001 \002(\002\022\014\n\004maxx\030\002 \002"
-      "(\002\022\014\n\004miny\030\003 \002(\002\022\014\n\004maxy\030\004 \002(\002\"\246\002\n\rwjLid"
-      "arParams\022\035\n\tangle_min\030\001 \001(\002:\n-2.3561945\022"
-      "\034\n\tangle_max\030\002 \001(\002:\t2.3561945\022 \n\017angle_i"
-      "ncrement\030\003 \001(\002:\0070.00582\022\037\n\016time_incremen"
-      "t\030\004 \001(\002:\0076.2e-05\022\024\n\trange_min\030\005 \001(\005:\0010\022\025"
-      "\n\trange_max\030\006 \001(\005:\00230\022!\n\nnet_config\030\007 \002("
-      "\0132\r.wj.netConfig\022\"\n\ttransform\030\010 \002(\0132\017.wj"
-      ".Transform2d\022!\n\nscan_limit\030\t \002(\0132\r.wj.sc"
-      "anLimit\"5\n\tnetConfig\022\024\n\nip_address\030\001 \001(\t"
-      ":\000\022\022\n\004port\030\002 \001(\005:\0048000\"m\n\013Transform2d\022\016\n"
-      "\003m00\030\001 \001(\002:\0011\022\016\n\003m01\030\002 \001(\002:\0010\022\016\n\003m02\030\003 \001"
-      "(\002:\0010\022\016\n\003m10\030\004 \001(\002:\0010\022\016\n\003m11\030\005 \001(\002:\0011\022\016\n"
-      "\003m12\030\006 \001(\002:\0010\"o\n\tscanLimit\022\025\n\ndist_limit"
-      "\030\001 \001(\002:\0018\022\020\n\004minx\030\002 \001(\002:\002-6\022\022\n\004maxx\030\003 \001("
-      "\002:\004-0.2\022\022\n\004miny\030\004 \001(\002:\004-3.5\022\021\n\004maxy\030\005 \001("
-      "\002:\0033.5"
+      "(\t:\000\022#\n\016plc_ip_address\030\005 \001(\t:\013192.168.0."
+      "1\"@\n\006Region\022\014\n\004minx\030\001 \002(\002\022\014\n\004maxx\030\002 \002(\002\022"
+      "\014\n\004miny\030\003 \002(\002\022\014\n\004maxy\030\004 \002(\002\"\246\002\n\rwjLidarP"
+      "arams\022\035\n\tangle_min\030\001 \001(\002:\n-2.3561945\022\034\n\t"
+      "angle_max\030\002 \001(\002:\t2.3561945\022 \n\017angle_incr"
+      "ement\030\003 \001(\002:\0070.00582\022\037\n\016time_increment\030\004"
+      " \001(\002:\0076.2e-05\022\024\n\trange_min\030\005 \001(\005:\0010\022\025\n\tr"
+      "ange_max\030\006 \001(\005:\00230\022!\n\nnet_config\030\007 \002(\0132\r"
+      ".wj.netConfig\022\"\n\ttransform\030\010 \002(\0132\017.wj.Tr"
+      "ansform2d\022!\n\nscan_limit\030\t \002(\0132\r.wj.scanL"
+      "imit\"5\n\tnetConfig\022\024\n\nip_address\030\001 \001(\t:\000\022"
+      "\022\n\004port\030\002 \001(\005:\0048000\"m\n\013Transform2d\022\016\n\003m0"
+      "0\030\001 \001(\002:\0011\022\016\n\003m01\030\002 \001(\002:\0010\022\016\n\003m02\030\003 \001(\002:"
+      "\0010\022\016\n\003m10\030\004 \001(\002:\0010\022\016\n\003m11\030\005 \001(\002:\0011\022\016\n\003m1"
+      "2\030\006 \001(\002:\0010\"o\n\tscanLimit\022\025\n\ndist_limit\030\001 "
+      "\001(\002:\0018\022\020\n\004minx\030\002 \001(\002:\002-6\022\022\n\004maxx\030\003 \001(\002:\004"
+      "-0.2\022\022\n\004miny\030\004 \001(\002:\004-3.5\022\021\n\004maxy\030\005 \001(\002:\003"
+      "3.5"
   };
   ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
-      descriptor, 806);
+      descriptor, 843);
   ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
     "wj_lidar_conf.proto", &protobuf_RegisterTypes);
 }
@@ -362,11 +369,13 @@ namespace wj {
 
 void wjManagerParams::InitAsDefaultInstance() {
 }
+::google::protobuf::internal::ExplicitlyConstructed< ::std::string> wjManagerParams::_default_plc_ip_address_;
 #if !defined(_MSC_VER) || _MSC_VER >= 1900
 const int wjManagerParams::kWjLidarFieldNumber;
 const int wjManagerParams::kRegionsFieldNumber;
 const int wjManagerParams::kFenceDataPathFieldNumber;
 const int wjManagerParams::kFenceLogPathFieldNumber;
+const int wjManagerParams::kPlcIpAddressFieldNumber;
 #endif  // !defined(_MSC_VER) || _MSC_VER >= 1900
 
 wjManagerParams::wjManagerParams()
@@ -393,6 +402,10 @@ wjManagerParams::wjManagerParams(const wjManagerParams& from)
   if (from.has_fence_log_path()) {
     fence_log_path_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.fence_log_path_);
   }
+  plc_ip_address_.UnsafeSetDefault(&::wj::wjManagerParams::_default_plc_ip_address_.get());
+  if (from.has_plc_ip_address()) {
+    plc_ip_address_.AssignWithDefault(&::wj::wjManagerParams::_default_plc_ip_address_.get(), from.plc_ip_address_);
+  }
   // @@protoc_insertion_point(copy_constructor:wj.wjManagerParams)
 }
 
@@ -400,6 +413,7 @@ void wjManagerParams::SharedCtor() {
   _cached_size_ = 0;
   fence_data_path_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
   fence_log_path_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
+  plc_ip_address_.UnsafeSetDefault(&::wj::wjManagerParams::_default_plc_ip_address_.get());
 }
 
 wjManagerParams::~wjManagerParams() {
@@ -410,6 +424,7 @@ wjManagerParams::~wjManagerParams() {
 void wjManagerParams::SharedDtor() {
   fence_data_path_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
   fence_log_path_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
+  plc_ip_address_.DestroyNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get());
 }
 
 void wjManagerParams::SetCachedSize(int size) const {
@@ -444,7 +459,7 @@ void wjManagerParams::Clear() {
   wj_lidar_.Clear();
   regions_.Clear();
   cached_has_bits = _has_bits_[0];
-  if (cached_has_bits & 3u) {
+  if (cached_has_bits & 7u) {
     if (cached_has_bits & 0x00000001u) {
       GOOGLE_DCHECK(!fence_data_path_.IsDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()));
       (*fence_data_path_.UnsafeRawStringPointer())->clear();
@@ -453,6 +468,10 @@ void wjManagerParams::Clear() {
       GOOGLE_DCHECK(!fence_log_path_.IsDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()));
       (*fence_log_path_.UnsafeRawStringPointer())->clear();
     }
+    if (cached_has_bits & 0x00000004u) {
+      GOOGLE_DCHECK(!plc_ip_address_.IsDefault(&::wj::wjManagerParams::_default_plc_ip_address_.get()));
+      (*plc_ip_address_.UnsafeRawStringPointer())->assign(*&::wj::wjManagerParams::_default_plc_ip_address_.get());
+    }
   }
   _has_bits_.Clear();
   _internal_metadata_.Clear();
@@ -522,6 +541,22 @@ bool wjManagerParams::MergePartialFromCodedStream(
         break;
       }
 
+      // optional string plc_ip_address = 5 [default = "192.168.0.1"];
+      case 5: {
+        if (static_cast< ::google::protobuf::uint8>(tag) ==
+            static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) {
+          DO_(::google::protobuf::internal::WireFormatLite::ReadString(
+                input, this->mutable_plc_ip_address()));
+          ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField(
+            this->plc_ip_address().data(), static_cast<int>(this->plc_ip_address().length()),
+            ::google::protobuf::internal::WireFormat::PARSE,
+            "wj.wjManagerParams.plc_ip_address");
+        } else {
+          goto handle_unusual;
+        }
+        break;
+      }
+
       default: {
       handle_unusual:
         if (tag == 0) {
@@ -583,6 +618,16 @@ void wjManagerParams::SerializeWithCachedSizes(
       4, this->fence_log_path(), output);
   }
 
+  // optional string plc_ip_address = 5 [default = "192.168.0.1"];
+  if (cached_has_bits & 0x00000004u) {
+    ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField(
+      this->plc_ip_address().data(), static_cast<int>(this->plc_ip_address().length()),
+      ::google::protobuf::internal::WireFormat::SERIALIZE,
+      "wj.wjManagerParams.plc_ip_address");
+    ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased(
+      5, this->plc_ip_address(), output);
+  }
+
   if (_internal_metadata_.have_unknown_fields()) {
     ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
         _internal_metadata_.unknown_fields(), output);
@@ -636,6 +681,17 @@ void wjManagerParams::SerializeWithCachedSizes(
         4, this->fence_log_path(), target);
   }
 
+  // optional string plc_ip_address = 5 [default = "192.168.0.1"];
+  if (cached_has_bits & 0x00000004u) {
+    ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField(
+      this->plc_ip_address().data(), static_cast<int>(this->plc_ip_address().length()),
+      ::google::protobuf::internal::WireFormat::SERIALIZE,
+      "wj.wjManagerParams.plc_ip_address");
+    target =
+      ::google::protobuf::internal::WireFormatLite::WriteStringToArray(
+        5, this->plc_ip_address(), target);
+  }
+
   if (_internal_metadata_.have_unknown_fields()) {
     target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
         _internal_metadata_.unknown_fields(), target);
@@ -675,7 +731,7 @@ size_t wjManagerParams::ByteSizeLong() const {
     }
   }
 
-  if (_has_bits_[0 / 32] & 3u) {
+  if (_has_bits_[0 / 32] & 7u) {
     // optional string fence_data_path = 3 [default = ""];
     if (has_fence_data_path()) {
       total_size += 1 +
@@ -690,6 +746,13 @@ size_t wjManagerParams::ByteSizeLong() const {
           this->fence_log_path());
     }
 
+    // optional string plc_ip_address = 5 [default = "192.168.0.1"];
+    if (has_plc_ip_address()) {
+      total_size += 1 +
+        ::google::protobuf::internal::WireFormatLite::StringSize(
+          this->plc_ip_address());
+    }
+
   }
   int cached_size = ::google::protobuf::internal::ToCachedSize(total_size);
   GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
@@ -723,7 +786,7 @@ void wjManagerParams::MergeFrom(const wjManagerParams& from) {
   wj_lidar_.MergeFrom(from.wj_lidar_);
   regions_.MergeFrom(from.regions_);
   cached_has_bits = from._has_bits_[0];
-  if (cached_has_bits & 3u) {
+  if (cached_has_bits & 7u) {
     if (cached_has_bits & 0x00000001u) {
       set_has_fence_data_path();
       fence_data_path_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.fence_data_path_);
@@ -732,6 +795,10 @@ void wjManagerParams::MergeFrom(const wjManagerParams& from) {
       set_has_fence_log_path();
       fence_log_path_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.fence_log_path_);
     }
+    if (cached_has_bits & 0x00000004u) {
+      set_has_plc_ip_address();
+      plc_ip_address_.AssignWithDefault(&::wj::wjManagerParams::_default_plc_ip_address_.get(), from.plc_ip_address_);
+    }
   }
 }
 
@@ -765,6 +832,7 @@ void wjManagerParams::InternalSwap(wjManagerParams* other) {
   regions_.InternalSwap(&other->regions_);
   fence_data_path_.Swap(&other->fence_data_path_);
   fence_log_path_.Swap(&other->fence_log_path_);
+  plc_ip_address_.Swap(&other->plc_ip_address_);
   swap(_has_bits_[0], other->_has_bits_[0]);
   _internal_metadata_.Swap(&other->_internal_metadata_);
   swap(_cached_size_, other->_cached_size_);

+ 82 - 0
wj_lidar/wj_lidar_conf.pb.h

@@ -230,12 +230,29 @@ class wjManagerParams : public ::google::protobuf::Message /* @@protoc_insertion
   ::std::string* release_fence_log_path();
   void set_allocated_fence_log_path(::std::string* fence_log_path);
 
+  // optional string plc_ip_address = 5 [default = "192.168.0.1"];
+  bool has_plc_ip_address() const;
+  void clear_plc_ip_address();
+  static const int kPlcIpAddressFieldNumber = 5;
+  const ::std::string& plc_ip_address() const;
+  void set_plc_ip_address(const ::std::string& value);
+  #if LANG_CXX11
+  void set_plc_ip_address(::std::string&& value);
+  #endif
+  void set_plc_ip_address(const char* value);
+  void set_plc_ip_address(const char* value, size_t size);
+  ::std::string* mutable_plc_ip_address();
+  ::std::string* release_plc_ip_address();
+  void set_allocated_plc_ip_address(::std::string* plc_ip_address);
+
   // @@protoc_insertion_point(class_scope:wj.wjManagerParams)
  private:
   void set_has_fence_data_path();
   void clear_has_fence_data_path();
   void set_has_fence_log_path();
   void clear_has_fence_log_path();
+  void set_has_plc_ip_address();
+  void clear_has_plc_ip_address();
 
   ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_;
   ::google::protobuf::internal::HasBits<1> _has_bits_;
@@ -244,6 +261,8 @@ class wjManagerParams : public ::google::protobuf::Message /* @@protoc_insertion
   ::google::protobuf::RepeatedPtrField< ::wj::Region > regions_;
   ::google::protobuf::internal::ArenaStringPtr fence_data_path_;
   ::google::protobuf::internal::ArenaStringPtr fence_log_path_;
+  static ::google::protobuf::internal::ExplicitlyConstructed< ::std::string> _default_plc_ip_address_;
+  ::google::protobuf::internal::ArenaStringPtr plc_ip_address_;
   friend struct ::protobuf_wj_5flidar_5fconf_2eproto::TableStruct;
   friend void ::protobuf_wj_5flidar_5fconf_2eproto::InitDefaultswjManagerParamsImpl();
 };
@@ -1224,6 +1243,69 @@ inline void wjManagerParams::set_allocated_fence_log_path(::std::string* fence_l
   // @@protoc_insertion_point(field_set_allocated:wj.wjManagerParams.fence_log_path)
 }
 
+// optional string plc_ip_address = 5 [default = "192.168.0.1"];
+inline bool wjManagerParams::has_plc_ip_address() const {
+  return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void wjManagerParams::set_has_plc_ip_address() {
+  _has_bits_[0] |= 0x00000004u;
+}
+inline void wjManagerParams::clear_has_plc_ip_address() {
+  _has_bits_[0] &= ~0x00000004u;
+}
+inline void wjManagerParams::clear_plc_ip_address() {
+  plc_ip_address_.ClearToDefaultNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get());
+  clear_has_plc_ip_address();
+}
+inline const ::std::string& wjManagerParams::plc_ip_address() const {
+  // @@protoc_insertion_point(field_get:wj.wjManagerParams.plc_ip_address)
+  return plc_ip_address_.GetNoArena();
+}
+inline void wjManagerParams::set_plc_ip_address(const ::std::string& value) {
+  set_has_plc_ip_address();
+  plc_ip_address_.SetNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get(), value);
+  // @@protoc_insertion_point(field_set:wj.wjManagerParams.plc_ip_address)
+}
+#if LANG_CXX11
+inline void wjManagerParams::set_plc_ip_address(::std::string&& value) {
+  set_has_plc_ip_address();
+  plc_ip_address_.SetNoArena(
+    &::wj::wjManagerParams::_default_plc_ip_address_.get(), ::std::move(value));
+  // @@protoc_insertion_point(field_set_rvalue:wj.wjManagerParams.plc_ip_address)
+}
+#endif
+inline void wjManagerParams::set_plc_ip_address(const char* value) {
+  GOOGLE_DCHECK(value != NULL);
+  set_has_plc_ip_address();
+  plc_ip_address_.SetNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get(), ::std::string(value));
+  // @@protoc_insertion_point(field_set_char:wj.wjManagerParams.plc_ip_address)
+}
+inline void wjManagerParams::set_plc_ip_address(const char* value, size_t size) {
+  set_has_plc_ip_address();
+  plc_ip_address_.SetNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get(),
+      ::std::string(reinterpret_cast<const char*>(value), size));
+  // @@protoc_insertion_point(field_set_pointer:wj.wjManagerParams.plc_ip_address)
+}
+inline ::std::string* wjManagerParams::mutable_plc_ip_address() {
+  set_has_plc_ip_address();
+  // @@protoc_insertion_point(field_mutable:wj.wjManagerParams.plc_ip_address)
+  return plc_ip_address_.MutableNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get());
+}
+inline ::std::string* wjManagerParams::release_plc_ip_address() {
+  // @@protoc_insertion_point(field_release:wj.wjManagerParams.plc_ip_address)
+  clear_has_plc_ip_address();
+  return plc_ip_address_.ReleaseNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get());
+}
+inline void wjManagerParams::set_allocated_plc_ip_address(::std::string* plc_ip_address) {
+  if (plc_ip_address != NULL) {
+    set_has_plc_ip_address();
+  } else {
+    clear_has_plc_ip_address();
+  }
+  plc_ip_address_.SetAllocatedNoArena(&::wj::wjManagerParams::_default_plc_ip_address_.get(), plc_ip_address);
+  // @@protoc_insertion_point(field_set_allocated:wj.wjManagerParams.plc_ip_address)
+}
+
 // -------------------------------------------------------------------
 
 // Region

+ 57 - 0
wj_lidar/wj_lidar_conf.proto

@@ -0,0 +1,57 @@
+syntax = "proto2";
+package wj;
+
+message wjManagerParams
+{
+    repeated wjLidarParams wj_lidar=1;
+    repeated Region regions=2;
+    optional string fence_data_path=3 [default=""];
+    optional string fence_log_path=4 [default=""];
+    optional string plc_ip_address=5 [default="192.168.0.1"];
+}
+
+message Region
+{
+    required float minx=1;
+    required float maxx=2;
+    required float miny=3;
+    required float maxy=4;
+}
+
+message wjLidarParams
+{
+	optional float angle_min=1 [default=-2.35619449];
+	optional float angle_max=2 [default=2.35619449];
+	optional float angle_increment=3 [default=0.00582];
+	optional float time_increment=4 [default=0.000062];
+	optional int32 range_min=5 [default=0];
+	optional int32 range_max=6 [default=30];
+	required netConfig net_config=7;
+    required Transform2d transform=8;
+	required scanLimit scan_limit=9;
+}
+
+message netConfig
+{
+	optional string ip_address=1 [default=""];
+	optional int32 port=2 [default=8000];
+}
+
+message Transform2d
+{
+    optional float m00=1 [default=1.0];
+    optional float m01=2 [default=0.0];
+    optional float m02=3 [default=0.0];
+    optional float m10=4 [default=0.0];
+    optional float m11=5 [default=1.0];
+    optional float m12=6 [default=0.0];
+}
+
+message scanLimit
+{
+	optional float dist_limit=1 [default=8.0];
+    optional float minx=2 [default=-6];
+    optional float maxx=3 [default=-0.2];
+    optional float miny=4 [default=-3.5];
+    optional float maxy=5 [default=3.5];
+}

+ 151 - 0
wj_lidar/wj_lidar_uml.wsd

@@ -0,0 +1,151 @@
+@startuml
+
+title 电子围栏类图
+
+class async_client
+{
+    +Async_Client(boost::asio::io_service &io_service, boost::asio::ip::tcp::endpoint endpoint, fundata_t fundata_, void *p)//构造函数
+    +bool client_connection_status()//连接状态判断
+    +bool client_initialize_status()//初始化状态判断
+    +bool initialize(bool with_reconnection = true)//初始化函数
+    +bool close()//断开连接
+
+    +std::atomic<bool> mb_exit //客户端退出标志
+    -std::thread *m_connection_check_thread;// 连接状态主动检查线程
+}
+
+class wj_716_lidar_protocol
+{  
+    +Wj_716_lidar_protocol();// 构造
+    +~Wj_716_lidar_protocol();// 析构
+    +Error_manager initialize(wj::wjLidarParams params);//初始化函数
+    +Error_manager data_process(const char *data, const int reclen);// 数据处理
+    +Error_manager protocol(const char *data, const int len);// 万集通信协议
+    +Error_manager on_recv_process(char *data, int len);// 接收消息
+    +Error_manager check_xor(char *recvbuf, int recvlen);// 消息完整性检查
+    +bool get_initialize_status();// 获取初始化状态
+    +Error_manager get_scan_points(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out);// 获取扫描点云
+    +std::chrono::steady_clock::time_point get_scan_time();// 获取扫描点云更新时间点
+}
+
+class wj_lidar_encapsulation
+{
+    +Wj_lidar_encapsulation();// 无参构造函数
+    +~Wj_lidar_encapsulation();// 析构函数
+    +Error_manager initialize(wj::wjLidarParams params);// 初始化
+    +Error_manager get_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud, std::chrono::steady_clock::time_point command_time, int timeout_milli=1500);// 外部调用获取点云
+    +bool get_connection_status();// 获取连接状态
+    +bool get_initialize_status();// 获取初始化情况
+    -std::thread* m_client_thread; // 异步读取线程
+    -Async_Client* mp_client; // 异步客户端句柄
+    -Wj_716_lidar_protocol*  mp_protocol; // 万集雷达协议句柄
+}
+
+class wj_lidar_task
+{
+    +virtual Error_manager init(); // 父类继承,初始化函数
+    +Wj_lidar_Task();// 构造函数
+    +~Wj_lidar_Task();// 析构
+    +Error_manager get_command(wj_command &command);// 获取命令
+    +Error_manager set_command(wj_command command);// 设置测量命令
+    +Error_manager set_result(wj_measure_result result);// 将测量结果存入该任务单
+    +Error_manager get_result(wj_measure_result &result);// 将测量结果传出
+    +bool get_result_flag();// 获取测量结果是否已存入该任务单的指标
+}
+
+class Task_Base
+{
+    +~Task_Base();
+    +virtual Error_manager init();//初始化任务单,初始任务单类型为 UNKONW_TASK
+    +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();//获取状态说明
+}
+
+class plc_data << (S,#FF7700) Singleton >>
+{   
+    +static Plc_data *get_instance(std::string ip = "");// 获取plc通信类单例
+    +void update_data(int state_code, int border_status, int id);// 更新区域状态数据
+    +static void plc_update_thread(Plc_data *p);// plc更新线程
+    +bool get_plc_status();// 获取plc实时状态
+    -std::thread *mp_update_thread; // plc更新线程
+    -S7PLC m_plc; // S7协议句柄
+}
+
+class region_detect
+{
+    +Region_detector(int id, wj::Region region);// 有参构造函数
+    +~Region_detector();// 析构函数
+    +Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in);// 检测传入点云是否为合法四轮
+    +Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_in, double &x, double &y, double &c, double &wheelbase, double &width, bool print=true);// 检测传入点云,识别为四类返回中心点、角度、轮距与宽度
+    +int get_region_id();// 获得区域id
+    -wj::Region m_region_param; // 区域范围参数
+    -std::atomic<int> m_region_id; // 区域id
+}
+
+class region_worker
+{
+    +Region_worker(int id, wj::Region region, Verify_result* verify_handle);// 有参构造
+    +~Region_worker();// 析构函数
+    +void update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in);// 外部调用传入新点云
+    +static void detect_loop(Region_worker *worker);// 实时检测线程函数
+    +int get_id();// 获取区域id
+    +Error_manager get_wheel_result(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_in, double &x, double &y, double &c, double &wheelbase, double &width);// 获得中心点、角度等测量数据
+    -std::thread *m_detect_thread; // 实时检测线程
+    -Region_detector *m_detector; // 区域检测算法实例
+}
+
+note left of fence_controller
+    ×电子围栏主类,包括各雷达指针、区域指针以及plc指针
+    ×三个线程,更新线程负责获取各雷达点云,拼接并更新至各区域
+    ×轮距任务监听线程负责监听从nnxx获取的对特定终端区域计算任务,计算完成后的结果由发送线程以nnxx中间件发送
+    ×上述轮距计算任务也可以由主程序调用execute_task函数完成
+end note
+
+class fence_controller
+{ 
+    +Fence_controller(Verify_result* verify_handle);// 有参构造函数
+    +~Fence_controller();// 析构函数
+    +Error_manager initialize(wj::wjManagerParams params);// 初始化函数
+    +Error_manager get_current_status();// 获取当前整体状态函数
+    +Error_manager get_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out);// 外部获取点云
+    +bool get_initialize_status();// 获取初始化状态
+    +Error_manager execute_task(Task_Base* task);// 接收任务单进行阻塞式处理
+    -std::vector<Wj_lidar_encapsulation *> m_lidars_vector; // 万集雷达实例指针数组
+    -std::vector<Region_worker *> m_region_workers_vector;  // 区域功能实例指针数组
+    -Plc_data *mp_plc_data; // plc句柄
+    -std::thread *m_update_thread; // 更新线程
+    -std::thread *m_wheel_recv_thread;      // 轮距计算任务监听线程
+    -std::thread *m_wheel_send_thread;      // 轮距计算结果发送线程
+    -threadsafe_queue<MsgTask> m_msg_queue; // 轮距计算任务队列
+}
+
+class globalmsg << (M,#00FF77) message>>
+{
+
+}
+
+class wj_lidar_msg << (M,#00FF77) message>>
+{
+
+}
+
+class wj_lidar_conf << (M,#00FF77) message>>
+{
+
+}
+
+Task_Base <|-- wj_lidar_task
+wj_lidar_encapsulation <-- wj_716_lidar_protocol
+wj_lidar_encapsulation <-- async_client
+wj_716_lidar_protocol <-- wj_lidar_conf
+region_detect <-- wj_lidar_conf
+region_worker <-- region_detect
+fence_controller <-- plc_data
+fence_controller <-- wj_lidar_encapsulation
+fence_controller <-- region_worker
+fence_controller <-- wj_lidar_task
+fence_controller <-- globalmsg
+plc_data <-- wj_lidar_msg
+@enduml