Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

The "leak" is mainly a timing issue on slow CPUs #16

Open
wants to merge 26 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
1f1eb84
Prevent locking when ROS SIGINT arrives and the image queue is empty.
Apr 10, 2018
30926ca
The leak in reality is a 1000 slots queue slowly filling up because c…
4ndr3aR Apr 11, 2018
d66e686
Added ncurses to have the pause option just pressing P at any moment
4ndr3aR Jul 6, 2018
53454c4
Added ncurses to have the pause option just pressing P at any moment
4ndr3aR Jul 6, 2018
7cff42c
Made ncurses conditional via #ifdef macro. Also lost a lot of time be…
4ndr3aR Sep 17, 2018
857fbd1
Added mjpeg-stream-to-ros-topic.py to directly publish mjpeg frames w…
4ndr3aR Sep 18, 2018
f591245
Added variable quality republisher, seems to work ok...
4ndr3aR Sep 18, 2018
8b2f2ae
Cleaned up...
4ndr3aR Sep 18, 2018
daa9314
Trying to speed up original jpeg publishing...
4ndr3aR Sep 18, 2018
138dc18
Trying to speed up original jpeg publishing, tomorrow maybe...
4ndr3aR Sep 18, 2018
5d67de4
Trying to speed up original jpeg publishing, again...
4ndr3aR Sep 19, 2018
5ad2ea9
Trying to speed up original jpeg publishing, larger buffer...
4ndr3aR Sep 19, 2018
28140a5
Trying to speed up original jpeg publishing, variable larger buffer...
4ndr3aR Sep 19, 2018
370ab26
Mmm leaving it this way...
4ndr3aR Sep 19, 2018
9f7c881
Not publishing the _low_qual topic if jpeg_quality == 0
4ndr3aR Sep 19, 2018
ce03919
Variable larger buffer, now via argv parameter!
4ndr3aR Sep 19, 2018
dc202bd
Mmm fixed a femto bug with show_gui showing because roslaunch passes …
4ndr3aR Sep 19, 2018
27232e3
MmmGh, forgot python syntax
4ndr3aR Sep 19, 2018
ef54b8a
Added mjpg_stream_python.launch to launch the new python script to co…
4ndr3aR Sep 19, 2018
f2883db
Replaced argv parsing with ArgumentParser and now publishing also Cam…
4ndr3aR Sep 19, 2018
5db96b5
Made caminfo_file actually optional because it makes no sense for a 6…
4ndr3aR Sep 19, 2018
1c84778
Made --verbose and --caminfo_file option shorter (-v and -c) and chan…
4ndr3aR Sep 19, 2018
fbd10dd
Now ignoring unknown arguments (passed by ROS)
4ndr3aR Sep 19, 2018
1b12b99
Python doesn't know the meaning of ~ (tilde), let's pass the $HOME en…
4ndr3aR Sep 19, 2018
e567cfb
Cleaned up...
4ndr3aR Sep 19, 2018
3b63a78
Switched to OpenCV 4
4ndr3aR Sep 21, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 7 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
cmake_minimum_required(VERSION 2.8.3)
project(video_stream_opencv)

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g3 -O0 -std=c++11")

find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
Expand All @@ -10,8 +12,8 @@ find_package(catkin REQUIRED COMPONENTS
sensor_msgs
)


find_package(OpenCV)
find_package(OpenCV REQUIRED)
find_package(Curses REQUIRED)

catkin_package()

Expand All @@ -20,8 +22,10 @@ include_directories(
${OpenCV_INCLUDE_DIRS}
)

message("CURSES_LIBRARIES: ${CURSES_LIBRARIES}")

add_executable(video_stream src/video_stream.cpp)
target_link_libraries(video_stream ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
target_link_libraries(video_stream ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${CURSES_LIBRARIES})

install(TARGETS video_stream
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
Expand Down
3 changes: 2 additions & 1 deletion launch/camera.launch
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,8 @@

<!-- images will be published at /camera_name/image with the image transports plugins (e.g.: compressed) installed -->
<group ns="$(arg camera_name)">
<node pkg="video_stream_opencv" type="video_stream" name="$(arg camera_name)_stream" output="screen">
<!-- node pkg="video_stream_opencv" type="video_stream" name="$(arg camera_name)_stream" output="screen" launch-prefix="gnome-terminal - -maximize -x gdb - -args"-->
<node pkg="video_stream_opencv" type="video_stream" name="$(arg camera_name)_stream" output="screen">
<remap from="camera" to="image_raw" />
<param name="camera_name" type="string" value="$(arg camera_name)" />
<param name="video_stream_provider" type="string" value="$(arg video_stream_provider)" />
Expand Down
59 changes: 59 additions & 0 deletions launch/mjpg_stream_python.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
<?xml version="1.0"?>
<launch>

<arg name="camera_name" default="vivotek" />
<arg name="full_hd_stream" default="full_hd" />
<arg name="low_qual_stream" default="low_qual" />

<!-- images will be published at /camera_name/... -->
<group ns="$(arg camera_name)">

<!--

rosrun video_stream_opencv mjpeg-stream-to-ros-topic.py http://vivotek-0:8080/video.mjpg /vivotek_0_full_hd 0 409600
rosrun video_stream_opencv mjpeg-stream-to-ros-topic.py http://vivotek-0:8080/video3.mjpg /vivotek_0_low_qual 0 4096

rosrun video_stream_opencv mjpeg-stream-to-ros-topic.py http://vivotek-0:8080/video3.mjpg /vivotek_0_low_qual 4096 - -caminfo_file ~/.ros/camera_info/vivotek_IB8168_C.yaml

-->

<!-- images will be published at /camera_name/full_hd/... -->
<group ns="$(arg full_hd_stream)">
<!-- URL of the stream (e.g. http://vivotek-0:8080/video.mjpg or http://vivotek-0:8080/video3.mjpg or http://iris.not.iac.es/axis-cgi/mjpg/video.cgi?resolution=320x240 or whatever -->
<arg name="video_stream_url" default="http://vivotek-0:8080/video.mjpg" />
<!-- set the python socket receiving buffer: it's very important to set a read rate as close as possible to the expected frame size to optimize the (poor) python performance.
If unsure, enable the printing of statistics inside the script to have an idea of the size of the received images. -->
<arg name="buffer_queue_size" default="409600" />
<!-- topic name: will be preceded by group names and followed by /compressed -->
<arg name="topic_name" default="image" />
<!-- low_quality republishing % - leave it to 0 to avoid republishing... it's a job already done by the Vivotek itself -->
<arg name="jpeg_quality" default="0" />
<!-- the camera info file to also publish image resolution and rectification parameters along image topics -->
<!-- arg name="caminfo_file" default="~/.ros/camera_info/camera.yaml" / -->
<arg name="caminfo_file" default="$(optenv HOME)/.ros/camera_info/vivotek_IB8168_C.yaml"/>

<node pkg="video_stream_opencv" type="mjpeg-stream-to-ros-topic.py" args="$(arg video_stream_url) $(arg topic_name) $(arg buffer_queue_size) -c $(arg caminfo_file)"
name="mjpeg_stream_python_$(arg camera_name)_$(arg full_hd_stream)" output="screen">
</node>
</group>

<!-- images will be published at /camera_name/low_qual/... -->
<group ns="$(arg low_qual_stream)">
<!-- URL of the stream (e.g. http://vivotek-0:8080/video.mjpg or http://vivotek-0:8080/video3.mjpg or http://iris.not.iac.es/axis-cgi/mjpg/video.cgi?resolution=320x240 or whatever -->
<arg name="video_stream_url" default="http://vivotek-0:8080/video3.mjpg" />
<!-- set the python socket receiving buffer: it's very important to set a read rate as close as possible to the expected frame size to optimize the (poor) python performance.
If unsure, enable the printing of statistics inside the script to have an idea of the size of the received images. -->
<arg name="buffer_queue_size" default="4096" />
<!-- topic name: will be preceded by group names and followed by /compressed -->
<arg name="topic_name" default="image" />
<!-- low_quality republishing % - leave it to 0 to avoid republishing... it's a job already done by the Vivotek itself -->
<arg name="jpeg_quality" default="0" />

<node pkg="video_stream_opencv" type="mjpeg-stream-to-ros-topic.py" args="$(arg video_stream_url) $(arg topic_name) $(arg buffer_queue_size)"
name="mjpeg_stream_python_$(arg camera_name)_$(arg low_qual_stream)" output="screen">
</node>
</group>

</group>

</launch>
28 changes: 28 additions & 0 deletions launch/video_file_jpg.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>
<launch>
<!-- launch video stream -->
<include file="$(find video_stream_opencv)/launch/camera.launch" >
<!-- node name and ros graph name -->
<arg name="camera_name" value="videofile" />
<!-- full path to the video file -->
<!-- wget http://techslides.com/demos/sample-videos/small.mp4 -O /tmp/small.mp4 -->
<arg name="video_stream_provider" value="/tmp/test.jpg" />
<!-- set camera fps to (video files not affected) -->
<!-- <arg name="set_camera_fps" value="30"/> -->
<!-- set buffer queue size of frame capturing to -->
<arg name="buffer_queue_size" value="1000" />
<!-- throttling the querying of frames to -->
<arg name="fps" value="30" />
<!-- setting frame_id -->
<arg name="frame_id" value="videofile_frame" />
<!-- camera info loading, take care as it needs the "file:///" at the start , e.g.:
"file:///$(find your_camera_package)/config/your_camera.yaml" -->
<arg name="camera_info_url" value="" />
<!-- flip the image horizontally (mirror it) -->
<arg name="flip_horizontal" value="false" />
<!-- flip the image vertically -->
<arg name="flip_vertical" value="false" />
<!-- visualize on an image_view window the stream generated -->
<arg name="visualize" value="true" />
</include>
</launch>
138 changes: 138 additions & 0 deletions src/mjpeg-stream-to-ros-topic.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
#!/usr/bin/env python
# coding=UTF-8

import cv2
import urllib
import numpy as np

import roslib
roslib.load_manifest('video_stream_opencv')
import signal
import sys
import time
import rospy
import yaml
import argparse

from cv_bridge import CvBridge, CvBridgeError
#from sensor_msgs.msg import Image
from sensor_msgs.msg import CompressedImage
from sensor_msgs.msg import CameraInfo

print(sys.version)
print(sys.argv)

#args.topic_name = 'mjpeg_publisher'
#args.stream_url = 'http://iris.not.iac.es/axis-cgi/mjpg/video.cgi?resolution=320x240'
#args.jpeg_quality = 40
#args.est_image_size = 409600
#args.show_gui = False
#args.verbose = True
#args.caminfo_file = '/home/biagio/.ros/camera_info/vivotek_IB8168_C.yaml'

parser = argparse.ArgumentParser(description='Given a MJPEG HTTP stream, this node publishes a CompressedImage (and its CameraInfo) topics.')
parser.add_argument('stream_url', help='The MJPEG URL', metavar='http://vivotek-0:8080/video3.mjpg',
default='http://vivotek-0:8080/video.mjpg')
parser.add_argument('topic_name', help='The output topic', metavar='image',
default='vivotek_0')
parser.add_argument('-q', help='The jpeg quality for an optional republish', dest='jpeg_quality', type=int,
metavar='40')
parser.add_argument('est_image_size', help='The estimated image size, to optimize recv speed', type=int,
metavar='409600')
parser.add_argument('--show_gui', help='Show the images that are being received', dest='show_gui', type=bool,
metavar=False, default=False)
parser.add_argument('-v', help='Be more verbose', dest='verbose', type=bool,
metavar=False, default=False)
parser.add_argument('-c', help='Camera info file', metavar='~/.ros/camera_info/camera.yaml', dest='caminfo_file', default='')

args, unknown = parser.parse_known_args()

print("URL: ", args.stream_url, "Output topic: ", args.topic_name, "Est. image size: ", args.est_image_size, "Camera info file: ", args.caminfo_file, "Jpeg quality: ", args.jpeg_quality, "Show GUI: ", args.show_gui, "Verbose: ", args.verbose)


def parse_calibration_yaml(calib_file):
with file(calib_file, 'r') as f:
params = yaml.load(f)

cam_info = CameraInfo()
cam_info.header.frame_id = params['camera_name']
cam_info.height = params['image_height']
cam_info.width = params['image_width']
cam_info.distortion_model = params['distortion_model']
cam_info.K = params['camera_matrix']['data']
cam_info.D = params['distortion_coefficients']['data']
cam_info.R = params['rectification_matrix']['data']
cam_info.P = params['projection_matrix']['data']

return cam_info


stream = urllib.urlopen(args.stream_url)

rospy.init_node('mjpeg_stream_to_ros_topic', anonymous=True)
mjpeg_publisher = rospy.Publisher (args.topic_name + '/compressed' , CompressedImage, queue_size = 1)
if args.jpeg_quality > 0:
low_qual_republisher = rospy.Publisher (args.topic_name + '_low_qual' + '/compressed', CompressedImage, queue_size = 1)

if args.caminfo_file != '':
cam_pub = rospy.Publisher("camera_info", CameraInfo, queue_size = 1)
cam_info = parse_calibration_yaml(args.caminfo_file)
else:
cam_pub = None

def signal_handler(sig, frame):
print('Ctrl+C pressed, exiting...')
sys.exit(0)

def jpeg_publisher(data, publisher, cam_pub = None):
stamp = rospy.Time.now()
if cam_pub is not None:
cam_info.header.stamp = stamp
# publish the camera info messages first
cam_pub.publish(cam_info)
#### Create CompressedIamge ####
msg = CompressedImage()
msg.header.stamp = stamp
msg.format = "jpeg"
#msg.format = "rgb8; jpeg compressed bgr8"
#msg.data = np.array(cv2.imencode('.jpg', self.last_img)[1]).tostring()
msg.data = data.tostring()
# Publish new image
publisher.publish(msg)



signal.signal(signal.SIGINT, signal_handler)
print('Press Ctrl+C to quit')

bytes = ''
a = b = -1
while True:
bytes += stream.read(args.est_image_size)
if a == -1:
a = bytes.find('\xff\xd8')
if b == -1:
b = bytes.find('\xff\xd9')
if a != -1 and b != -1:
jpg = bytes[a:b+2]
bytes = bytes[b+2:]
#print("----------------------------------------------------------", a, b, len(bytes))

a = b = -1

numpy_data = np.fromstring(jpg, dtype=np.uint8)
if args.show_gui:
i = cv2.imdecode(numpy_data, cv2.IMREAD_COLOR)
cv2.imshow('img', i)
if cv2.waitKey(1) == 27:
exit(0)

if args.jpeg_quality > 0:
i = cv2.imdecode(numpy_data, cv2.IMREAD_COLOR)
retval, jpeg_data = cv2.imencode('.jpg', i, [cv2.IMWRITE_JPEG_QUALITY, args.jpeg_quality])
if args.verbose:
print("Successful recompression: {} - orig jpeg: {} - recompressed: {}".format(retval, numpy_data.size, jpeg_data.size))
if retval:
jpeg_publisher(jpeg_data, low_qual_republisher)

jpeg_publisher(numpy_data, mjpeg_publisher, cam_pub)
Loading