static_virtual_camera.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
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 from sensor_msgs.msg import CameraInfo
00016 
00017 
00018 def timer_cb(event):
00019     imgmsg.header.stamp = rospy.Time.now()
00020     info_msg.header.stamp = imgmsg.header.stamp
00021     pub_img.publish(imgmsg)
00022     pub_info.publish(info_msg)
00023 
00024 
00025 if __name__ == '__main__':
00026     rospy.init_node('static_virtual_camera')
00027 
00028     pub_img = rospy.Publisher('~image_color', Image, queue_size=1)
00029     pub_info = rospy.Publisher('~camera_info', CameraInfo, queue_size=1)
00030 
00031     bridge = cv_bridge.CvBridge()
00032     imgmsg = bridge.cv2_to_imgmsg(img, encoding='bgr8')
00033     imgmsg.header.frame_id = 'static_virtual_camera'
00034 
00035     info_msg = CameraInfo()
00036     info_msg.header.frame_id = imgmsg.header.frame_id
00037     height, width = img.shape[:2]
00038     info_msg.height = height
00039     info_msg.width = width
00040 
00041     rospy.Timer(rospy.Duration(0.1), timer_cb)
00042     rospy.spin()


jsk_recognition_utils
Author(s):
autogenerated on Sun Oct 8 2017 02:42:48