3 from __future__
import division
5 from laser_assembler.srv
import AssembleScans2
7 from sensor_msgs.msg
import PointCloud2
10 if __name__ ==
'__main__':
11 rospy.init_node(
'sample_laser_scan_assembler_client')
12 pub = rospy.Publisher(
'~output', PointCloud2, queue_size=1)
13 rospy.wait_for_service(
'~assemble_scans2')
14 r = rospy.Rate(rospy.get_param(
'~rate', 1.0))
15 while not rospy.is_shutdown():
17 srv_caller = rospy.ServiceProxy(
'~assemble_scans2', AssembleScans2)
19 pub.publish(res.cloud)
20 except rospy.ServiceException
as e:
21 rospy.logwarn(
'Service call failed:\n{}'.format(e))
25 except rospy.ROSTimeMovedBackwardsException: