IE-482-582 / spring2023

5 stars 8 forks source link

Capturing a Webcam Video Stream #12

Open cmurray3 opened 1 year ago

cmurray3 commented 1 year ago

We are going to use/modify the code below to capture the video feed from our laptop cameras (or from another camera connected to our computer).

After verifying that the code works as-is, we'll modify it to filter for certain colors (like yellow).

"""
This script will display the video feed from a camera.

Type `ls /dev/` and look for something that starts with `video`. 
This is likely to be your camera device.  Update the `cap = ` line below
with your camera device.
"""

import numpy as np
import cv2 as cv

cap = cv.VideoCapture('/dev/video0')
# cap = cv.VideoCapture('/dev/video4')

if not cap.isOpened():
    print("Cannot open camera")
    exit()

while True:
    # Capture frame-by-frame
    ret, frame = cap.read()
    # if frame is read correctly ret is True
    if not ret:
        print("Can't receive frame (stream end?). Exiting ...")
        break

    # Our operations on the frame come here
    '''
    # convert to grayscale
    gray = cv.cvtColor(frame, cv.COLOR_BGR2GRAY)
    cv.imshow('frame', gray)
    '''

    # Display the resulting frame
    cv.imshow('frame', frame)

    if cv.waitKey(1) == ord('q'):
        break

# When everything done, release the capture
cap.release()
cv.destroyAllWindows()
print("all done")
cmurray3 commented 1 year ago

We will discuss the attached files today in class, with the aim of streaming a webcam across a local network.

webcam.zip

cmurray3 commented 1 year ago

This is the webcam_subscribe_mask.py script that we created at the end of class today:

#!/usr/bin/env python3

import numpy as np
import cv2
import rospy
from sensor_msgs.msg import CompressedImage

def webcam_callback(msg):
    #### direct conversion to CV2 ####
    # np_arr = np.fromstring(msg.data, np.uint8)
    np_arr = np.frombuffer(msg.data, dtype=np.uint8) # .reshape(self.res_rows, self.res_cols, 3)

    # myNumpyArray = cv2.imdecode(np_arr, cv2.CV_LOAD_IMAGE_COLOR)
    myNumpyArray = cv2.imdecode(np_arr, cv2.IMREAD_COLOR) # OpenCV >= 3.0:

    hsv = cv2.cvtColor(myNumpyArray, cv2.COLOR_BGR2HSV)
    lower_yellow = np.array([(46-30)/2, ((55-30)/100)*255, ((84-30)/100)*255])
    upper_yellow = np.array([(46+30)/2, ((55+30)/100)*255, ((84+30)/100)*255])
    mask = cv2.inRange(hsv, lower_yellow, upper_yellow)
    masked_for_yellow = cv2.bitwise_and(myNumpyArray, myNumpyArray, mask=mask)

    # print(myNumpyArray.shape)
    # cv2.imshow('frame', myNumpyArray)
    cv2.imshow('frame', masked_for_yellow)

    if cv2.waitKey(1) == ord('q'):
        print('quitting')

def main():

    rospy.init_node('webcam_subscribe', anonymous=True)
    subscriber = rospy.Subscriber("/webcam/image_raw/compressed", CompressedImage, webcam_callback,  queue_size = 1)

    try:    
        rospy.spin()
    except KeyboardInterrupt:
        print("Shutting Down")

    cv2.destroyAllWindows()
    print("all done")

if __name__ == '__main__':
    main()