A high-performance web server for the Earth Rover Mini robot that provides real-time sensor data streaming via WebSocket and HTTP APIs, with RTK GPS support for centimeter-level positioning accuracy.
- Direct Hardware Access Mode: Reads sensor data directly from STM32 via UART (UCP protocol)
- API Proxy Mode: Proxies requests to frodobot.bin API
- Real-time WebSocket Streaming: Stream sensor data at up to 50Hz
- AHRS Filtering: Madgwick filter for drift-free orientation tracking
- RTK GPS Support: Centimeter-level positioning via NTRIP correction data
- NTRIP Client: Automatic connection to RTK correction services (GeodNet, RTK2Go, Emlid, custom)
- Base Station Tracking: Real-time base station position and distance monitoring
- RTCM3 Injection: Automatic RTCM correction data injection into GPS module
- CRC16 Validation: Ensures data integrity with hardware checksums
- GPS Integration: Reads GPS data from /dev/ttyS2 with NMEA and UBX protocol support
- Modern TypeScript Client: Vite-based web application with 3D visualization
- Calibration Tools: Web-based magnetometer and IMU calibration
- GPS Time Synchronization: Dual-layer time sync with Chrony NTP server (Stratum 1)
- Debug Mode: Real-time console output for troubleshooting
STM32 → /dev/ttyS0 (UCP Protocol) → Go Webserver → WebSocket/HTTP → Dashboard
└─ GPS /dev/ttyS2 ──────────┘
↑
NTRIP Caster (GeodNet/RTK2Go) → RTCM Corrections
Advantages:
- Higher data rate (up to 50Hz vs 10Hz API limit)
- Lower latency
- AHRS filtering for accurate orientation
- RTK GPS support for centimeter-level positioning
- No dependency on frodobot.bin
Requirements:
- frodobot.bin must be stopped:
adb shell "killall frodobot.sh frodobot.bin"
frodobot.bin API → Go Webserver → WebSocket/HTTP → Dashboard
Use when:
- Need frodobot.bin services running
- Lower update rate is acceptable
This project uses the Earth Rover Mini SDK as a git submodule. When cloning the repository, use the --recursive flag:
git clone --recursive https://github.com/jleppert/frodobot.gitIf you've already cloned without the --recursive flag, initialize the submodule:
git submodule update --init --recursiveTo update the earth-rover-mini SDK to the latest version:
git submodule update --remote earth-rover-mini- Go 1.25+ - For webserver and tools
- Node.js 16+ - For TypeScript client build
- Docker - For camera daemon cross-compilation
- ADB - For device deployment
make build # Build Go webserver for ARM
make build-client # Build TypeScript clientmake deploy # Deploys server binary and all web pagesmake update # Build, deploy, and restart serverOr manually:
# Stop frodobot to free up serial port
adb shell "killall frodobot.sh frodobot.bin"
# Run webserver
adb shell "cd /data/apps && ./webserver --direct"The webserver includes an NTRIP client for receiving RTK correction data, enabling centimeter-level GPS accuracy.
GeodNet (Recommended)
- Requires paid subscription ($50-100/year)
- Automatic base station selection
- Global coverage
- Configuration:
{ "enabled": true, "service": "geodnet", "host": "rtk.geodnet.com", "port": 2101, "mountpoint": "AUTO", "username": "your_email", "password": "your_password", "gga_interval_seconds": 10, "reconnect_interval_seconds": 30 }
RTK2Go (Free)
- Free public service
- Requires mountpoint selection (find nearest base station)
- Variable coverage depending on base station availability
- Configuration:
{ "enabled": true, "service": "rtk2go", "host": "rtk2go.com", "port": 2101, "mountpoint": "YOUR_MOUNTPOINT", "username": "your_email", "password": "none", "gga_interval_seconds": 10, "reconnect_interval_seconds": 30 }
Emlid Caster
- Free tier available (limited hours/month)
- Good for testing
- Requires registration
Configuration File: /data/rtk_config.json
Example configuration:
{
"enabled": true,
"service": "geodnet",
"host": "rtk.geodnet.com",
"port": 2101,
"mountpoint": "AUTO",
"username": "user@example.com",
"password": "your_password",
"gga_interval_seconds": 10,
"reconnect_interval_seconds": 30
}- NTRIP Connection: Server connects to NTRIP caster on startup
- GGA Position Updates: Server sends rover position (GGA NMEA sentence) to caster every 10 seconds
- RTCM Corrections: Caster sends RTCM3 correction data based on nearest base station
- GPS Injection: Server injects RTCM data into GPS module via /dev/ttyS2
- RTK Fix: GPS processes corrections and achieves RTK Float (±10cm) or RTK Fixed (±2cm) accuracy
- Base Station Tracking: Server parses RTCM messages 1005/1006 to extract base station position and calculate distance
| Fix Quality | Accuracy | Description |
|---|---|---|
| 0 | N/A | Invalid/No fix |
| 1 | ±5-10m | Standard GPS |
| 2 | ±1-3m | DGPS (Differential) |
| 4 | ±2cm | RTK Fixed (best) |
| 5 | ±10-50cm | RTK Float |
Check RTK status via API:
curl http://192.168.4.1:3000/api/rtk-statusResponse:
{
"connected": true,
"enabled": true,
"host": "rtk.geodnet.com",
"port": 2101,
"mountpoint": "AUTO",
"bytes_received": 1234567,
"rtcm_message_rate": 3.2,
"base_station_lat": 37.7749,
"base_station_lon": -122.4194,
"base_station_alt": 52.3,
"base_station_dist": 12.4,
"base_station_id": "1234",
"base_station_found": true,
"last_connected": "2025-10-11T12:34:56Z",
"last_error": ""
}The rover implements a GPS-based time synchronization system that provides accurate time to the system and distributes it over the network as a Stratum 1 NTP server.
- Dual-Layer Architecture: Initial one-time system time sync + continuous Chrony NTP discipline
- Stratum 1 NTP Server: Direct GPS reference clock (port 123)
- Shared Memory Interface: System V SHM for GPS-to-Chrony communication
- chronyc Monitoring: Full command-line monitoring and management
- Automatic Service Management: Integrated with webserver-ctl.sh lifecycle
- Network Time Distribution: Serves GPS-disciplined time to all devices
# Check NTP server status
make status-chrony
# View GPS reference clock
make sources-chrony
# View connected NTP clients
make clients-chrony
# View Chrony logs
make logs-chronyOther devices can sync their time from the rover:
Linux/macOS:
# One-time sync
sudo ntpdate 192.168.11.1
# Or add to /etc/chrony/chrony.conf
server 192.168.11.1 iburst preferWindows:
# PowerShell (as Administrator)
w32tm /config /manualpeerlist:192.168.11.1 /syncfromflags:manual /reliable:yes /update
w32tm /resyncFor complete documentation, see docs/time-synchronization.md:
- Architecture and design details
- Configuration files and options
- All monitoring commands
- Troubleshooting guide
- Technical implementation details
The rover includes Tailscale VPN for secure remote access from anywhere. Tailscale creates a mesh network that allows you to access your rover's webserver, SSH, and services even when it's behind NAT or roaming between WiFi and LTE networks.
- Secure Mesh VPN: Encrypted WireGuard-based connections
- Global Access: Connect to your rover from anywhere with internet
- NAT Traversal: Works behind firewalls and NAT without port forwarding
- Automatic Failover: Maintains connection when rover switches between WiFi/LTE
- Zero Configuration: Auto-starts on boot, auto-authenticates, self-healing
- Integrated Management: Controlled via webserver-ctl.sh
Once connected, your rover will have a Tailscale IP address (typically in the 100.x.x.x range):
# Check Tailscale status on rover
adb shell "/data/apps/tailscale-ctl.sh status"
# Example output:
# 100.77.197.13 rockchip yourname@ linux -
# 100.82.204.12 your-laptop yourname@ macOS -Once both your workstation and rover are connected to Tailscale:
# Web dashboard (replace with your rover's Tailscale IP)
http://100.77.197.13:3000/dashboard
# API access
curl http://100.77.197.13:3000/api/status
# WebSocket streaming
ws://100.77.197.13:3000/ws?hz=25Install Tailscale on your workstation:
Linux/Ubuntu:
curl -fsSL https://tailscale.com/install.sh | sh
sudo tailscale up --accept-routes --sshmacOS:
brew install tailscale
sudo tailscale up --accept-routes --sshWindows: Download from https://tailscale.com/download
Verify connection:
tailscale status
# Should show your rover in the listTailscale is pre-configured on the rover and starts automatically on boot. It's managed by the webserver control script.
Configuration Files:
/data/apps/tailscaled- Tailscale daemon binary/data/apps/tailscale- Tailscale CLI binary/data/apps/tailscale-ctl.sh- Control script/data/tailscale/tailscaled.state- Persistent state/data/tailscale.log- Log file
Manual Control (if needed):
# Start Tailscale
adb shell "/data/apps/tailscale-ctl.sh start"
# Stop Tailscale
adb shell "/data/apps/tailscale-ctl.sh stop"
# Check status
adb shell "/data/apps/tailscale-ctl.sh status"
# View logs
adb shell "tail -f /data/tailscale.log"Tailscale is automatically managed by the webserver control script:
# Start all services (including Tailscale)
make start
# Or manually:
adb shell "/data/apps/webserver-ctl.sh start"
# Start with monitoring (auto-restart on crash)
adb shell "/data/apps/webserver-ctl.sh start --monitor"
# Check all service status (includes Tailscale)
adb shell "/data/apps/webserver-ctl.sh status"Tailscale binaries and configuration are deployed via Makefile:
# Deploy Tailscale to device
make deploy-tailscale
# Start Tailscale daemon
make start-tailscale
# Authenticate (uses pre-configured auth key)
make up-tailscale AUTHKEY=your-auth-key
# Check status
make status-tailscale
# View logs
make logs-tailscaleAll Tailscale commands:
make deploy-tailscale- Deploy binaries and control scriptsmake start-tailscale- Start tailscaled daemonmake stop-tailscale- Stop daemonmake restart-tailscale- Restart daemonmake status-tailscale- Check connection statusmake up-tailscale- Authenticate and connectmake down-tailscale- Disconnectmake logs-tailscale- View logs
Userspace Networking Mode:
The rover runs Tailscale in userspace networking mode (--tun=userspace-networking) because the kernel lacks CONFIG_TUN support. This mode:
- Works without kernel TUN/TAP modules
- Proxies incoming connections to localhost
- Fully supports HTTP, WebSocket, and SSH access
- May have slightly higher latency than kernel mode
System Time Synchronization: The device clock resets to 2021 on boot, which breaks SSL certificate validation. The startup scripts automatically set the time to a valid date (2026-01-01) to enable Tailscale connections. For production use, consider implementing NTP synchronization.
Auto-Start on Boot:
Tailscale starts automatically via /data/apps/power_lost_test.sh:
- Sets system time to valid date
- Starts tailscaled daemon
- Waits 3 seconds for initialization
- Authenticates using reusable auth key
- Connects to Tailscale network
Check daemon status:
adb shell "/data/apps/tailscale-ctl.sh status"Check if daemon is running:
adb shell "ps | grep tailscaled"Check logs for errors:
adb shell "tail -50 /data/tailscale.log"Common issues:
-
SSL certificate errors - System clock is incorrect
# Check current time adb shell "date" # Set time manually (done automatically by startup script) adb shell 'date -s "2026-01-01 00:00:00"'
-
Daemon crashes immediately - Check for OOM (out of memory)
adb shell "free -m" adb shell "dmesg | grep -i oom"
-
Authentication fails - Auth key may be expired
- Generate new auth key in Tailscale admin console
- Update TAILSCALE_AUTHKEY in webserver-ctl.sh
- Redeploy:
make deploy
-
Can't reach rover from workstation - Workstation not connected
# On workstation, check Tailscale status tailscale status # Reconnect if needed sudo tailscale up
Test basic connectivity:
# From workstation, ping rover's Tailscale IP
ping 100.77.197.13
# Test HTTP
curl -v http://100.77.197.13:3000/api/statusVerify services are listening:
adb shell "netstat -an | grep :3000"
# Should show: tcp 0 0 0.0.0.0:3000 0.0.0.0:* LISTENTailscale uses ~40-50MB RAM in userspace mode. To reduce memory usage:
- Stop Tailscale when not needed:
make stop-tailscale - Disable auto-start: Remove Tailscale section from power_lost_test.sh
The rover prioritizes WiFi over LTE for cost efficiency, with automatic failover:
- WiFi: Metric 10 (higher priority, lower cost)
- LTE: Metric 100 (backup, used only when WiFi unavailable)
- Self-healing: Routes checked every 10 seconds, auto-corrected if changed
- Fast recovery: 1-2 second failover time when WiFi drops
Tailscale traffic follows these routing rules automatically, preferring WiFi when available and seamlessly failing over to LTE.
Landing page with system information and navigation links.
Main dashboard with real-time 3D visualization, RTK GPS status, and telemetry data.
Sensor calibration tool for magnetometer and IMU calibration.
Returns current sensor data in JSON format (SDK-compatible).
Response:
{
"battery": 21,
"signal_level": 0,
"orientation": 45,
"roll": 1.2,
"pitch": 3.4,
"yaw": 45.6,
"lamp": 0,
"speed": 0.0,
"gps_signal": 85.5,
"avg_snr": 42.3,
"snr_values": [
{"sat_id": 1, "snr": 45.2},
{"sat_id": 2, "snr": 38.7}
],
"latitude": 37.7749,
"longitude": -122.4194,
"altitude": 52.3,
"satellites": 12,
"fix_quality": 4,
"hdop": 0.7,
"hpe": 0.021,
"vibration": 0.0,
"timestamp": 1728123456.789,
"accels": [[0.01, 0.03, 1.04, 1728123456]],
"gyros": [[0.0, 0.0, 0.2, 1728123456]],
"mags": [[-2156, -47, 321, 1728123456]],
"rpms": [[0, 0, 0, 0, 1728123456]]
}Fields:
gps_signal: GPS signal strength 0-100% (based on average SNR)avg_snr: Average signal-to-noise ratio in dBHzsnr_values: Individual satellite SNR valuesfix_quality: 0=Invalid, 1=GPS, 2=DGPS, 4=RTK Fixed, 5=RTK Floathdop: Horizontal Dilution of Precisionhpe: Horizontal Position Error in meters (estimated accuracy)
Real-time sensor data streaming via WebSocket.
Parameters:
hz(optional): Update rate (0.1-100 Hz, default: 10)
Message Format: Same as /data endpoint
Commands (Client → Server):
{"type": "motor", "data": {"speed": 50, "angular": 0}}
{"type": "keepalive"}
{"type": "imu_start"}
{"type": "imu_end"}
{"type": "mag_start"}
{"type": "mag_end"}
{"type": "imu_write", "data": {"accBiasX": 0, "accBiasY": 0, "accBiasZ": 0, "gyroBiasX": 0, "gyroBiasY": 0, "gyroBiasZ": 0}}
{"type": "mag_write", "data": {"magBiasX": 0, "magBiasY": 0, "magBiasZ": 0}}
{"type": "imu_read"}Example:
const ws = new WebSocket('ws://192.168.4.1:3000/ws?hz=25');
ws.onmessage = (event) => {
const data = JSON.parse(event.data);
console.log('RTK Fix:', data.fix_quality, 'Accuracy:', data.hpe, 'm');
};
// Send motor command
ws.send(JSON.stringify({
type: "motor",
data: {speed: 50, angular: 0}
}));Server health check.
Response:
{
"status": "ok",
"time": "2025-10-11T05:18:31Z"
}Server version information.
Response:
{
"version": "1.0.0",
"build_time": "2025-10-11_12:34:56_UTC",
"git_hash": "7872491"
}Performance statistics.
Response:
{
"packets_last_10s": 250,
"errors_last_10s": 0,
"data_rate_hz": 25.0,
"uptime_seconds": 120.5
}Retrieve current RTK configuration.
Response:
{
"enabled": true,
"service": "geodnet",
"host": "rtk.geodnet.com",
"port": 2101,
"mountpoint": "AUTO",
"username": "user@example.com",
"password": "********",
"gga_interval_seconds": 10,
"reconnect_interval_seconds": 30
}Update RTK configuration.
Request Body:
{
"enabled": true,
"service": "geodnet",
"host": "rtk.geodnet.com",
"port": 2101,
"mountpoint": "AUTO",
"username": "your_email",
"password": "your_password",
"gga_interval_seconds": 10,
"reconnect_interval_seconds": 30
}Response:
{
"success": true,
"config": {...}
}Get current NTRIP connection status.
See "Monitoring RTK Status" section above for response format.
Get list of predefined RTK service configurations.
Response:
[
{
"name": "GeodNet",
"notes": "Requires subscription - automatic base station selection",
"config": {...}
},
{
"name": "RTK2Go",
"notes": "Free - requires registration and mountpoint selection",
"config": {...}
}
]Retrieve IMU calibration data from /data/imu.json.
Response:
{
"acc_bias": [0, 0, 0],
"gyro_bias": [0, 0, 0],
"mag_bias": [0, 0, 0],
"mag_scale": [1, 1, 1]
}Get yaw offset for heading correction.
Response:
{
"yaw_offset": 0
}Update yaw offset (-180 to 180 degrees).
Request:
{
"yaw_offset": 15
}Response:
{
"success": true,
"yaw_offset": 15
}The project uses a dual build system: Go for the server and Vite/TypeScript for the web client.
Files:
webserver.go- Main server, HTTP/WebSocket handlersucp.go- UCP protocol implementationahrs.go- Madgwick AHRS filtergps.go- GPS reader for /dev/ttyS2ntrip.go- NTRIP client for RTK correctionsrtk_config.go- RTK configuration managementcalibration.go- Sensor calibration handlershardware.go- Hardware interfacewebsocket.go- WebSocket connection managementconfig.go- Server configuration
Build Commands:
make build # Cross-compile for ARM v7
make test-local # Build and run locally (Mac/x86)Build Configuration:
GOOS=linux GOARCH=arm GOARM=7 go build \
-ldflags "-X 'main.Version=1.0.0' -X 'main.BuildTime=$(date)' -X 'main.GitHash=$(git rev-parse --short HEAD)'" \
-o webserver-arm \
webserver.go hardware.go calibration.go config.go websocket.go rtk_config.go ntrip.go ucp.go gps.go ahrs.goThe web client is built with TypeScript and Vite, producing three single-file HTML pages with inlined CSS and JavaScript.
Directory Structure:
client/
├── src/
│ ├── dashboard.ts # Dashboard entry point
│ ├── calibration.ts # Calibration tool entry point
│ ├── index.ts # Landing page entry point
│ ├── types.ts # TypeScript interfaces for sensor data
│ ├── scene3d.ts # Three.js 3D scene management
│ ├── websocket.ts # WebSocket connection handler
│ ├── ui.ts # Dashboard UI updates
│ ├── styles/
│ │ ├── styles.css # Dashboard styles
│ │ ├── calibration.css # Calibration tool styles
│ │ └── landing.css # Landing page styles
│ └── vite-env.d.ts # TypeScript environment declarations
├── index.html # Landing page template
├── dashboard.html # Dashboard template
├── calibration.html # Calibration template
├── package.json # Dependencies and build scripts
├── tsconfig.json # TypeScript configuration
├── vite.config.index.ts # Vite config for index page
├── vite.config.dashboard.ts # Vite config for dashboard
├── vite.config.calibration.ts # Vite config for calibration
└── README.md # Client documentation
Build Commands:
cd client
yarn install # Install dependencies
yarn dev # Start dev server with hot reload
yarn build # Build all pages for production
# Or from project root:
make build-client # Build client (all pages)Build Process:
- TypeScript Compilation: Type-checks all TypeScript files
- Separate Builds: Each page is built independently with its own Vite config
- Bundle Optimization: Vite optimizes and minifies JavaScript/CSS
- Single File Output:
vite-plugin-singlefileinlines all assets into HTML
Output Files (in project root):
index.html- 4.3 KB (landing page)dashboard.html- 490 KB (includes Three.js)calibration.html- 17 KB (calibration tool)
Technologies:
- TypeScript - Type-safe JavaScript
- Vite - Fast build tool and dev server
- Three.js - 3D graphics for rover visualization
- vite-plugin-singlefile - Bundles everything into single HTML files
Why Separate Configs?
The vite-plugin-singlefile plugin sets inlineDynamicImports: true, which is incompatible with Vite's multiple input feature. To work around this, we use separate Vite config files for each page and build them sequentially.
Full Deployment:
make update # Build server + client, deploy, and restartDeploy Specific Components:
make build # Build server only
make build-client # Build client only
make deploy # Deploy server + client (no rebuild)
make restart # Restart server on deviceManual Deployment:
# Deploy server binary
adb push webserver-arm /data/apps/webserver
adb shell "chmod +x /data/apps/webserver"
# Deploy web pages
adb push index.html /data/apps/index.html
adb push dashboard.html /data/apps/dashboard.html
adb push calibration.html /data/apps/calibration.html
# Restart server
adb shell "/data/apps/webserver-ctl.sh restart"The STM32 communicates via UART Control Protocol (UCP) on /dev/ttyS0 at 115200 baud.
<0xFD 0xFF> <Header> <Payload> <CRC16>
| | | |
Sync 4 bytes N bytes 2 bytes
typedef struct {
uint16_t len; // Total packet size (header + payload)
uint8_t id; // Message ID (0x05 for telemetry)
uint8_t index; // Sequence number
} ucp_hd_t;typedef struct {
ucp_hd_t hd; // 4 bytes
uint16_t voltage; // 2 bytes - Battery voltage
int16_t rpm[4]; // 8 bytes - Motor RPMs
int16_t acc[3]; // 6 bytes - Accelerometer (x,y,z)
int16_t gyros[3]; // 6 bytes - Gyroscope (x,y,z)
int16_t mag[3]; // 6 bytes - Magnetometer (x,y,z)
int16_t heading; // 2 bytes - Compass heading
uint8_t stop_switch; // 1 byte - Emergency stop status
uint8_t error_code; // 1 byte - System error code
uint16_t reserve; // 2 bytes - Reserved
uint16_t version; // 2 bytes - Protocol version
} ucp_rep_t; // Total: 40 bytesDesign Rate: 50Hz (20ms per packet)
Accelerometer (±2g range):
value_g = raw_value / 16384.0
Gyroscope (±250°/s range):
value_dps = raw_value / 131.0
Magnetometer:
value_uT = raw_value * 0.15
Battery Voltage:
voltage_V = raw_value * 0.3
# Building
make build # Build ARM binary
make build-client # Build client (TypeScript → HTML)
# Deployment
make deploy # Build and deploy to device
make update # Build, deploy, and restart (recommended)
make start # Deploy and start server
# Server Control
make restart # Restart server on device
make stop # Stop server on device
make status # Check if server is running
# Monitoring
make logs # View server logs (snapshot)
make tail # Follow server logs in real-time
# Cleanup
make clean # Remove local build files
# Development
make test-local # Run server locally on Mac
# Help
make help # Show all commandsEnvironment Variables:
DEVICE_IP- Device IP address (default: 10.227.1.117)
Examples:
make update # Use default IP
make deploy DEVICE_IP=192.168.4.1 # Override IPSymptoms:
- GPS stays at fix quality 1 (standard GPS)
- No RTK Float or Fixed status
- Base station distance shows 0 or incorrect value
Solutions:
-
Check NTRIP connection:
curl http://192.168.4.1:3000/api/rtk-status
- Verify
connected: true - Check
last_errorfield for issues
- Verify
-
Verify credentials:
- Check username/password in
/data/rtk_config.json - Test credentials on service website
- Check username/password in
-
Check GPS position:
- Ensure GPS has valid position (fix_quality > 0)
- NTRIP requires valid position to select base station
-
Monitor RTCM injection:
- Check logs:
make tail - Should see "NTRIP: Received and injected X RTCM messages"
- Typical rate: 1-5 messages/second
- Check logs:
-
Base station distance:
- RTK works best within 10-20 km of base station
- Check
base_station_distin status - Use service with nearer base stations if > 30 km
-
GPS module configuration:
- Some GPS modules need RTK mode enabled
- Check if GPS firmware supports RTK
Cause: frodobot.bin is running and competing for /dev/ttyS0
Solution:
adb shell "killall frodobot.sh frodobot.bin"Cause: Incorrect packet parsing or corrupted data
Check:
- Verify struct alignment matches C definition exactly
- Ensure
header.leninterpretation (includes 4-byte header) - Check CRC16 calculation matches Modbus standard
Causes:
- frodobot.bin still running
- Serial port permissions
- Hardware not sending data
Debug:
# Check raw serial data
adb shell "hexdump -C /dev/ttyS0 | head -20"
# Should see: fd ff 28 00 05 ... (sync bytes: fd ff)Expected: 50Hz design rate, typically achieve 20-30Hz
Factors:
- CPU load
- USB/ADB overhead
- Network latency
Check current rate:
curl http://192.168.4.1:3000/api/statsCause: /etc/init.d/S95frodobots restarts frodobot.sh which has a while true loop
Solution: Kill the parent process
adb shell "killall frodobot.sh frodobot.bin"Symptoms:
- Latitude/longitude always 0
- No satellites
- fix_quality = 0
Solutions:
-
Check GPS serial port:
adb shell "cat /dev/ttyS2" # Should see NMEA sentences like $GNGGA,...
-
Verify antenna connection:
- Check GPS antenna is connected
- Move to clear view of sky
-
Check GPS power:
- Ensure GPS module has power
- Check for GPS LED indicator
frodobot/
├── webserver.go # Main server, HTTP/WebSocket handlers
├── ucp.go # UCP protocol implementation
├── ahrs.go # Madgwick AHRS filter
├── gps.go # GPS reader for /dev/ttyS2
├── ntrip.go # NTRIP client for RTK corrections
├── rtk_config.go # RTK configuration management
├── calibration.go # Sensor calibration handlers
├── hardware.go # Hardware interface
├── websocket.go # WebSocket connection management
├── config.go # Server configuration
├── logger.go # Data logging system
├── camera_handler.go # Camera daemon integration
├── client/ # TypeScript web application
│ ├── src/ # TypeScript source files
│ ├── index.html # Landing page
│ ├── dashboard.html # Dashboard
│ ├── calibration.html # Calibration tool
│ └── package.json # Client dependencies
├── camera-daemon/ # Camera RTSP streaming daemon
│ ├── src/ # C++ source files
│ ├── include/ # Header files
│ ├── CMakeLists.txt # Build configuration
│ └── docker-build.sh # Cross-compilation script
├── earth-rover-mini/ # Git submodule - Earth Rover SDK
│ └── Software/Linux/toolchain/ # Rockchip libraries & headers
├── docs/ # Documentation
│ ├── comms.md # Network configuration guide
│ ├── logging.md # Data logging documentation
│ ├── camera-system.md # Camera system guide
│ └── time-synchronization.md # GPS time sync & NTP server guide
├── Makefile # Build configuration
├── .gitmodules # Git submodule configuration
└── README.md # This file
1. Add new UCP command:
const UCP_NEW_COMMAND = 0xB
func WriteNewCommand(port io.Writer, data []byte) error {
// Implement command packet
}2. Add new HTTP endpoint:
http.HandleFunc("/api/new", func(w http.ResponseWriter, r *http.Request) {
w.Header().Set("Content-Type", "application/json")
// Handler implementation
})3. Add new WebSocket command:
Update command handling in handleWebSocket():
case "new_command":
var cmd NewCommand
json.Unmarshal(command.Data, &cmd)
// Handle command4. Modify sensor scaling:
Update conversion functions in ucp.go:
func (t *UCPTelemetry) GetAccelG() (x, y, z float64) {
scale := 1.0 / 16384.0 // Adjust for different range
// ...
}Enable detailed logging with --debug flag:
- Prints sensor values every packet
- Shows UCP protocol errors
- Logs packet parsing details
- Reports NTRIP connection status
- Shows RTCM message parsing
adb shell "cd /data/apps && ./webserver --direct --debug"- SDK Repository (Submodule): https://github.com/jleppert/earth-rover-mini
- UCP Protocol Spec:
earth-rover-mini/wiki/docs/zh/05-STM32-Control.md - C Implementation:
earth-rover-mini/Software/STM32/applications/ucp.h - Linux Examples:
earth-rover-mini/Software/Linux/src/Examples/move.cpp - Camera Daemon Dependencies:
earth-rover-mini/Software/Linux/toolchain/media/
- Madgwick Filter: https://x-io.co.uk/open-source-imu-and-ahrs-algorithms/
- NTRIP Protocol: https://www.use-snip.com/kb/knowledge-base/ntrip-rev1-versus-rev2/
- RTCM3 Standard: https://rtcm.myshopify.com/collections/differential-global-navigation-satellite-dgnss-standards
- Vite Documentation: https://vitejs.dev/
- Three.js Documentation: https://threejs.org/
Part of the Earth Rover Mini project by Frodobots.ai
For issues or questions:
- Check this README troubleshooting section
- Enable debug mode:
./webserver --direct --debug - Monitor raw serial:
adb shell "hexdump -C /dev/ttyS0" - Check stats:
curl http://192.168.4.1:3000/api/stats - Check RTK status:
curl http://192.168.4.1:3000/api/rtk-status - View logs:
make tail