Skip to content

Commit 8b59679

Browse files
use new Events for communicating between ROS and UI
1 parent 9464811 commit 8b59679

File tree

1 file changed

+24
-15
lines changed
  • examples/ros2/ros2_ws/src/gui/gui

1 file changed

+24
-15
lines changed

examples/ros2/ros2_ws/src/gui/gui/node.py

Lines changed: 24 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -7,17 +7,21 @@
77
from rclpy.executors import ExternalShutdownException
88
from rclpy.node import Node
99

10-
from nicegui import Client, app, ui, ui_run
10+
from nicegui import Event, app, ui, ui_run
1111

1212

1313
class NiceGuiNode(Node):
1414

1515
def __init__(self) -> None:
1616
super().__init__('nicegui')
17+
self.pose_update = Event()
18+
self.speed_update = Event()
19+
1720
self.cmd_vel_publisher = self.create_publisher(Twist, 'cmd_vel', 1)
18-
self.subscription = self.create_subscription(Pose, 'pose', self.handle_pose, 1)
21+
self.subscription = self.create_subscription(Pose, 'pose', self.pose_update.emit, 1)
1922

20-
with Client.auto_index_client:
23+
@ui.page('/')
24+
def page():
2125
with ui.row().classes('items-stretch'):
2226
with ui.card().classes('w-44 text-center items-center'):
2327
ui.label('Control').classes('text-2xl')
@@ -29,31 +33,36 @@ def __init__(self) -> None:
2933
ui.label('Data').classes('text-2xl')
3034
ui.label('linear velocity').classes('text-xs mb-[-1.8em]')
3135
slider_props = 'readonly selection-color=transparent'
32-
self.linear = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props)
36+
linear = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props)
3337
ui.label('angular velocity').classes('text-xs mb-[-1.8em]')
34-
self.angular = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props)
38+
angular = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props)
3539
ui.label('position').classes('text-xs mb-[-1.4em]')
36-
self.position = ui.label('---')
40+
position = ui.label('---')
3741
with ui.card().classes('w-96 h-96 items-center'):
3842
ui.label('Visualization').classes('text-2xl')
3943
with ui.scene(350, 300) as scene:
40-
with scene.group() as self.robot_3d:
44+
with scene.group() as robot_3d:
4145
prism = [[-0.5, -0.5], [0.5, -0.5], [0.75, 0], [0.5, 0.5], [-0.5, 0.5]]
42-
self.robot_object = scene.extrusion(prism, 0.4).material('#4488ff', 0.5)
46+
scene.extrusion(prism, 0.4).material('#4488ff', 0.5)
47+
48+
@self.pose_update.subscribe
49+
def update_pose(msg: Pose):
50+
position.text = f'x: {msg.position.x:.2f}, y: {msg.position.y:.2f}'
51+
robot_3d.move(msg.position.x, msg.position.y)
52+
robot_3d.rotate(0, 0, 2 * math.atan2(msg.orientation.z, msg.orientation.w))
53+
54+
@self.speed_update.subscribe
55+
def update_speed(msg: Twist):
56+
linear.value = msg.linear.x
57+
angular.value = msg.angular.z
4358

4459
def send_speed(self, x: float, y: float) -> None:
4560
msg = Twist()
4661
msg.linear.x = x
4762
msg.angular.z = -y
48-
self.linear.value = x
49-
self.angular.value = y
63+
self.speed_update.emit(msg)
5064
self.cmd_vel_publisher.publish(msg)
5165

52-
def handle_pose(self, msg: Pose) -> None:
53-
self.position.text = f'x: {msg.position.x:.2f}, y: {msg.position.y:.2f}'
54-
self.robot_3d.move(msg.position.x, msg.position.y)
55-
self.robot_3d.rotate(0, 0, 2 * math.atan2(msg.orientation.z, msg.orientation.w))
56-
5766

5867
def main() -> None:
5968
# NOTE: This function is defined as the ROS entry point in setup.py, but it's empty to enable NiceGUI auto-reloading

0 commit comments

Comments
 (0)