image_subscriber.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 # BSD 3-Clause License
3 
4 # Copyright (c) 2019, Noam C. Golombek
5 # All rights reserved.
6 
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions are met:
9 
10 # 1. Redistributions of source code must retain the above copyright notice, this
11 # list of conditions and the following disclaimer.
12 
13 # 2. Redistributions in binary form must reproduce the above copyright notice,
14 # this list of conditions and the following disclaimer in the documentation
15 # and/or other materials provided with the distribution.
16 
17 # 3. Neither the name of the copyright holder nor the names of its
18 # contributors may be used to endorse or promote products derived from
19 # this software without specific prior written permission.
20 
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31 
32 import timeit
33 import numpy as np
34 import cv2
35 
36 import rospy
37 from cv_bridge import CvBridge, CvBridgeError
38 from sensor_msgs.msg import Image, CompressedImage
39 
40 class ImageSubscriber(object):
41  '''A class to subscribe to a ROS camera'''
42 
43  def __init__(self, topic="usb_cam/image_raw"):
44  '''Initialize ros publisher, ros subscriber'''
45 
46  self.currentImage = None
47  self.currentHeader = None
48  self.compressed = True if "compressed" in topic else False
49  self.frame_count = 0
50  self.start_time = timeit.default_timer()
51 
52  if not self.compressed:
53  self.bridge = CvBridge()
54  self.subscriber = rospy.Subscriber(topic,
55  Image, self.callback, queue_size=1)
56  else:
57  self.subscriber = rospy.Subscriber(
58  topic, CompressedImage, self.callback, queue_size=1)
59 
60  def callback(self, ros_data):
61  '''Callback function of subscribed topic.
62  Here images get converted to cv2 format'''
63 
64  if not self.compressed:
65  self.currentImage = cv2.resize(
66  self.bridge.imgmsg_to_cv2(ros_data, "rgb8"),
67  (640, 480))
68  else:
69  np_arr = np.fromstring(ros_data.data, np.uint8)
70  image_np = cv2.imdecode(np_arr, 1)
71 
72  self.currentImage = cv2.cvtColor(image_np, cv2.COLOR_BGR2RGB)
73 
74  self.currentHeader = ros_data.header
75 
76  self.frame_count += 1
def __init__(self, topic="usb_cam/image_raw")


cnn_bridge
Author(s): Noam C. Golombek , Alexander Beringolts
autogenerated on Mon Jun 10 2019 12:53:26