lidar_viewer.py 2.8 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495
  1. import rclpy
  2. from rclpy.node import Node
  3. from sensor_msgs.msg import PointCloud2
  4. import numpy as np
  5. import open3d as o3d
  6. from pyvistaqt import BackgroundPlotter
  7. import pyvista as pv
  8. import queue
  9. import threading
  10. class LidarViewer(Node):
  11. def __init__(self, data_queue):
  12. super().__init__('lidar_pyvista_viewer')
  13. self.data_queue = data_queue
  14. self.subscription = self.create_subscription(
  15. PointCloud2,
  16. '/rs_lidar/points', # 替换为你的 topic
  17. self.pointcloud_callback,
  18. 10
  19. )
  20. self.get_logger().info('等待点云数据...')
  21. def pointcloud_callback(self, msg):
  22. # 这里只做快速解析,不进行可视化操作!
  23. points = self.pointcloud2_to_array(msg)
  24. if points is not None:
  25. # 将点云放入队列(线程安全)
  26. self.data_queue.put(points)
  27. self.get_logger().info(f'显示 {len(points)} 个点')
  28. def pointcloud2_to_array(self, msg):
  29. # 简化版:假设是 XYZ 格式(根据你的实际格式调整)
  30. try:
  31. data = np.frombuffer(msg.data, dtype=np.float32)
  32. points = data.reshape(-1, 4)[:, :3] # 取 x, y, z
  33. return points
  34. except Exception as e:
  35. self.get_logger().error(f'解析失败: {e}')
  36. return None
  37. def main():
  38. rclpy.init()
  39. data_queue = queue.Queue()
  40. node = LidarViewer(data_queue)
  41. # 启动 ROS 2 spin 线程(非阻塞)
  42. ros_thread = threading.Thread(target=rclpy.spin, args=(node,), daemon=True)
  43. ros_thread.start()
  44. # 初始化 PyVista 可视化(主线程)
  45. plotter = BackgroundPlotter()
  46. plotter.add_axes()
  47. point_cloud_actor = None
  48. try:
  49. while rclpy.ok():
  50. # 从队列取最新点云(非阻塞)
  51. try:
  52. points = data_queue.get_nowait()
  53. cloud = pv.PolyData(points)
  54. # 如果之前有点云 actor,先移除它
  55. if point_cloud_actor is not None:
  56. plotter.remove_actor(point_cloud_actor)
  57. # 添加新的点云并获取新的 actor
  58. point_cloud_actor = plotter.add_points(
  59. cloud,
  60. render_points_as_spheres=False,
  61. point_size=2
  62. )
  63. # 自动缩放到包含所有点云的范围
  64. plotter.reset_camera()
  65. except queue.Empty:
  66. pass
  67. # 让 PyVista 处理 GUI 事件(关键!)
  68. plotter.app.processEvents()
  69. # 短暂休眠避免 CPU 占用过高
  70. import time
  71. time.sleep(0.01)
  72. except KeyboardInterrupt:
  73. pass
  74. finally:
  75. node.destroy_node()
  76. rclpy.shutdown()
  77. plotter.close()
  78. if __name__ == '__main__':
  79. main()