quality: run and fix pylint check

This commit is contained in:
2022-10-20 15:05:23 +02:00
committed by Cyrille Nofficial
parent fa4c7eef03
commit c3396b13ac
5 changed files with 925 additions and 33 deletions

View File

@ -1,27 +1,36 @@
"""
Mqtt gateway for oak-lite device
"""
import argparse
import logging
import os
from . import depthai as cam
import paho.mqtt.client as mqtt
import argparse
from . import depthai as cam
logger = logging.getLogger(__name__)
logging.basicConfig(level=logging.INFO)
default_client_id = "robocar-depthai"
_DEFAULT_CLIENT_ID = "robocar-depthai"
def init_mqtt_client(broker_host: str, broker_port, user: str, password: str, client_id: str) -> mqtt.Client:
def _init_mqtt_client(broker_host: str, broker_port, user: str, password: str, client_id: str) -> mqtt.Client:
logger.info("Start part.py-robocar-oak-camera")
client = mqtt.Client(client_id=client_id, clean_session=True, userdata=None, protocol=mqtt.MQTTv311)
client.username_pw_set(user, password)
logger.info("Connect to mqtt broker "+ broker_host)
logger.info("Connect to mqtt broker %s", broker_host)
client.connect(host=broker_host, port=broker_port, keepalive=60)
logger.info("Connected to mqtt broker")
return client
def execute_from_command_line():
def execute_from_command_line() -> None:
"""
Cli entrypoint
:return:
"""
logging.basicConfig(level=logging.INFO)
parser = argparse.ArgumentParser()
@ -40,10 +49,10 @@ def execute_from_command_line():
default=_get_env_int_value("MQTT_BROKER_PORT", 1883))
parser.add_argument("-C", "--mqtt-client-id",
help="MQTT client id",
default=_get_env_value("MQTT_CLIENT_ID", default_client_id))
default=_get_env_value("MQTT_CLIENT_ID", _DEFAULT_CLIENT_ID))
parser.add_argument("-c", "--mqtt-topic-robocar-oak-camera",
help="MQTT topic where to publish robocar-oak-camera frames",
default=_get_env_value("MQTT_TOPIC_CAMERA","/oak/camera_rgb"))
default=_get_env_value("MQTT_TOPIC_CAMERA", "/oak/camera_rgb"))
parser.add_argument("-o", "---mqtt-topic-robocar-objects",
help="MQTT topic where to publish objects detection results",
default=_get_env_value("MQTT_TOPIC_OBJECTS", "/objects"))
@ -60,12 +69,12 @@ def execute_from_command_line():
args = parser.parse_args()
client = init_mqtt_client(broker_host=args.mqtt_broker_host,
broker_port=args.mqtt_broker_port,
user=args.mqtt_username,
password=args.mqtt_password,
client_id=args.mqtt_client_id,
)
client = _init_mqtt_client(broker_host=args.mqtt_broker_host,
broker_port=args.mqtt_broker_port,
user=args.mqtt_username,
password=args.mqtt_password,
client_id=args.mqtt_client_id,
)
frame_processor = cam.FramePublisher(mqtt_client=client,
frame_topic=args.mqtt_topic_robocar_oak_camera,
objects_topic=args.mqtt_topic_robocar_objects,

View File

@ -1,13 +1,16 @@
"""
Camera event loop
"""
import datetime
import logging
import cv2
import depthai as dai
import numpy as np
import paho.mqtt.client as mqtt
import events.events_pb2
import depthai as dai
import cv2
import numpy as np
logger = logging.getLogger(__name__)
NN_PATH = "/models/mobile_object_localizer_192x192_openvino_2021.4_6shave.blob"
@ -16,6 +19,10 @@ NN_HEIGHT = 192
class FramePublisher:
"""
Camera controller that publish events from camera
"""
def __init__(self, mqtt_client: mqtt.Client, frame_topic: str, objects_topic: str, objects_threshold: float,
img_width: int, img_height: int):
self._mqtt_client = mqtt_client
@ -25,6 +32,7 @@ class FramePublisher:
self._img_width = img_width
self._img_height = img_height
self._pipeline = self._configure_pipeline()
self._stop = False
def _configure_pipeline(self) -> dai.Pipeline:
logger.info("configure pipeline")
@ -53,7 +61,6 @@ class FramePublisher:
xout_rgb = pipeline.create(dai.node.XLinkOut)
xout_rgb.setStreamName("rgb")
# Properties
cam_rgb.setBoardSocket(dai.CameraBoardSocket.RGB)
cam_rgb.setPreviewSize(width=self._img_width, height=self._img_height)
@ -72,7 +79,11 @@ class FramePublisher:
logger.info("pipeline configured")
return pipeline
def run(self):
def run(self) -> None:
"""
Start event loop
:return:
"""
# Connect to device and start pipeline
with dai.Device(self._pipeline) as device:
logger.info('MxId: %s', device.getDeviceInfo().getMxId())
@ -87,12 +98,15 @@ class FramePublisher:
q_rgb = device.getOutputQueue(name="rgb", maxSize=queue_size, blocking=False)
q_nn = device.getOutputQueue(name="nn", maxSize=queue_size, blocking=False)
self._stop = False
while True:
if self._stop:
return
try:
logger.debug("wait for new frame")
inRgb = q_rgb.get() # blocking call, will wait until a new data has arrived
in_rgb = q_rgb.get() # blocking call, will wait until a new data has arrived
im_resize = inRgb.getCvFrame()
im_resize = in_rgb.getCvFrame()
is_success, im_buf_arr = cv2.imencode(".jpg", im_resize)
byte_im = im_buf_arr.tobytes()
@ -127,14 +141,14 @@ class FramePublisher:
for i in range(boxes.shape[0]):
bbox = boxes[i]
logger.debug("new object detected: %s", str(bbox))
o = events.events_pb2.Object()
o.type = events.events_pb2.TypeObject.ANY
o.top = bbox[0].astype(float)
o.right = bbox[3].astype(float)
o.bottom = bbox[2].astype(float)
o.left = bbox[1].astype(float)
o.confidence = scores[i].astype(float)
objs.append(o)
obj = events.events_pb2.Object()
obj.type = events.events_pb2.TypeObject.ANY
obj.top = bbox[0].astype(float)
obj.right = bbox[3].astype(float)
obj.bottom = bbox[2].astype(float)
obj.left = bbox[1].astype(float)
obj.confidence = scores[i].astype(float)
objs.append(obj)
objects_msg.objects.extend(objs)
objects_msg.frame_ref.name = frame_msg.id.name
@ -147,5 +161,13 @@ class FramePublisher:
qos=0,
retain=False)
except Exception as e:
logger.exception("unexpected error: %s", str(e))
# pylint: disable=broad-except # bad frame or event must not stop loop
except Exception as excpt:
logger.exception("unexpected error: %s", str(excpt))
def stop(self):
"""
Stop event loop, if loop is not running, do nothing
:return:
"""
self._stop = True