Go to the documentation of this file.00001
00002
00003 import cv2
00004 try:
00005 from scipy.misc import face
00006 img = face()[:, :, ::-1]
00007 except ImportError:
00008 import numpy as np
00009 from scipy.misc import lena
00010 img = cv2.cvtColor(lena().astype(np.uint8), cv2.COLOR_GRAY2BGR)
00011
00012 import cv_bridge
00013 import rospy
00014 from sensor_msgs.msg import Image
00015
00016
00017 def timer_cb(event):
00018 imgmsg.header.stamp = rospy.Time.now()
00019 pub_img.publish(imgmsg)
00020
00021
00022 if __name__ == '__main__':
00023 rospy.init_node('static_image_publisher')
00024
00025 pub_img = rospy.Publisher('~output', Image, queue_size=1)
00026
00027 bridge = cv_bridge.CvBridge()
00028 imgmsg = bridge.cv2_to_imgmsg(img, encoding='bgr8')
00029
00030 rospy.Timer(rospy.Duration(0.1), timer_cb)
00031 rospy.spin()