slam_viewer.py 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182
  1. #!/usr/bin/env python3
  2. """
  3. FIXED:
  4. 1. 正确更新 PyVista 点云(使用 mesh.copy_from)
  5. 2. 安全退出(避免卡死)
  6. 3. 兼容 Fast-LIVO 的 /cloud_registered_rgb
  7. """
  8. import sys
  9. import rclpy
  10. from rclpy.node import Node
  11. from sensor_msgs.msg import PointCloud2
  12. from sensor_msgs_py import point_cloud2
  13. import numpy as np
  14. import pyvista as pv
  15. from PySide2.QtWidgets import (
  16. QApplication, QMainWindow, QVBoxLayout, QWidget, QLabel, QPushButton
  17. )
  18. from PySide2.QtCore import QThread, Signal, Slot, QTimer
  19. from pyvistaqt import QtInteractor
  20. class SLAMViewerNode(Node):
  21. def __init__(self, callback):
  22. super().__init__('slam_qt_viewer_node')
  23. self.callback = callback
  24. self.subscription = self.create_subscription(
  25. PointCloud2,
  26. '/cloud_registered_rgb',
  27. self.listener_callback,
  28. 10
  29. )
  30. self.get_logger().info("Subscribed to /cloud_registered_rgb")
  31. def listener_callback(self, msg):
  32. points = []
  33. colors = []
  34. for pt in point_cloud2.read_points(msg, field_names=('x', 'y', 'z', 'rgb'), skip_nans=True):
  35. x, y, z = pt[0], pt[1], pt[2]
  36. rgb_packed = pt[3]
  37. if np.isnan(rgb_packed):
  38. r, g, b = 255, 255, 255
  39. else:
  40. rgb_uint = np.float32(rgb_packed).view('uint32')
  41. r = (rgb_uint >> 16) & 0xFF
  42. g = (rgb_uint >> 8) & 0xFF
  43. b = (rgb_uint >> 0) & 0xFF
  44. points.append([x, y, z])
  45. colors.append([r, g, b])
  46. if points:
  47. pts = np.array(points, dtype=np.float32)
  48. cols = np.array(colors, dtype=np.uint8)
  49. self.callback(pts, cols)
  50. class ROS2SubscriberThread(QThread):
  51. new_cloud = Signal(np.ndarray, np.ndarray)
  52. def __init__(self):
  53. super().__init__()
  54. self.node = None
  55. self._running = True
  56. def run(self):
  57. try:
  58. rclpy.init()
  59. self.node = SLAMViewerNode(self.new_cloud.emit)
  60. while self._running and rclpy.ok():
  61. rclpy.spin_once(self.node, timeout_sec=0.1) # 非阻塞,可响应退出
  62. except KeyboardInterrupt:
  63. pass
  64. finally:
  65. if rclpy.ok():
  66. rclpy.shutdown()
  67. def stop(self):
  68. self._running = False
  69. if self.node:
  70. self.node.destroy_node()
  71. self.quit()
  72. self.wait(2000) # 最多等2秒
  73. class MainWindow(QMainWindow):
  74. def __init__(self):
  75. super().__init__()
  76. self.setWindowTitle("SLAM Viewer - /cloud_registered_rgb (FIXED)")
  77. self.setGeometry(100, 100, 1000, 700)
  78. central_widget = QWidget()
  79. self.setCentralWidget(central_widget)
  80. layout = QVBoxLayout(central_widget)
  81. self.plotter = QtInteractor(self)
  82. layout.addWidget(self.plotter)
  83. self.status_label = QLabel("Waiting for /cloud_registered_rgb...")
  84. layout.addWidget(self.status_label)
  85. exit_btn = QPushButton("Exit")
  86. exit_btn.clicked.connect(self.close)
  87. layout.addWidget(exit_btn)
  88. # 初始化一个空点云(必须有有效数据才能显示)
  89. initial_pts = np.array([[0.0, 0.0, 0.0]], dtype=np.float32)
  90. initial_cols = np.array([[0, 0, 0]], dtype=np.uint8)
  91. self.cloud = pv.PolyData(initial_pts)
  92. self.cloud.point_data['colors'] = initial_cols
  93. self.actor = self.plotter.add_points(
  94. self.cloud,
  95. scalars='colors',
  96. rgb=True,
  97. point_size=2.0,
  98. render_points_as_spheres=False
  99. )
  100. self.plotter.add_axes()
  101. self.plotter.show_grid(color='white')
  102. self.plotter.background_color = 'black'
  103. self.last_update_time = 0.0
  104. self.update_interval = 1.0
  105. self.latest_data = None
  106. self.ros_thread = ROS2SubscriberThread()
  107. self.ros_thread.new_cloud.connect(self.on_new_cloud_received)
  108. self.ros_thread.start()
  109. self.timer = QTimer()
  110. self.timer.timeout.connect(self.try_update_plot)
  111. self.timer.start(100)
  112. @Slot(np.ndarray, np.ndarray)
  113. def on_new_cloud_received(self, points, colors):
  114. self.latest_data = (points, colors)
  115. def try_update_plot(self):
  116. import time
  117. current_time = time.time()
  118. if self.latest_data is not None and (current_time - self.last_update_time) >= self.update_interval:
  119. pts, cols = self.latest_data
  120. n_pts = pts.shape[0]
  121. # ✅ 关键修复:创建新 PolyData 并替换
  122. new_cloud = pv.PolyData(pts)
  123. new_cloud.point_data['colors'] = cols
  124. # 替换 actor 的输入
  125. self.actor.GetMapper().SetInputData(new_cloud)
  126. self.plotter.render()
  127. self.status_label.setText(f"Updated: {n_pts:,} points | Topic: /cloud_registered_rgb")
  128. self.last_update_time = current_time
  129. self.latest_data = None
  130. def closeEvent(self, event):
  131. # 先停定时器
  132. self.timer.stop()
  133. # 停止 ROS 线程(关键!)
  134. self.ros_thread.stop()
  135. # 再关闭渲染器
  136. try:
  137. self.plotter.close()
  138. except Exception:
  139. pass
  140. event.accept()
  141. def main():
  142. app = QApplication(sys.argv)
  143. window = MainWindow()
  144. window.show()
  145. sys.exit(app.exec_())
  146. if __name__ == '__main__':
  147. main()