Skip to content

Commit 1ed24f1

Browse files
committed
Add UI for testing face expression movement and changes
1 parent 8f3b17c commit 1ed24f1

File tree

10 files changed

+338
-1
lines changed

10 files changed

+338
-1
lines changed

coffee_ws/README.md

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,4 +30,19 @@ ros2 run coffee_face coffee_eyes
3030
**NOTE:** We define the location of `expressions.json` in the `setup.py` file inside `coffee_expressions` directory.
3131

3232
Running the animator
33-
- Animations are saved in `~/.ros/motion_files` as `.json` files.
33+
- Animations are saved in `~/.ros/motion_files` as `.json` files.
34+
35+
36+
# Sample Command
37+
38+
```
39+
src $ ros2 pkg create --build-type ament_python coffee_expressions_test_ui --dependencies rclpy coffee_expressions_msgs python3-pyqt5
40+
```
41+
42+
```
43+
colcon build --packages-select coffee_expressions_test_ui
44+
```
45+
46+
```
47+
source install/setup.bash && ros2 run coffee_expressions_test_ui expressions_test_ui
48+
```

coffee_ws/src/coffee_expressions_test_ui/coffee_expressions_test_ui/__init__.py

Whitespace-only changes.
Lines changed: 197 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,197 @@
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()
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>coffee_expressions_test_ui</name>
5+
<version>0.0.0</version>
6+
<description>TODO: Package description</description>
7+
<maintainer email="[email protected]">kpatch</maintainer>
8+
<license>TODO: License declaration</license>
9+
10+
<depend>rclpy</depend>
11+
<depend>coffee_expressions_msgs</depend>
12+
<depend>python3-pyqt5</depend>
13+
14+
<test_depend>ament_copyright</test_depend>
15+
<test_depend>ament_flake8</test_depend>
16+
<test_depend>ament_pep257</test_depend>
17+
<test_depend>python3-pytest</test_depend>
18+
19+
<export>
20+
<build_type>ament_python</build_type>
21+
</export>
22+
</package>

coffee_ws/src/coffee_expressions_test_ui/resource/coffee_expressions_test_ui

Whitespace-only changes.
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
[develop]
2+
script_dir=$base/lib/coffee_expressions_test_ui
3+
[install]
4+
install_scripts=$base/lib/coffee_expressions_test_ui
Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
from setuptools import setup
2+
3+
package_name = 'coffee_expressions_test_ui'
4+
5+
setup(
6+
name=package_name,
7+
version='0.0.0',
8+
packages=[package_name],
9+
data_files=[
10+
('share/ament_index/resource_index/packages',
11+
['resource/' + package_name]),
12+
('share/' + package_name, ['package.xml']),
13+
],
14+
install_requires=['setuptools'],
15+
zip_safe=True,
16+
maintainer='kpatch',
17+
maintainer_email='[email protected]',
18+
description='Qt-based UI for testing coffee expressions',
19+
license='Apache-2.0',
20+
tests_require=['pytest'],
21+
entry_points={
22+
'console_scripts': [
23+
'expressions_test_ui = coffee_expressions_test_ui.expressions_test_ui:main',
24+
],
25+
},
26+
)
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Copyright 2015 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_copyright.main import main
16+
import pytest
17+
18+
19+
# Remove the `skip` decorator once the source file(s) have a copyright header
20+
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
21+
@pytest.mark.copyright
22+
@pytest.mark.linter
23+
def test_copyright():
24+
rc = main(argv=['.', 'test'])
25+
assert rc == 0, 'Found errors'
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Copyright 2017 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_flake8.main import main_with_errors
16+
import pytest
17+
18+
19+
@pytest.mark.flake8
20+
@pytest.mark.linter
21+
def test_flake8():
22+
rc, errors = main_with_errors(argv=[])
23+
assert rc == 0, \
24+
'Found %d code style errors / warnings:\n' % len(errors) + \
25+
'\n'.join(errors)
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
# Copyright 2015 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_pep257.main import main
16+
import pytest
17+
18+
19+
@pytest.mark.linter
20+
@pytest.mark.pep257
21+
def test_pep257():
22+
rc = main(argv=['.', 'test'])
23+
assert rc == 0, 'Found code style errors / warnings'

0 commit comments

Comments
 (0)