-
Notifications
You must be signed in to change notification settings - Fork 2
Exception Handling #114
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: cv_integration
Are you sure you want to change the base?
Exception Handling #114
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,136 +1,157 @@ | ||
| #!/usr/bin/env python3 | ||
| import struct | ||
| import sys | ||
| import time | ||
| import json | ||
| import os | ||
| import struct | ||
|
|
||
| import cv2 | ||
| import numpy as np | ||
| import redis | ||
| import onnx | ||
| import onnxruntime as ort | ||
|
|
||
| import onnxruntime as ort | ||
| import redis | ||
| import rospkg | ||
|
|
||
| from line_fitting import fit_lanes | ||
|
|
||
|
|
||
| WIDTH: int = 330 | ||
| HEIGHT: int = 180 | ||
| DEBUG_MODE: bool = True | ||
|
|
||
|
|
||
| class CVModelInferencer: | ||
| def __init__(self): | ||
| self.redis = redis.Redis(host='127.0.0.1', port=6379, db=3) | ||
| self.redis = redis.Redis(host="127.0.0.1", port=6379, db=3) | ||
|
|
||
| rospack = rospkg.RosPack() | ||
| model_path = rospack.get_path('lane_detection') + '/models/unet_with_sigmoid.onnx' | ||
| model_path = ( | ||
| rospack.get_path("lane_detection") + "/models/unet_with_sigmoid.onnx" | ||
| ) | ||
|
|
||
| self.model = onnx.load(model_path) | ||
| onnx.checker.check_model(self.model) | ||
|
|
||
| self.ort_session = ort.InferenceSession(model_path, providers=['CUDAExecutionProvider']) | ||
| self.ort_session = ort.InferenceSession( | ||
| model_path, providers=["CUDAExecutionProvider"] | ||
| ) | ||
|
|
||
| def run(self): | ||
| raw = self._fromRedisImg("zed/preprocessed") | ||
| if raw is not None: | ||
| img = get_input(raw.copy()) | ||
| if raw is None: | ||
| return | ||
| img = get_input(raw) # Does not return None | ||
|
|
||
| # Do model inference | ||
| output = self.ort_session.run(None, {'Inputs': img.astype(np.float32)})[0][0][0] | ||
| mask = np.where(output > 0.5, 1., 0.) | ||
| self._toRedisImg(mask, "cv/model/output") | ||
| # Do model inference | ||
| outputs = self.ort_session.run(None, {"Inputs": img.astype(np.float32)}) | ||
| mask = np.where(outputs[0][0][0] > 0.5, 1.0, 0.0) | ||
| self._toRedisImg(mask, "cv/model/output") | ||
|
|
||
| lanes = fit_lanes(mask) | ||
| if lanes is not None: | ||
| self._toRedisLanes(lanes, "lane_detection") | ||
| lanes = fit_lanes(mask) | ||
| if lanes is not None: | ||
| self._toRedisLanes(lanes, "lane_detection") | ||
|
|
||
| # toshow = np.concatenate([cv2.resize(raw, (330, 180)), np.tile(mask[...,np.newaxis]*255, (1, 1, 3))], axis=1).astype(np.uint8) | ||
| # cv2.imshow("image", toshow) | ||
| # cv2.waitKey(1) | ||
| if DEBUG_MODE: | ||
| toshow = np.concatenate([cv2.resize(raw, (330, 180)), np.tile(mask[...,np.newaxis]*255, (1, 1, 3))], axis=1).astype(np.uint8) | ||
| cv2.imshow("image", toshow) | ||
| cv2.waitKey(1) | ||
|
|
||
| def _toRedisLanes(self,lanes,name): | ||
| def _toRedisLanes(self, lanes, name): | ||
| """Store given Numpy array 'img' in Redis under key 'name'""" | ||
|
|
||
| encoded = json.dumps(lanes) | ||
| # Store encoded data in Redis | ||
| self.redis.set(name,encoded) | ||
| self.redis.set(name, encoded) | ||
|
|
||
| def _fromRedisImg(self, name): | ||
| """Retrieve Numpy array from Redis key 'n'""" | ||
| encoded = self.redis.get(name) | ||
| if encoded is None: | ||
| return None | ||
| h, w = struct.unpack('>II',encoded[:8]) | ||
| a = cv2.imdecode(np.frombuffer(encoded, dtype=np.uint8, offset=8), 1).reshape(h,w,3) | ||
| h, w = struct.unpack(">II", encoded[:8]) | ||
| a = cv2.imdecode(np.frombuffer(encoded, dtype=np.uint8, offset=8), 1).reshape( | ||
| h, w, 3 | ||
| ) | ||
| return a | ||
|
|
||
| def _toRedisImg(self,img,name): | ||
| def _toRedisImg(self, img, name): | ||
| """Store given Numpy array 'img' in Redis under key 'name'""" | ||
| h, w = img.shape[:2] | ||
| shape = struct.pack('>II',h,w) | ||
| shape = struct.pack(">II", h, w) | ||
|
|
||
| retval, buffer = cv2.imencode('.png', img) | ||
| retval, buffer = cv2.imencode(".png", img) | ||
| img_bytes = np.array(buffer).tostring() | ||
|
|
||
| encoded = shape + img_bytes | ||
|
|
||
| # Store encoded data in Redis | ||
| self.redis.set(name,encoded) | ||
| self.redis.set(name, encoded) | ||
|
|
||
| return | ||
|
|
||
|
|
||
| def find_edge_channel(img): | ||
| edges_mask = np.zeros((img.shape[0],img.shape[1]),dtype=np.uint8) | ||
| edges_mask = np.zeros(img.shape[0:2], dtype=np.uint8) | ||
| width = img.shape[1] | ||
| height = img.shape[0] | ||
|
|
||
| gray_im = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY) | ||
| gray_im = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) | ||
| # gray_im = cv2.GaussianBlur(gray_im,(3,3),0) | ||
| # Separate into quadrants | ||
| med1 = np.median(gray_im[:height//2,:width//2]) | ||
| med2 = np.median(gray_im[:height//2,width//2:]) | ||
| med3 = np.median(gray_im[height//2:,width//2:]) | ||
| med4 = np.median(gray_im[height//2:,:width//2]) | ||
| med1 = np.median(gray_im[: height // 2, : width // 2]) | ||
| med2 = np.median(gray_im[: height // 2, width // 2 :]) | ||
| med3 = np.median(gray_im[height // 2 :, width // 2 :]) | ||
| med4 = np.median(gray_im[height // 2 :, : width // 2]) | ||
|
|
||
| l1 = int(max(0,(1-0.205)*med1)) | ||
| u1 = int(min(255,(1+0.205)*med1)) | ||
| e1 = cv2.Canny(gray_im[:height//2,:width//2],l1,u1) | ||
| l1 = int(max(0, (1 - 0.205) * med1)) | ||
| u1 = int(min(255, (1 + 0.205) * med1)) | ||
| e1 = cv2.Canny(gray_im[: height // 2, : width // 2], l1, u1) | ||
|
|
||
| l2 = int(max(0,(1-0.205)*med2)) | ||
| u2 = int(min(255,(1+0.205)*med2)) | ||
| e2 = cv2.Canny(gray_im[:height//2,width//2:],l2,u2) | ||
| l2 = int(max(0, (1 - 0.205) * med2)) | ||
| u2 = int(min(255, (1 + 0.205) * med2)) | ||
| e2 = cv2.Canny(gray_im[: height // 2, width // 2 :], l2, u2) | ||
|
|
||
| l3 = int(max(0,(1-0.205)*med3)) | ||
| u3 = int(min(255,(1+0.205)*med3)) | ||
| e3 = cv2.Canny(gray_im[height//2:,width//2:],l3,u3) | ||
| l3 = int(max(0, (1 - 0.205) * med3)) | ||
| u3 = int(min(255, (1 + 0.205) * med3)) | ||
| e3 = cv2.Canny(gray_im[height // 2 :, width // 2 :], l3, u3) | ||
|
|
||
| l4 = int(max(0,(1-0.205)*med4)) | ||
| u4 = int(min(255,(1+0.205)*med4)) | ||
| e4 = cv2.Canny(gray_im[height//2:,:width//2],l4,u4) | ||
| l4 = int(max(0, (1 - 0.205) * med4)) | ||
| u4 = int(min(255, (1 + 0.205) * med4)) | ||
| e4 = cv2.Canny(gray_im[height // 2 :, : width // 2], l4, u4) | ||
|
|
||
| # Stitch the edges together | ||
| edges_mask[:height//2,:width//2] = e1 | ||
| edges_mask[:height//2,width//2:] = e2 | ||
| edges_mask[height//2:,width//2:] = e3 | ||
| edges_mask[height//2:,:width//2] = e4 | ||
| edges_mask[: height // 2, : width // 2] = e1 | ||
| edges_mask[: height // 2, width // 2 :] = e2 | ||
| edges_mask[height // 2 :, width // 2 :] = e3 | ||
| edges_mask[height // 2 :, : width // 2] = e4 | ||
|
|
||
| edges_mask_inv = cv2.bitwise_not(edges_mask) | ||
|
|
||
| return edges_mask, edges_mask_inv | ||
|
|
||
|
|
||
| def get_input(frame): | ||
| frame = cv2.resize(frame,(1280,720),interpolation=cv2.INTER_AREA) | ||
|
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I deleted this because it makes the model do work on an unnecessarily large image |
||
| def get_input(frame: np.ndarray) -> np.ndarray: | ||
|
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Added typing. Okay in Python 3 only |
||
| frame_copy = np.copy(frame) | ||
|
|
||
| test_edges,test_edges_inv = find_edge_channel(frame_copy) | ||
| frame_copy = np.append(frame_copy,test_edges.reshape(test_edges.shape[0],test_edges.shape[1],1),axis=2) | ||
| frame_copy = np.append(frame_copy,test_edges_inv.reshape(test_edges_inv.shape[0],test_edges_inv.shape[1],1),axis=2) | ||
| frame_copy = cv2.resize(frame_copy,(330,180)) | ||
|
|
||
| input = (frame_copy/255.).transpose(2,0,1).reshape(1,5,180,330) | ||
| frame_copy = cv2.resize(frame_copy, (WIDTH, HEIGHT), interpolation=cv2.INTER_AREA) | ||
|
|
||
| test_edges, test_edges_inv = find_edge_channel(frame_copy) | ||
|
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. REAL CHANGE I combined the np.append's into a single np.block. I also moved the resize to the top (I'm fairly sure the function that is called on frame_copy is shape agnostic) |
||
| frame_copy = np.block( | ||
| [ | ||
| frame_copy, # shape: (180, 330, 3) | ||
| test_edges.reshape(*test_edges.shape, 1), # shape: (180, 330, 1) | ||
| test_edges_inv.reshape(*test_edges_inv.shape, 1), # shape: (180, 330, 1) | ||
| ] | ||
| ) # (330, 180, 5) | ||
|
|
||
| input = (frame_copy / 255.0).transpose(2, 0, 1).reshape(1, 5, *test_edges.shape) | ||
| return input | ||
|
|
||
|
|
||
| if __name__ == '__main__': | ||
| if __name__ == "__main__": | ||
| wrapper = CVModelInferencer() | ||
|
|
||
| while True: | ||
| wrapper.run() | ||
| if DEBUG_MODE: | ||
| while True: | ||
| wrapper.run() | ||
| else: | ||
| while True: | ||
| try: | ||
| wrapper.run() | ||
| except: | ||
| pass | ||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
First "real" change (moved logic to if-guard)