app.py 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. #!/usr/bin/env python
  2. # coding: utf-8
  3. import rospy
  4. from std_msgs.msg import String, Header
  5. import message_filters
  6. from sensor_msgs.msg import PointCloud2, PointField
  7. import sensor_msgs.point_cloud2 as pc2
  8. from geometry_msgs.msg import PoseStamped, Point32
  9. import math
  10. import time
  11. import pcl
  12. import pprint
  13. pp = pprint.PrettyPrinter(indent=2)
  14. class PC2DownSampler(object):
  15. def __init__(self):
  16. self.__previous_time = time.time()
  17. self.__period = None # [sec]
  18. self.__frame_id = None
  19. self.__leaf_size = None
  20. def callback(self, raw_data, republisher):
  21. current_time = time.time()
  22. if self.__period < current_time - self.__previous_time:
  23. self.__previous_time += (1+int((current_time - self.__previous_time)/self.__period)) * self.__period
  24. points = []
  25. for point in pc2.read_points(raw_data):
  26. points.append(list(point[0:3]))
  27. points_map_pcl = pcl.PointCloud(points)
  28. pc_filter = points_map_pcl.make_voxel_grid_filter()
  29. pc_filter.set_leaf_size(*self.__leaf_size)
  30. points_map_pcl = pc_filter.filter()
  31. header = Header()
  32. header.stamp = rospy.Time.now()
  33. header.frame_id = self.__frame_id
  34. downsampled_data = pc2.create_cloud_xyz32(header, points_map_pcl.to_list())
  35. republisher.publish(downsampled_data)
  36. def setup(self, topic_name, period=1.0, frame_id="world", leaf_size=(10.0, 10.0, 10.0), latch=False):
  37. self.__period = period
  38. self.__frame_id = frame_id
  39. self.__leaf_size = leaf_size
  40. topic_name = topic_name if topic_name[0] != "/" else topic_name[1:]
  41. pc2_subscriber = message_filters.Subscriber('/{}'.format(topic_name), PointCloud2)
  42. pc2_republisher = rospy.Publisher('/downsampled_{}'.format(topic_name), PointCloud2, queue_size=3, latch=latch)
  43. pc2_subscriber.registerCallback(self.callback, pc2_republisher)
  44. if __name__ == '__main__':
  45. rospy.init_node("pc2_downsampler", anonymous=True)
  46. PC2DownSampler().setup("/points_map", 1.5, frame_id="map", leaf_size=(10.0, 10.0, 25.0), latch=True)
  47. PC2DownSampler().setup("/points_raw", 1.0, frame_id="velodyne", leaf_size=(0.5, 0.5, 0.5))
  48. rospy.spin()