sample_laser_scan_assembler_client.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import division
4 
5 from laser_assembler.srv import AssembleScans2
6 import rospy
7 from sensor_msgs.msg import PointCloud2
8 
9 
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():
16  try:
17  srv_caller = rospy.ServiceProxy('~assemble_scans2', AssembleScans2)
18  res = srv_caller(rospy.Time(0), rospy.Time.now())
19  pub.publish(res.cloud)
20  except rospy.ServiceException as e:
21  rospy.logwarn('Service call failed:\n{}'.format(e))
22 
23  try:
24  r.sleep()
25  except rospy.ROSTimeMovedBackwardsException:
26  pass


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47