$search
00001 #!/usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('nxt_assisted_teleop') 00004 import nxt.locator 00005 import rospy 00006 import math 00007 import thread 00008 from sensor_msgs.msg import PointCloud 00009 from nxt_msgs.msg import Range 00010 from geometry_msgs.msg import Point32 00011 from math import sin, cos 00012 00013 class Converter: 00014 def __init__(self): 00015 self.sub = rospy.Subscriber('range_topic', Range, self.sub_cb) 00016 self.pub = rospy.Publisher('cloud_topic', PointCloud) 00017 00018 def sub_cb(self, msg): 00019 pnt = PointCloud() 00020 pnt.header = msg.header 00021 angle_step = 1.0/(msg.range*100.0) 00022 angle = -msg.spread_angle 00023 if msg.range < msg.range_max and msg.range > msg.range_min: 00024 while angle < msg.spread_angle: 00025 pnt.points.append(Point32(msg.range*cos(angle), msg.range*sin(angle), 0)) 00026 angle += angle_step 00027 self.pub.publish(pnt) 00028 00029 def main(): 00030 rospy.init_node('range_to_pointcloud') 00031 converter = Converter() 00032 rospy.spin() 00033 00034 00035 00036 if __name__ == '__main__': 00037 main()