Browse Source

230112 other changes

yct 2 years ago
parent
commit
4a71fe6048

+ 2 - 2
plc调度节点/dispatch/dispatch_ground_lidar.cpp

@@ -77,9 +77,9 @@ Error_manager Dispatch_ground_lidar::execute_for_ground_status_msg_new(measure_i
 	Time_tool::get_instance_references().time_end(time_key);
 	if ( Time_tool::get_instance_references().timetool_map.find(time_key)!=Time_tool::get_instance_references().timetool_map.end() )
 	{
-		if ( Time_tool::get_instance_references().timetool_map[time_key].t_time_difference >= std::chrono::milliseconds(1) )
+		if ( Time_tool::get_instance_references().timetool_map[time_key].t_time_difference >= std::chrono::milliseconds(1000) )
 		{
-			Time_tool::get_instance_references().cout_time_microsecond(time_key);
+			Time_tool::get_instance_references().cout_time_millisecond(time_key);
             double dieoutTime=(double)Time_tool::get_instance_references().timetool_map[time_key].t_time_difference.count()/1000000;
 //            std::cout << "计时器:"<<key<<" 计时的时间为:" <<dieoutTime<<" 毫秒" << std::endl;
             LOG(INFO) << "计时器:"<<time_key<<" 计时的时间为:" <<dieoutTime<<" 毫秒" << " --- " << this;

+ 3 - 3
入口单片机节点/node.py

@@ -9,9 +9,9 @@ mcpu_paramters=[
                 [1,1,"192.168.1.120",40002],
                 [1,2,"192.168.1.121",40002],
                 [2,3,"192.168.1.122",40002],
-                [2,4,"192.168.1.123",40002],
-                [3,5,"192.168.1.124",40002],
-                [3,6,"192.168.1.125",40002]
+                [2,4,"192.168.1.123",40002]#,
+             #   [3,5,"192.168.1.124",40002],
+             #   [3,6,"192.168.1.125",40002]
             ]
 
 '''

+ 71 - 0
出口单片机节点 (wk)/DatabaseSearchPickCmd.py

@@ -0,0 +1,71 @@
+import time
+import pymysql as psql
+import message_pb2 as message
+import  mysqlhelper
+class DBSeacherPickCmd():
+    def __init__(self,ip,port,database,user,password):
+        self.ip=ip
+        self.port=port
+        self.database=database
+        self.user=user
+        self.password=password
+        self._close=False
+        self._opendoor_callback=None
+        self.db = mysqlhelper.MySqLHelper()
+        # self.conn=psql.connect(host=ip,
+        #                        port=port,
+        #                        database=database,
+        #                        charset="utf8",
+        #                        user=user,
+        #                        passwd=password)
+
+    def close(self):
+        self._close=True
+        self.join()
+        # self.conn.close()
+    def search_pickcmd(self):
+        sql = "select * from command_queue where statu=2 "
+        return self.db.selectall(sql)
+
+        # self.conn.begin()
+        # cursor=self.conn.cursor()
+        # SQL="select * from command_queue where statu=2 "    #寻找已到出口的取车指令
+        # cursor.execute(SQL)
+        # pick_cmds=cursor.fetchall()
+        # self.conn.commit()
+        # cursor.close()
+
+        # return pick_cmds
+
+    def delete_cmd(self,id):
+        sql = "delete from command_queue where statu=2 and export_id=%s"
+        return self.db.delete(sql,id)
+
+        # self.conn.begin()
+        # cursor=self.conn.cursor()
+        # SQL="delete from command_queue where statu=2 and export_id=%d"%id
+        # cursor.execute(SQL)
+        # self.conn.commit()
+        # cursor.close()
+
+'''
+    def run(self):
+        while self._close==False:
+            cmds=self.search_pickcmd()
+            
+            for cmd in cmds:
+                if len(cmd)>=9:
+                    table=message.pick_table()
+                    table.car_number=cmd[0]
+                    table.primary_key=cmd[1]
+                    table.unit=cmd[2]
+                    table.queue_id=cmd[3]
+                    table.type=cmd[4]
+                    table.statu=cmd[5]
+                    table.export_id=cmd[8]
+                    if not table.export_id==None:
+                        self._opendoor_callback(table.export_id,table)
+
+            time.sleep(1)
+
+'''

+ 201 - 0
出口单片机节点 (wk)/ExportIO.py

@@ -0,0 +1,201 @@
+
+import json
+import message_pb2 as message
+import google.protobuf.text_format as tf
+import queue
+import time
+import asyncio
+import async_communication as ASC
+import threading
+'''
+单片机状态,2表示门已经关闭
+'''
+
+class ExportIO(threading.Thread):
+    def __init__(self,parameter,rabbitmq_parameter):
+        threading.Thread.__init__(self)
+        self._unit,self._id,self._ip,self._port=parameter
+        self._close=False
+        self._latest_iomsg=None
+        self._last_user_table = None
+
+        self._send_queue=queue.Queue()
+
+        self._last_statucall_time=time.time()
+        self._user_leave_callback=None
+        self._last_table=None
+
+        self._open_door_flag = False
+
+
+        self._rabbit_mq=ASC.RabbitAsyncCommunicator(rabbitmq_parameter["ip"],rabbitmq_parameter["port"],
+                                                    rabbitmq_parameter['user'],rabbitmq_parameter['password'])
+
+        #消费关门消息
+        self._rabbit_mq.Init(None, None)
+        self._rabbit_mq.start()
+
+        #数据库重试的次数, 超过3次就重启数据库梁
+        self._retry_count = 0
+
+
+
+    def SetUserLeaveCallback(self,callback):
+        self._user_leave_callback=callback
+
+    def close(self):
+        self._close=True
+        self._rabbit_mq.close()
+        self.join()
+
+    def export_idle(self):
+        if self._latest_iomsg==None:
+            return False
+        else:
+            return self._latest_iomsg.outside_safety==1
+
+    #open_door 函数,负责修改开门任务标记,只要数据库查到了,就把_open_door_flag修改为true
+    #open_door 函数被node_py的主函数调用,不要做太多的事,剩余的开门控制和数据库清理,交给open_door_loop
+    def open_door(self,table):
+        self._open_door_flag = True
+        
+        return
+
+    async def open_door_loop(self):
+        while self._close==False:
+            try:
+                if (self._latest_iomsg is not None) and self._open_door_flag == True:
+                    #门不是开状态,那么就发送开门,无论里面是否有车
+                    if self._latest_iomsg.door_statu != 2:
+                        print(" 出口编号:%d , 执行开门  " % (self._id))
+                        opencmd = "{\"TerminalID\": %d, \"DispatchDirection\": 2, \"OutPutDo\": {\"Do0\": 0, \"Do1\": 0, \"Do2\": 0,\"Do3\": 0,\"Do4\": 0, \"Do5\": 0, \"Do6\": 0, \"Do7\": 0}, \"ProcessControl\": 4}" % (
+                                    self._id - 1)
+                        print(opencmd)
+                        self._send_queue.put(opencmd)
+                        print(" opendoor queue size:%d"%self._send_queue.qsize())
+                        await asyncio.sleep(3)
+                    #如果门开到位,则检查汽车是否离开,如果没车就删库,清除flag, 注意了, 在汽车离开3秒后,由单片机底层自动关门,我们不用管
+                    elif self._latest_iomsg.outside_safety == 1:
+                        if not self._user_leave_callback == None:
+                            self._user_leave_callback(self._id)
+                            self._open_door_flag = False
+                            self._retry_count = self._retry_count + 1
+                            print(" _retry_count = %d"%self._retry_count)
+                    else:#else  无限等待,什么也不做,  等待汽车离开
+                        self._retry_count = 0
+
+            except:
+                pass
+            await asyncio.sleep(0)
+
+
+    async def connect(self):
+        print("Trying to connect {}:{}".format(self._ip, self._port))
+        while self._close == False:
+            try:
+                reader, writer = await asyncio.open_connection(
+                    self._ip, self._port
+                )
+                break
+            except Exception as e:
+                print("Failed to connect {} {}: {}".format(self._ip, self._port, e))
+                await asyncio.sleep(3)
+        print("Connected to {}:{}".format(self._ip, self._port))
+        return reader, writer
+    async def recv_loop(self):
+    #    if (self._id == 5):
+    #        print(" test 1 ")
+        while self._close==False:
+     #       if (self._id == 5):
+     #           print(" test 2 ")
+            try:
+                recieve=await self._reader.readuntil(b'$')
+                if (self._id == 5):
+                    print(" 00 recieve = " + str(recieve))
+            except Exception as e:
+                print("self._reader.readuntil(b'$') error")
+                print("  e: {}".format(e))
+                self._reader,self._writer=await self.connect()
+                await asyncio.sleep(0.001)
+                continue
+                #socket.ConnectionResetError:
+            # print(recieve)
+
+            start_index = recieve.find(b'@')
+            end_index = recieve.find(b'$')
+            if start_index >= 0 and end_index >= 0 and end_index >=start_index:
+                bytes = recieve[start_index + 4:end_index]
+                self._latest_iomsg =self.recieve2message(bytes)
+                if (not self._rabbit_mq == None) and (not self._latest_iomsg == None):
+                    if self._latest_iomsg.outside_safety == 0 or self._latest_iomsg.door_statu == 0:
+                        print("self._latest_iomsg error")
+                        continue
+                    else:
+                        if (self._id == 5):
+                            print(" 11 recieve = " + str(recieve))
+                        ex_name = "statu_ex"
+                        key = "out_mcpu_%d_statu_port" % self._id
+                        self._rabbit_mq.publish(ex_name, key, tf.MessageToString(self._latest_iomsg, as_utf8=True))
+                else:
+                    print("self._rabbit_mq")
+                    print(self._rabbit_mq)
+                    print("self._latest_iomsg")
+                    print(self._latest_iomsg)
+            else:
+                print(" start_index = %s"%start_index)
+                print("end_index = %s"%end_index)
+                print("WARNING : mcpu recieve format error , time = %s"%time.time())
+                print(" 22 recieve = " + str(recieve))
+                await asyncio.sleep(0)
+
+                continue
+
+            await asyncio.sleep(0)
+
+    async def send_loop(self):
+        while self._close == False:
+            try:
+                if self._send_queue.qsize() > 0:
+                    print("给单片机发送指令 size:%d" % self._send_queue.qsize())
+                    msg = self._send_queue.get(False)
+                    if not msg == None:
+                        self._writer.write(msg.encode())
+                        await self._writer.drain()
+            except Exception as e:
+                print(" send error :{}".format(e))
+                self._reader, self._writer = await self.connect()
+            await asyncio.sleep(0)
+            time.sleep(0.001)
+    async def main(self):
+        self._reader,self._writer=await self.connect()
+        await asyncio.gather(self.recv_loop(),self.send_loop(),self.open_door_loop())
+    def run(self):
+        asyncio.run(self.main())
+
+    def recieve2message(self,bytes):
+        try:
+            data=json.loads(bytes)
+        except:
+            print("tf json load error  ")
+            return None
+        statu_msg=message.out_mcpu_statu()
+
+        if 'InsideExistenceFlag' in data.keys():
+            statu_msg.outside_safety = data['InsideExistenceFlag'] + 1
+        else:
+            print("statu_msg.outside_safety not live")
+            print(bytes)
+            statu_msg.outside_safety = 0
+
+        if 'OutsideDoorStatus' in data.keys():
+            statu_msg.door_statu = data["OutsideDoorStatus"] + 1  # 1 k  2g 3 running
+        else:
+            print("statu_msg.door_statu not live ")
+            print(bytes)
+            statu_msg.door_statu = 0
+
+        return statu_msg
+
+
+
+

+ 59 - 0
出口单片机节点 (wk)/README.md

@@ -0,0 +1,59 @@
+# 1,功能描述
+    1,发送自身io状态,发送端口:out_mcpu_N_statu_port
+
+    2,根据调度完成消息执行开门动作
+        数据库存在状态为2 的指令,且雷达检测到有信号,执行开门
+    3,车辆开走后,门自动关闭后,删除对应指令
+        门自动关后, 数据库队列表存在该出口的指令,且指令状态为2(已到出口),
+        且雷达检测到无信号,删除指令
+    
+# 2,使用平台:
+    linux x64 / linux-arm
+# 3,业务逻辑
+    出口单片机发送数据格式:前四位为头(@501),后三位为尾($\0\0),中间为json格式消息体
+    
+    楚天出入口单片机通信协议_jansson
+
+    一、楚天项目出入口传感器设备由单片机控制,负责采集光电开关,出口雷达,内门控制等。
+
+    二、单片机使用tcp通信,jansson协议。
+    单片机:TCP server
+    ip:192,168,1, (120+(DISPATCH_DIRECTION-1)*10+TERMINAL_ID
+    DISPATCH_DIRECTION:入口为1, 出口为2。
+    TERMINAL_ID:0~5分别对应0~5的出入口编号。
+    例如,A1入口:192.168.1.120B2出口:192.168.1.133
+    端口:默认40000(40000~40007都行,8个端口可以连接8个client)
+    上位机:TCP client
+    ip:192.168.1.xxx   (须相同网段)
+
+    三、jansson协议模板
+    例如:B1出口
+    单片机-》上位机
+    {"TerminalID": 2, "ProcessControl": 0, "CarHeightStatusPassing": 0, "OutsideDoorStatus": 3, 
+    "DispatchDirection": 2, "InPutDi": {"Di0": 0, "Di4": 0, "Di1": 0, "Di5": 0, "Di9": 0, 
+    "Di2": 0, "Di3": 0, "Di6": 0, "Di7": 0, "Di8": 0, "Di10": 0, "Di12": 0, "Di11": 0, "Di13": 0,
+    "Di14": 0, "Di15": 0}, "OutsideExistenceFlag": 1, "InsideExistenceFlag": 1, 
+    "OverBorderStatus": 1, "DispatchFinishFlag": 0, "ProcessStatus": 40, 
+    "CarHeightStatusCurrent": 0, "OutsideDoorControl": 0, "ResetFlag": 0, "StopFlag": 0}
+
+    上位机-》单片机
+    {"TerminalID": 2, "DispatchDirection": 2, "OutPutDo": {"Do0": 0, "Do1": 0, "Do2": 0, 
+    "Do3": 0,"Do4": 0, "Do5": 0, "Do6": 0, "Do7": 0}, "ProcessControl": 0}
+
+    四、jansson协议解释
+    TerminalID:0~5分别对应0~5的出入口编号。
+    DispatchDirection:入口为1, 出口为2。
+    OutsideExistenceFlag:出口是否有障碍物,1有0无
+    ProcessControl:
+    PROCESS_CONTROL_UNKNOWN= 0,//未知
+    PROCESS_CONTROL_FULL_AUTO= 1,//全自动,
+    PROCESS_CONTROL_MANUAL= 2,//手动
+    PROCESS_CONTROL_AUTO_CLOSE= 3,//半自动关门
+    PROCESS_CONTROL_AUTO_OPEN= 4,//半自动开门
+    PROCESS_CONTROL_TO_READY= 5,//切换到待机
+    入口需要上位机控制关门,那么 "ProcessControl": 3
+    出口需要上位机控制开门,那么 "ProcessControl": 4
+    特殊情况下可以手动设置8个输出量, "ProcessControl": 2
+
+# 4,编译
+# 5,部署

+ 132 - 0
出口单片机节点 (wk)/async_communication.py

@@ -0,0 +1,132 @@
+import threading
+import time
+import asyncio
+import aio_pika
+import queue
+
+class TimeStatu:
+    def __init__(self,statu=None,timeout=3):
+        self.statu=statu
+        self.time=time.time()
+        self.timeout_ms=timeout
+
+    def timeout(self):
+        tm=time.time()
+        return tm-self.time>self.timeout_ms
+
+class RabbitAsyncCommunicator(threading.Thread):
+    def __init__(self, host,port, user, password):
+        threading.Thread.__init__(self)
+        self._host = host
+        self._port=port
+        self._user = user
+        self._password = password
+        self._connection = None
+        self._channel_consumer = None
+        self._channel_send = None
+        self._channel_statu = None
+
+        self._consumer_callbacks= None
+        self._recv_status=None
+        self._queue_callbacks= {}
+        self._publish_msg_queue=queue.Queue()
+        self._status={}
+        self._statu_callbacks={}
+        self._closing = False
+
+    def Init(self,consumer_callbacks,recv_status):
+        self._consumer_callbacks=consumer_callbacks
+        self._recv_status=recv_status
+        if self._recv_status==None:
+            return
+        for ex_name,key in self._recv_status:
+            self._status[ex_name+":"+key]=TimeStatu(None,0.1)
+
+    def publish(self,ex_name,key,msg):
+        self._publish_msg_queue.put([ex_name,key,msg])
+
+    def bind_statu_callback(self,ex_name,key,callback):
+        self._statu_callbacks[ex_name+":"+key]=callback
+
+    def close(self):
+        self._closing=True
+
+    async def init(self):
+        connection_string="amqp://%s:%s@%s/"%(self._user,self._password,self._host)
+        self._connection = await aio_pika.connect_robust(connection_string)
+        self._channel_consumer = await self._connection.channel()
+        self._channel_send = await self._connection.channel()
+        self._channel_statu = await self._connection.channel()
+        # Will take no more than 10 messages in advance
+        await self._channel_consumer.set_qos(prefetch_count=1)
+        if self._consumer_callbacks==None:
+            return
+        for queue_name,callback in self._consumer_callbacks:
+            queue= await self._channel_consumer.get_queue(queue_name)
+            self._queue_callbacks[queue]=callback
+
+
+    def statu_callback(self,ex,key,msg):
+        id=ex+":"+key
+        self._status[id]=TimeStatu(msg)
+        callback=self._statu_callbacks.get(id)
+        if not callback==None:
+            callback(self._status[id])
+
+    def __getitem__(self, key):
+        return self._status[key]
+    def __setitem__(self, key, value):
+        self._status[key]=value
+
+    async def recv(self,queue,callback):
+        async with queue.iterator() as queue_iter:
+            async for message in queue_iter:
+                if not callback==None:
+                    callback(message.body.decode())
+                    await message.ack()
+                if self._closing==True:
+                    return
+    async def recv_statu(self,ex_name,key,ttl=1000):
+        statu_ex=await self._channel_statu.get_exchange(ex_name)
+        arg={}
+        arg["x-message-ttl"]=ttl
+        queue=await self._channel_statu.declare_queue("", auto_delete=True,arguments=arg)
+        await queue.bind(statu_ex,routing_key=key)
+        async with queue.iterator() as queue_iter:
+            async for message in queue_iter:
+                async with message.process():
+                    self.statu_callback(ex_name,key,message.body.decode())
+                if self._closing==True:
+                    return
+
+    async def send(self):
+        ex_map={}
+        while self._closing==False:
+            if self._publish_msg_queue.qsize()>0:
+                try:
+                    msg_bag = self._publish_msg_queue.get(False)
+                    if not msg_bag == None:
+                        ex_name, key, msg = msg_bag
+                        ex=ex_map.get(ex_name)
+                        if ex == None:
+                            ex = await self._channel_send.get_exchange(ex_name)
+                            ex_map[ex_name]=ex
+                        await ex.publish(aio_pika.Message(body=msg.encode()), routing_key=key)
+
+                except:
+                    await asyncio.sleep(1)
+            await asyncio.sleep(0)
+            time.sleep(0.001)
+    async def main(self):
+        await self.init()
+        tasks=[]
+        tasks.append(self.send())
+        if not self._consumer_callbacks==None:
+            for queue,callback in self._queue_callbacks.items():
+                tasks.append(self.recv(queue,callback))
+        if not self._recv_status==None:
+            for ex_name,key in self._recv_status:
+                tasks.append(self.recv_statu(ex_name,key))
+        await asyncio.gather(*tasks)
+    def run(self):
+        asyncio.run(self.main())

+ 44 - 0
出口单片机节点 (wk)/db_config.py

@@ -0,0 +1,44 @@
+#!/usr/bin/env python
+# -*- coding:utf-8 -*-
+# author:SunXiuWen
+# make_time:2019/1/13
+# -*- coding: UTF-8 -*-
+import pymysql
+
+# 数据库信息
+DB_TEST_HOST = "192.168.1.233"
+# DB_TEST_HOST = "127.0.0.1"
+
+DB_TEST_PORT = 3306
+DB_TEST_DBNAME = "ct_project"
+DB_TEST_USER = "zx"
+DB_TEST_PASSWORD = "zx123456"
+# DB_TEST_USER = "root"
+# DB_TEST_PASSWORD = "123456"
+# 数据库连接编码
+DB_CHARSET = "utf8"
+
+# mincached : 启动时开启的闲置连接数量(缺省值 0 开始时不创建连接)
+DB_MIN_CACHED = 10
+
+# maxcached : 连接池中允许的闲置的最多连接数量(缺省值 0 代表不闲置连接池大小)
+DB_MAX_CACHED = 10
+
+# maxshared : 共享连接数允许的最大数量(缺省值 0 代表所有连接都是专用的)如果达到了最大数量,被请求为共享的连接将会被共享使用
+DB_MAX_SHARED = 20
+
+# maxconnecyions : 创建连接池的最大数量(缺省值 0 代表不限制)
+DB_MAX_CONNECYIONS = 100
+
+# blocking : 设置在连接池达到最大数量时的行为(缺省值 0 或 False 代表返回一个错误<toMany......> 其他代表阻塞直到连接数减少,连接被分配)
+DB_BLOCKING = True
+
+# maxusage : 单个连接的最大允许复用次数(缺省值 0 或 False 代表不限制的复用).当达到最大数时,连接会自动重新连接(关闭和重新打开)
+DB_MAX_USAGE = 0
+
+# setsession : 一个可选的SQL命令列表用于准备每个会话,如["set datestyle to german", ...]
+DB_SET_SESSION = None
+
+# creator : 使用连接数据库的模块
+DB_CREATOR = pymysql
+

File diff suppressed because it is too large
+ 718 - 0
出口单片机节点 (wk)/message_pb2.py


+ 185 - 0
出口单片机节点 (wk)/mysqlhelper.py

@@ -0,0 +1,185 @@
+#!/usr/bin/env python
+# -*- coding:utf-8 -*-
+# author:SunXiuWen
+# make_time:2019/1/13
+import pymysql
+from DBUtils.PooledDB import PooledDB
+import db_config as config
+
+"""
+@功能:创建数据库连接池
+"""
+
+class MyConnectionPool(object):
+    __pool = None
+
+    # 创建数据库连接conn和游标cursor
+    def __enter__(self):
+        self.conn = self.__getconn()
+        self.cursor = self.conn.cursor()
+
+    # 创建数据库连接池
+    def __getconn(self):
+        if self.__pool is None:
+            self.__pool = PooledDB(
+                creator=config.DB_CREATOR,
+                mincached=config.DB_MIN_CACHED,
+                maxcached=config.DB_MAX_CACHED,
+                maxshared=config.DB_MAX_SHARED,
+                maxconnections=config.DB_MAX_CONNECYIONS,
+                blocking=config.DB_BLOCKING,
+                maxusage=config.DB_MAX_USAGE,
+                setsession=config.DB_SET_SESSION,
+                host=config.DB_TEST_HOST,
+                port=config.DB_TEST_PORT,
+                user=config.DB_TEST_USER,
+                passwd=config.DB_TEST_PASSWORD,
+                db=config.DB_TEST_DBNAME,
+                use_unicode=True,
+                charset=config.DB_CHARSET
+            )
+        return self.__pool.connection()
+
+    # 释放连接池资源
+    def __exit__(self, exc_type, exc_val, exc_tb):
+        self.cursor.close()
+        self.conn.close()
+
+    # 从连接池中取出一个连接
+    def getconn(self):
+        conn = self.__getconn()
+        cursor = conn.cursor(cursor=pymysql.cursors.DictCursor)
+        return cursor, conn
+
+
+"""执行语句查询有结果返回结果没有返回0;增/删/改返回变更数据条数,没有返回0"""
+
+
+
+class MySqLHelper(object):
+    def __init__(self):
+        self.db = MyConnectionPool()  # 从数据池中获取连接
+
+    def __new__(cls, *args, **kwargs):
+        if not hasattr(cls, 'inst'):  # 单例
+            cls.inst = super(MySqLHelper, cls).__new__(cls, *args, **kwargs)
+        return cls.inst
+
+    # 封装执行命令
+    def execute(self, sql, param=None, autoclose=False):
+        """
+        【主要判断是否有参数和是否执行完就释放连接】
+        :param sql: 字符串类型,sql语句
+        :param param: sql语句中要替换的参数"select %s from tab where id=%s" 其中的%s就是参数
+        :param autoclose: 是否关闭连接
+        :return: 返回连接conn和游标cursor
+        """
+        cursor, conn = self.db.getconn()  # 从连接池获取连接
+        count = 0
+        try:
+            # count : 为改变的数据条数
+            if param:
+                count = cursor.execute(sql, param)
+            else:
+                count = cursor.execute(sql)
+            conn.commit()
+            if autoclose:
+                self.close(cursor, conn)
+        except Exception as e:
+            print("db error_msg:", e.args)
+        return cursor, conn, count
+
+    # 释放连接
+    def close(self, cursor, conn):
+        """释放连接归还给连接池"""
+        cursor.close()
+        conn.close()
+
+    # 查询所有
+    def selectall(self, sql, param=None):
+        try:
+            cursor, conn, count = self.execute(sql, param)
+            res = cursor.fetchall()
+            return res
+        except Exception as e:
+            print("db error_msg:", e.args)
+            self.close(cursor, conn)
+            return count
+
+    # 查询单条
+    def selectone(self, sql, param=None):
+        try:
+            cursor, conn, count = self.execute(sql, param)
+            res = cursor.fetchone()
+            self.close(cursor, conn)
+            return res
+        except Exception as e:
+            print("db error_msg:", e.args)
+            self.close(cursor, conn)
+            return count
+
+    # 增加
+    def insertone(self, sql, param):
+        try:
+            cursor, conn, count = self.execute(sql, param)
+            conn.commit()
+            self.close(cursor, conn)
+            return count
+        except Exception as e:
+            print("db error_msg:", e.args)
+            conn.rollback()
+            self.close(cursor, conn)
+            return count
+
+    # 删除
+    def delete(self, sql, param=None):
+        try:
+            cursor, conn, count = self.execute(sql, param)
+            conn.commit()
+            self.close(cursor, conn)
+            return count
+        except Exception as e:
+            print("db error_msg:", e.args)
+            conn.rollback()
+            self.close(cursor, conn)
+            return count
+
+    # 修改
+    def update(self, sql, param=None):
+        try:
+            cursor, conn, count = self.execute(sql, param)
+            conn.commit()
+            self.close(cursor, conn)
+            return count
+        except Exception as e:
+            print("db error_msg:", e.args)
+            conn.rollback()
+            self.close(cursor, conn)
+            return count
+
+
+if __name__ == '__main__':
+    db = MySqLHelper()
+    # 查询单条
+    sql1 = 'select * from space where unit=%s'
+    args = '2'
+    ret = db.selectone(sql=sql1, param=args)
+    print(ret)  # (79, 2, 1, 2.2, None, 2, 1)
+    #查询所有
+    sql2 = "select * from space"
+    ret = db.selectall(sql=sql2)
+    print(ret)
+    # 增加
+    sql3 = 'insert into vehicle (car_number,primary_key) VALUES (%s,%s)'
+    ret = db.insertone(sql3, ('鄂A6X3B0','DASDASDEFDFSDASDADASDAS'))
+    print(ret)
+    # 删除
+    sql4 = 'delete from vehicle WHERE car_number=%s'
+    args = '鄂A6X3B0'
+    ret = db.delete(sql4, args)
+    print(ret)
+    # 修改
+    sql5 = 'update command_queue set export_id=%s WHERE car_number LIKE %s'
+    args = ('100', 'WK0001')
+    ret = db.update(sql5, args)
+    print(ret)

+ 78 - 0
出口单片机节点 (wk)/node.py

@@ -0,0 +1,78 @@
+import time
+import asyncio
+import async_communication as ASC
+import  ExportIO as EIO
+import google.protobuf.text_format as tf
+import threading
+import DatabaseSearchPickCmd as DBS
+import message_pb2 as message
+import queue
+#db参数
+db_parameter={"dbname":"ct_project","ip":"192.168.1.233","port":3306,"user":"zx","password":"zx123456"}
+
+rabbitmq_parameter={"ip":"192.168.1.233","port":5672,"user":"zx","password":"zx123456"}
+
+#[单元号,出口号,单片机ip,port]
+mcpu_paramters=[[1,1, "192.168.1.130", 40004],
+                [2,2, "192.168.1.131", 40004],
+                [2,3, "192.168.1.132", 40004],
+                [2,4, "192.168.1.133", 40004]#,
+        #        [3,5,"192.168.1.134",40004],
+         #       [3,6,"192.168.1.135",40004]
+                ]
+
+# mcpu_paramters=[[2,3,"192.168.1.132",40004]]
+
+g_rabbitmq=ASC.RabbitAsyncCommunicator(rabbitmq_parameter["ip"],rabbitmq_parameter["port"],
+                                       rabbitmq_parameter['user'],rabbitmq_parameter['password'])
+g_db=DBS.DBSeacherPickCmd(db_parameter["ip"],db_parameter["port"],db_parameter["dbname"],
+                        db_parameter["user"],db_parameter["password"])
+g_exports={}
+
+
+def user_leave_callback(id):
+    print("出口:%d 用户已经离开,删除出口取车指令"%(id))
+    g_db.delete_cmd(id)
+
+
+if __name__=="__main__":
+    print("出口 danpianji")
+
+    for parameter in mcpu_paramters:
+        id=parameter[1]
+        if not g_exports.get(id)==None:
+            raise("出口单片机id重复")
+        g_exports[id]=EIO.ExportIO(parameter,rabbitmq_parameter)
+        g_exports[id].SetUserLeaveCallback(user_leave_callback)
+
+    for _,export in g_exports.items():
+        export.start()
+
+    while True:
+        pickcmds=g_db.search_pickcmd()
+        # print(pickcmds)
+        if len(pickcmds)>0:
+            for cmd in pickcmds:
+                table=message.pick_table()
+                # table.car_number=cmd[0]
+                # table.primary_key=cmd[1]
+                # table.unit_id=cmd[2]
+                # table.queue_id=cmd[3]
+                # table.export_id=cmd[8]
+                table.car_number=cmd["car_number"]
+                table.primary_key=cmd["primary_key"]
+                table.unit_id=cmd["unit"]
+                table.queue_id=cmd["queue_id"]
+                table.export_id=cmd["export_id"]
+                # print(table)
+                if not table.export_id==None:
+                    export=g_exports.get(table.export_id)
+                    if not export==None:
+                        # if export.export_idle()==False:
+                        export.open_door(table)
+
+        time.sleep(1)
+
+    for _,export in g_exports.items():
+        export.join()
+

+ 1 - 0
出口单片机节点 (wk)/proto.sh

@@ -0,0 +1 @@
+protoc -I=../ --python_out=./ ../message.proto

+ 2 - 2
指令入队节点/PushCommand.py

@@ -190,9 +190,9 @@ class DBCommand():
                     time_mns=diff.total_seconds()/60
                     queue_id=int(last_num+1+ time_mns*1)
 
-                SQL="insert into command_queue values('%s','%s',%d,%d,1,0,NULL,'%s',NULL, NULL)"%(
+                SQL="insert into command_queue values('%s','%s',%d,%d,1,0,NULL,'%s', %d , NULL)"%(
                     cmd.car_number,cmd.primary_key,cmd.unit_id,queue_id
-                    ,tf.MessageToString(cmd.entrance_measure_info,as_utf8=True) )
+                    ,tf.MessageToString(cmd.entrance_measure_info,as_utf8=True), cmd.terminal_id )
                 cursor.execute(SQL)
                 #更新指令时间表,
                 dt=datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S")

+ 6 - 2
指令检查节点/CheckEntrance.py

@@ -47,7 +47,7 @@ class EntranceChecker(threading.Thread):
             return tf.MessageToString(park, as_utf8=True)     
         tm = time.time()
         if self.error_str == 'OK':
-            while time.time() - tm < 0.5:
+            while time.time() - tm < 1:
                 if measure_info.border_statu == MeasureStatu["ok"] and measure_info.ground_status == 0:
                     park.statu.execute_statu = message.eNormal
                     park.statu.statu_description = self.error_str
@@ -61,11 +61,15 @@ class EntranceChecker(threading.Thread):
                     elif im_mcpu_statu.heighth == 4:
                         park.entrance_measure_info.height = 1.90
                     return tf.MessageToString(park, as_utf8=True)
-                time.sleep(0.1)
+                else:
+                    tf.Parse(self.measure_statu.statu, measure_info)
+                time.sleep(0.05)
+            print(measure_info)
             park.statu.execute_statu = message.eError
             park.statu.statu_description = "请检查入口处是否有人员逗留!"
             return tf.MessageToString(park, as_utf8=True)
         else:
+            print(measure_info)
             park.statu.execute_statu = message.eError
             park.statu.statu_description = self.error_str
             return tf.MessageToString(park, as_utf8=True)

+ 7 - 1
测量节点/velodyne_lidar/ground_region.cpp

@@ -430,7 +430,7 @@ Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, d
     {
         last_result.cx = car_pose_x;
         last_result.cy = car_pose_y;
-        last_result.theta = 90 - car_pose_theta * 180.0 / M_PI;
+        last_result.theta = - car_pose_theta * 180.0 / M_PI;
         return Error_manager(VELODYNE_REGION_ANGLE_PRECHECK_FAILED, NEGLIGIBLE_ERROR, "find general car pose value failed.");
     }
     // LOG_IF(INFO, m_region.region_id() == 0) << "car pose :::: cx: " << car_pose_x+m_region.plc_offsetx() << ", cy: " << car_pose_y+m_region.plc_offsety() << ", theta: " << car_pose_theta*180.0/M_PI << std::endl;
@@ -1116,6 +1116,12 @@ void Ground_region::thread_measure_func()
                 m_car_wheel_information.single_wheel_width = 0.0;
                 m_car_wheel_information.single_wheel_length = 0.0;
 
+                // 添加plc偏移
+                m_car_wheel_information.car_center_x += m_region.plc_offsetx();
+                m_car_wheel_information.car_center_y += m_region.plc_offsety();
+                m_car_wheel_information.uniform_car_x += m_region.plc_offsetx();
+                m_car_wheel_information.uniform_car_y += m_region.plc_offsety();
+
                 m_car_wheel_information.theta_uniform(m_region.turnplate_cx(), m_region.turnplate_cy());
                 m_car_wheel_information.range_status |= m_car_wheel_information.car_angle<0?Range_status::Range_angle_clock:Range_status::Range_angle_anti_clock;
             }