laser_camera_fov_sample.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 from sensor_msgs.msg import CameraInfo, PointCloud2
00005 
00006 if __name__ == "__main__":
00007     rospy.init_node("laser_camera_fov_sample")
00008     pub_info = rospy.Publisher("~info", CameraInfo)
00009     pub_cloud = rospy.Publisher("~cloud", PointCloud2)
00010     rate = rospy.Rate(1)
00011     while not rospy.is_shutdown():
00012         info = CameraInfo()
00013         info.header.stamp = rospy.Time.now()
00014         info.header.frame_id = "origin"
00015         info.height = 544
00016         info.width = 1024
00017         info.D = [-0.20831339061260223, 0.11341656744480133,
00018                   -0.00035378438769839704, -1.746419547998812e-05,
00019                   0.013720948249101639, 0.0, 0.0, 0.0]
00020         info.K = [598.6097412109375, 0.0, 515.5960693359375,
00021                   0.0, 600.0813598632812, 255.42999267578125,
00022                   0.0, 0.0, 1.0]
00023         info.R = [0.999993085861206, 0.0022128731943666935, -0.0029819998890161514,
00024                   -0.0022144035901874304, 0.9999974370002747, -0.0005100672133266926,
00025                   0.002980863442644477, 0.0005166670307517052, 0.9999954104423523]
00026         info.P = [575.3445434570312, 0.0, 519.5, 0.0,
00027                   0.0, 575.3445434570312, 259.5, 0.0,
00028                   0.0, 0.0, 1.0, 0.0]
00029         pub_info.publish(info)
00030         cloud = PointCloud2()
00031         cloud.header.frame_id = "origin"
00032         pub_cloud.publish(cloud)
00033         rate.sleep()


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49