Go to the documentation of this file.00001
00002 import sys
00003
00004 import cv2
00005 import glob
00006 import rospkg
00007 import rospy
00008 from sensor_msgs.msg import Image, CompressedImage
00009 from cv_bridge import CvBridge, CvBridgeError
00010
00011 class image_pub():
00012 def __init__(self):
00013 rospy.init_node("image_pub")
00014 rospack = rospkg.RosPack()
00015 self.images = glob.glob(rospack.get_path('rail_object_detector') + '/libs/darknet/data/*.jpg')
00016 self.rate = rospy.get_param('~rate', default=1)
00017 self.image_topic = rospy.Publisher('/kinect/qhd/image_color_rect', Image, queue_size=2)
00018 self.bridge = CvBridge()
00019
00020 def run(self):
00021 rate = rospy.Rate(self.rate)
00022 while not rospy.is_shutdown():
00023 for image in self.images:
00024 img = cv2.imread(image)
00025 image_msg = self.bridge.cv2_to_imgmsg(img, "bgr8")
00026 self.image_topic.publish(image_msg)
00027 rate.sleep()
00028
00029 if __name__ == '__main__':
00030 pubber = image_pub()
00031 pubber.run()