send_range.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import roslib; roslib.load_manifest('rviz')
00004 from sensor_msgs.msg import Range
00005 import rospy
00006 
00007 topic = 'test_range'
00008 publisher = rospy.Publisher(topic, Range)
00009 
00010 rospy.init_node('range_test')
00011 
00012 dist = 3
00013 
00014 while not rospy.is_shutdown():
00015 
00016    r = Range()
00017    r.header.frame_id = "/moon"
00018    r.header.stamp = rospy.Time.now()
00019    
00020    r.radiation_type = 0
00021    r.field_of_view = 2.0/dist
00022    r.min_range = .4
00023    r.max_range = 10
00024    r.range = dist
00025 
00026    publisher.publish( r )
00027 
00028    rospy.sleep(0.1)
00029 
00030    dist += .3
00031    if dist > 10:
00032       dist = 3


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:33