12 from cv_bridge
import CvBridge
16 sub_lock = threading.Lock()
19 context.register_handler(
"/image", image_handler)
24 img = bridge.imgmsg_to_cv(msg,
"bgr8")
25 data = cv.EncodeImage(
".jpeg", img).tostring()
28 images[topic].append(data)
34 topic = qdict.get(
'topic', [
''])[0]
37 m = roslib.scriptutil.get_master()
38 code, _, topics = m.getPublishedTopics(
'/'+rosweb.PKG_NAME,
'/')
42 for t, topic_type
in topics:
48 msg_class = roslib.message.get_message_class(topic_type)
50 if topic
in subscriptions:
51 cond = subscriptions[topic][1]
53 cond = threading.Condition()
55 subscriptions[topic] = (rospy.Subscriber(topic, msg_class, image_callback, (topic, cond)), cond)
58 self.send_response(200)
59 self.send_header(
'Content-Type',
'multipart/x-mixed-replace; boundary=--myboundary')
63 while len(images[topic]) == 0:
67 if len(images[topic]) > 0:
68 data = images[topic][-1]
70 self.wfile.write(
'--myboundary\r\n')
71 self.wfile.write(
'Content-Type: image/jpeg\r\n')
72 self.wfile.write(
'Content-Length: %s\r\n' % len(data))
73 self.wfile.write(
'\r\n')
74 self.wfile.write(data)
def config_plugin(context)
def image_callback(msg, t)
def image_handler(self, path, qdict)