Initial web ui and control for robot
This commit is contained in:
@@ -18,7 +18,7 @@ RUN groupadd --gid $USER_GID $USERNAME \
|
||||
RUN apt-get update && apt-get upgrade -y
|
||||
|
||||
# C++ development tools
|
||||
RUN apt-get install -y \
|
||||
RUN apt-get update && apt-get install -y \
|
||||
build-essential \
|
||||
cmake \
|
||||
gdb \
|
||||
@@ -28,8 +28,9 @@ RUN apt-get install -y \
|
||||
libboost-all-dev
|
||||
|
||||
# Python development tools
|
||||
RUN apt-get install -y \
|
||||
RUN apt-get update && apt-get install -y \
|
||||
python3-pip \
|
||||
python3-venv \
|
||||
python3-dev \
|
||||
python3-argcomplete \
|
||||
python3-colcon-common-extensions \
|
||||
@@ -45,6 +46,17 @@ RUN apt-get install -y \
|
||||
# ros-${ROS_DISTRO}-ament-lint-auto \
|
||||
# ros-${ROS_DISTRO}-ament-lint-common
|
||||
|
||||
# Node.js for frontend development
|
||||
RUN curl -fsSL https://deb.nodesource.com/setup_22.x | bash - \
|
||||
&& apt-get install -y nodejs
|
||||
|
||||
# Python venv for webui backend (isolated from system packages)
|
||||
RUN python3 -m venv /opt/webui-venv \
|
||||
&& /opt/webui-venv/bin/pip install --no-cache-dir \
|
||||
fastapi \
|
||||
"uvicorn[standard]" \
|
||||
numpy
|
||||
|
||||
ENV SHELL /bin/bash
|
||||
|
||||
# ********************************************************
|
||||
|
||||
@@ -39,5 +39,5 @@
|
||||
"source=/tmp/.X11-unix,target=/tmp/.X11-unix,type=bind,consistency=cached",
|
||||
"source=/dev/dri,target=/dev/dri,type=bind,consistency=cached"
|
||||
],
|
||||
"postCreateCommand": "sudo rosdep update && sudo rosdep install --from-paths src --ignore-src -y && sudo chown -R $(whoami) /home/ws/"
|
||||
"postCreateCommand": "sudo rosdep update && sudo rosdep install --from-paths lidar/src robot/src --ignore-src -y && sudo chown -R $(whoami) /home/ws/ && npm --prefix /home/ws/webui/frontend install"
|
||||
}
|
||||
@@ -12,6 +12,7 @@ services:
|
||||
- linux/arm64
|
||||
image: raspbot_v2:latest
|
||||
network_mode: host
|
||||
ipc: host
|
||||
devices:
|
||||
- /dev/i2c-1:/dev/i2c-1
|
||||
environment:
|
||||
@@ -27,6 +28,7 @@ services:
|
||||
- linux/arm64
|
||||
image: raspbot_v2_lidar:latest
|
||||
network_mode: host
|
||||
ipc: host
|
||||
devices:
|
||||
- ${LIDAR_PORT:-/dev/ttyUSB0}:${LIDAR_PORT:-/dev/ttyUSB0}
|
||||
environment:
|
||||
@@ -43,3 +45,20 @@ services:
|
||||
- scan_qos_depth:=${LIDAR_QOS_DEPTH:-2}
|
||||
- scan_qos_reliability:=${LIDAR_QOS_RELIABILITY:-best_effort}
|
||||
restart: unless-stopped
|
||||
|
||||
webui:
|
||||
build:
|
||||
context: webui
|
||||
dockerfile: Dockerfile
|
||||
platforms:
|
||||
- linux/arm64
|
||||
args:
|
||||
# WebSocket URL of the GStreamer signaling server, baked into the frontend bundle.
|
||||
# Override with: VITE_WEBRTC_WS_URL=ws://raspberrypi.local:8443
|
||||
VITE_WEBRTC_WS_URL: ${VITE_WEBRTC_WS_URL:-}
|
||||
image: raspbot_v2_webui:latest
|
||||
network_mode: host
|
||||
ipc: host
|
||||
environment:
|
||||
- ROS_DOMAIN_ID=${ROS_DOMAIN_ID:-0}
|
||||
restart: unless-stopped
|
||||
|
||||
@@ -4,6 +4,6 @@ set -e
|
||||
source /opt/ros/${ROS_DISTRO}/setup.bash
|
||||
source /ws/install/setup.bash
|
||||
|
||||
ros2 daemon start
|
||||
# Don't start daemon - nodes don't need it, only CLI tools do
|
||||
|
||||
exec "$@"
|
||||
|
||||
@@ -0,0 +1,36 @@
|
||||
# Stage 1: Build the Vite/React frontend
|
||||
FROM node:22-alpine AS frontend-builder
|
||||
|
||||
WORKDIR /build
|
||||
COPY frontend/package.json ./
|
||||
RUN npm install
|
||||
COPY frontend/ ./
|
||||
|
||||
# Passed in via docker-compose build args so the URL is baked into the bundle.
|
||||
# e.g. VITE_WEBRTC_WS_URL=ws://raspberrypi.local:8443
|
||||
ARG VITE_WEBRTC_WS_URL
|
||||
ENV VITE_WEBRTC_WS_URL=${VITE_WEBRTC_WS_URL}
|
||||
|
||||
RUN npm run build
|
||||
|
||||
# Stage 2: FastAPI + ROS 2 runtime
|
||||
FROM ros:kilted-ros-core
|
||||
|
||||
ARG DEBIAN_FRONTEND=noninteractive
|
||||
|
||||
RUN apt-get update && apt-get install -y --no-install-recommends \
|
||||
python3-venv \
|
||||
&& rm -rf /var/lib/apt/lists/*
|
||||
|
||||
COPY backend/requirements.txt /tmp/requirements.txt
|
||||
RUN python3 -m venv /app/venv && \
|
||||
/app/venv/bin/pip install --no-cache-dir -r /tmp/requirements.txt
|
||||
|
||||
COPY --from=frontend-builder /build/dist /app/static
|
||||
COPY backend/ /app/
|
||||
|
||||
WORKDIR /app
|
||||
|
||||
EXPOSE 8080
|
||||
|
||||
CMD ["/bin/bash", "-c", "source /opt/ros/$ROS_DISTRO/setup.bash && /app/venv/bin/python3 main.py"]
|
||||
+124
@@ -0,0 +1,124 @@
|
||||
# Raspbot Web UI
|
||||
|
||||
Browser-based controller for the Raspbot V2. Displays a live WebRTC camera feed and provides keyboard / on-screen controls for robot movement and camera pan/tilt.
|
||||
|
||||
## Architecture
|
||||
|
||||
```
|
||||
Browser
|
||||
│
|
||||
├─── WebSocket /ws ──────────► FastAPI backend (port 8080)
|
||||
│ │
|
||||
│ └─ rclpy node
|
||||
│ ├─ publishes /cmd_vel
|
||||
│ ├─ publishes /joint_command
|
||||
│ ├─ subscribes /joint_states
|
||||
│ └─ subscribes /ultrasonic/range
|
||||
│
|
||||
└─── WebSocket ws://<host>:8443 ──► GStreamer WebRTC server (separate container)
|
||||
```
|
||||
|
||||
The FastAPI backend **is** the ROS 2 node — no rosbridge needed. The Vite/React frontend is built into static files and served directly by FastAPI in production.
|
||||
|
||||
## ROS topics
|
||||
|
||||
| Direction | Topic | Type |
|
||||
|-----------|-------|------|
|
||||
| Publish | `/cmd_vel` | `geometry_msgs/Twist` |
|
||||
| Publish | `/joint_command` | `sensor_msgs/JointState` (joints: `pan`, `tilt`) |
|
||||
| Subscribe | `/joint_states` | `sensor_msgs/JointState` |
|
||||
| Subscribe | `/ultrasonic/range` | `sensor_msgs/Range` |
|
||||
|
||||
## Controls
|
||||
|
||||
| Input | Action |
|
||||
|-------|--------|
|
||||
| W / ↑ | Drive forward |
|
||||
| S / ↓ | Drive backward |
|
||||
| A / ← | Turn left |
|
||||
| D / → | Turn right |
|
||||
| Pan slider | Camera pan (±90°) |
|
||||
| Tilt slider | Camera tilt (−30° to +55°) |
|
||||
| Centre button | Return camera to home position |
|
||||
|
||||
The D-pad buttons on screen mirror the keyboard controls and work on touch devices.
|
||||
|
||||
---
|
||||
|
||||
## Development (devcontainer)
|
||||
|
||||
Running locally in the devcontainer gives a fast edit → reload loop without needing to rebuild Docker images.
|
||||
|
||||
### Prerequisites
|
||||
|
||||
Rebuild the devcontainer at least once after the Node.js addition to `.devcontainer/Dockerfile` was made — VS Code will prompt you, or run **Dev Containers: Rebuild Container** from the command palette.
|
||||
|
||||
### Running
|
||||
|
||||
```bash
|
||||
./webui/dev.sh
|
||||
```
|
||||
|
||||
Then open **http://localhost:5173**.
|
||||
|
||||
The script will:
|
||||
- Create a Python venv at `webui/backend/.venv` (first run only)
|
||||
- Install backend and frontend dependencies
|
||||
- Start the FastAPI backend on port 8080
|
||||
- Start the Vite dev server on port 5173, proxying `/ws` to the backend
|
||||
|
||||
Both processes are stopped together with **Ctrl+C**.
|
||||
|
||||
### ROS domain ID
|
||||
|
||||
The devcontainer uses `ROS_DOMAIN_ID=42` by default, but the robot and lidar containers default to `0`. Override when running the script to match whichever domain the robot is on:
|
||||
|
||||
```bash
|
||||
ROS_DOMAIN_ID=0 ./webui/dev.sh
|
||||
```
|
||||
|
||||
### WebRTC camera
|
||||
|
||||
The camera feed connects to the GStreamer signaling server at `ws://<hostname>:8443` by default. If your WebRTC container runs on a different host or port, set `VITE_WEBRTC_WS_URL` before starting the frontend (it is baked into the bundle at build time, but the dev server reads it from the shell):
|
||||
|
||||
```bash
|
||||
VITE_WEBRTC_WS_URL=ws://raspbot-v2.local:8443 ./webui/dev.sh
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## Production (Docker Compose)
|
||||
|
||||
### Build
|
||||
|
||||
```bash
|
||||
docker compose build webui
|
||||
```
|
||||
|
||||
To bake a specific WebRTC server URL into the bundle:
|
||||
|
||||
```bash
|
||||
VITE_WEBRTC_WS_URL=ws://raspbot-v2.local:8443 docker compose build webui
|
||||
```
|
||||
|
||||
### Run
|
||||
|
||||
```bash
|
||||
docker compose up webui
|
||||
```
|
||||
|
||||
Or start everything together:
|
||||
|
||||
```bash
|
||||
docker compose up
|
||||
```
|
||||
|
||||
The web UI is served on **port 8080** of the host.
|
||||
|
||||
### Configuration
|
||||
|
||||
| Variable | Default | Description |
|
||||
|----------|---------|-------------|
|
||||
| `ROS_DOMAIN_ID` | `0` | ROS 2 DDS domain — must match the robot container |
|
||||
| `VITE_WEBRTC_WS_URL` | `ws://<page-hostname>:8443` | WebRTC signaling server URL (baked in at build time) |
|
||||
| `CAMERA_DEVICE` | `0` | (unused in production — camera is handled by the WebRTC container) |
|
||||
@@ -0,0 +1,105 @@
|
||||
import asyncio
|
||||
import logging
|
||||
from contextlib import asynccontextmanager
|
||||
from pathlib import Path
|
||||
|
||||
from fastapi import FastAPI, WebSocket, WebSocketDisconnect
|
||||
from fastapi.responses import FileResponse, JSONResponse
|
||||
|
||||
from ros_node import get_node, start_ros, stop_ros
|
||||
|
||||
logging.basicConfig(level=logging.INFO)
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
STATIC_DIR = Path(__file__).parent / 'static'
|
||||
|
||||
|
||||
class ConnectionManager:
|
||||
def __init__(self) -> None:
|
||||
self.connections: list[WebSocket] = []
|
||||
self._loop: asyncio.AbstractEventLoop | None = None
|
||||
|
||||
def set_loop(self, loop: asyncio.AbstractEventLoop) -> None:
|
||||
self._loop = loop
|
||||
|
||||
async def connect(self, ws: WebSocket) -> None:
|
||||
await ws.accept()
|
||||
self.connections.append(ws)
|
||||
|
||||
def disconnect(self, ws: WebSocket) -> None:
|
||||
if ws in self.connections:
|
||||
self.connections.remove(ws)
|
||||
|
||||
def broadcast_from_thread(self, data: dict) -> None:
|
||||
if self._loop and self._loop.is_running():
|
||||
asyncio.run_coroutine_threadsafe(self._broadcast(data), self._loop)
|
||||
|
||||
async def _broadcast(self, data: dict) -> None:
|
||||
dead = []
|
||||
for ws in self.connections:
|
||||
try:
|
||||
await ws.send_json(data)
|
||||
except Exception:
|
||||
dead.append(ws)
|
||||
for ws in dead:
|
||||
self.disconnect(ws)
|
||||
|
||||
|
||||
manager = ConnectionManager()
|
||||
|
||||
|
||||
@asynccontextmanager
|
||||
async def lifespan(app: FastAPI):
|
||||
manager.set_loop(asyncio.get_event_loop())
|
||||
node = start_ros()
|
||||
node.on_joint_states_callbacks.append(manager.broadcast_from_thread)
|
||||
node.on_ultrasonic_callbacks.append(manager.broadcast_from_thread)
|
||||
yield
|
||||
stop_ros()
|
||||
|
||||
|
||||
app = FastAPI(lifespan=lifespan)
|
||||
|
||||
|
||||
@app.websocket('/ws')
|
||||
async def websocket_endpoint(ws: WebSocket):
|
||||
await manager.connect(ws)
|
||||
node = get_node()
|
||||
try:
|
||||
while True:
|
||||
data = await ws.receive_json()
|
||||
msg_type = data.get('type')
|
||||
if msg_type == 'cmd_vel':
|
||||
node.publish_cmd_vel(data.get('linear_x', 0.0), data.get('angular_z', 0.0))
|
||||
elif msg_type == 'joint_command':
|
||||
node.publish_joint_command(data.get('pan', 0.0), data.get('tilt', 0.0))
|
||||
except WebSocketDisconnect:
|
||||
pass
|
||||
except Exception as e:
|
||||
logger.error('WebSocket error: %s', e)
|
||||
finally:
|
||||
manager.disconnect(ws)
|
||||
try:
|
||||
node.publish_cmd_vel(0.0, 0.0)
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
|
||||
@app.get('/{full_path:path}')
|
||||
async def serve_spa(full_path: str):
|
||||
index = STATIC_DIR / 'index.html'
|
||||
if not index.exists():
|
||||
return JSONResponse(
|
||||
{'detail': 'Frontend not built. In dev mode open http://localhost:5173'},
|
||||
status_code=404,
|
||||
)
|
||||
candidate = (STATIC_DIR / full_path).resolve()
|
||||
static_root = STATIC_DIR.resolve()
|
||||
if str(candidate).startswith(str(static_root)) and full_path and candidate.is_file():
|
||||
return FileResponse(candidate)
|
||||
return FileResponse(index)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
import uvicorn
|
||||
uvicorn.run(app, host='0.0.0.0', port=8080)
|
||||
@@ -0,0 +1,3 @@
|
||||
fastapi>=0.115.0
|
||||
uvicorn[standard]>=0.32.0
|
||||
numpy
|
||||
@@ -0,0 +1,76 @@
|
||||
import threading
|
||||
|
||||
import rclpy
|
||||
from geometry_msgs.msg import Twist
|
||||
from rclpy.node import Node
|
||||
from sensor_msgs.msg import JointState, Range
|
||||
|
||||
|
||||
class RobotBridgeNode(Node):
|
||||
def __init__(self):
|
||||
super().__init__('webui_bridge')
|
||||
|
||||
self._cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10)
|
||||
self._joint_cmd_pub = self.create_publisher(JointState, '/joint_command', 10)
|
||||
|
||||
self.create_subscription(JointState, '/joint_states', self._on_joint_states, 10)
|
||||
self.create_subscription(Range, '/ultrasonic/range', self._on_ultrasonic, 10)
|
||||
|
||||
self.on_joint_states_callbacks: list = []
|
||||
self.on_ultrasonic_callbacks: list = []
|
||||
|
||||
def publish_cmd_vel(self, linear_x: float, angular_z: float) -> None:
|
||||
# print(f'Publishing cmd_vel: linear_x={linear_x}, angular_z={angular_z}')
|
||||
msg = Twist()
|
||||
msg.linear.x = float(linear_x)
|
||||
msg.angular.z = float(angular_z)
|
||||
try:
|
||||
self._cmd_vel_pub.publish(msg)
|
||||
except Exception as e:
|
||||
print('Failed to publish cmd_vel:', e)
|
||||
# self._cmd_vel_pub.publish(msg)
|
||||
|
||||
def publish_joint_command(self, pan: float, tilt: float) -> None:
|
||||
msg = JointState()
|
||||
msg.header.stamp = self.get_clock().now().to_msg()
|
||||
msg.name = ['pan', 'tilt']
|
||||
msg.position = [float(pan), float(tilt)]
|
||||
self._joint_cmd_pub.publish(msg)
|
||||
|
||||
def _on_joint_states(self, msg: JointState) -> None:
|
||||
data = {'type': 'joint_states', 'positions': dict(zip(msg.name, msg.position))}
|
||||
for cb in self.on_joint_states_callbacks:
|
||||
cb(data)
|
||||
|
||||
def _on_ultrasonic(self, msg: Range) -> None:
|
||||
data = {'type': 'ultrasonic', 'range': msg.range}
|
||||
for cb in self.on_ultrasonic_callbacks:
|
||||
cb(data)
|
||||
|
||||
|
||||
_node: RobotBridgeNode | None = None
|
||||
_spin_thread: threading.Thread | None = None
|
||||
|
||||
|
||||
def start_ros() -> RobotBridgeNode:
|
||||
global _node, _spin_thread
|
||||
rclpy.init()
|
||||
_node = RobotBridgeNode()
|
||||
_spin_thread = threading.Thread(target=rclpy.spin, args=(_node,), daemon=True)
|
||||
_spin_thread.start()
|
||||
return _node
|
||||
|
||||
|
||||
def get_node() -> RobotBridgeNode:
|
||||
assert _node is not None, "ROS node not started"
|
||||
return _node
|
||||
|
||||
|
||||
def stop_ros() -> None:
|
||||
global _node
|
||||
try:
|
||||
if _node:
|
||||
_node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
except Exception:
|
||||
pass
|
||||
@@ -0,0 +1,39 @@
|
||||
import asyncio
|
||||
import os
|
||||
|
||||
import av
|
||||
import cv2
|
||||
from aiortc import VideoStreamTrack
|
||||
|
||||
CAMERA_DEVICE = int(os.environ.get('CAMERA_DEVICE', '0'))
|
||||
|
||||
|
||||
class CameraVideoTrack(VideoStreamTrack):
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
self._cap = cv2.VideoCapture(CAMERA_DEVICE)
|
||||
self._cap.set(cv2.CAP_PROP_FRAME_WIDTH, 640)
|
||||
self._cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 480)
|
||||
self._cap.set(cv2.CAP_PROP_FPS, 30)
|
||||
self._cap.set(cv2.CAP_PROP_BUFFERSIZE, 1)
|
||||
|
||||
async def recv(self) -> av.VideoFrame:
|
||||
pts, time_base = await self.next_timestamp()
|
||||
|
||||
loop = asyncio.get_event_loop()
|
||||
ret, frame = await loop.run_in_executor(None, self._cap.read)
|
||||
|
||||
if not ret:
|
||||
import numpy as np
|
||||
frame = np.zeros((480, 640, 3), dtype=np.uint8)
|
||||
else:
|
||||
frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)
|
||||
|
||||
video_frame = av.VideoFrame.from_ndarray(frame, format='rgb24')
|
||||
video_frame.pts = pts
|
||||
video_frame.time_base = time_base
|
||||
return video_frame
|
||||
|
||||
def __del__(self) -> None:
|
||||
if self._cap:
|
||||
self._cap.release()
|
||||
Executable
+90
@@ -0,0 +1,90 @@
|
||||
#!/usr/bin/env bash
|
||||
# Starts the FastAPI backend and Vite frontend for local development.
|
||||
# Run from anywhere — paths are resolved relative to this script.
|
||||
set -euo pipefail
|
||||
|
||||
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
|
||||
BACKEND_DIR="$SCRIPT_DIR/backend"
|
||||
FRONTEND_DIR="$SCRIPT_DIR/frontend"
|
||||
VENV="$BACKEND_DIR/.venv"
|
||||
|
||||
# Match whichever ROS_DOMAIN_ID the robot containers are using (default 0).
|
||||
# Override: ROS_DOMAIN_ID=42 ./dev.sh
|
||||
ROS_DOMAIN_ID="${ROS_DOMAIN_ID:-0}"
|
||||
|
||||
# Hostname of the WebRTC signaling server (default: same host as the page).
|
||||
# Override: VITE_WEBRTC_HOST=rapsbot-v2.local ./dev.sh
|
||||
# Or set VITE_WEBRTC_HOST in frontend/.env.local (see .env.local.example).
|
||||
export VITE_WEBRTC_HOST="${VITE_WEBRTC_HOST:-}"
|
||||
|
||||
# ── colour helpers ────────────────────────────────────────────────────────────
|
||||
G='\033[0;32m'; Y='\033[1;33m'; R='\033[0;31m'; NC='\033[0m'
|
||||
info() { echo -e "${G}[webui]${NC} $*"; }
|
||||
warn() { echo -e "${Y}[webui]${NC} $*"; }
|
||||
error() { echo -e "${R}[webui]${NC} $*" >&2; }
|
||||
|
||||
# ── sanity checks ─────────────────────────────────────────────────────────────
|
||||
if [ -z "${ROS_DISTRO:-}" ]; then
|
||||
error "ROS_DISTRO is not set. Source a ROS setup file first, or rebuild the devcontainer."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if ! command -v node &>/dev/null; then
|
||||
error "Node.js not found. Rebuild the devcontainer to install it (see .devcontainer/Dockerfile)."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# ── backend: venv ─────────────────────────────────────────────────────────────
|
||||
# Prefer the venv baked into the devcontainer image; fall back to a local one.
|
||||
if [ -d "/opt/webui-venv" ]; then
|
||||
VENV="/opt/webui-venv"
|
||||
info "Using devcontainer venv at $VENV"
|
||||
else
|
||||
if [ ! -d "$VENV" ]; then
|
||||
info "Creating Python venv at $VENV..."
|
||||
python3 -m venv "$VENV"
|
||||
fi
|
||||
info "Syncing backend dependencies..."
|
||||
"$VENV/bin/pip" install -q -r "$BACKEND_DIR/requirements.txt"
|
||||
fi
|
||||
|
||||
# ── frontend: npm deps ────────────────────────────────────────────────────────
|
||||
if [ ! -d "$FRONTEND_DIR/node_modules" ]; then
|
||||
info "Installing frontend dependencies..."
|
||||
npm --prefix "$FRONTEND_DIR" install
|
||||
fi
|
||||
|
||||
# ── cleanup on exit ───────────────────────────────────────────────────────────
|
||||
BACKEND_PID=""
|
||||
FRONTEND_PID=""
|
||||
|
||||
cleanup() {
|
||||
warn "Shutting down..."
|
||||
[ -n "$BACKEND_PID" ] && kill "$BACKEND_PID" 2>/dev/null || true
|
||||
[ -n "$FRONTEND_PID" ] && kill "$FRONTEND_PID" 2>/dev/null || true
|
||||
wait "$BACKEND_PID" "$FRONTEND_PID" 2>/dev/null || true
|
||||
}
|
||||
trap cleanup EXIT INT TERM
|
||||
|
||||
# ── start backend ─────────────────────────────────────────────────────────────
|
||||
info "Starting FastAPI backend on :8080 (ROS_DOMAIN_ID=$ROS_DOMAIN_ID)"
|
||||
(
|
||||
# shellcheck disable=SC1091
|
||||
set +u # ROS setup.bash references AMENT_TRACE_SETUP_FILES without a default
|
||||
source "/opt/ros/$ROS_DISTRO/setup.bash"
|
||||
export ROS_DOMAIN_ID
|
||||
exec "$VENV/bin/python3" "$BACKEND_DIR/main.py"
|
||||
) &
|
||||
BACKEND_PID=$!
|
||||
|
||||
# ── start frontend ────────────────────────────────────────────────────────────
|
||||
info "Starting Vite dev server on :5173"
|
||||
npm --prefix "$FRONTEND_DIR" run dev &
|
||||
FRONTEND_PID=$!
|
||||
|
||||
info "Ready — open http://localhost:5173"
|
||||
info "Press Ctrl+C to stop both processes."
|
||||
echo
|
||||
|
||||
# Exit as soon as either process dies
|
||||
wait -n "$BACKEND_PID" "$FRONTEND_PID"
|
||||
@@ -0,0 +1,8 @@
|
||||
# Copy this file to .env.local and edit for your setup.
|
||||
# .env.local is gitignored — safe for local overrides.
|
||||
|
||||
# Hostname of the WebRTC signaling server (GStreamer webrtcsink) for the video stream.
|
||||
# Defaults to the same host as the page when unset (fine for production).
|
||||
# Override to point at a remote robot during development:
|
||||
# VITE_WEBRTC_HOST=rapsbot-v2.local
|
||||
VITE_WEBRTC_HOST=
|
||||
@@ -0,0 +1,3 @@
|
||||
node_modules/
|
||||
dist/
|
||||
.env.local
|
||||
@@ -0,0 +1,16 @@
|
||||
<!doctype html>
|
||||
<html lang="en">
|
||||
<head>
|
||||
<meta charset="UTF-8" />
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1.0" />
|
||||
<title>Raspbot Control</title>
|
||||
<style>
|
||||
*, *::before, *::after { box-sizing: border-box; margin: 0; padding: 0; }
|
||||
body { background: #111; color: #eee; font-family: monospace; overflow: hidden; }
|
||||
</style>
|
||||
</head>
|
||||
<body>
|
||||
<div id="root"></div>
|
||||
<script type="module" src="/src/main.jsx"></script>
|
||||
</body>
|
||||
</html>
|
||||
Generated
+1794
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,19 @@
|
||||
{
|
||||
"name": "raspbot-webui",
|
||||
"private": true,
|
||||
"version": "0.1.0",
|
||||
"type": "module",
|
||||
"scripts": {
|
||||
"dev": "vite",
|
||||
"build": "vite build",
|
||||
"preview": "vite preview"
|
||||
},
|
||||
"dependencies": {
|
||||
"react": "^18.3.1",
|
||||
"react-dom": "^18.3.1"
|
||||
},
|
||||
"devDependencies": {
|
||||
"@vitejs/plugin-react": "^4.3.4",
|
||||
"vite": "^6.0.5"
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
import { useState } from 'react'
|
||||
import { CameraControls } from './components/CameraControls.jsx'
|
||||
import { RobotControls } from './components/RobotControls.jsx'
|
||||
import { VideoStream } from './components/VideoStream.jsx'
|
||||
import { useWebSocket } from './hooks/useWebSocket.js'
|
||||
|
||||
export default function App() {
|
||||
const [jointStates, setJointStates] = useState({})
|
||||
const [range, setRange] = useState(null)
|
||||
|
||||
const send = useWebSocket((msg) => {
|
||||
if (msg.type === 'joint_states') setJointStates(msg.positions)
|
||||
if (msg.type === 'ultrasonic') setRange(msg.range)
|
||||
})
|
||||
|
||||
return (
|
||||
<div style={{ display: 'flex', flexDirection: 'column', height: '100vh', padding: 8, gap: 8 }}>
|
||||
{/* Header */}
|
||||
<div style={{ display: 'flex', alignItems: 'center', justifyContent: 'space-between', flexShrink: 0 }}>
|
||||
<span style={{ fontSize: 13, color: '#4ade80', letterSpacing: 2 }}>RASPBOT</span>
|
||||
{range !== null && (
|
||||
<span style={{ fontSize: 12, color: range < 0.3 ? '#f87171' : '#facc15' }}>
|
||||
▶ {range.toFixed(2)} m
|
||||
</span>
|
||||
)}
|
||||
</div>
|
||||
|
||||
{/* Video */}
|
||||
<div style={{ flexShrink: 0 }}>
|
||||
<VideoStream />
|
||||
</div>
|
||||
|
||||
{/* Controls */}
|
||||
<div style={{ display: 'flex', justifyContent: 'space-between', alignItems: 'flex-start', gap: 16, flex: 1 }}>
|
||||
<RobotControls send={send} />
|
||||
<CameraControls send={send} jointStates={jointStates} />
|
||||
</div>
|
||||
</div>
|
||||
)
|
||||
}
|
||||
@@ -0,0 +1,64 @@
|
||||
import { useState } from 'react'
|
||||
|
||||
const PAN_MIN = -Math.PI / 2 // -90°
|
||||
const PAN_MAX = Math.PI / 2 // +90°
|
||||
const TILT_MIN = -0.524 // -30°
|
||||
const TILT_MAX = 0.960 // +55°
|
||||
|
||||
const toDeg = (r) => Math.round(r * 180 / Math.PI)
|
||||
|
||||
export function CameraControls({ send, jointStates }) {
|
||||
const [pan, setPan] = useState(0)
|
||||
const [tilt, setTilt] = useState(0)
|
||||
|
||||
const sendCmd = (p, t) => send({ type: 'joint_command', pan: p, tilt: t })
|
||||
|
||||
const row = { display: 'flex', flexDirection: 'column', gap: 4 }
|
||||
const label = { fontSize: 12, color: '#888', display: 'flex', justifyContent: 'space-between' }
|
||||
|
||||
return (
|
||||
<div style={{ display: 'flex', flexDirection: 'column', gap: 10, minWidth: 180 }}>
|
||||
<div style={{ fontSize: 12, color: '#555', borderBottom: '1px solid #2a2a2a', paddingBottom: 4 }}>
|
||||
Camera
|
||||
</div>
|
||||
|
||||
<div style={row}>
|
||||
<div style={label}>
|
||||
<span>Pan</span>
|
||||
<span style={{ color: '#4ade80' }}>{toDeg(jointStates?.pan ?? pan)}°</span>
|
||||
</div>
|
||||
<input
|
||||
type="range"
|
||||
min={PAN_MIN} max={PAN_MAX} step={0.01}
|
||||
value={pan}
|
||||
style={{ accentColor: '#4ade80', width: '100%' }}
|
||||
onChange={(e) => { const v = +e.target.value; setPan(v); sendCmd(v, tilt) }}
|
||||
/>
|
||||
</div>
|
||||
|
||||
<div style={row}>
|
||||
<div style={label}>
|
||||
<span>Tilt</span>
|
||||
<span style={{ color: '#4ade80' }}>{toDeg(jointStates?.tilt ?? tilt)}°</span>
|
||||
</div>
|
||||
<input
|
||||
type="range"
|
||||
min={TILT_MIN} max={TILT_MAX} step={0.01}
|
||||
value={tilt}
|
||||
style={{ accentColor: '#4ade80', width: '100%' }}
|
||||
onChange={(e) => { const v = +e.target.value; setTilt(v); sendCmd(pan, v) }}
|
||||
/>
|
||||
</div>
|
||||
|
||||
<button
|
||||
onClick={() => { setPan(0); setTilt(0); sendCmd(0, 0) }}
|
||||
style={{
|
||||
background: '#2a2a2a', color: '#aaa', border: '1px solid #444',
|
||||
padding: '4px 8px', borderRadius: 4, cursor: 'pointer', fontSize: 12,
|
||||
}}
|
||||
>
|
||||
Centre
|
||||
</button>
|
||||
</div>
|
||||
)
|
||||
}
|
||||
@@ -0,0 +1,111 @@
|
||||
import { useEffect, useRef, useState } from 'react'
|
||||
|
||||
const LINEAR_SPEED = 0.3 // m/s
|
||||
const ANGULAR_SPEED = 1.0 // rad/s
|
||||
const SEND_HZ = 100 // ms between cmd_vel publishes
|
||||
|
||||
// Keys that map to velocity deltas
|
||||
const KEY_VELS = {
|
||||
w: { linear_x: LINEAR_SPEED, angular_z: 0 },
|
||||
s: { linear_x: -LINEAR_SPEED, angular_z: 0 },
|
||||
a: { linear_x: 0, angular_z: ANGULAR_SPEED },
|
||||
d: { linear_x: 0, angular_z: -ANGULAR_SPEED },
|
||||
ArrowUp: { linear_x: LINEAR_SPEED, angular_z: 0 },
|
||||
ArrowDown: { linear_x: -LINEAR_SPEED, angular_z: 0 },
|
||||
ArrowLeft: { linear_x: 0, angular_z: ANGULAR_SPEED },
|
||||
ArrowRight: { linear_x: 0, angular_z: -ANGULAR_SPEED },
|
||||
}
|
||||
|
||||
// Map D-pad button ids to their keyboard equivalents
|
||||
const DPAD = [
|
||||
{ id: 'w', label: '▲', row: 0, col: 1 },
|
||||
{ id: 'a', label: '◄', row: 1, col: 0 },
|
||||
{ id: 's', label: '▼', row: 1, col: 1 },
|
||||
{ id: 'd', label: '►', row: 1, col: 2 },
|
||||
]
|
||||
|
||||
export function RobotControls({ send }) {
|
||||
const keysRef = useRef(new Set())
|
||||
const [activeKeys, setActiveKeys] = useState(new Set())
|
||||
|
||||
const computeVelocity = () => {
|
||||
let linear_x = 0, angular_z = 0
|
||||
for (const k of keysRef.current) {
|
||||
const v = KEY_VELS[k]
|
||||
if (v) { linear_x += v.linear_x; angular_z += v.angular_z }
|
||||
}
|
||||
return {
|
||||
linear_x: Math.max(-LINEAR_SPEED, Math.min(LINEAR_SPEED, linear_x)),
|
||||
angular_z: Math.max(-ANGULAR_SPEED, Math.min(ANGULAR_SPEED, angular_z)),
|
||||
}
|
||||
}
|
||||
|
||||
useEffect(() => {
|
||||
const press = (key) => {
|
||||
if (!KEY_VELS[key] || keysRef.current.has(key)) return
|
||||
keysRef.current.add(key)
|
||||
setActiveKeys(new Set(keysRef.current))
|
||||
}
|
||||
const release = (key) => {
|
||||
if (!KEY_VELS[key]) return
|
||||
keysRef.current.delete(key)
|
||||
setActiveKeys(new Set(keysRef.current))
|
||||
}
|
||||
|
||||
const onKeyDown = (e) => { press(e.key); if (KEY_VELS[e.key]) e.preventDefault() }
|
||||
const onKeyUp = (e) => { release(e.key); if (KEY_VELS[e.key]) e.preventDefault() }
|
||||
|
||||
window.addEventListener('keydown', onKeyDown)
|
||||
window.addEventListener('keyup', onKeyUp)
|
||||
|
||||
const timer = setInterval(() => send({ type: 'cmd_vel', ...computeVelocity() }), SEND_HZ)
|
||||
|
||||
return () => {
|
||||
window.removeEventListener('keydown', onKeyDown)
|
||||
window.removeEventListener('keyup', onKeyUp)
|
||||
clearInterval(timer)
|
||||
send({ type: 'cmd_vel', linear_x: 0, angular_z: 0 })
|
||||
}
|
||||
}, [send])
|
||||
|
||||
// Aliases: treat w/ArrowUp etc. as the same logical key for D-pad highlighting
|
||||
const isActive = (id) => activeKeys.has(id) || activeKeys.has(
|
||||
{ w: 'ArrowUp', s: 'ArrowDown', a: 'ArrowLeft', d: 'ArrowRight' }[id]
|
||||
)
|
||||
|
||||
const dpadPress = (id) => () => {
|
||||
keysRef.current.add(id)
|
||||
setActiveKeys(new Set(keysRef.current))
|
||||
}
|
||||
const dpadRelease = (id) => () => {
|
||||
keysRef.current.delete(id)
|
||||
setActiveKeys(new Set(keysRef.current))
|
||||
}
|
||||
|
||||
return (
|
||||
<div style={{ display: 'flex', flexDirection: 'column', alignItems: 'center', gap: 8 }}>
|
||||
<div style={{ display: 'grid', gridTemplateColumns: 'repeat(3, 48px)', gridTemplateRows: 'repeat(2, 48px)', gap: 4 }}>
|
||||
{DPAD.map(({ id, label, row, col }) => (
|
||||
<button
|
||||
key={id}
|
||||
onMouseDown={dpadPress(id)}
|
||||
onMouseUp={dpadRelease(id)}
|
||||
onMouseLeave={dpadRelease(id)}
|
||||
onTouchStart={(e) => { e.preventDefault(); dpadPress(id)() }}
|
||||
onTouchEnd={(e) => { e.preventDefault(); dpadRelease(id)() }}
|
||||
style={{
|
||||
gridRow: row + 1, gridColumn: col + 1,
|
||||
background: isActive(id) ? '#4ade80' : '#2a2a2a',
|
||||
color: isActive(id) ? '#000' : '#aaa',
|
||||
border: '1px solid #444', borderRadius: 6,
|
||||
cursor: 'pointer', fontSize: 18, userSelect: 'none',
|
||||
}}
|
||||
>
|
||||
{label}
|
||||
</button>
|
||||
))}
|
||||
</div>
|
||||
<div style={{ fontSize: 11, color: '#555' }}>WASD / arrow keys</div>
|
||||
</div>
|
||||
)
|
||||
}
|
||||
@@ -0,0 +1,78 @@
|
||||
import { useEffect, useRef } from 'react'
|
||||
|
||||
// Signaling host for the GStreamer WebRTC server (hostname only, e.g. rapsbot-v2.local).
|
||||
// Set VITE_WEBRTC_HOST in .env.local or as an env var; defaults to the current page host.
|
||||
const signalingHost = import.meta.env.VITE_WEBRTC_HOST || window.location.hostname
|
||||
const SIGNALING_WS_URL = `ws://${signalingHost}:8443`
|
||||
|
||||
export function VideoStream() {
|
||||
const videoRef = useRef(null)
|
||||
const pcRef = useRef(null)
|
||||
const wsRef = useRef(null)
|
||||
|
||||
useEffect(() => {
|
||||
console.log('[WebRTC] Connecting to', SIGNALING_WS_URL)
|
||||
const pc = new RTCPeerConnection({})
|
||||
const ws = new WebSocket(SIGNALING_WS_URL)
|
||||
|
||||
pcRef.current = pc
|
||||
wsRef.current = ws
|
||||
|
||||
pc.onconnectionstatechange = () => console.log('[WebRTC] PC state:', pc.connectionState)
|
||||
pc.oniceconnectionstatechange = () => console.log('[WebRTC] ICE state:', pc.iceConnectionState)
|
||||
|
||||
pc.ontrack = ({ streams }) => {
|
||||
console.log('[WebRTC] Track received, streams:', streams.length)
|
||||
if (videoRef.current) videoRef.current.srcObject = streams[0]
|
||||
}
|
||||
|
||||
pc.onicecandidate = ({ candidate }) => {
|
||||
if (candidate && ws.readyState === WebSocket.OPEN) {
|
||||
ws.send(JSON.stringify({
|
||||
type: 'ice',
|
||||
mlineindex: candidate.sdpMLineIndex,
|
||||
candidate: candidate.candidate,
|
||||
}))
|
||||
}
|
||||
}
|
||||
|
||||
ws.onopen = () => console.log('[WebRTC] Signaling connected')
|
||||
ws.onclose = () => console.log('[WebRTC] Signaling closed')
|
||||
|
||||
ws.onmessage = async (event) => {
|
||||
const msg = JSON.parse(event.data)
|
||||
console.log('[WebRTC] Signal:', msg.type, msg)
|
||||
|
||||
if (msg.type === 'offer') {
|
||||
await pc.setRemoteDescription({ type: 'offer', sdp: msg.sdp })
|
||||
const answer = await pc.createAnswer()
|
||||
await pc.setLocalDescription(answer)
|
||||
ws.send(JSON.stringify({ type: 'answer', sdp: answer.sdp }))
|
||||
console.log('[WebRTC] Answer sent')
|
||||
} else if (msg.type === 'ice') {
|
||||
await pc.addIceCandidate({ sdpMLineIndex: msg.mlineindex, candidate: msg.candidate })
|
||||
}
|
||||
}
|
||||
|
||||
let cleanedUp = false
|
||||
ws.onerror = (e) => {
|
||||
if (!cleanedUp) console.error('[WebRTC] Signaling error', e)
|
||||
}
|
||||
|
||||
return () => {
|
||||
cleanedUp = true
|
||||
pc.close()
|
||||
ws.close()
|
||||
}
|
||||
}, [])
|
||||
|
||||
return (
|
||||
<video
|
||||
ref={videoRef}
|
||||
autoPlay
|
||||
playsInline
|
||||
muted
|
||||
style={{ width: '100%', maxHeight: '60vh', background: '#000', display: 'block' }}
|
||||
/>
|
||||
)
|
||||
}
|
||||
@@ -0,0 +1,31 @@
|
||||
import { useCallback, useEffect, useRef } from 'react'
|
||||
|
||||
export function useWebSocket(onMessage) {
|
||||
const wsRef = useRef(null)
|
||||
const onMessageRef = useRef(onMessage)
|
||||
onMessageRef.current = onMessage
|
||||
|
||||
useEffect(() => {
|
||||
const ws = new WebSocket(`ws://${window.location.host}/ws`)
|
||||
wsRef.current = ws
|
||||
|
||||
ws.onmessage = (e) => {
|
||||
try { onMessageRef.current(JSON.parse(e.data)) } catch {}
|
||||
}
|
||||
let cleanedUp = false
|
||||
ws.onerror = (e) => {
|
||||
if (!cleanedUp) console.error('WebSocket error', e)
|
||||
}
|
||||
|
||||
return () => {
|
||||
cleanedUp = true
|
||||
ws.close()
|
||||
}
|
||||
}, [])
|
||||
|
||||
return useCallback((data) => {
|
||||
if (wsRef.current?.readyState === WebSocket.OPEN) {
|
||||
wsRef.current.send(JSON.stringify(data))
|
||||
}
|
||||
}, [])
|
||||
}
|
||||
@@ -0,0 +1,4 @@
|
||||
import { createRoot } from 'react-dom/client'
|
||||
import App from './App.jsx'
|
||||
|
||||
createRoot(document.getElementById('root')).render(<App />)
|
||||
@@ -0,0 +1,12 @@
|
||||
import { defineConfig } from 'vite'
|
||||
import react from '@vitejs/plugin-react'
|
||||
|
||||
export default defineConfig({
|
||||
plugins: [react()],
|
||||
server: {
|
||||
proxy: {
|
||||
'/offer': 'http://localhost:8080',
|
||||
'/ws': { target: 'ws://localhost:8080', ws: true },
|
||||
},
|
||||
},
|
||||
})
|
||||
Reference in New Issue
Block a user