Skip to content

Commit

Permalink
idiomatic code in camera_data
Browse files Browse the repository at this point in the history
  • Loading branch information
carloskiki committed Mar 5, 2024
1 parent a9ed647 commit 4b48194
Show file tree
Hide file tree
Showing 4 changed files with 37 additions and 61 deletions.
26 changes: 10 additions & 16 deletions camera_data/src/camera_publisher.py
Original file line number Diff line number Diff line change
@@ -1,16 +1,13 @@
#!/usr/bin/env python3
import os, sys
from pydoc_data.topics import topics

currentdir = os.path.dirname(os.path.realpath(__file__))
sys.path.append(currentdir)
import rospy
import cv2
import time
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
from std_msgs.msg import Int16
from PyQt5 import QtGui
import sys

stop = False
Expand All @@ -24,23 +21,20 @@ def __init__(self):

rospy.init_node('camera_frame_publisher')
self.camera_select_subscriber = rospy.Subscriber("camera_selection", Int16, self.select_camera)
self.timer = rospy.Timer(rospy.Duration(0.03), self.timer_callback)
_30fps_ns = 30000000
self.timer = rospy.Timer(rospy.Duration(0, _30fps_ns), self.timer_callback)
self.camera_frame_publisher = rospy.Publisher('/camera_frames', Image, queue_size=10)

def timer_callback(self, event):
try:
ret, frame = self.video_capture.read()
# these code cause error
encode_params = [int(cv2.IMWRITE_JPEG_QUALITY), 90]
result, frame = cv2.imencode(".jpg", frame, encode_params)
def timer_callback(self, _):
ret, frame = self.video_capture.read()
if ret:
encode_params = [cv2.IMWRITE_JPEG_QUALITY, 90]
_, frame = cv2.imencode(".jpg", frame, encode_params)
self.frames = self.openCV_to_ros_image(frame)
if ret:
print("Publishing frame")
self.camera_frame_publisher.publish(self.frames)
except:
print("Publishing frame")
self.camera_frame_publisher.publish(self.frames)
else:
print("No camera found")
finally:
pass

def openCV_to_ros_image(self, cv_image):
try:
Expand Down
6 changes: 2 additions & 4 deletions camera_data/src/camera_subscriber.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
import os, sys
from pydoc_data.topics import topics
currentdir = os.path.dirname(os.path.realpath(__file__))
sys.path.append(currentdir)

import rospy
currentdir = os.path.dirname(os.path.realpath(__file__))
sys.path.append(currentdir)
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
Expand Down Expand Up @@ -34,4 +32,4 @@ def ros_to_openCV_image(self, ros_image):

if __name__ == "__main__":
driver = Node_CameraFrameSub()
rospy.spin()
rospy.spin()
49 changes: 23 additions & 26 deletions camera_data/src/getCameraFeeds.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,44 +2,41 @@


class CameraHandler:
vids = [] # available cameras
available_cameras = []

def __init__(self):
# Loop 25 times and collect all found cameras
# Collect all found cameras
# Assumes sequential indices
for i in range (25):
newCap = cv2.VideoCapture(i, cv2.CAP_V4L2)

if newCap is not None:
newCap.open(i)

# check if object is not null
if newCap is not None and newCap.isOpened():
# add the camera found
self.vids.append(newCap)
if newCap is not None and newCap.open(i):
self.available_cameras.append(newCap)

def get_all_feeds(self):
retAndFrame = []
# read each capture object in vids and add as a tuple to retAndFrame
for i in range(len(self.vids)):
newFeed = self.vids[i].read()
retAndFrame.append((newFeed[0], newFeed[1], i))
for camera in self.available_cameras:
newFeed = camera.read()
retAndFrame.append((newFeed[0], newFeed[1]))

return retAndFrame

# # Runnable for displaying camera feeds
def run_feeds(self):
while True:
# display each frame (camera feed) in the list
for index, (ret, frame) in enumerate(self.get_all_feeds()):
if ret:
cv2.imshow(f"frame {index}", frame)

# press 'q' to stop displaying
if cv2.waitKey(1) & 0xFF == ord('q'):
for vid in self.available_cameras:
vid.release()
cv2.destroyAllWindows()
break

# Runnable to display camera feeds
if __name__ == '__main__':
camHandler = CameraHandler()
while True:
retAndFrame = camHandler.get_all_feeds()
# display each frame (camera feed) in the list
for ret, frame, index in retAndFrame:
if ret:
cv2.imshow(f"frame {index}", frame)

# press 'q' to stop displaying
if cv2.waitKey(1) & 0xFF == ord('q'):
for vid in camHandler.vids:
vid.release()
cv2.destroyAllWindows()
break
camHandler.run_feeds()
17 changes: 2 additions & 15 deletions camera_data/test/test_getCam.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
import cv2
import sys
import os

Expand All @@ -9,18 +8,6 @@

import getCameraFeeds as gcf

# Runnable for displaying camera feeds
# Runnable to display camera feeds
camHandler = gcf.CameraHandler()
while True:
retAndFrame = camHandler.get_all_feeds()
# display each frame (camera feed) in the list
for ret, frame, index in retAndFrame:
cv2.imshow(f"frame {index}", frame)

# press 'q' to stop displaying
if cv2.waitKey(1) & 0xFF == ord('q'):
for vid in camHandler.vids:
vid.release()
cv2.destroyAllWindows()
break

camHandler.run_feeds()

0 comments on commit 4b48194

Please sign in to comment.