From 7670b8b01a56438645370dfabc57388d3f6d0189 Mon Sep 17 00:00:00 2001 From: Cyrille Nofficial Date: Wed, 26 Oct 2022 17:32:35 +0200 Subject: [PATCH] refactor: fix pylint --- camera/depthai.py | 84 +++++++++++++++++++++++++++++--------------- events/__init__.py | 0 events/events_pb2.py | 53 ---------------------------- 3 files changed, 56 insertions(+), 81 deletions(-) delete mode 100644 events/__init__.py delete mode 100644 events/events_pb2.py diff --git a/camera/depthai.py b/camera/depthai.py index 0af8add..3f8d57d 100644 --- a/camera/depthai.py +++ b/camera/depthai.py @@ -5,14 +5,14 @@ import abc import datetime import logging import typing +from dataclasses import dataclass import cv2 import depthai as dai +import events.events_pb2 import numpy as np import paho.mqtt.client as mqtt -import events.events_pb2 - logger = logging.getLogger(__name__) _NN_PATH = "/models/mobile_object_localizer_192x192_openvino_2021.4_6shave.blob" @@ -92,7 +92,7 @@ class FrameProcessor: def process(self, img: dai.ImgFrame) -> typing.Any: """ Publish camera frames - :param img: + :param img: image read from camera :return: id frame reference :raise: @@ -119,13 +119,23 @@ class FrameProcessor: class Source(abc.ABC): - @abc.abstractmethod - def get_stream_name(self) -> str: - pass + """Base class for image source""" @abc.abstractmethod - def link_preview(self, input_node: dai.Node.Input): - pass + def get_stream_name(self) -> str: + """ + Queue/stream name to use to get data + + :return: steam name + """ + + @abc.abstractmethod + def link(self, input_node: dai.Node.Input) -> None: + """ + Link this source to the input node + + :param: input_node: input node to link + """ class ObjectDetectionNN: @@ -165,9 +175,18 @@ class ObjectDetectionNN: return xout_nn def get_stream_name(self) -> str: + """ + Queue/stream name to use to get data + + :return: stream name + """ return self._xout.getStreamName() def get_input(self) -> dai.Node.Input: + """ + Get input node to use to link with source node + :return: input to link with source output, see Source.link() + """ return self._manip_image.inputImage @@ -192,23 +211,29 @@ class CameraSource(Source): # link camera preview to output cam_rgb.preview.link(xout_rgb.input) - def link_preview(self, input_node: dai.Node.Input): + def link(self, input_node: dai.Node.Input) -> None: self._cam_rgb.preview.link(input_node) def get_stream_name(self) -> str: return self._xout_rgb.getStreamName() +@dataclass +class MqttConfig: + """MQTT configuration""" + host: str + topic: str + port: int = 1883 + qos: int = 0 + + class MqttSource(Source): """Image source based onto mqtt stream""" - def __init__(self, device: dai.Device, pipeline: dai.Pipeline, mqtt_host: str, mqtt_topic: str, - mqtt_port: int = 1883, mqtt_qos: int = 0): - self._mqtt_host = mqtt_host - self._mqtt_port = mqtt_port - + def __init__(self, device: dai.Device, pipeline: dai.Pipeline, mqtt_config: MqttConfig): + self._mqtt_config = mqtt_config self._client = mqtt.Client() - self._client.user_data_set({"topic": mqtt_topic, "qos": str(mqtt_qos)}) + self._client.user_data_set(mqtt_config) self._client.on_connect = self._on_connect self._client.on_message = self._on_message @@ -220,27 +245,32 @@ class MqttSource(Source): self._img_in_queue = device.getInputQueue(self._img_in.getStreamName()) - def run(self): - self._client.connect(host=self._mqtt_host, port=self._mqtt_port) + def run(self) -> None: + """ Connect and start mqtt loop """ + self._client.connect(host=self._mqtt_config.host, port=self._mqtt_config.port) self._client.loop_start() - def stop(self): + def stop(self) -> None: + """Stop and disconnect mqtt loop""" self._client.loop_stop() self._client.disconnect() @staticmethod - def _on_connect(client: mqtt.Client, userdata: dict[str, str], flags, rc): + # pylint: disable=unused-argument + def _on_connect(client: mqtt.Client, userdata: MqttConfig, flags: typing.Any, + result_connection: typing.Any) -> None: # if we lose the connection and reconnect then subscriptions will be renewed. - client.subscribe(topic=userdata["topic"], qos=int(userdata["qos"])) + client.subscribe(topic=userdata.topic, qos=userdata.qos) - def _on_message(self, _: mqtt.Client, user_data: dict[str, str], msg: mqtt.MQTTMessage): + # pylint: disable=unused-argument + def _on_message(self, _: mqtt.Client, user_data: MqttConfig, msg: mqtt.MQTTMessage) -> None: frame_msg = events.events_pb2.FrameMessage() frame_msg.ParseFromString(msg.payload) frame = np.asarray(frame_msg.frame, dtype="uint8") frame = cv2.imdecode(frame, cv2.IMREAD_COLOR) nn_data = dai.NNData() - nn_data.setLayer("data", _to_planar(frame, frame.shape())) + nn_data.setLayer("data", _to_planar(frame, (300, 300))) self._img_in_queue.send(nn_data) def get_stream_name(self) -> str: @@ -261,8 +291,6 @@ class PipelineController: def __init__(self, img_width: int, img_height: int, frame_processor: FrameProcessor, object_processor: ObjectProcessor, camera: Source, object_node: ObjectDetectionNN): - self._img_width = img_width - self._img_height = img_height self._pipeline = self._configure_pipeline() self._frame_processor = frame_processor self._object_processor = object_processor @@ -277,7 +305,7 @@ class PipelineController: pipeline.setOpenVINOVersion(version=dai.OpenVINO.VERSION_2021_4) # Link preview to manip and manip to nn - self._camera.link_preview(self._object_node.get_input()) + self._camera.link(self._object_node.get_input()) logger.info("pipeline configured") return pipeline @@ -288,7 +316,7 @@ class PipelineController: :return: """ # Connect to device and start pipeline - with dai.Device(self._pipeline) as device: + with dai.Device(pipeline=self._pipeline) as device: logger.info('MxId: %s', device.getDeviceInfo().getMxId()) logger.info('USB speed: %s', device.getUsbSpeed()) logger.info('Connected cameras: %s', device.getConnectedCameras()) @@ -311,7 +339,7 @@ class PipelineController: except Exception as ex: logger.exception("unexpected error: %s", str(ex)) - def _loop_on_camera_events(self, q_nn: dai.DataOutputQueue, q_rgb: dai.DataOutputQueue): + def _loop_on_camera_events(self, q_nn: dai.DataOutputQueue, q_rgb: dai.DataOutputQueue) -> None: logger.debug("wait for new frame") # Wait for frame @@ -325,7 +353,7 @@ class PipelineController: in_nn: dai.NNData = q_nn.get() self._object_processor.process(in_nn, frame_ref) - def stop(self): + def stop(self) -> None: """ Stop event loop, if loop is not running, do nothing :return: diff --git a/events/__init__.py b/events/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/events/events_pb2.py b/events/events_pb2.py deleted file mode 100644 index 65ada3c..0000000 --- a/events/events_pb2.py +++ /dev/null @@ -1,53 +0,0 @@ -# -*- coding: utf-8 -*- -# Generated by the protocol buffer compiler. DO NOT EDIT! -# source: events/events.proto -"""Generated protocol buffer code.""" -from google.protobuf.internal import builder as _builder -from google.protobuf import descriptor as _descriptor -from google.protobuf import descriptor_pool as _descriptor_pool -from google.protobuf import symbol_database as _symbol_database -# @@protoc_insertion_point(imports) - -_sym_db = _symbol_database.Default() - - -from google.protobuf import timestamp_pb2 as google_dot_protobuf_dot_timestamp__pb2 - - -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x13\x65vents/events.proto\x12\x0erobocar.events\x1a\x1fgoogle/protobuf/timestamp.proto\"T\n\x08\x46rameRef\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\n\n\x02id\x18\x02 \x01(\t\x12.\n\ncreated_at\x18\x03 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\"C\n\x0c\x46rameMessage\x12$\n\x02id\x18\x01 \x01(\x0b\x32\x18.robocar.events.FrameRef\x12\r\n\x05\x66rame\x18\x02 \x01(\x0c\"d\n\x0fSteeringMessage\x12\x10\n\x08steering\x18\x01 \x01(\x02\x12\x12\n\nconfidence\x18\x02 \x01(\x02\x12+\n\tframe_ref\x18\x03 \x01(\x0b\x32\x18.robocar.events.FrameRef\"d\n\x0fThrottleMessage\x12\x10\n\x08throttle\x18\x01 \x01(\x02\x12\x12\n\nconfidence\x18\x02 \x01(\x02\x12+\n\tframe_ref\x18\x03 \x01(\x0b\x32\x18.robocar.events.FrameRef\"A\n\x10\x44riveModeMessage\x12-\n\ndrive_mode\x18\x01 \x01(\x0e\x32\x19.robocar.events.DriveMode\"f\n\x0eObjectsMessage\x12\'\n\x07objects\x18\x01 \x03(\x0b\x32\x16.robocar.events.Object\x12+\n\tframe_ref\x18\x02 \x01(\x0b\x32\x18.robocar.events.FrameRef\"\x80\x01\n\x06Object\x12(\n\x04type\x18\x01 \x01(\x0e\x32\x1a.robocar.events.TypeObject\x12\x0c\n\x04left\x18\x02 \x01(\x02\x12\x0b\n\x03top\x18\x03 \x01(\x02\x12\r\n\x05right\x18\x04 \x01(\x02\x12\x0e\n\x06\x62ottom\x18\x05 \x01(\x02\x12\x12\n\nconfidence\x18\x06 \x01(\x02\"&\n\x13SwitchRecordMessage\x12\x0f\n\x07\x65nabled\x18\x01 \x01(\x08\"\x8c\x01\n\x0bRoadMessage\x12&\n\x07\x63ontour\x18\x01 \x03(\x0b\x32\x15.robocar.events.Point\x12(\n\x07\x65llipse\x18\x02 \x01(\x0b\x32\x17.robocar.events.Ellipse\x12+\n\tframe_ref\x18\x03 \x01(\x0b\x32\x18.robocar.events.FrameRef\"\x1d\n\x05Point\x12\t\n\x01x\x18\x01 \x01(\x05\x12\t\n\x01y\x18\x02 \x01(\x05\"r\n\x07\x45llipse\x12%\n\x06\x63\x65nter\x18\x01 \x01(\x0b\x32\x15.robocar.events.Point\x12\r\n\x05width\x18\x02 \x01(\x05\x12\x0e\n\x06height\x18\x03 \x01(\x05\x12\r\n\x05\x61ngle\x18\x04 \x01(\x02\x12\x12\n\nconfidence\x18\x05 \x01(\x02\"\x82\x01\n\rRecordMessage\x12+\n\x05\x66rame\x18\x01 \x01(\x0b\x32\x1c.robocar.events.FrameMessage\x12\x31\n\x08steering\x18\x02 \x01(\x0b\x32\x1f.robocar.events.SteeringMessage\x12\x11\n\trecordSet\x18\x03 \x01(\t*-\n\tDriveMode\x12\x0b\n\x07INVALID\x10\x00\x12\x08\n\x04USER\x10\x01\x12\t\n\x05PILOT\x10\x02*2\n\nTypeObject\x12\x07\n\x03\x41NY\x10\x00\x12\x07\n\x03\x43\x41R\x10\x01\x12\x08\n\x04\x42UMP\x10\x02\x12\x08\n\x04PLOT\x10\x03\x42\nZ\x08./eventsb\x06proto3') - -_builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, globals()) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'events.events_pb2', globals()) -if _descriptor._USE_C_DESCRIPTORS == False: - - DESCRIPTOR._options = None - DESCRIPTOR._serialized_options = b'Z\010./events' - _DRIVEMODE._serialized_start=1196 - _DRIVEMODE._serialized_end=1241 - _TYPEOBJECT._serialized_start=1243 - _TYPEOBJECT._serialized_end=1293 - _FRAMEREF._serialized_start=72 - _FRAMEREF._serialized_end=156 - _FRAMEMESSAGE._serialized_start=158 - _FRAMEMESSAGE._serialized_end=225 - _STEERINGMESSAGE._serialized_start=227 - _STEERINGMESSAGE._serialized_end=327 - _THROTTLEMESSAGE._serialized_start=329 - _THROTTLEMESSAGE._serialized_end=429 - _DRIVEMODEMESSAGE._serialized_start=431 - _DRIVEMODEMESSAGE._serialized_end=496 - _OBJECTSMESSAGE._serialized_start=498 - _OBJECTSMESSAGE._serialized_end=600 - _OBJECT._serialized_start=603 - _OBJECT._serialized_end=731 - _SWITCHRECORDMESSAGE._serialized_start=733 - _SWITCHRECORDMESSAGE._serialized_end=771 - _ROADMESSAGE._serialized_start=774 - _ROADMESSAGE._serialized_end=914 - _POINT._serialized_start=916 - _POINT._serialized_end=945 - _ELLIPSE._serialized_start=947 - _ELLIPSE._serialized_end=1061 - _RECORDMESSAGE._serialized_start=1064 - _RECORDMESSAGE._serialized_end=1194 -# @@protoc_insertion_point(module_scope)