Skip to content

Commit 4b48194

Browse files
committed
idiomatic code in camera_data
1 parent a9ed647 commit 4b48194

File tree

4 files changed

+37
-61
lines changed

4 files changed

+37
-61
lines changed

camera_data/src/camera_publisher.py

Lines changed: 10 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,13 @@
11
#!/usr/bin/env python3
22
import os, sys
3-
from pydoc_data.topics import topics
43

54
currentdir = os.path.dirname(os.path.realpath(__file__))
65
sys.path.append(currentdir)
76
import rospy
87
import cv2
9-
import time
108
from cv_bridge import CvBridge
119
from sensor_msgs.msg import Image
1210
from std_msgs.msg import Int16
13-
from PyQt5 import QtGui
1411
import sys
1512

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

2522
rospy.init_node('camera_frame_publisher')
2623
self.camera_select_subscriber = rospy.Subscriber("camera_selection", Int16, self.select_camera)
27-
self.timer = rospy.Timer(rospy.Duration(0.03), self.timer_callback)
24+
_30fps_ns = 30000000
25+
self.timer = rospy.Timer(rospy.Duration(0, _30fps_ns), self.timer_callback)
2826
self.camera_frame_publisher = rospy.Publisher('/camera_frames', Image, queue_size=10)
2927

30-
def timer_callback(self, event):
31-
try:
32-
ret, frame = self.video_capture.read()
33-
# these code cause error
34-
encode_params = [int(cv2.IMWRITE_JPEG_QUALITY), 90]
35-
result, frame = cv2.imencode(".jpg", frame, encode_params)
28+
def timer_callback(self, _):
29+
ret, frame = self.video_capture.read()
30+
if ret:
31+
encode_params = [cv2.IMWRITE_JPEG_QUALITY, 90]
32+
_, frame = cv2.imencode(".jpg", frame, encode_params)
3633
self.frames = self.openCV_to_ros_image(frame)
37-
if ret:
38-
print("Publishing frame")
39-
self.camera_frame_publisher.publish(self.frames)
40-
except:
34+
print("Publishing frame")
35+
self.camera_frame_publisher.publish(self.frames)
36+
else:
4137
print("No camera found")
42-
finally:
43-
pass
4438

4539
def openCV_to_ros_image(self, cv_image):
4640
try:

camera_data/src/camera_subscriber.py

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,8 @@
11
import os, sys
2-
from pydoc_data.topics import topics
32
currentdir = os.path.dirname(os.path.realpath(__file__))
43
sys.path.append(currentdir)
4+
55
import rospy
6-
currentdir = os.path.dirname(os.path.realpath(__file__))
7-
sys.path.append(currentdir)
86
import cv2
97
from sensor_msgs.msg import Image
108
from cv_bridge import CvBridge
@@ -34,4 +32,4 @@ def ros_to_openCV_image(self, ros_image):
3432

3533
if __name__ == "__main__":
3634
driver = Node_CameraFrameSub()
37-
rospy.spin()
35+
rospy.spin()

camera_data/src/getCameraFeeds.py

Lines changed: 23 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -2,44 +2,41 @@
22

33

44
class CameraHandler:
5-
vids = [] # available cameras
5+
available_cameras = []
66

77
def __init__(self):
8-
# Loop 25 times and collect all found cameras
8+
# Collect all found cameras
99
# Assumes sequential indices
1010
for i in range (25):
1111
newCap = cv2.VideoCapture(i, cv2.CAP_V4L2)
1212

13-
if newCap is not None:
14-
newCap.open(i)
15-
16-
# check if object is not null
17-
if newCap is not None and newCap.isOpened():
18-
# add the camera found
19-
self.vids.append(newCap)
13+
if newCap is not None and newCap.open(i):
14+
self.available_cameras.append(newCap)
2015

2116
def get_all_feeds(self):
2217
retAndFrame = []
2318
# read each capture object in vids and add as a tuple to retAndFrame
24-
for i in range(len(self.vids)):
25-
newFeed = self.vids[i].read()
26-
retAndFrame.append((newFeed[0], newFeed[1], i))
19+
for camera in self.available_cameras:
20+
newFeed = camera.read()
21+
retAndFrame.append((newFeed[0], newFeed[1]))
2722

2823
return retAndFrame
2924

30-
# # Runnable for displaying camera feeds
25+
def run_feeds(self):
26+
while True:
27+
# display each frame (camera feed) in the list
28+
for index, (ret, frame) in enumerate(self.get_all_feeds()):
29+
if ret:
30+
cv2.imshow(f"frame {index}", frame)
31+
32+
# press 'q' to stop displaying
33+
if cv2.waitKey(1) & 0xFF == ord('q'):
34+
for vid in self.available_cameras:
35+
vid.release()
36+
cv2.destroyAllWindows()
37+
break
38+
39+
# Runnable to display camera feeds
3140
if __name__ == '__main__':
3241
camHandler = CameraHandler()
33-
while True:
34-
retAndFrame = camHandler.get_all_feeds()
35-
# display each frame (camera feed) in the list
36-
for ret, frame, index in retAndFrame:
37-
if ret:
38-
cv2.imshow(f"frame {index}", frame)
39-
40-
# press 'q' to stop displaying
41-
if cv2.waitKey(1) & 0xFF == ord('q'):
42-
for vid in camHandler.vids:
43-
vid.release()
44-
cv2.destroyAllWindows()
45-
break
42+
camHandler.run_feeds()

camera_data/test/test_getCam.py

Lines changed: 2 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
import cv2
21
import sys
32
import os
43

@@ -9,18 +8,6 @@
98

109
import getCameraFeeds as gcf
1110

12-
# Runnable for displaying camera feeds
11+
# Runnable to display camera feeds
1312
camHandler = gcf.CameraHandler()
14-
while True:
15-
retAndFrame = camHandler.get_all_feeds()
16-
# display each frame (camera feed) in the list
17-
for ret, frame, index in retAndFrame:
18-
cv2.imshow(f"frame {index}", frame)
19-
20-
# press 'q' to stop displaying
21-
if cv2.waitKey(1) & 0xFF == ord('q'):
22-
for vid in camHandler.vids:
23-
vid.release()
24-
cv2.destroyAllWindows()
25-
break
26-
13+
camHandler.run_feeds()

0 commit comments

Comments
 (0)