Go to the documentation of this file.00001
00002
00003 PKG = 'laser_filters'
00004 import roslib; roslib.load_manifest(PKG)
00005
00006 import rospy
00007 from sensor_msgs.msg import LaserScan
00008 from Numeric import ones
00009
00010 def laser_test():
00011 pub = rospy.Publisher('laser_scan', LaserScan)
00012 rospy.init_node('laser_test')
00013 laser_msg = LaserScan()
00014
00015 laser_msg.header.frame_id = 'laser'
00016 laser_msg.angle_min = -1.5
00017 laser_msg.angle_max = 1.5
00018 laser_msg.angle_increment = 0.1
00019 laser_msg.time_increment = 0.1
00020 laser_msg.scan_time = 0.1
00021 laser_msg.range_min = 0.5
00022 laser_msg.range_max = 1.5
00023 laser_msg.ranges = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 9.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.1, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 5.0, 1.0]
00024 laser_msg.intensities = laser_msg.ranges
00025
00026 r = rospy.Rate(10)
00027 while not rospy.is_shutdown():
00028 laser_msg.header.stamp = rospy.get_rostime()
00029 pub.publish(laser_msg)
00030 r.sleep()
00031
00032
00033 if __name__ == '__main__':
00034 try:
00035 laser_test()
00036 except rospy.ROSInterruptException: pass
00037
00038
00039