|
| 1 | +#!/usr/bin/env python3 |
| 2 | + |
| 3 | +import sys |
| 4 | +import rclpy |
| 5 | +from rclpy.node import Node |
| 6 | +from PyQt5.QtWidgets import (QApplication, QMainWindow, QWidget, QVBoxLayout, |
| 7 | + QHBoxLayout, QComboBox, QRadioButton, QButtonGroup, |
| 8 | + QSlider, QLabel, QCheckBox, QPushButton, QFrame) |
| 9 | +from PyQt5.QtCore import Qt, QTimer |
| 10 | +from PyQt5.QtGui import QPainter, QColor, QPen |
| 11 | +from coffee_expressions_msgs.msg import AffectiveState |
| 12 | +from geometry_msgs.msg import Point |
| 13 | + |
| 14 | +class GazePreviewWidget(QFrame): |
| 15 | + def __init__(self, parent=None): |
| 16 | + super().__init__(parent) |
| 17 | + self.setMinimumSize(200, 200) |
| 18 | + self.setFrameStyle(QFrame.Box | QFrame.Plain) |
| 19 | + self.x = 0.0 |
| 20 | + self.y = 0.0 |
| 21 | + |
| 22 | + def setPosition(self, x: float, y: float): |
| 23 | + self.x = x |
| 24 | + self.y = y |
| 25 | + self.update() |
| 26 | + |
| 27 | + def mousePressEvent(self, event): |
| 28 | + size = min(self.width(), self.height()) |
| 29 | + x = (event.x() - self.width()/2) / (size/2) |
| 30 | + y = -(event.y() - self.height()/2) / (size/2) # Invert Y for Qt coordinates |
| 31 | + self.x = max(-1.0, min(1.0, x)) |
| 32 | + self.y = max(-1.0, min(1.0, y)) |
| 33 | + self.update() |
| 34 | + if self.parent(): |
| 35 | + self.parent().updateSliders(self.x, self.y) |
| 36 | + |
| 37 | + def paintEvent(self, event): |
| 38 | + super().paintEvent(event) |
| 39 | + painter = QPainter(self) |
| 40 | + painter.setRenderHint(QPainter.Antialiasing) |
| 41 | + |
| 42 | + # Draw coordinate system |
| 43 | + painter.translate(self.width()/2, self.height()/2) |
| 44 | + size = min(self.width(), self.height()) |
| 45 | + |
| 46 | + # Draw axes |
| 47 | + painter.setPen(QPen(QColor(200, 200, 200), 1)) |
| 48 | + painter.drawLine(-size/2, 0, size/2, 0) |
| 49 | + painter.drawLine(0, -size/2, 0, size/2) |
| 50 | + |
| 51 | + # Draw gaze target point |
| 52 | + painter.setPen(QPen(Qt.red, 3)) |
| 53 | + x_pos = self.x * size/2 |
| 54 | + y_pos = -self.y * size/2 # Invert Y for Qt coordinates |
| 55 | + painter.drawPoint(x_pos, y_pos) |
| 56 | + |
| 57 | +class ExpressionsTestUI(QMainWindow): |
| 58 | + def __init__(self): |
| 59 | + super().__init__() |
| 60 | + |
| 61 | + # Initialize ROS node |
| 62 | + rclpy.init() |
| 63 | + self.node = Node('expressions_test_ui') |
| 64 | + self.publisher = self.node.create_publisher( |
| 65 | + AffectiveState, |
| 66 | + 'affective_state', |
| 67 | + 10 |
| 68 | + ) |
| 69 | + |
| 70 | + # Setup UI |
| 71 | + self.setWindowTitle('Expressions Test UI') |
| 72 | + self.central_widget = QWidget() |
| 73 | + self.setCentralWidget(self.central_widget) |
| 74 | + self.layout = QVBoxLayout(self.central_widget) |
| 75 | + |
| 76 | + # Expression dropdown |
| 77 | + self.expression_layout = QHBoxLayout() |
| 78 | + self.expression_label = QLabel('Expression:') |
| 79 | + self.expression_combo = QComboBox() |
| 80 | + self.expression_combo.addItems(['Happy', 'Curious', 'Neutral', 'Sad', 'Surprised']) |
| 81 | + self.expression_layout.addWidget(self.expression_label) |
| 82 | + self.expression_layout.addWidget(self.expression_combo) |
| 83 | + self.layout.addLayout(self.expression_layout) |
| 84 | + |
| 85 | + # Trigger source radio buttons |
| 86 | + self.trigger_group = QButtonGroup() |
| 87 | + self.trigger_layout = QHBoxLayout() |
| 88 | + self.trigger_label = QLabel('Trigger Source:') |
| 89 | + self.trigger_layout.addWidget(self.trigger_label) |
| 90 | + |
| 91 | + for source in ['vision', 'audio', 'event', 'mock']: |
| 92 | + radio = QRadioButton(source) |
| 93 | + self.trigger_layout.addWidget(radio) |
| 94 | + self.trigger_group.addButton(radio) |
| 95 | + if source == 'mock': |
| 96 | + radio.setChecked(True) |
| 97 | + |
| 98 | + self.layout.addLayout(self.trigger_layout) |
| 99 | + |
| 100 | + # Gaze preview |
| 101 | + self.preview = GazePreviewWidget(self) |
| 102 | + self.layout.addWidget(self.preview) |
| 103 | + |
| 104 | + # X and Y sliders |
| 105 | + for coord in ['X', 'Y']: |
| 106 | + slider_layout = QHBoxLayout() |
| 107 | + label = QLabel(f'{coord}:') |
| 108 | + slider = QSlider(Qt.Horizontal) |
| 109 | + slider.setMinimum(-100) |
| 110 | + slider.setMaximum(100) |
| 111 | + value_label = QLabel('0.0') |
| 112 | + |
| 113 | + slider.valueChanged.connect( |
| 114 | + lambda v, c=coord, l=value_label: self.onSliderChanged(v, c, l)) |
| 115 | + |
| 116 | + setattr(self, f'{coord.lower()}_slider', slider) |
| 117 | + setattr(self, f'{coord.lower()}_label', value_label) |
| 118 | + |
| 119 | + slider_layout.addWidget(label) |
| 120 | + slider_layout.addWidget(slider) |
| 121 | + slider_layout.addWidget(value_label) |
| 122 | + self.layout.addLayout(slider_layout) |
| 123 | + |
| 124 | + # Is Idle checkbox |
| 125 | + self.idle_check = QCheckBox('Is Idle') |
| 126 | + self.layout.addWidget(self.idle_check) |
| 127 | + |
| 128 | + # Real-time publishing checkbox |
| 129 | + self.realtime_check = QCheckBox('Real-time Publishing') |
| 130 | + self.realtime_check.stateChanged.connect(self.onRealtimeChanged) |
| 131 | + self.layout.addWidget(self.realtime_check) |
| 132 | + |
| 133 | + # Publish button |
| 134 | + self.publish_button = QPushButton('Publish Message') |
| 135 | + self.publish_button.clicked.connect(self.publishMessage) |
| 136 | + self.layout.addWidget(self.publish_button) |
| 137 | + |
| 138 | + # Status bar |
| 139 | + self.status_label = QLabel('Status: Ready') |
| 140 | + self.layout.addWidget(self.status_label) |
| 141 | + |
| 142 | + # Timer for ROS spin |
| 143 | + self.spin_timer = QTimer() |
| 144 | + self.spin_timer.timeout.connect(lambda: rclpy.spin_once(self.node, timeout_sec=0)) |
| 145 | + self.spin_timer.start(100) # 10Hz |
| 146 | + |
| 147 | + # Timer for real-time publishing |
| 148 | + self.publish_timer = QTimer() |
| 149 | + self.publish_timer.timeout.connect(self.publishMessage) |
| 150 | + |
| 151 | + def updateSliders(self, x: float, y: float): |
| 152 | + self.x_slider.setValue(int(x * 100)) |
| 153 | + self.y_slider.setValue(int(y * 100)) |
| 154 | + |
| 155 | + def onSliderChanged(self, value: int, coord: str, label: QLabel): |
| 156 | + float_value = value / 100.0 |
| 157 | + label.setText(f'{float_value:.2f}') |
| 158 | + |
| 159 | + if coord == 'X': |
| 160 | + self.preview.setPosition(float_value, self.y_slider.value() / 100.0) |
| 161 | + else: |
| 162 | + self.preview.setPosition(self.x_slider.value() / 100.0, float_value) |
| 163 | + |
| 164 | + def onRealtimeChanged(self, state): |
| 165 | + if state == Qt.Checked: |
| 166 | + self.publish_timer.start(100) # 10Hz |
| 167 | + else: |
| 168 | + self.publish_timer.stop() |
| 169 | + |
| 170 | + def publishMessage(self): |
| 171 | + msg = AffectiveState() |
| 172 | + msg.expression = self.expression_combo.currentText() |
| 173 | + msg.trigger_source = self.trigger_group.checkedButton().text() |
| 174 | + |
| 175 | + msg.gaze_target = Point() |
| 176 | + msg.gaze_target.x = self.x_slider.value() / 100.0 |
| 177 | + msg.gaze_target.y = self.y_slider.value() / 100.0 |
| 178 | + msg.gaze_target.z = 0.0 |
| 179 | + |
| 180 | + msg.is_idle = self.idle_check.isChecked() |
| 181 | + |
| 182 | + self.publisher.publish(msg) |
| 183 | + self.status_label.setText(f'Status: Published at {self.node.get_clock().now().to_msg().sec}') |
| 184 | + |
| 185 | + def closeEvent(self, event): |
| 186 | + self.node.destroy_node() |
| 187 | + rclpy.shutdown() |
| 188 | + super().closeEvent(event) |
| 189 | + |
| 190 | +def main(): |
| 191 | + app = QApplication(sys.argv) |
| 192 | + window = ExpressionsTestUI() |
| 193 | + window.show() |
| 194 | + sys.exit(app.exec_()) |
| 195 | + |
| 196 | +if __name__ == '__main__': |
| 197 | + main() |
0 commit comments