Go to the documentation of this file.00001
00002
00003 import rospy
00004 from sensor_msgs.msg import Image, CameraInfo
00005
00006 rospy.init_node("dummy_camera")
00007
00008 pub = rospy.Publisher("~image", Image)
00009 pub_info = rospy.Publisher("~camera_info", CameraInfo)
00010 frame_id = rospy.get_param('~frame_id', 'dummy_camera')
00011 width = rospy.get_param('~width', 640)
00012 height = rospy.get_param('~height', 480)
00013
00014 r = rospy.Rate(10)
00015 while not rospy.is_shutdown():
00016 now = rospy.Time(0)
00017 dummy_camera_info = CameraInfo()
00018 dummy_camera_info.width = width
00019 dummy_camera_info.height = height
00020 dummy_camera_info.header.frame_id = frame_id
00021 dummy_camera_info.header.stamp = now
00022 dummy_camera_info.D = [0.0, 0.0, 0.0, 0.0, 0.0]
00023 dummy_camera_info.K = [525.0, 0.0, 319.5, 0.0, 525.0, 239.5, 0.0, 0.0, 1.0]
00024 dummy_camera_info.R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
00025 dummy_camera_info.P = [525.0, 0.0, 319.5, 0.0, 0.0, 525.0, 239.5, 0.0, 0.0, 0.0, 1.0, 0.0]
00026 dummy_camera_info.distortion_model = "plumb_bob"
00027 pub_info.publish(dummy_camera_info)
00028
00029 dummy_img = Image()
00030 dummy_img.width = width
00031 dummy_img.height = height
00032 dummy_img.header.frame_id = frame_id
00033 dummy_img.header.stamp = now
00034 dummy_img.step = width
00035 dummy_img.encoding = "mono8"
00036 dummy_img.data = [0] * width * height
00037 pub.publish(dummy_img)
00038 r.sleep()