Project 2: Teleop Dashboard with Camera Streaming
Overview
Build a web-based teleoperation dashboard that combines Project 1’s interactive features with ROS2 capabilities. The dashboard provides real-time camera streaming, movement controls, and system monitoring - all accessible from any device on your network.
Learning Objectives
By completing this project, you will:
- Create a web-based robot control interface
- Stream camera images using ROS2 topics
- Integrate ROS2 with Flask web framework
- Understand coordinate transforms and visualization
- Build a complete remote control system
Prerequisites
| Lab | Topic | Skills Used |
|---|---|---|
| Project 1 | Interactive Pet | All Jupyter Lab skills |
| ROS2 Lab 1 | ROS2 Basics | Nodes, topics, publishers |
| ROS2 Lab 2 | Camera Topics | Image streaming |
| ROS2 Lab 3 | TF Transforms | Coordinate frames |
| ROS2 Lab 4 | RViz Visualization | Robot state display |
Hardware Requirements
- Mini Pupper v2 with camera
- WiFi connection
- Computer/tablet/phone for dashboard access
Part 1: System Architecture
┌─────────────────────────────────────────────────────────────────────┐
│ Teleop Dashboard System │
├─────────────────────────────────────────────────────────────────────┤
│ │
│ ┌─────────────────────────────────────────────────────────────┐ │
│ │ Web Browser │ │
│ │ ┌──────────┐ ┌──────────┐ ┌──────────┐ ┌──────────┐ │ │
│ │ │ Camera │ │ Movement │ │ Status │ │ Emotions │ │ │
│ │ │ View │ │ Controls │ │ Panel │ │ Controls │ │ │
│ │ └────┬─────┘ └────┬─────┘ └────┬─────┘ └────┬─────┘ │ │
│ └───────┼─────────────┼─────────────┼─────────────┼─────────┘ │
│ │ │ │ │ │
│ ▼ ▼ ▼ ▼ │
│ ┌─────────────────────────────────────────────────────────────┐ │
│ │ Flask Web Server │ │
│ │ ┌──────────────────────────────────────────────────────┐ │ │
│ │ │ ROS2 Bridge Node │ │ │
│ │ └──────────────────────────────────────────────────────┘ │ │
│ └──────────────────────────┬──────────────────────────────────┘ │
│ │ │
│ ┌──────────────────────────▼──────────────────────────────────┐ │
│ │ ROS2 Topics │ │
│ │ /image_raw /cmd_vel /joint_states /robot_state │ │
│ └─────────────────────────────────────────────────────────────┘ │
│ │
│ ┌──────────────────────────────────────────────────────────────┐ │
│ │ Mini Pupper Hardware │ │
│ └──────────────────────────────────────────────────────────────┘ │
└─────────────────────────────────────────────────────────────────────┘
Part 2: Project Setup
Step 1: Create Project Structure
mkdir -p ~/teleop_dashboard/{src,templates,static/{css,js,images}}
cd ~/teleop_dashboard
Step 2: Install Dependencies
pip3 install flask flask-socketio opencv-python-headless
Part 3: ROS2 Bridge Node
Create src/ros_bridge.py:
#!/usr/bin/env python3
"""
ROS2 Bridge Node - Connects ROS2 to Web Dashboard
Based on ROS2 Labs 1-4
"""
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image, JointState
from geometry_msgs.msg import Twist
from std_msgs.msg import String
from cv_bridge import CvBridge
import cv2
import numpy as np
import json
from threading import Lock
from dataclasses import dataclass
from typing import Optional, Dict, Any
@dataclass
class RobotState:
"""Current robot state"""
joint_positions: Dict[str, float]
joint_velocities: Dict[str, float]
battery_level: float
is_moving: bool
current_emotion: str
class ROSBridge(Node):
"""Bridge between ROS2 and web dashboard"""
def __init__(self):
super().__init__('teleop_dashboard_bridge')
self.bridge = CvBridge()
self.lock = Lock()
# State
self.current_image: Optional[np.ndarray] = None
self.robot_state = RobotState(
joint_positions={},
joint_velocities={},
battery_level=100.0,
is_moving=False,
current_emotion='neutral'
)
# Subscribers
self.image_sub = self.create_subscription(
Image, '/image_raw', self.image_callback, 10
)
self.joint_sub = self.create_subscription(
JointState, '/joint_states', self.joint_callback, 10
)
# Publishers
self.cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10)
self.emotion_pub = self.create_publisher(String, '/emotion', 10)
# Timer for status updates
self.status_timer = self.create_timer(0.1, self.update_status)
self.get_logger().info('ROS Bridge started!')
def image_callback(self, msg: Image):
"""Handle incoming camera images"""
try:
cv_image = self.bridge.imgmsg_to_cv2(msg, 'bgr8')
with self.lock:
self.current_image = cv_image
except Exception as e:
self.get_logger().error(f'Image conversion error: {e}')
def joint_callback(self, msg: JointState):
"""Handle joint state updates"""
with self.lock:
for i, name in enumerate(msg.name):
if i < len(msg.position):
self.robot_state.joint_positions[name] = msg.position[i]
if i < len(msg.velocity):
self.robot_state.joint_velocities[name] = msg.velocity[i]
def update_status(self):
"""Update robot status"""
# Check if robot is moving
with self.lock:
velocities = list(self.robot_state.joint_velocities.values())
self.robot_state.is_moving = any(abs(v) > 0.01 for v in velocities)
def get_image_jpeg(self) -> Optional[bytes]:
"""Get current image as JPEG bytes"""
with self.lock:
if self.current_image is None:
return None
ret, buffer = cv2.imencode('.jpg', self.current_image,
[cv2.IMWRITE_JPEG_QUALITY, 80])
if ret:
return buffer.tobytes()
return None
def get_state_json(self) -> str:
"""Get robot state as JSON"""
with self.lock:
state = {
'joint_positions': self.robot_state.joint_positions,
'battery_level': self.robot_state.battery_level,
'is_moving': self.robot_state.is_moving,
'current_emotion': self.robot_state.current_emotion
}
return json.dumps(state)
def send_velocity(self, linear_x: float, linear_y: float, angular_z: float):
"""Send velocity command"""
twist = Twist()
twist.linear.x = linear_x
twist.linear.y = linear_y
twist.angular.z = angular_z
self.cmd_vel_pub.publish(twist)
def send_emotion(self, emotion: str):
"""Send emotion command"""
msg = String()
msg.data = emotion
self.emotion_pub.publish(msg)
with self.lock:
self.robot_state.current_emotion = emotion
# Global bridge instance
ros_bridge: Optional[ROSBridge] = None
def init_ros():
"""Initialize ROS2 and bridge"""
global ros_bridge
rclpy.init()
ros_bridge = ROSBridge()
return ros_bridge
def spin_ros():
"""Spin ROS2 node"""
global ros_bridge
if ros_bridge:
rclpy.spin(ros_bridge)
def shutdown_ros():
"""Shutdown ROS2"""
global ros_bridge
if ros_bridge:
ros_bridge.destroy_node()
rclpy.shutdown()
Part 4: Flask Web Server
Create src/web_server.py:
#!/usr/bin/env python3
"""
Flask Web Server for Teleop Dashboard
"""
import os
from flask import Flask, render_template, Response, jsonify, request
from flask_socketio import SocketIO, emit
from threading import Thread
import time
from ros_bridge import init_ros, spin_ros, shutdown_ros, ros_bridge
# Initialize Flask app
app = Flask(__name__,
template_folder='../templates',
static_folder='../static')
app.config['SECRET_KEY'] = 'minipupper-dashboard'
socketio = SocketIO(app, cors_allowed_origins="*")
@app.route('/')
def index():
"""Main dashboard page"""
return render_template('dashboard.html')
@app.route('/video_feed')
def video_feed():
"""Video streaming route"""
def generate():
while True:
if ros_bridge:
frame = ros_bridge.get_image_jpeg()
if frame:
yield (b'--frame\r\n'
b'Content-Type: image/jpeg\r\n\r\n' + frame + b'\r\n')
time.sleep(0.033) # ~30 FPS
return Response(generate(),
mimetype='multipart/x-mixed-replace; boundary=frame')
@app.route('/api/state')
def get_state():
"""Get current robot state"""
if ros_bridge:
return Response(ros_bridge.get_state_json(),
mimetype='application/json')
return jsonify({'error': 'ROS not connected'})
@app.route('/api/velocity', methods=['POST'])
def set_velocity():
"""Set robot velocity"""
data = request.json
if ros_bridge:
ros_bridge.send_velocity(
data.get('linear_x', 0.0),
data.get('linear_y', 0.0),
data.get('angular_z', 0.0)
)
return jsonify({'success': True})
return jsonify({'error': 'ROS not connected'})
@app.route('/api/emotion', methods=['POST'])
def set_emotion():
"""Set robot emotion"""
data = request.json
emotion = data.get('emotion', 'neutral')
if ros_bridge:
ros_bridge.send_emotion(emotion)
return jsonify({'success': True})
return jsonify({'error': 'ROS not connected'})
@app.route('/api/stop', methods=['POST'])
def stop_robot():
"""Emergency stop"""
if ros_bridge:
ros_bridge.send_velocity(0.0, 0.0, 0.0)
return jsonify({'success': True})
return jsonify({'error': 'ROS not connected'})
# WebSocket handlers
@socketio.on('connect')
def handle_connect():
"""Handle client connection"""
print('Client connected')
emit('status', {'connected': True})
@socketio.on('disconnect')
def handle_disconnect():
"""Handle client disconnection"""
print('Client disconnected')
# Stop robot on disconnect for safety
if ros_bridge:
ros_bridge.send_velocity(0.0, 0.0, 0.0)
@socketio.on('joystick')
def handle_joystick(data):
"""Handle joystick input"""
if ros_bridge:
# Scale joystick values to velocities
linear_x = data.get('y', 0) * 0.15 # Forward/back
angular_z = -data.get('x', 0) * 0.5 # Left/right turn
ros_bridge.send_velocity(linear_x, 0.0, angular_z)
@socketio.on('emotion')
def handle_emotion(data):
"""Handle emotion button press"""
emotion = data.get('emotion', 'neutral')
if ros_bridge:
ros_bridge.send_emotion(emotion)
def run_server(host='0.0.0.0', port=5000):
"""Run the web server"""
# Start ROS in background thread
ros_bridge_instance = init_ros()
ros_thread = Thread(target=spin_ros, daemon=True)
ros_thread.start()
try:
# Run Flask with SocketIO
socketio.run(app, host=host, port=port, debug=False)
finally:
shutdown_ros()
if __name__ == '__main__':
run_server()
Part 5: Dashboard HTML Template
Create templates/dashboard.html:
<!DOCTYPE html>
<html lang="en">
<head>
<meta charset="UTF-8">
<meta name="viewport" content="width=device-width, initial-scale=1.0">
<title>Mini Pupper Teleop Dashboard</title>
<link rel="stylesheet" href="/static/css/dashboard.css">
<script src="https://cdn.socket.io/4.5.4/socket.io.min.js"></script>
</head>
<body>
<div class="dashboard">
<header>
<h1>🐕 Mini Pupper Dashboard</h1>
<div class="status-bar">
<span id="connection-status" class="status disconnected">Disconnected</span>
<span id="battery-level">🔋 ---%</span>
</div>
</header>
<main>
<!-- Camera View -->
<section class="camera-section">
<h2>Camera View</h2>
<div class="video-container">
<img id="video-feed" src="/video_feed" alt="Camera Feed">
<div class="video-overlay">
<span id="fps-counter">-- FPS</span>
</div>
</div>
</section>
<!-- Control Section -->
<section class="control-section">
<h2>Movement Controls</h2>
<!-- Virtual Joystick -->
<div class="joystick-container">
<div id="joystick" class="joystick">
<div id="joystick-knob" class="joystick-knob"></div>
</div>
</div>
<!-- D-Pad Alternative -->
<div class="dpad-container">
<button class="dpad-btn" id="btn-forward" data-direction="forward">↑</button>
<div class="dpad-row">
<button class="dpad-btn" id="btn-left" data-direction="left">←</button>
<button class="dpad-btn stop-btn" id="btn-stop">⬛</button>
<button class="dpad-btn" id="btn-right" data-direction="right">→</button>
</div>
<button class="dpad-btn" id="btn-backward" data-direction="backward">↓</button>
</div>
<!-- Speed Control -->
<div class="speed-control">
<label for="speed-slider">Speed:</label>
<input type="range" id="speed-slider" min="0.1" max="1.0" step="0.1" value="0.5">
<span id="speed-value">50%</span>
</div>
</section>
<!-- Emotion Section -->
<section class="emotion-section">
<h2>Emotions</h2>
<div class="emotion-grid">
<button class="emotion-btn" data-emotion="happy">😊 Happy</button>
<button class="emotion-btn" data-emotion="sad">😢 Sad</button>
<button class="emotion-btn" data-emotion="excited">🤩 Excited</button>
<button class="emotion-btn" data-emotion="sleepy">😴 Sleepy</button>
<button class="emotion-btn" data-emotion="curious">🤔 Curious</button>
<button class="emotion-btn" data-emotion="love">😍 Love</button>
</div>
<div class="current-emotion">
Current: <span id="current-emotion">neutral</span>
</div>
</section>
<!-- Status Section -->
<section class="status-section">
<h2>Robot Status</h2>
<div class="status-grid">
<div class="status-item">
<span class="label">Movement:</span>
<span id="movement-status" class="value">Stopped</span>
</div>
<div class="status-item">
<span class="label">Linear X:</span>
<span id="linear-x" class="value">0.00</span>
</div>
<div class="status-item">
<span class="label">Angular Z:</span>
<span id="angular-z" class="value">0.00</span>
</div>
</div>
</section>
</main>
<!-- Emergency Stop -->
<button id="emergency-stop" class="emergency-btn">🛑 EMERGENCY STOP</button>
</div>
<script src="/static/js/dashboard.js"></script>
</body>
</html>
Part 6: Dashboard CSS
Create static/css/dashboard.css:
* {
margin: 0;
padding: 0;
box-sizing: border-box;
}
body {
font-family: 'Segoe UI', Arial, sans-serif;
background: linear-gradient(135deg, #1a1a2e 0%, #16213e 100%);
color: #ffffff;
min-height: 100vh;
}
.dashboard {
max-width: 1400px;
margin: 0 auto;
padding: 20px;
}
header {
display: flex;
justify-content: space-between;
align-items: center;
padding: 15px 20px;
background: rgba(255, 255, 255, 0.1);
border-radius: 10px;
margin-bottom: 20px;
}
header h1 {
font-size: 1.8em;
color: #00d9ff;
}
.status-bar {
display: flex;
gap: 20px;
}
.status {
padding: 5px 15px;
border-radius: 20px;
font-size: 0.9em;
}
.status.connected {
background: #00ff88;
color: black;
}
.status.disconnected {
background: #ff4444;
}
main {
display: grid;
grid-template-columns: 2fr 1fr;
gap: 20px;
}
section {
background: rgba(255, 255, 255, 0.05);
border-radius: 15px;
padding: 20px;
}
section h2 {
color: #00d9ff;
margin-bottom: 15px;
font-size: 1.2em;
}
/* Camera Section */
.camera-section {
grid-column: 1 / 2;
grid-row: 1 / 3;
}
.video-container {
position: relative;
width: 100%;
border-radius: 10px;
overflow: hidden;
background: #000;
}
.video-container img {
width: 100%;
display: block;
}
.video-overlay {
position: absolute;
top: 10px;
right: 10px;
background: rgba(0, 0, 0, 0.7);
padding: 5px 10px;
border-radius: 5px;
font-size: 0.8em;
}
/* Control Section */
.control-section {
grid-column: 2 / 3;
}
.joystick-container {
display: flex;
justify-content: center;
margin-bottom: 20px;
}
.joystick {
width: 150px;
height: 150px;
background: rgba(0, 217, 255, 0.2);
border-radius: 50%;
border: 3px solid #00d9ff;
position: relative;
touch-action: none;
}
.joystick-knob {
width: 50px;
height: 50px;
background: #00d9ff;
border-radius: 50%;
position: absolute;
top: 50%;
left: 50%;
transform: translate(-50%, -50%);
cursor: pointer;
transition: box-shadow 0.2s;
}
.joystick-knob:hover {
box-shadow: 0 0 20px #00d9ff;
}
.dpad-container {
display: flex;
flex-direction: column;
align-items: center;
gap: 5px;
margin-bottom: 20px;
}
.dpad-row {
display: flex;
gap: 5px;
}
.dpad-btn {
width: 50px;
height: 50px;
font-size: 1.5em;
background: rgba(0, 217, 255, 0.3);
border: 2px solid #00d9ff;
border-radius: 10px;
color: white;
cursor: pointer;
transition: all 0.2s;
}
.dpad-btn:hover, .dpad-btn:active {
background: #00d9ff;
color: black;
}
.stop-btn {
background: rgba(255, 68, 68, 0.3);
border-color: #ff4444;
}
.stop-btn:hover {
background: #ff4444;
}
.speed-control {
display: flex;
align-items: center;
gap: 10px;
justify-content: center;
}
.speed-control input[type="range"] {
width: 150px;
}
/* Emotion Section */
.emotion-section {
grid-column: 2 / 3;
}
.emotion-grid {
display: grid;
grid-template-columns: repeat(2, 1fr);
gap: 10px;
}
.emotion-btn {
padding: 12px;
font-size: 1em;
background: rgba(255, 255, 255, 0.1);
border: 2px solid rgba(255, 255, 255, 0.3);
border-radius: 10px;
color: white;
cursor: pointer;
transition: all 0.2s;
}
.emotion-btn:hover {
background: rgba(255, 255, 255, 0.2);
border-color: #00d9ff;
}
.emotion-btn.active {
background: #00d9ff;
color: black;
}
.current-emotion {
margin-top: 15px;
text-align: center;
color: #888;
}
#current-emotion {
color: #00d9ff;
font-weight: bold;
}
/* Status Section */
.status-section {
grid-column: 1 / 3;
}
.status-grid {
display: grid;
grid-template-columns: repeat(3, 1fr);
gap: 20px;
}
.status-item {
background: rgba(0, 0, 0, 0.3);
padding: 15px;
border-radius: 10px;
text-align: center;
}
.status-item .label {
display: block;
color: #888;
margin-bottom: 5px;
}
.status-item .value {
font-size: 1.2em;
color: #00d9ff;
}
/* Emergency Stop */
.emergency-btn {
position: fixed;
bottom: 20px;
right: 20px;
padding: 20px 30px;
font-size: 1.2em;
background: #ff4444;
border: none;
border-radius: 10px;
color: white;
cursor: pointer;
box-shadow: 0 5px 20px rgba(255, 68, 68, 0.5);
transition: all 0.2s;
z-index: 1000;
}
.emergency-btn:hover {
transform: scale(1.05);
box-shadow: 0 5px 30px rgba(255, 68, 68, 0.8);
}
/* Responsive */
@media (max-width: 900px) {
main {
grid-template-columns: 1fr;
}
.camera-section {
grid-column: 1;
grid-row: auto;
}
.status-grid {
grid-template-columns: 1fr;
}
}
Part 7: Dashboard JavaScript
Create static/js/dashboard.js:
// WebSocket connection
const socket = io();
// State
let currentSpeed = 0.5;
let isConnected = false;
// DOM Elements
const connectionStatus = document.getElementById('connection-status');
const batteryLevel = document.getElementById('battery-level');
const currentEmotionSpan = document.getElementById('current-emotion');
const movementStatus = document.getElementById('movement-status');
const linearXSpan = document.getElementById('linear-x');
const angularZSpan = document.getElementById('angular-z');
const speedSlider = document.getElementById('speed-slider');
const speedValue = document.getElementById('speed-value');
// Socket events
socket.on('connect', () => {
isConnected = true;
connectionStatus.textContent = 'Connected';
connectionStatus.className = 'status connected';
console.log('Connected to server');
});
socket.on('disconnect', () => {
isConnected = false;
connectionStatus.textContent = 'Disconnected';
connectionStatus.className = 'status disconnected';
console.log('Disconnected from server');
});
socket.on('status', (data) => {
console.log('Status:', data);
});
// Joystick control
const joystick = document.getElementById('joystick');
const knob = document.getElementById('joystick-knob');
let isDragging = false;
function getJoystickPosition(event) {
const rect = joystick.getBoundingClientRect();
const centerX = rect.width / 2;
const centerY = rect.height / 2;
let x, y;
if (event.touches) {
x = event.touches[0].clientX - rect.left - centerX;
y = event.touches[0].clientY - rect.top - centerY;
} else {
x = event.clientX - rect.left - centerX;
y = event.clientY - rect.top - centerY;
}
// Clamp to circle
const maxRadius = centerX - 25;
const distance = Math.sqrt(x * x + y * y);
if (distance > maxRadius) {
x = (x / distance) * maxRadius;
y = (y / distance) * maxRadius;
}
return {
x: x / maxRadius, // -1 to 1
y: -y / maxRadius // -1 to 1 (inverted for natural feel)
};
}
function updateJoystick(x, y) {
// Update knob position
const rect = joystick.getBoundingClientRect();
const maxRadius = rect.width / 2 - 25;
knob.style.transform = `translate(calc(-50% + ${x * maxRadius}px), calc(-50% + ${-y * maxRadius}px))`;
// Send to server
socket.emit('joystick', { x: x * currentSpeed, y: y * currentSpeed });
// Update status display
linearXSpan.textContent = (y * currentSpeed * 0.15).toFixed(2);
angularZSpan.textContent = (-x * currentSpeed * 0.5).toFixed(2);
movementStatus.textContent = (Math.abs(x) > 0.1 || Math.abs(y) > 0.1) ? 'Moving' : 'Stopped';
}
joystick.addEventListener('mousedown', (e) => {
isDragging = true;
const pos = getJoystickPosition(e);
updateJoystick(pos.x, pos.y);
});
joystick.addEventListener('touchstart', (e) => {
isDragging = true;
const pos = getJoystickPosition(e);
updateJoystick(pos.x, pos.y);
e.preventDefault();
});
document.addEventListener('mousemove', (e) => {
if (isDragging) {
const pos = getJoystickPosition(e);
updateJoystick(pos.x, pos.y);
}
});
document.addEventListener('touchmove', (e) => {
if (isDragging) {
const pos = getJoystickPosition(e);
updateJoystick(pos.x, pos.y);
}
});
document.addEventListener('mouseup', () => {
if (isDragging) {
isDragging = false;
updateJoystick(0, 0);
}
});
document.addEventListener('touchend', () => {
if (isDragging) {
isDragging = false;
updateJoystick(0, 0);
}
});
// D-Pad controls
const directions = {
forward: { x: 0, y: 1 },
backward: { x: 0, y: -1 },
left: { x: -1, y: 0 },
right: { x: 1, y: 0 }
};
document.querySelectorAll('.dpad-btn[data-direction]').forEach(btn => {
const dir = btn.dataset.direction;
btn.addEventListener('mousedown', () => {
const d = directions[dir];
if (d) updateJoystick(d.x, d.y);
});
btn.addEventListener('mouseup', () => {
updateJoystick(0, 0);
});
btn.addEventListener('touchstart', (e) => {
const d = directions[dir];
if (d) updateJoystick(d.x, d.y);
e.preventDefault();
});
btn.addEventListener('touchend', () => {
updateJoystick(0, 0);
});
});
// Stop button
document.getElementById('btn-stop').addEventListener('click', () => {
updateJoystick(0, 0);
fetch('/api/stop', { method: 'POST' });
});
// Emergency stop
document.getElementById('emergency-stop').addEventListener('click', () => {
updateJoystick(0, 0);
fetch('/api/stop', { method: 'POST' });
alert('Emergency stop activated!');
});
// Speed control
speedSlider.addEventListener('input', (e) => {
currentSpeed = parseFloat(e.target.value);
speedValue.textContent = Math.round(currentSpeed * 100) + '%';
});
// Emotion buttons
document.querySelectorAll('.emotion-btn').forEach(btn => {
btn.addEventListener('click', () => {
const emotion = btn.dataset.emotion;
// Update UI
document.querySelectorAll('.emotion-btn').forEach(b => b.classList.remove('active'));
btn.classList.add('active');
currentEmotionSpan.textContent = emotion;
// Send to server
socket.emit('emotion', { emotion: emotion });
});
});
// Periodic state update
setInterval(() => {
fetch('/api/state')
.then(response => response.json())
.then(data => {
if (data.battery_level !== undefined) {
batteryLevel.textContent = `🔋 ${Math.round(data.battery_level)}%`;
}
if (data.current_emotion) {
currentEmotionSpan.textContent = data.current_emotion;
}
})
.catch(err => console.log('State fetch error:', err));
}, 1000);
// Keyboard controls
document.addEventListener('keydown', (e) => {
switch(e.key) {
case 'ArrowUp':
case 'w':
updateJoystick(0, 1);
break;
case 'ArrowDown':
case 's':
updateJoystick(0, -1);
break;
case 'ArrowLeft':
case 'a':
updateJoystick(-1, 0);
break;
case 'ArrowRight':
case 'd':
updateJoystick(1, 0);
break;
case ' ':
updateJoystick(0, 0);
fetch('/api/stop', { method: 'POST' });
break;
}
});
document.addEventListener('keyup', (e) => {
if (['ArrowUp', 'ArrowDown', 'ArrowLeft', 'ArrowRight', 'w', 'a', 's', 'd'].includes(e.key)) {
updateJoystick(0, 0);
}
});
console.log('Dashboard loaded. Keyboard controls: WASD or Arrow keys, Space to stop.');
Part 8: Running the Dashboard
Create src/main.py:
#!/usr/bin/env python3
"""
Teleop Dashboard - Main Entry Point
"""
import argparse
from web_server import run_server
def main():
parser = argparse.ArgumentParser(description='Mini Pupper Teleop Dashboard')
parser.add_argument('--host', default='0.0.0.0', help='Host address')
parser.add_argument('--port', type=int, default=5000, help='Port number')
args = parser.parse_args()
print(f"""
╔═══════════════════════════════════════════════════╗
║ Mini Pupper Teleop Dashboard ║
╠═══════════════════════════════════════════════════╣
║ Access at: http://<robot-ip>:{args.port} ║
║ Controls: WASD or Arrow keys, Space = Stop ║
║ Press Ctrl+C to exit ║
╚═══════════════════════════════════════════════════╝
""")
run_server(host=args.host, port=args.port)
if __name__ == '__main__':
main()
Deliverables
| Deliverable | Description |
|---|---|
src/ros_bridge.py | ROS2 to web bridge |
src/web_server.py | Flask web server |
templates/dashboard.html | Dashboard UI |
static/css/dashboard.css | Dashboard styling |
static/js/dashboard.js | Dashboard logic |
src/main.py | Entry point |
README.md | Setup instructions |
| Video Demo | Remote control demonstration |
Extension Ideas
- Multiple Cameras: Support front and back cameras
- Recording: Record video and control sessions
- Gamepad Support: USB/Bluetooth controller input
- Path Planning: Click-to-navigate on camera view
- Telemetry Graphs: Real-time charts of robot data
- Mobile App: Native iOS/Android version
Grading Rubric
| Component | Points | Criteria |
|---|---|---|
| Camera Streaming | 20 | Smooth video feed, good framerate |
| Movement Control | 25 | Responsive joystick/D-pad control |
| ROS2 Integration | 20 | Proper topic pub/sub |
| Web Dashboard | 15 | Clean, responsive UI |
| Emotion Control | 10 | Integration with Project 1 |
| Code Quality | 10 | Clean, documented code |
| Total | 100 |