tilt_scan_to_pointcloud.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import roslib; roslib.load_manifest('external_camera_localizer')
00003 
00004 from laser_assembler.srv import AssembleScans
00005 from sensor_msgs.msg import PointCloud
00006 import rospy
00007 
00008 if __name__ == '__main__':
00009         rospy.init_node('tilt_scan_to_pointcloud')
00010         rospy.wait_for_service('assemble_scans')
00011         assemble_scans = rospy.ServiceProxy('assemble_scans', AssembleScans)
00012         cloud_pub = rospy.Publisher('laser_cloud', PointCloud)
00013         loop_rate = rospy.Rate(10)
00014         while not rospy.is_shutdown():
00015                 try:
00016                         resp = assemble_scans(rospy.Time(0), rospy.Time.now())
00017                         cloud_pub.publish(resp.cloud)
00018                         loop_rate.sleep()
00019                 except rospy.ServiceException, e:
00020                         rospy.logerr('Failed to assemble scans: %s' % e)


external_camera_localizer
Author(s): Daniel Lazewatsky
autogenerated on Mon Oct 6 2014 10:07:41