feature/multi-robots-types #12
|
@ -64,8 +64,8 @@ async def main():
|
|||
|
||||
#Add a new robot
|
||||
with new_robot_widget:
|
||||
ui.label("Add new robot").classes("text-3xl")
|
||||
for name, robot in robot_types.items():
|
||||
ui.label(f"Add new {name}").classes("text-3xl")
|
||||
await robot.launch_widget(robots_widget)
|
||||
|
||||
# Start the NiceGUI application
|
||||
|
|
|
@ -21,12 +21,15 @@ from rclpy.node import Node
|
|||
import rclpy
|
||||
import threading
|
||||
|
||||
|
||||
def ros_main() -> None:
|
||||
async def ros_loop():
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('async_subscriber')
|
||||
while rclpy.ok():
|
||||
rclpy.spin_once(node, timeout_sec=0)
|
||||
await asyncio.sleep(0.1)
|
||||
|
||||
|
||||
app.on_startup(lambda: threading.Thread(target=ros_main).start())
|
||||
app.on_startup(ros_loop())
|
||||
|
||||
|
||||
@contextlib.contextmanager
|
||||
|
@ -186,6 +189,9 @@ class Spirimu(Robot):
|
|||
ui.label(topic[0])
|
||||
await asyncio.sleep(10)
|
||||
|
||||
async def ui_actions(self, element):
|
||||
pass
|
||||
|
||||
async def ui(self, element):
|
||||
adocker = aiodocker.Docker()
|
||||
|
||||
|
@ -209,11 +215,14 @@ class Spirimu(Robot):
|
|||
with ui.tabs() as tabs:
|
||||
tab_containers = ui.tab("Containers")
|
||||
tab_ros = ui.tab("ROS Topics")
|
||||
tab_actions = ui.tab("Actions")
|
||||
with ui.tab_panels(tabs, value=tab_containers):
|
||||
tab = ui.tab_panel(tab_containers).classes("w-full")
|
||||
asyncio.create_task(self.ui_containers(tab))
|
||||
tab = ui.tab_panel(tab_ros).classes("w-full")
|
||||
asyncio.create_task(self.ui_ros(tab))
|
||||
tab = ui.tab_panel(tab_actions).classes("w-full")
|
||||
asyncio.create_task(self.ui_actions(tab))
|
||||
|
||||
async def async_stop(self):
|
||||
return await run.io_bound(self.stop)
|
||||
|
|
Loading…
Reference in New Issue