Merge pull request 'Move GUI toolkit from tkinter to nicegui for easier prototyping' (#7) from feature/webui into master
Build Docs / build (push) Failing after 41s Details

Reviewed-on: #7
This commit is contained in:
Alex Davies 2024-11-07 13:13:32 -04:00
commit 98aafbb5e9
12 changed files with 2657 additions and 147 deletions

View File

@ -25,16 +25,23 @@ services:
#- ${XDG_RUNTIME_DIR}/wayland-0:${XDG_RUNTIME_DIR}/wayland-0
# Allow access to the host's GPU
- /dev/dri:/dev/dri
#Auto reload on code changes
- ./guiTools/spiri_sdk_guitools/:/app/spiri_sdk_guitools/
# Enable launching the SDK from the SDK
# - ./:/app/sdk
- ./robots:/robots
- /var/run/docker.sock:/var/run/docker.sock
devices:
# Provide access to GPU devices
- /dev/dri:/dev/dri
network_mode: host
ports:
- 8923:8923
ipc: host
#user: "${UID}:${GID}"
privileged: true # Allow privileged access if necessary (e.g., for GPU access)
# restart: unless-stopped
# command: /bin/bash -c "source /opt/ros/foxy/setup.bash && rvis2" # Replace with the actual command to run Gazebo Ignition
profiles: [ui]
deploy:
resources:
reservations:
@ -43,102 +50,3 @@ services:
device_ids:
- nvidia.com/gpu=all
ardupilot:
env_file:
- .env
image: git.spirirobotics.com/spiri/ardupilot:spiri-master
command:
- /bin/bash
- -c
- |
./Tools/autotest/sim_vehicle.py $ARDUPILOT_VEHICLE --no-rebuild \
--no-mavproxy --enable-dds --sysid $DRONE_SYS_ID -I$INSTANCE
profiles:
- uav-sim
stdin_open: true
tty: true
network_mode: host
mavproxy:
env_file:
- .env
image: git.spirirobotics.com/spiri/services-mavproxy:main
command: >
mavproxy.py --non-interactive
--master tcp:127.0.0.1:$SERIAL0_PORT
--out udpout:0.0.0.0:$MAVROS2_PORT
--out udpout:0.0.0.0:$MAVROS1_PORT
--sitl 127.0.0.1:$SITL_PORT
--out udp:0.0.0.0:$GCS_PORT
profiles:
- uav-sim
ipc: host
network_mode: host
restart: always
mavros2:
env_file:
- .env
image: git.spirirobotics.com/spiri/services-ros2-mavros:main
command: ros2 launch mavros apm.launch fcu_url:="udp://0.0.0.0:$MAVROS2_PORT@:14555" namespace:="spiri$DRONE_SYS_ID" tgt_system:="$DRONE_SYS_ID"
profiles:
- uav-sim
ipc: host
network_mode: host
restart: always
depends_on:
ardupilot:
condition: service_started
mavproxy:
condition: service_started
deploy:
resources:
limits:
# cpus: '0.01'
memory: 200M
ulimits:
nofile:
soft: 1024
hard: 524288
mavros:
#This service bridges our mavlink-based robot-coprosessor into ROS
#In this example it connects to a simulated coprocessor.
env_file:
- .env
image: git.spirirobotics.com/spiri/services-ros1-mavros:master
command: rosrun mavros mavros_node __name:=spiri$DRONE_SYS_ID _fcu_url:="udp://0.0.0.0:$MAVROS1_PORT@:14559" _target_system_id:="$DRONE_SYS_ID"
profiles:
- uav-sim
ipc: host
network_mode: host
restart: always
deploy:
resources:
limits:
# cpus: '0.01'
memory: 200M
ulimits:
nofile:
soft: 1024
hard: 524288
ros-master:
env_file:
- .env
image: git.spirirobotics.com/spiri/services-ros1-core:main
command: stdbuf -o L roscore
profiles:
- ros-master
ipc: host
network_mode: host
restart: always
deploy:
resources:
limits:
memory: 1G
# Madness, setting a low ulimit here fixes memory leaks
# https://answers.ros.org/question/336963/rosout-high-memory-usage/
ulimits:
nofile:
soft: 1024
hard: 524288

View File

@ -4,12 +4,16 @@ RUN apt-get update
RUN apt-get -y install qterminal mesa-utils \
libgstreamer1.0-dev \
libgstreamer-plugins-base1.0-dev \
docker-compose \
python3.12-venv \
python3-pip \
gstreamer1.0-libav \
gstreamer1.0-gl \
gstreamer1.0-plugins-good \
gstreamer1.0-plugins-bad \
gstreamer1.0-plugins-ugly
COPY --from=git.spirirobotics.com/spiri/gazebo-resources:main /plugins /ardupilot_gazebo/plugins
COPY --from=git.spirirobotics.com/spiri/gazebo-resources:main /models /ardupilot_gazebo/models
COPY --from=git.spirirobotics.com/spiri/gazebo-resources:main /worlds /ardupilot_gazebo/worlds
@ -20,8 +24,23 @@ ENV GZ_SIM_RESOURCE_PATH=/ardupilot_gazebo/models:/ardupilot_gazebo/worlds
COPY ./spawn_drones.sh /spawn_drones.sh
RUN chmod +x /spawn_drones.sh
COPY ./launcher.py /launcher.py
CMD python3 /launcher.py
WORKDIR /app
RUN python3 -m venv /opt/venv
ENV PATH="/opt/venv/bin:$PATH"
RUN pip3 install poetry
COPY ./pyproject.toml ./poetry.lock ./README.md ./
COPY ./spiri_sdk_guitools ./spiri_sdk_guitools
RUN poetry env use python3
RUN poetry config virtualenvs.create false && poetry install --no-dev --no-interaction --no-ansi
CMD poetry run python3 spiri_sdk_guitools/launcher.py

0
guiTools/README.md Normal file
View File

View File

@ -1,44 +0,0 @@
import tkinter as tk
import subprocess
# Dictionary of applications: key is the button text, value is the command to execute
applications = {
"Launch Terminal": ["qterminal"],
"Launch rqt": ["rqt"],
"Launch rviz2": ["rviz2"],
"Launch Gazebo": ["/spawn_drones.sh"],
"Launch Gazebo Standalone": "gz sim -v4".split(),
# Add more applications here if needed
}
# Function to launch an application
def launch_app(command):
try:
subprocess.Popen(command)
except FileNotFoundError:
print(
f"{command[0]} not found. Make sure it's installed and accessible in the PATH."
)
# Create the main application window
root = tk.Tk()
root.title("Spiri SDK Launcher")
label = tk.Label(root, text="Spiri Robotics SDK", font=("Arial", 14))
label.pack(pady=10)
# Create and place buttons dynamically based on the dictionary
for app_name, command in applications.items():
button = tk.Button(
root,
text=app_name,
command=lambda cmd=command: launch_app(cmd),
width=20,
height=2,
)
button.pack()
# Run the Tkinter main loop
root.mainloop()

2210
guiTools/poetry.lock generated Normal file

File diff suppressed because it is too large Load Diff

21
guiTools/pyproject.toml Normal file
View File

@ -0,0 +1,21 @@
[tool.poetry]
name = "spiri_sdk_guitools"
version = "0.1.0"
description = ""
authors = ["Spiri Robotics"]
readme = "README.md"
[tool.poetry.dependencies]
python = "^3.11"
nicegui = "^2.5.0"
pywebview = "^5.3.2"
loguru = "^0.7.2"
sh = "^2.1.0"
docker = "^7.1.0"
aiodocker = "^0.23.0"
numpy = "^2.1.3"
[build-system]
requires = ["poetry-core"]
build-backend = "poetry.core.masonry.api"

View File

View File

@ -0,0 +1,80 @@
from nicegui import ui, binding, app, run
import subprocess
from collections import defaultdict
import docker
import time
docker_client = docker.from_env()
# Dictionary of applications: key is the button text, value is the command to execute
applications = {
"Terminal": ["qterminal"],
"rqt": ["rqt"],
"rviz2": ["rviz2"],
"Gazebo": ["/spawn_drones.sh"],
"Gazebo Standalone": "gz sim -v4".split(),
# Add more applications here if needed
}
# Function to launch an application
def launch_app(command):
try:
subprocess.Popen(command)
except FileNotFoundError:
print(f"{command[0]} not found. Make sure it's installed and accessible in the PATH.")
# Create the NiceGUI interface
ui.label("Spiri Robotics SDK").style('font-size: 40px; margin-bottom: 10px;').classes('w-full text-center')
robots = []
from spiri_sdk_guitools.sim_drone import Robot
import aiodocker
import asyncio
@ui.page('/')
async def main():
with ui.tabs().classes('w-full') as tabs:
tab_tools = ui.tab('Tools')
tab_robots = ui.tab('Robots')
# two = ui.tab('Two')
with ui.tab_panels(tabs, value=tab_tools).classes("w-full"):
with ui.tab_panel(tab_tools):
# Create and place buttons dynamically based on the dictionary
with ui.grid(columns=3):
for app_name, command in applications.items():
ui.button(app_name, on_click=lambda cmd=command: launch_app(cmd)).style('width: 150px; height: 50px; margin: 5px;')
with ui.tab_panel(tab_robots):
new_robot_widget = ui.element().classes("w-1/2")
with ui.element().classes("w-1/2"):
ui.label("Debug").classes("text-xl")
def cleanup_all_containers():
#Find all containers that start with spiri-sdk
containers = docker_client.containers.list(all=True)
removal_count = 0
for container in containers:
if container.name.startswith("robot-sim-"):
container.remove(force=True)
removal_count += 1
ui.label(f"Removed {removal_count} containers")
ui.button("Cleanup all containers", on_click=cleanup_all_containers)
ui.separator()
ui.label("Current robots").classes("text-3xl")
robots_widget = ui.element().classes("w-full")
#Add a new robot
with new_robot_widget:
ui.label("Add new robot").classes("text-3xl")
newRobotParams = defaultdict(binding.BindableProperty)
ui.number(value=1, label="SysID", min=1, max=254,
).bind_value(newRobotParams, 'sysid')
ui.textarea(value="/robots/spiri-mu/core/docker-compose.yaml", label="Compose files (comma or newline seperated)").bind_value(newRobotParams, 'compose_files')
async def new_robot():
robot = Robot(**newRobotParams)
asyncio.tasks.create_task(robot.ui(robots_widget))
newRobotParams['sysid'] += 1
ui.button("Add", on_click=new_robot)
# Start the NiceGUI application
ui.run(title="Spiri SDK Launcher", port=8923, dark=None)

View File

@ -0,0 +1,202 @@
from loguru import logger
from pathlib import Path
import contextlib
from typing import List
import os
import sh
import subprocess
from nicegui import ui, run, app
import docker
import aiodocker
import asyncio
docker_client = docker.from_env()
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
import rclpy
import threading
def ros_main() -> None:
rclpy.init()
try:
rclpy.spin()
except ExternalShutdownException:
pass
app.on_startup(lambda: threading.Thread(target=ros_main).start())
@contextlib.contextmanager
def modified_environ(*remove, **update):
"""
Temporarily updates the ``os.environ`` dictionary in-place.
The ``os.environ`` dictionary is updated in-place so that the modification
is sure to work in all situations.
:param remove: Environment variables to remove.
:param update: Dictionary of environment variables and values to add/update.
"""
env = os.environ
update = update or {}
remove = remove or []
# List of environment variables being updated or removed.
stomped = (set(update.keys()) | set(remove)) & set(env.keys())
# Environment variables and values to restore on exit.
update_after = {k: env[k] for k in stomped}
# Environment variables and values to remove on exit.
remove_after = frozenset(k for k in update if k not in env)
try:
env.update(update)
[env.pop(k, None) for k in remove]
yield
finally:
env.update(update_after)
[env.pop(k) for k in remove_after]
robots = set()
async def container_logs(container, element):
adocker = aiodocker.Docker()
with element:
with ui.scroll_area():
acontainer = await adocker.containers.get(container.id)
async for log in acontainer.log(stdout=True, stderr=True, follow=True):
for line in log.splitlines():
ui.label(line)
# ui.html(conv.convert(bytes(log,'utf-8').decode('utf-8', 'xmlcharrefreplace'), full=False))
class Robot:
robot_type = "spiri-mu"
def __init__(self, sysid: int, compose_files: List[Path] | str ):
if sysid > 255 or sysid < 0:
raise ValueError("sysid must be between 0 and 255")
self.sysid = int(sysid)
if isinstance(compose_files, str):
compose_files = [ Path(file) for file in compose_files.replace("\n",",").split(",") ]
self.compose_files = compose_files
self.processes = []
robots.add(self)
async def ui_containers(self, element):
docker_elements = {}
container_status = {}
with element:
while True:
#Poll for data that changes
for container in self.containers():
try:
health = container.attrs['State']['Health']['Status']
except KeyError:
health = "Unknown"
container_status[container] = f"{container.name} {container.status} {health}"
if container not in docker_elements:
docker_elements[container] = ui.element().classes("w-full")
with docker_elements[container]:
ui.label().bind_text(container_status, container).classes("text-lg")
logelement = ui.expansion("Logs").style('margin: 10px;').classes('w-full outline outline-1')
asyncio.create_task(container_logs(container, logelement))
#Check for containers that have been removed
removed = set(docker_elements.keys()) - set(self.containers())
for container in removed:
self.robot_ui.remove(docker_elements[container])
docker_elements.pop(container)
await asyncio.sleep(1)
async def ui_ros(self, element):
with element:
node_dummy = Node("_ros2cli_dummy_to_show_topic_list")
scroll_area = ui.scroll_area()
with scroll_area:
while True:
scroll_area.clear()
for topic in node_dummy.get_topic_names_and_types():
ui.label(topic)
await asyncio.sleep(10)
async def ui(self, element):
adocker = aiodocker.Docker()
with element:
self.robot_ui = ui.element().classes("w-full outline p-4")
with self.robot_ui:
ui.label(f"{self.robot_type} {self.sysid}").classes("text-2xl")
ui.label(f"""Sysid: {self.sysid}""")
ui.button("Start", on_click=self.start).classes("m-2")
ui.button("Stop", on_click=self.async_stop).classes("m-2")
async def delete_robot():
await self.async_stop()
robots.remove(self)
element.remove(self.robot_ui)
ui.button("Delete", on_click=delete_robot).classes("m-2")
with ui.tabs() as tabs:
tab_containers = ui.tab('Containers')
tab_ros = ui.tab('ROS Topics')
with ui.tab_panels(tabs, value=tab_containers):
tab = ui.tab_panel(tab_containers).classes("w-full")
asyncio.create_task(self.ui_containers(tab))
with ui.tab_panels(tabs, value=tab_ros):
tab = ui.tab_panel(tab_ros).classes("w-full")
asyncio.create_task(self.ui_ros(tab))
async def async_stop(self):
return await run.io_bound(self.stop)
def stop(self):
#Signal all processes to stop
for process in self.processes:
process.terminate()
process.kill()
self.processes = []
for container in self.containers():
# container.stop()
container.remove(force=True)
def containers(self):
return docker_client.containers.list(all=True, filters={"name": f"robot-sim-{self.robot_type}-{self.sysid}"})
def start(self):
"""Starts the simulated drone with a given sysid,
each drone must have it's own unique ID.
"""
instance = self.sysid-1
sysid = self.sysid
with logger.contextualize(syd_id=sysid):
env = os.environ
with modified_environ(
SERIAL0_PORT=str(int(env["SERIAL0_PORT"]) + 10 * instance),
MAVROS2_PORT=str(int(env["MAVROS2_PORT"]) + 10 * instance),
MAVROS1_PORT=str(int(env["MAVROS1_PORT"]) + 10 * instance),
FDM_PORT_IN=str(int(env["FDM_PORT_IN"]) + 10 * instance),
SITL_PORT=str(int(env["SITL_PORT"]) + 10 * instance),
INSTANCE=str(instance),
DRONE_SYS_ID=str(self.sysid),
):
logger.info("Starting drone stack, this may take some time")
for compose_file in self.compose_files:
if not isinstance(compose_file, Path):
compose_file = Path(compose_file)
if not compose_file.exists():
raise FileNotFoundError(f"File {compose_file} does not exist")
args = [
"docker-compose",
"--profile",
"uav-sim",
"-p",
f"robot-sim-{self.robot_type}-{sysid}",
"-f",
compose_file.as_posix(),
"up",
]
command = " ".join(args)
logger.info(f"Starting drone stack with command: {command}")
docker_stack = subprocess.Popen(
args,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
)

19
robots/spiri-mu/core/.env Normal file
View File

@ -0,0 +1,19 @@
DRONE_SYS_ID=1
INSTANCE=0
SERIAL0_PORT=5760
SITL_PORT=5501
MAVROS2_PORT=14560
MAVROS1_PORT=14561
FDM_PORT_IN=9002
GSTREAMER_UDP_PORT=5600
ROS_MASTER_URI="http://0.0.0.0:11311"
ARDUPILOT_VEHICLE="-v copter -f gazebo-mu --model=JSON -L CitadelHill"
WORLD_FILE_NAME="citadel_hill_world.sdf"
WORLD_NAME="citadel_hill"
DRONE_MODEL="spiri_mu"
SIM_DRONE_COUNT=1
GCS_PORT=14550

View File

@ -0,0 +1,95 @@
services:
ardupilot:
env_file:
- .env
image: git.spirirobotics.com/spiri/ardupilot:spiri-master
command:
- /bin/bash
- -c
- |
./Tools/autotest/sim_vehicle.py $ARDUPILOT_VEHICLE --no-rebuild \
--no-mavproxy --enable-dds --sysid $DRONE_SYS_ID -I$INSTANCE
stdin_open: true
tty: true
network_mode: host
mavproxy:
env_file:
- .env
image: git.spirirobotics.com/spiri/services-mavproxy:main
command: >
mavproxy.py --non-interactive
--master tcp:127.0.0.1:$SERIAL0_PORT
--out udpout:0.0.0.0:$MAVROS2_PORT
--out udpout:0.0.0.0:$MAVROS1_PORT
--sitl 127.0.0.1:$SITL_PORT
--out udp:0.0.0.0:$GCS_PORT
ipc: host
network_mode: host
restart: always
mavros2:
env_file:
- .env
image: git.spirirobotics.com/spiri/services-ros2-mavros:main
command: ros2 launch mavros apm.launch fcu_url:="udp://0.0.0.0:$MAVROS2_PORT@:14555" namespace:="spiri$DRONE_SYS_ID" tgt_system:="$DRONE_SYS_ID"
ipc: host
network_mode: host
restart: always
depends_on:
ardupilot:
condition: service_started
mavproxy:
condition: service_started
deploy:
resources:
limits:
# cpus: '0.01'
memory: 200M
ulimits:
nofile:
soft: 1024
hard: 524288
mavros:
#This service bridges our mavlink-based robot-coprosessor into ROS
#In this example it connects to a simulated coprocessor.
env_file:
- .env
image: git.spirirobotics.com/spiri/services-ros1-mavros:master
command: rosrun mavros mavros_node __name:=spiri$DRONE_SYS_ID _fcu_url:="udp://0.0.0.0:$MAVROS1_PORT@:14559" _target_system_id:="$DRONE_SYS_ID"
profiles:
- ros1
ipc: host
network_mode: host
restart: always
deploy:
resources:
limits:
# cpus: '0.01'
memory: 200M
ulimits:
nofile:
soft: 1024
hard: 524288
ros-master:
env_file:
- .env
image: git.spirirobotics.com/spiri/services-ros1-core:main
command: stdbuf -o L roscore
profiles:
- ros1-master
ipc: host
network_mode: host
restart: always
deploy:
resources:
limits:
memory: 1G
# Madness, setting a low ulimit here fixes memory leaks
# https://answers.ros.org/question/336963/rosout-high-memory-usage/
ulimits:
nofile:
soft: 1024
hard: 524288

View File

@ -109,7 +109,7 @@ def start(instance: int = 0, sys_id: int = 1):
"--profile",
"uav-sim",
"-p",
f"spiri-sdk-{sys_id}",
f"robot-sim-{sys_id}",
"up",
_out=outputLogger("docker_stack", sys_id),
_err=sys.stderr,