First implementation
This commit is contained in:
0
camera/__init__.py
Normal file
0
camera/__init__.py
Normal file
67
camera/cli.py
Normal file
67
camera/cli.py
Normal file
@ -0,0 +1,67 @@
|
||||
"""
|
||||
Publish data from oak-lite device
|
||||
|
||||
Usage: rc-oak-robocar-oak-camera [-u USERNAME | --mqtt-username=USERNAME] [--mqtt-password=PASSWORD] [--mqtt-broker=HOSTNAME]
|
||||
[--mqtt-topic-robocar-oak-camera="TOPIC_CAMERA"] [--mqtt-client-id=CLIENT_ID]
|
||||
|
||||
Options:
|
||||
-h --help Show this screen.
|
||||
-u USERID --mqtt-username=USERNAME MQTT user
|
||||
-p PASSWORD --mqtt-password=PASSWORD MQTT password
|
||||
-b HOSTNAME --mqtt-broker=HOSTNAME MQTT broker host
|
||||
-C CLIENT_ID --mqtt-client-id=CLIENT_ID MQTT client id
|
||||
-c TOPIC_CAMERA --mqtt-topic-robocar-oak-camera=TOPIC_CAMERA MQTT topic where to publish robocar-oak-camera frames
|
||||
-H IMG_HEIGHT --image-height=IMG_HEIGHT IMG_HEIGHT image height
|
||||
-W IMG_WIDTH --image-width=IMG_width IMG_WIDTH image width
|
||||
"""
|
||||
import logging
|
||||
import os
|
||||
import camera.depthai as cam
|
||||
from docopt import docopt
|
||||
import paho.mqtt.client as mqtt
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
logging.basicConfig(level=logging.INFO)
|
||||
|
||||
default_client_id = "robocar-depthai"
|
||||
|
||||
|
||||
def init_mqtt_client(broker_host: str, 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")
|
||||
client.connect(host=broker_host, port=1883, keepalive=60)
|
||||
logger.info("Connected to mqtt broker")
|
||||
return client
|
||||
|
||||
|
||||
def execute_from_command_line():
|
||||
logging.basicConfig(level=logging.INFO)
|
||||
|
||||
args = docopt(__doc__)
|
||||
|
||||
client = init_mqtt_client(broker_host=get_default_value(args["--mqtt-broker"], "MQTT_BROKER", "localhost"),
|
||||
user=get_default_value(args["--mqtt-username"], "MQTT_USERNAME", ""),
|
||||
password=get_default_value(args["--mqtt-password"], "MQTT_PASSWORD", ""),
|
||||
client_id=get_default_value(args["--mqtt-client-id"], "MQTT_CLIENT_ID",
|
||||
default_client_id),
|
||||
)
|
||||
frame_topic = get_default_value(args["--mqtt-topic-robocar-oak-camera"], "MQTT_TOPIC_CAMERA", "/oak/camera_rgb")
|
||||
|
||||
frame_processor = cam.FramePublisher(mqtt_client=client,
|
||||
frame_topic=frame_topic,
|
||||
img_width=int(get_default_value(args["--image-width"], "IMAGE_WIDTH", 160)),
|
||||
img_height=int(get_default_value(args["--image-height"], "IMAGE_HEIGHT", 120)))
|
||||
frame_processor.start()
|
||||
|
||||
client.loop_forever()
|
||||
|
||||
|
||||
def get_default_value(value, env_var: str, default_value) -> str:
|
||||
if value:
|
||||
return value
|
||||
if env_var in os.environ:
|
||||
return os.environ[env_var]
|
||||
return default_value
|
98
camera/depthai.py
Normal file
98
camera/depthai.py
Normal file
@ -0,0 +1,98 @@
|
||||
import logging
|
||||
import paho.mqtt.client as mqtt
|
||||
|
||||
import events.events_pb2
|
||||
from google.protobuf.timestamp_pb2 import Timestamp
|
||||
|
||||
import depthai as dai
|
||||
import cv2
|
||||
|
||||
|
||||
from threading import Thread
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
"""
|
||||
This example shows usage of Camera Control message as well as ColorCamera configInput to change crop x and y
|
||||
Uses 'WASD' controls to move the crop window, 'C' to capture a still image, 'T' to trigger autofocus, 'IOKL,.[]'
|
||||
for manual exposure/focus/white-balance:
|
||||
Control: key[dec/inc] min..max
|
||||
exposure time: I O 1..33000 [us]
|
||||
sensitivity iso: K L 100..1600
|
||||
focus: , . 0..255 [far..near]
|
||||
white balance: [ ] 1000..12000 (light color temperature K)
|
||||
To go back to auto controls:
|
||||
'E' - autoexposure
|
||||
'F' - autofocus (continuous)
|
||||
'B' - auto white-balance
|
||||
"""
|
||||
|
||||
|
||||
class FramePublisher(Thread):
|
||||
def __init__(self, mqtt_client: mqtt.Client, frame_topic: str, img_width: int, img_height: int):
|
||||
super().__init__(name="FrameProcessor")
|
||||
self._mqtt_client = mqtt_client
|
||||
self._frame_topic = frame_topic
|
||||
self._img_width = img_width
|
||||
self._img_height = img_height
|
||||
self._pipeline = self._configure_pipeline()
|
||||
|
||||
def _configure_pipeline(self) -> dai.Pipeline:
|
||||
logger.info("configure pipeline")
|
||||
pipeline = dai.Pipeline()
|
||||
cam_rgb = pipeline.create(dai.node.ColorCamera)
|
||||
cam_rgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P)
|
||||
cam_rgb.setInterleaved(False)
|
||||
cam_rgb.setColorOrder(dai.ColorCameraProperties.ColorOrder.RGB)
|
||||
|
||||
# Define sources and outputs
|
||||
manip = pipeline.create(dai.node.ImageManip)
|
||||
|
||||
manip_out = pipeline.create(dai.node.XLinkOut)
|
||||
|
||||
manip_out.setStreamName("manip")
|
||||
|
||||
# Properties
|
||||
cam_rgb.setBoardSocket(dai.CameraBoardSocket.RGB)
|
||||
cam_rgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P)
|
||||
|
||||
manip.initialConfig.setResize(self._img_width, self._img_height)
|
||||
|
||||
# Linking
|
||||
cam_rgb.video.link(manip.inputImage)
|
||||
manip.out.link(manip_out.input)
|
||||
logger.info("pipeline configured")
|
||||
return pipeline
|
||||
|
||||
def run(self):
|
||||
# Connect to device and start pipeline
|
||||
with dai.Device(self._pipeline) as device:
|
||||
# Queues
|
||||
queue_size = 8
|
||||
queue_manip = device.getOutputQueue("manip", queue_size)
|
||||
|
||||
while True:
|
||||
try:
|
||||
while queue_manip.has():
|
||||
im_resize = queue_manip.get().getData().getCvFrame()
|
||||
|
||||
is_success, im_buf_arr = cv2.imencode(".jpg", im_resize)
|
||||
byte_im = im_buf_arr.tobytes()
|
||||
|
||||
timestamp = Timestamp()
|
||||
frame_msg = events.events_pb2.FrameMessage()
|
||||
frame_msg.id = events.events_pb2.FrameRef()
|
||||
frame_msg.id.name = "robocar-oak-camera-oak"
|
||||
frame_msg.id.id = timestamp.ToMilliseconds()
|
||||
frame_msg.id.created_at = timestamp.GetCurrentTime()
|
||||
frame_msg.frame = byte_im
|
||||
|
||||
self._mqtt_client.publish(topic=self._frame_topic,
|
||||
payload=frame_msg.SerializeToString(),
|
||||
qos=0,
|
||||
retain=False)
|
||||
|
||||
except Exception as e:
|
||||
logger.exception("unexpected error")
|
||||
|
||||
|
Reference in New Issue
Block a user