How to speed up the video stream publishing?

asked 2018-12-11 01:25:19 -0500

Hunter gravatar image

I have just write a simple node to publish the video that captured from the picamera on a topic, and another node that subscribe to that topic to get the video. But the delay is large, about 5s or more. Anyone can tell me how to optimize the code to speed up the procedure.

environment: raspi3 with camera module; ubuntu mate 16; ROS kinetic.

publisher.py

import time
import rospy
from sensor_msgs.msg import Image
from picamera.array import PiRGBArray
from picamera import PiCamera
import cv2
from cv_bridge import CvBridge, CvBridgeError
import pdb

def hentai():
        camera = PiCamera()
        camera.resolution = (640, 480)
        camera.framerate = 30
        rawCapture = PiRGBArray(camera, size=(640, 480))
        time.sleep(0.1)
        rospy.init_node('kuroko', anonymous=True)
        pub = rospy.Publisher('line', Image, queue_size=100)
        rate = rospy.Rate(30)
        bridge = CvBridge()
        while not rospy.is_shutdown():
                rospy.loginfo("start capturing video from picamera.")
                for frame in camera.capture_continuous(rawCapture, format='bgr', use_video_port=True):
                        image = frame.array
                        image_ros = bridge.cv2_to_imgmsg(image, encoding="bgr8")
                        pub.publish(image_ros)
                        rawCapture.truncate(0)
                rate.sleep()

if __name__ == '__main__':
        hentai()

subscriber.py

#!/usr/bin/env python
import rospy
from std_msgs.msg import String
from sensor_msgs.msg import Image
import cv2
import pdb
from cv_bridge import CvBridge, CvBridgeError

def callback(msg):
        bridge = CvBridge()
        cv_image = bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8")

        cv2.imshow("frame", cv_image)
        if cv2.waitKey(1) & 0xFF == ord('q'):
                rospy.loginfo("finished.")

def levelfive():
        rospy.init_node('mikoto', anonymous=False)
        sub = rospy.Subscriber('line', Image, callback)
        rospy.spin()
        cv2.destoryAllWindows()

if __name__ == '__main__':
        levelfive()
edit retag flag offensive close merge delete

Comments

1

Are you viewing the video on a different computer possibly over wi-fi? The biggest improvement you can make would be to used the compressed image transport.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-12-11 05:42:12 -0500 )edit

Actually no. The two nodes were running on the same raspi. Thank you for your advice. I will check the compressed image transport that you mentioned.

Hunter gravatar image Hunter  ( 2018-12-11 23:28:38 -0500 )edit