pub_random_clouds.py
Go to the documentation of this file.
00001 import roslib; roslib.load_manifest('python_msg_conversions')
00002 import numpy as np
00003 import rospy
00004 from sensor_msgs.msg import PointCloud2
00005 
00006 from python_msg_conversions import pointclouds
00007 
00008 rospy.init_node('pub_random_clouds', anonymous=True)
00009 
00010 pub = rospy.Publisher('/random_clouds', PointCloud2)
00011 
00012 npoints = 1000
00013 
00014 while not rospy.is_shutdown():
00015     points_arr = np.zeros((npoints,), dtype=[
00016         ('x', np.float32),
00017         ('y', np.float32),
00018         ('z', np.float32),
00019         ('r', np.uint8),
00020         ('g', np.uint8),
00021         ('b', np.uint8)])
00022     points_arr['x'] = np.random.random((npoints,))
00023     points_arr['y'] = np.random.random((npoints,))
00024     points_arr['z'] = np.random.random((npoints,))
00025     points_arr['r'] = np.floor(np.random.random((npoints,))*255)
00026     points_arr['g'] = 0
00027     points_arr['b'] = 255
00028 
00029     #print points_arr
00030     cloud_msg = pointclouds.array_to_pointcloud2(points_arr, stamp=rospy.Time.now(), frame_id='/base_link', merge_rgb=True)
00031     pub.publish(cloud_msg)
00032     rospy.sleep(0.001)


python_msg_conversions
Author(s): Jonathan Binney
autogenerated on Thu Jan 2 2014 11:37:16