Browse Source

refactoring

Rodja Trappe 1 năm trước cách đây
mục cha
commit
cf4dfc1ced

+ 28 - 44
examples/ros2/ros2_ws/src/gui/gui/node.py

@@ -12,30 +12,40 @@ from nicegui import app, run, ui
 class NiceGuiNode(Node):
     def __init__(self) -> None:
         super().__init__('nicegui')
-        self.linear = 0.0
-        self.angular = 0.0
-        self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 1)
-        timer_period = 0.15  # seconds
-        self.timer = self.create_timer(timer_period, self.timer_callback)
+        self.cmd_vel_publisher = self.create_publisher(Twist, 'cmd_vel', 1)
         self.subscription = self.create_subscription(Pose, 'pose', self.on_pose, 1)
 
-    def timer_callback(self) -> None:
+        @ui.page('/')
+        def index() -> None:
+            with ui.row().classes('items-stretch'):
+                with ui.card().classes('w-44 text-center items-center'):
+                    ui.label('Control').classes('text-2xl')
+                    ui.joystick(
+                        color='blue', size=50,
+                        on_move=lambda e: self.send_speed(e.y, e.x),
+                        on_end=lambda _: self.send_speed(0.0, 0.0),
+                    )
+                    ui.label('Publish steering commands by dragging your mouse around in the blue field')
+                with ui.card().classes('w-44 text-center items-center'):
+                    ui.label('Data').classes('text-2xl')
+                    ui.label('linear speed')
+                    ui.label().bind_text_from(self, 'linear', backward=lambda value: f'{value:.3f}')
+                    ui.label('angular speed')
+                    ui.label().bind_text_from(self, 'angular', backward=lambda value: f'{value:.3f}')
+                with ui.card().classes('w-96 items-center'):
+                    ui.label('Visualization').classes('text-2xl')
+                    map = ui.html()
+
+    def send_speed(self, x, y) -> None:
         msg = Twist()
-        msg.linear.x = float(self.linear)
-        msg.angular.z = float(-self.angular)
-        self.publisher_.publish(msg)
-
-    def update_speeds(self, x, y) -> None:
-        self.linear = x
-        self.angular = y
+        msg.linear.x = float(x)
+        msg.angular.z = float(-y)
+        self.cmd_vel_publisher.publish(msg)
 
     def on_pose(self, msg: Pose) -> None:
         print(f'pose: {msg}')
 
 
-active_node: NiceGuiNode = None
-
-
 def node_spin(node: Node) -> None:
     try:
         print('starting node')
@@ -44,40 +54,14 @@ def node_spin(node: Node) -> None:
         print('stopped node')
 
 
-@ui.page('/')
-def index() -> None:
-    with ui.row().classes('items-stretch'):
-        with ui.card().classes('w-44'):
-            ui.markdown('''
-                ## Control
-
-                Publish steering commands by dragging your mouse around in the blue field
-            ''')
-            ui.joystick(
-                color='blue',
-                size=50,
-                on_move=lambda e: active_node.update_speeds(e.y, e.x),
-                on_end=lambda _: active_node.update_speeds(0.0, 0.0),
-            ).classes('my-joystick')
-        with ui.card():
-            ui.markdown('### Status')
-            ui.label('linear speed')
-            ui.label().bind_text_from(active_node, 'linear', backward=lambda value: f'{value:.3f}')
-            ui.label('angular speed')
-            ui.label().bind_text_from(active_node, 'angular', backward=lambda value: f'{value:.3f}')
-        with ui.card().classes('w-96'):
-            map = ui.html()
-
-
 def main() -> None:
     pass  # NOTE: This is originally used as the ROS entry point, but we give the control of the node to NiceGUI.
 
 
 def ros_main() -> None:
-    global active_node
     rclpy.init()
-    active_node = NiceGuiNode()
-    threading.Thread(target=node_spin, args=(active_node,), daemon=True).start()
+    node = NiceGuiNode()
+    threading.Thread(target=node_spin, args=(node,), daemon=True).start()
 
 
 app.on_startup(lambda: threading.Thread(target=ros_main).start())

+ 2 - 6
examples/ros2/ros2_ws/src/simulator/simulator/node.py

@@ -8,14 +8,10 @@ class Simulator(Node):
     def __init__(self):
         super().__init__('simulator')
         self.pose_publisher_ = self.create_publisher(Pose, 'pose', 1)
-        self.subscription = self.create_subscription(
-            Twist,
-            'cmd_vel',
-            self.listener_callback,
-            10)
+        self.subscription = self.create_subscription(Twist, 'cmd_vel', self.on_steering, 1)
         self.pose = Pose()
 
-    def listener_callback(self, msg):
+    def on_steering(self, msg):
         self.pose.position.x += msg.linear.x
         self.pose.orientation.z += msg.angular.z
         self.pose_publisher_.publish(self.pose)