-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Added test capability for laptop webcam
- Loading branch information
Showing
4 changed files
with
83 additions
and
5 deletions.
There are no files selected for viewing
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,16 @@ | ||
<launch> | ||
<node | ||
pkg="people_tracking" | ||
type="yolo.py" | ||
name="listener" | ||
output="screen" | ||
/> | ||
|
||
<node | ||
pkg="people_tracking" | ||
type="webcam.py" | ||
name="webcam_pub" | ||
output="screen" | ||
/> | ||
|
||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,59 @@ | ||
#!/usr/bin/env python3 | ||
# Basics ROS program to publish real-time streaming | ||
# video from your built-in webcam | ||
# https://automaticaddison.com/working-with-ros-and-opencv-in-ros-noetic/ | ||
|
||
# Import the necessary libraries | ||
import rospy # Python library for ROS | ||
from sensor_msgs.msg import Image # Image is the message type | ||
from cv_bridge import CvBridge # Package to convert between ROS and OpenCV Images | ||
import cv2 # OpenCV library | ||
|
||
|
||
def publish_message(): | ||
# Node is publishing to the video_frames topic using | ||
# the message type Image | ||
pub = rospy.Publisher('video_frames', Image, queue_size=10) | ||
|
||
# Tells rospy the name of the node. | ||
# Anonymous = True makes sure the node has a unique name. Random | ||
# numbers are added to the end of the name. | ||
rospy.init_node('video_pub_py', anonymous=True) | ||
|
||
# Go through the loop 10 times per second | ||
rate = rospy.Rate(30) # 10hz | ||
|
||
# Create a VideoCapture object | ||
# The argument '0' gets the default webcam. | ||
cap = cv2.VideoCapture(0) | ||
|
||
# Used to convert between ROS and OpenCV images | ||
br = CvBridge() | ||
|
||
# While ROS is still running. | ||
while not rospy.is_shutdown(): | ||
|
||
# Capture frame-by-frame | ||
# This method returns True/False as well | ||
# as the video frame. | ||
ret, frame = cap.read() | ||
|
||
if ret == True: | ||
# Print debugging information to the terminal | ||
# rospy.loginfo('publishing video frame') | ||
|
||
# Publish the image. | ||
# The 'cv2_to_imgmsg' method converts an OpenCV | ||
# image to a ROS image message | ||
pub.publish(br.cv2_to_imgmsg(frame)) | ||
|
||
# Sleep just enough to maintain the desired rate | ||
rate.sleep() | ||
|
||
|
||
if __name__ == '__main__': | ||
try: | ||
publish_message() | ||
except rospy.ROSInterruptException: | ||
pass | ||
rospy.spin() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters