File size: 45,564 Bytes
14eec7b ef118cf 802f2c1 dcf1b21 1227fda 223bbeb 1227fda 85d769f 1227fda eaf03f4 1227fda 223bbeb 1227fda ef118cf a091821 9078db7 a091821 9078db7 ef118cf 52e6c73 dcf1b21 52e6c73 64f0005 52e6c73 64f0005 dcf1b21 52e6c73 1227fda ef118cf 1227fda eaf03f4 1227fda ef118cf a091821 ef118cf 223bbeb ef118cf a091821 436f91f eaf03f4 223bbeb ef118cf eaf03f4 ef118cf eaf03f4 c525614 eaf03f4 ef118cf c525614 1227fda 436f91f 223bbeb eaf03f4 223bbeb eaf03f4 223bbeb eaf03f4 223bbeb eaf03f4 223bbeb ef118cf 223bbeb a091821 ef118cf 223bbeb eaf03f4 223bbeb a091821 1227fda a091821 1227fda a091821 1227fda a091821 eaf03f4 a091821 1227fda a091821 eaf03f4 a091821 eaf03f4 a091821 1227fda a091821 1227fda a091821 eaf03f4 a091821 eaf03f4 a091821 ef118cf 52e6c73 a091821 52e6c73 64f0005 52e6c73 9013e5d 52e6c73 ef118cf 52e6c73 ef118cf 7362afb 9078db7 2425670 7362afb be47e69 e2fcf08 be47e69 52e6c73 be47e69 52e6c73 be47e69 9013e5d be47e69 9013e5d be47e69 a091821 e2fcf08 a091821 e2fcf08 be47e69 e2fcf08 be47e69 e2fcf08 9013e5d e2fcf08 c525614 9013e5d e2fcf08 9078db7 9013e5d 9078db7 2425670 e9e2294 9078db7 7e77839 2425670 7e77839 9078db7 2425670 e2fcf08 9013e5d e2fcf08 2425670 e9e2294 9078db7 c525614 9013e5d be47e69 9013e5d be47e69 9013e5d e2fcf08 a091821 9013e5d 9078db7 9013e5d be47e69 9013e5d be47e69 9013e5d 9078db7 9013e5d be47e69 e2fcf08 be47e69 e2fcf08 be47e69 e2fcf08 be47e69 e2fcf08 be47e69 e2fcf08 be47e69 e2fcf08 be47e69 e2fcf08 be47e69 52e6c73 64f0005 52e6c73 64f0005 52e6c73 223bbeb e2fcf08 be47e69 e2fcf08 52e6c73 be47e69 e2fcf08 9078db7 e2fcf08 c525614 9013e5d c525614 e2fcf08 be47e69 a091821 52e6c73 9078db7 52e6c73 dcf1b21 c525614 9013e5d c525614 dcf1b21 52e6c73 9078db7 223bbeb 9013e5d 223bbeb ec12dc0 9078db7 dcf1b21 9078db7 52e6c73 223bbeb 1227fda c525614 1227fda 223bbeb 1227fda 223bbeb 1227fda a091821 be47e69 e2fcf08 9078db7 9013e5d 9078db7 e636f34 9078db7 a091821 7362afb 9013e5d 2425670 9078db7 e636f34 7362afb dcf1b21 59625d9 dcf1b21 59625d9 dcf1b21 59625d9 dcf1b21 a75f112 9078db7 a75f112 9078db7 a75f112 9078db7 a75f112 dcf1b21 a75f112 dcf1b21 a75f112 dcf1b21 a75f112 dcf1b21 a75f112 dcf1b21 a75f112 dcf1b21 0551bb3 a75f112 dcf1b21 0551bb3 dcf1b21 e636f34 c525614 e636f34 ef118cf a091821 9013e5d 7362afb 9013e5d 7362afb 9078db7 9013e5d 9078db7 | 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 | ---
title: Nova Sim
colorFrom: yellow
colorTo: green
sdk: docker
app_port: 7860
---
# Nova Sim
A unified MuJoCo-based robot simulation platform with web interface for multiple robot types.


## Outline
1. [Overview](#overview)
2. [Highlights](#highlights)
3. [Supported Robots](#supported-robots)
4. [Project Structure](#project-structure)
5. [Quick Start](#quick-start)
6. [Docker Deployment](#docker-deployment)
7. [Controls](#controls)
8. [Architecture](#architecture)
9. [API](#api)
10. [Wandelbots Nova API Integration](#wandelbots-nova-api-integration)
11. [Testing](#testing)
12. [License](#license)
## Overview
Nova Sim combines MuJoCo physics, a Flask/WebSocket server, and a browser UI so you can explore locomotion and manipulation robots from a single web interface. The platform streams MJPEG video of the rendered scene, exposes HTTP endpoints for trainers and RL clients, and lets you switch robots and control inputs without restarting the server.
## Highlights
- Real-time MuJoCo physics simulation
- Web-based video streaming interface with TypeScript frontend
- WebSocket-based state/command communication
- Simple venv-based setup with Python and npm
- Gym-style WebSocket API for RL/IL clients
- Interactive camera controls (rotate, zoom, pan)
- Robot switching without restart
- Keyboard and button controls for locomotion
## Supported Robots
### Unitree G1 (Humanoid)
- 29 degrees of freedom
- RL-based walking policy from unitree_rl_gym
- Full body control with arms and waist
### Boston Dynamics Spot (Quadruped)
- 12 degrees of freedom (3 per leg)
- Multiple gait controllers:
- **MPC Gait**: Feedback-based balance control with trot pattern (default)
- **PyMPC Gait**: Uses standalone gait generator (no external dependencies needed)
- **Trot Gait**: Simple open-loop trot pattern
- **Note**: Spot controllers are now fully self-contained with extracted dependencies from gym_quadruped and Quadruped-PyMPC. See [robots/spot/DEPENDENCIES.md](robots/spot/DEPENDENCIES.md) for details.
### Universal Robots UR5e (Robot Arm)
- 6 degrees of freedom (6-axis industrial arm)
- Robotiq 2F-85 gripper (in regular scene only; T-push scene uses a push stick tool)
- Two control modes:
- **IK Mode**: Set target XYZ position and orientation (Roll/Pitch/Yaw), inverse kinematics computes joint angles using damped least squares with 6-DOF Jacobian
- **Joint Mode**: Direct control of individual joint positions
- End-effector position and orientation tracking
- Full 6-DOF IK with orientation control (can be toggled on/off)
- **Optional [Wandelbots Nova API](#wandelbots-nova-api-integration) integration** for real robot state streaming and cloud-based IK
## Project Structure
```
nova_sim/
├── mujoco_server.py # Main Flask server with WebSocket
├── Dockerfile # Docker build configuration
├── docker-compose.yml # CPU/OSMesa configuration
├── docker-compose.gpu.yml # GPU/EGL configuration
├── requirements.txt # Python dependencies
├── frontend/ # Web UI (TypeScript + Vite)
│ ├── src/
│ │ ├── index.html # HTML template
│ │ ├── main.ts # Main TypeScript entry point
│ │ ├── styles.css # CSS styles
│ │ ├── api/
│ │ │ └── client.ts # WebSocket client
│ │ └── types/
│ │ └── protocol.ts # TypeScript protocol types
│ ├── package.json # Node.js dependencies
│ ├── tsconfig.json # TypeScript configuration
│ └── vite.config.ts # Vite bundler configuration
├── templates/ # Flask templates
│ └── index.html # Main HTML template
├── robots/
│ ├── g1/ # Unitree G1 humanoid
│ │ ├── g1_env.py # Gymnasium environment
│ │ ├── scene.xml # MuJoCo scene
│ │ ├── g1_29dof.xml # Robot model
│ │ ├── meshes/ # 3D mesh files
│ │ ├── policy/ # RL policy weights
│ │ └── controllers/ # G1 controllers
│ │ ├── rl_policy.py # RL walking policy
│ │ ├── pd_standing.py # Standing controller
│ │ └── keyframe.py # Keyframe controller
│ ├── spot/ # Boston Dynamics Spot quadruped
│ │ ├── spot_env.py # Gymnasium environment
│ │ ├── model/ # MuJoCo model files
│ │ └── controllers/ # Spot controllers
│ │ ├── mpc_gait.py # MPC-inspired gait (default)
│ │ ├── quadruped_pympc_controller.py # PyMPC gait
│ │ ├── trot_gait.py # Simple trot gait
│ │ └── pd_standing.py # Standing controller
│ └── ur5/ # Universal Robots UR5e arm
│ ├── ur5_env.py # Gymnasium environment
│ ├── model/ # MuJoCo model files
│ │ ├── scene.xml # Combined UR5e + Robotiq scene
│ │ └── assets/ # Mesh files
│ └── controllers/
│ └── ik_controller.py # Damped least-squares IK
└── README.md
```
## Quick Start
### Setup
```bash
# Create and activate a virtualenv
python3 -m venv .venv
source .venv/bin/activate
# Install Python dependencies
pip install -r requirements.txt
# Install frontend dependencies
cd frontend && npm install && cd ..
# Build frontend
cd frontend && npm run build && cd ..
# Start the server
python mujoco_server.py
# Open browser at http://localhost:5000/nova-sim
```
**Reward Threshold**: Episodes automatically terminate when the robot reaches within the specified distance of the target. See [REWARD_THRESHOLD.md](REWARD_THRESHOLD.md) for details.
## Docker Deployment
### Quick Start
```bash
# Build and run (CPU/software rendering)
docker-compose up --build
# Or with GPU acceleration (requires NVIDIA GPU)
docker-compose -f docker-compose.gpu.yml up --build
# Access at: http://localhost:3004/nova-sim
```
### Docker Commands
```bash
# Build and run (CPU mode)
docker-compose up --build
# Run with GPU support
docker-compose -f docker-compose.gpu.yml up --build
# View logs
docker-compose logs -f
# Stop containers
docker-compose down
# Or with docker run directly
docker run -p 3004:5000 nova-sim
```
### Configuration & Tuning
#### Performance Optimization
Docker uses software rendering (OSMesa) which is slower than native GPU rendering. Configure these environment variables to optimize performance:
| Variable | Default | Description |
|----------|---------|-------------|
| `RENDER_WIDTH` | 640 | Render width in pixels |
| `RENDER_HEIGHT` | 360 | Render height in pixels |
| `TARGET_FPS` | 30 | Target frame rate |
| `SIM_STEPS_PER_FRAME` | 10 | Physics steps per rendered frame |
| `OMP_NUM_THREADS` | 4 | OpenMP thread count |
| `MKL_NUM_THREADS` | 4 | MKL thread count |
#### docker-compose.yml (CPU - Default)
```yaml
services:
nova-sim:
build: .
ports:
- "3004:5000" # Host:Container
environment:
- MUJOCO_GL=osmesa
- PYOPENGL_PLATFORM=osmesa
- RENDER_WIDTH=640 # Lower resolution for speed
- RENDER_HEIGHT=360
- TARGET_FPS=30
```
#### docker-compose.gpu.yml (NVIDIA GPU)
For significantly better performance, use GPU acceleration:
```bash
# Requires: NVIDIA GPU + nvidia-container-toolkit
docker-compose -f docker-compose.gpu.yml up
# Or: make docker-gpu
```
```yaml
services:
nova-sim:
build: .
ports:
- "3004:5000" # Host:Container
environment:
- MUJOCO_GL=egl # GPU rendering
- PYOPENGL_PLATFORM=egl
- RENDER_WIDTH=1280 # Full resolution
- RENDER_HEIGHT=720
- TARGET_FPS=60
deploy:
resources:
reservations:
devices:
- driver: nvidia
count: 1
capabilities: [gpu]
```
#### Performance Comparison
| Mode | Resolution | Expected FPS | Notes |
|------|------------|--------------|-------|
| Native (macOS/Linux) | 1280x720 | 60+ | Best performance |
| Docker + GPU (EGL) | 1280x720 | 60 | Requires NVIDIA GPU |
| Docker + CPU (OSMesa) | 640x360 | 15-20 | Slower, but compatible |
| Docker + CPU (OSMesa) | 320x180 | 30+ | Very low quality |
#### Custom Docker Run
```bash
# Ultra-low resolution for maximum speed
docker run -p 3004:5000 \
-e RENDER_WIDTH=320 \
-e RENDER_HEIGHT=180 \
-e MUJOCO_GL=osmesa \
nova-sim
# High quality with GPU
docker run --gpus all -p 3004:5000 \
-e RENDER_WIDTH=1920 \
-e RENDER_HEIGHT=1080 \
-e MUJOCO_GL=egl \
nova-sim
```
## Controls
### Locomotion Robots (G1, Spot)
- **W / Arrow Up**: Walk forward
- **S / Arrow Down**: Walk backward
- **A / Arrow Left**: Turn left
- **D / Arrow Right**: Turn right
- **Q**: Strafe left
- **E**: Strafe right
### Robot Arm (UR5)
- **IK Mode**: Use XYZ sliders to set end-effector target position, RPY sliders for orientation
- **Orientation Control**: Toggle checkbox to enable/disable 6-DOF orientation tracking
- **Joint Mode**: Use J1-J6 sliders to control individual joints
- **Gripper**: Open/Close buttons for Robotiq gripper
- **Home**: Return to home position (joint mode)
- **Keyboard Teleop**: With the UR5 selected, W/A/S/D jogs the tool in the XY plane, R/F nudges along Z, and every keystroke streams a `teleop_action` event so the browser panel and any trainer see the same velocity delta.
### Common Controls
- **Mouse drag**: Rotate camera
- **Scroll wheel**: Zoom camera
- **Robot selector**: Switch between G1, Spot, and UR5
- **Reset button**: Reset robot to default pose
### UR5 Scene & Camera Hints
- The UI now selects between exactly two UR5 options: the gripper-ready scene and the T-push scene (both enumerated via `/nova-sim/api/v1/metadata`). Scene-specific camera feeds are available via the `/env` endpoint, so trainers can build dashboards based on the available streams.
- Auxiliary camera tiles now appear only when you add cameras via the dynamic camera API (see API section below). The UI refreshes when a new camera is announced.
- The T-shape target stays anchored at its configured pose across resets, which keeps the training objective consistent even when you hit Reset from the UI.
## Architecture
```
┌─────────────────────────────────────────────────────────────────────────┐
│ Browser │
│ ┌─────────────────┐ ┌─────────────────┐ ┌─────────────────┐ │
│ │ Video Player │ │ Control Panel │ │ State Display │ │
│ │ (MJPEG img) │ │ (buttons/keys) │ │ (joint data) │ │
│ └────────┬────────┘ └────────┬────────┘ └────────▲────────┘ │
└───────────┼──────────────────────┼──────────────────────┼──────────────┘
│ HTTP GET │ WebSocket │ WebSocket
│ /video_feed │ command/reset │ state
▼ ▼ │
┌─────────────────────────────────────────────────────────────────────────┐
│ mujoco_server.py │
│ ┌─────────────────┐ ┌─────────────────┐ ┌─────────────────┐ │
│ │ Flask + WSGI │ │ WebSocket │ │ Render Thread │ │
│ │ HTTP endpoints │ │ cmd, reset, │ │ 60 FPS loop │ │
│ │ │ │ switch_robot │ │ MJPEG encode │ │
│ └─────────────────┘ └────────┬────────┘ └────────┬────────┘ │
│ │ │ │
│ ▼ ▼ │
│ ┌───────────────────────────────────┐ │
│ │ Active Environment (env) │ │
│ │ G1Env, SpotEnv, or UR5Env (Gym) │ │
│ └───────────────────────────────────┘ │
└─────────────────────────────────────────────────────────────────────────┘
│
│ env.step(action)
▼
┌─────────────────────────────────────────────────────────────────────────┐
│ Robot Environments │
│ │
│ ┌────────────────────────────┐ ┌────────────────────────────┐ │
│ │ G1Env │ │ SpotEnv │ │
│ │ ┌──────────────────────┐ │ │ ┌──────────────────────┐ │ │
│ │ │ MuJoCo Model (XML) │ │ │ │ MuJoCo Model (XML) │ │ │
│ │ │ g1_29dof.xml │ │ │ │ spot.xml │ │ │
│ │ └──────────────────────┘ │ │ └──────────────────────┘ │ │
│ │ ┌──────────────────────┐ │ │ ┌──────────────────────┐ │ │
│ │ │ Controller │ │ │ │ Controller │ │ │
│ │ │ rl_policy.py │ │ │ │ (selectable) │ │ │
│ │ │ (PyTorch .pt file) │ │ │ │ - mpc_gait.py │ │ │
│ │ └──────────────────────┘ │ │ │ - pympc_controller │ │ │
│ │ │ │ │ - trot_gait.py │ │ │
│ │ 29 DOF Humanoid │ │ └──────────────────────┘ │ │
│ │ - Torso, arms, legs │ │ │ │
│ │ - RL locomotion policy │ │ 12 DOF Quadruped │ │
│ └────────────────────────────┘ │ - 4 legs × 3 joints │ │
│ │ - Gait-based locomotion │ │
│ └────────────────────────────┘ │
│ │
│ ┌────────────────────────────┐ │
│ │ UR5Env │ 6 DOF Robot Arm │
│ │ ┌──────────────────────┐ │ - IK or direct joint control │
│ │ │ scene.xml (UR5e + │ │ - Robotiq 2F-85 gripper │
│ │ │ Robotiq 2F-85) │ │ - End-effector tracking │
│ │ └──────────────────────┘ │ │
│ │ ┌──────────────────────┐ │ │
│ │ │ ik_controller.py │ │ │
│ │ │ (Damped LS IK) │ │ │
│ │ └──────────────────────┘ │ │
│ └────────────────────────────┘ │
└─────────────────────────────────────────────────────────────────────────┘
│
│ mujoco.mj_step()
▼
┌─────────────────────────────────────────────────────────────────────────┐
│ MuJoCo Physics Engine │
│ ┌─────────────────┐ ┌─────────────────┐ ┌─────────────────┐ │
│ │ Rigid Body │ │ Collision │ │ Rendering │ │
│ │ Dynamics │ │ Detection │ │ (OpenGL/ │ │
│ │ │ │ │ │ OSMesa/EGL) │ │
│ └─────────────────┘ └─────────────────┘ └─────────────────┘ │
└─────────────────────────────────────────────────────────────────────────┘
```
### Data Flow
1. **User Input** → Browser captures keyboard/button events
2. **WebSocket** → Commands sent as `{vx, vy, vyaw}` velocity targets
3. **Controller** → Converts velocity actions to joint position targets
4. **MuJoCo** → Simulates physics at 500Hz (0.002s timestep)
5. **Renderer** → Captures frames at 60 FPS (native) or 30 FPS (Docker)
6. **MJPEG Stream** → Frames encoded as JPEG and streamed to browser
7. **State Broadcast** → Robot state sent via WebSocket at render rate
### Controller Architecture
**G1 (Humanoid)**: Uses a pre-trained RL policy (PyTorch) that maps observations (body orientation, joint positions/velocities, actions) to joint position targets.
**Spot (Quadruped)**: Uses gait-based controllers:
- **MPC Gait**: Phase-based trot with feedback balance control
- **PyMPC**: Integrates Quadruped-PyMPC's gait generator for timing
- **Trot**: Simple open-loop sinusoidal gait pattern
All controllers output joint position targets; MuJoCo's built-in PD control tracks these targets.
## API
All endpoints are prefixed with `/nova-sim/api/v1`.
### WebSocket
Connect using standard WebSocket:
```javascript
const ws = new WebSocket('ws://localhost:3004/nova-sim/api/v1/ws');
// Send message
ws.send(JSON.stringify({type: 'action', data: {vx: 0.5, vy: 0, vyaw: 0}}));
// Receive messages
ws.onmessage = (event) => {
const msg = JSON.parse(event.data);
if (msg.type === 'state') {
console.log(msg.data);
}
};
```
Nova-Sim uses `/ws` as the shared control channel for the browser UI, trainers, and any RL clients. Every UI interaction (teleop, camera controls, robot switching) and the trainer handshake/notifications flows through this single socket; the UI `state` messages shown below now also carry the action velocities, integrated reward, and trainer connection status that RL agents need.
### HTTP Endpoints
Nova-Sim provides a minimal HTTP API for static information:
| Endpoint | Method | Description |
|----------|--------|-------------|
| `/env` | `GET` | Returns static environment information: robot, scene, has_gripper, action_space, observation_space, camera_feeds |
| `/metadata` | `GET` | Returns available robots, scenes, actions, and system configuration |
| `/video_feed` | `GET` | MJPEG video stream of the main camera |
| `/camera/<name>/video_feed` | `GET` | MJPEG video stream of auxiliary cameras (added via `/cameras`) |
| `/cameras` | `POST` | Register a new auxiliary camera for the current robot/scene |
| `/homing` | `GET` | **Blocking** homing for UR5 via Nova jogging (pauses joggers while executing) |
**Example `/env` response:**
```json
{
"robot": "ur5",
"scene": "scene",
"has_gripper": true,
"control_mode": "ik",
"action_space": {...},
"observation_space": {...},
"camera_feeds": [
{
"name": "main",
"label": "Main Camera",
"url": "/nova-sim/api/v1/video_feed",
"pose": {
"position": {"x": 0.75, "y": -0.75, "z": 0.9},
"orientation": {"w": 0.92, "x": -0.16, "y": -0.36, "z": 0.04}
},
"intrinsics": {"fx": 869.1, "fy": 869.1, "cx": 640.0, "cy": 360.0, "width": 1280, "height": 720, "fovy_degrees": 45.0}
},
{
"name": "aux_side",
"label": "Aux Side View",
"url": "/nova-sim/api/v1/camera/aux_side/video_feed",
"pose": {
"position": {"x": 0.5, "y": 0.2, "z": 0.9},
"orientation": {"w": 0.99, "x": -0.08, "y": 0.02, "z": 0.02}
},
"intrinsics": {"fx": 193.1, "fy": 193.1, "cx": 120.0, "cy": 80.0, "width": 240, "height": 160, "fovy_degrees": 45.0}
}
],
"home_pose": [-1.57, -1.57, 1.57, -1.57, -1.57, 0.0]
}
```
The `/env` endpoint returns scene-specific information including camera feeds available for the current robot/scene configuration. Dynamic cameras added via `POST /cameras` appear here immediately.
All dynamic operations (reset, switching robots, sending actions) are performed via WebSocket messages. Training data (observations, rewards, etc.) come from the `/ws` state stream.
**Add a camera (`POST /cameras`)**
```json
{
"name": "aux_side",
"label": "Aux Side View",
"lookat": [0.55, -0.1, 0.42],
"distance": 0.9,
"azimuth": -45,
"elevation": -30,
"replace": true
}
```
Notes:
- Cameras are scoped to the current robot + scene and show up in `/env` under `camera_feeds`.
- The UI listens for a `state` message containing `camera_event` and refreshes tiles automatically.
**Blocking homing (`GET /homing`)**
```
/nova-sim/api/v1/homing?timeout_s=30&tolerance=0.01&poll_interval_s=0.1
```
Notes:
- This endpoint is **blocking**: it returns only after the robot reaches `home_pose` or a timeout occurs.
- While homing is active, jogging commands are paused (incoming jog/teleop actions are ignored).
### Client → Server WebSocket Messages
**`action`** - Send velocity actions to all robots:
```json
{"type": "action", "data": {"vx": 0.5, "vy": 0.0, "vyaw": 0.0}}
```
For locomotion robots (G1, Spot):
- `vx`: Forward/backward velocity [-1, 1]
- `vy`: Left/right strafe velocity [-1, 1]
- `vyaw`: Turn rate [-1, 1]
For robot arms (UR5):
- `vx`, `vy`, `vz`: Cartesian translation velocities (m/s)
- `vrx`, `vry`, `vrz`: Cartesian rotation velocities (rad/s)
- `j1`-`j6`: Joint velocities (rad/s)
- `gripper`: Gripper position [0-255]
**Note:** Old message type `command` is still accepted for backward compatibility.
**`reset`** - Reset the environment:
```json
{"type": "reset", "data": {"seed": 42}}
```
- `seed`: Optional random seed for environment reset
**`switch_robot`** - Switch to a different robot/scene:
```json
{"type": "switch_robot", "data": {"robot": "ur5", "scene": "scene"}}
```
- `robot`: Required. One of: `"g1"`, `"spot"`, `"ur5"`, `"ur5_t_push"`
- `scene`: Optional scene name (see `/metadata` for available scenes)
**`teleop_action`** - Send teleoperation action (primarily for UR5 keyboard control):
```json
{"type": "teleop_action", "data": {"vx": 0.01, "vy": 0.0, "vz": 0.0}}
```
- For UR5: `vx`, `vy`, `vz` represent Cartesian velocity deltas (m/s)
- Backward compatible: old `dx`, `dy`, `dz` format is auto-mapped to `vx`, `vy`, `vz`
- **Note:** Old message type `teleop_command` is still accepted for backward compatibility.
**`camera`:**
```json
// Rotate camera
{"type": "camera", "data": {"action": "rotate", "dx": 10, "dy": 5}}
// Zoom camera
{"type": "camera", "data": {"action": "zoom", "dz": -50}}
// Pan camera
{"type": "camera", "data": {"action": "pan", "dx": 10, "dy": 5}}
// Set absolute distance
{"type": "camera", "data": {"action": "set_distance", "distance": 3.0}}
```
**`camera_follow`:**
```json
{"type": "camera_follow", "data": {"follow": true}}
```
#### UR5-Specific Messages
**`arm_target`** (IK mode - set end-effector target position):
```json
{"type": "arm_target", "data": {"x": 0.4, "y": 0.0, "z": 0.6}}
```
- `x`, `y`, `z`: Target position in meters
**`arm_orientation`** (IK mode - set end-effector target orientation):
```json
{"type": "arm_orientation", "data": {"roll": 0.0, "pitch": 1.57, "yaw": 0.0}}
```
- `roll`, `pitch`, `yaw`: Target orientation in radians (XYZ Euler convention)
- Default pointing down: `pitch = 1.57` (π/2)
**`use_orientation`** (Toggle orientation control):
```json
{"type": "use_orientation", "data": {"enabled": true}}
```
- `enabled`: `true` for 6-DOF IK (position + orientation), `false` for 3-DOF IK (position only)
**`joint_positions`** (Joint mode - direct joint control):
```json
{"type": "joint_positions", "data": {"positions": [-1.57, -1.57, 1.57, -1.57, -1.57, 0.0]}}
```
- `positions`: Array of 6 joint angles in radians [J1, J2, J3, J4, J5, J6]
**`control_mode`** (Switch control mode):
```json
{"type": "control_mode", "data": {"mode": "ik"}}
```
- `mode`: `"ik"` (end-effector target) or `"joint"` (direct joint positions)
**`gripper`** (Control gripper):
```json
{"type": "gripper", "data": {"action": "close"}}
```
- `action`: `"open"` or `"close"`
**`set_nova_mode`** (Configure Nova API integration):
```json
{"type": "set_nova_mode", "data": {"state_streaming": true, "ik": false}}
```
- `enabled`: (Optional, legacy) Enable/disable all Nova features
- `state_streaming`: (Optional) Enable/disable Nova state streaming
- `ik`: (Optional) Enable/disable Nova IK computation
#### Client Identity & Notification Messages
**`client_identity`** (Client handshake):
```json
{"type": "client_identity", "data": {"client_id": "my_client_v1"}}
```
- `client_id`: Unique identifier for the external client
- **Note:** Old `trainer_identity` type is still supported for backward compatibility
**`client_notification`** (Send client notification to all connected clients):
```json
{"type": "client_notification", "data": {"message": "Starting epoch 5", "level": "info"}}
```
- `message`: Notification text
- `level`: `"info"`, `"warning"`, or `"error"`
- **Note:** Old `notification` type is still supported for backward compatibility
**`episode_control`** (Control episode state):
```json
{"type": "episode_control", "data": {"action": "terminate"}}
```
- `action`: `"terminate"` (episode ended successfully) or `"truncate"` (episode cut short)
#### Server → Client Messages
**`state`** (broadcast at ~10 Hz):
For locomotion robots (G1, Spot):
```json
{
"type": "state",
"data": {
"observation": {
"position": {"x": 0.0, "y": 0.0, "z": 0.46},
"orientation": {"w": 1.0, "x": 0.0, "y": 0.0, "z": 0.0}
},
"steps": 1234,
"reward": 0.0,
"teleop_action": {"vx": 0.5, "vy": 0.0, "vz": 0.0, "vyaw": 0.0, "vrx": 0.0, "vry": 0.0, "vrz": 0.0, "j1": 0.0, "j2": 0.0, "j3": 0.0, "j4": 0.0, "j5": 0.0, "j6": 0.0, "gripper": 0.0},
"trainer_connected": true
}
}
```
For robot arm (UR5):
```json
{
"type": "state",
"data": {
"observation": {
"end_effector": {"x": 0.4, "y": 0.0, "z": 0.6},
"ee_orientation": {"w": 0.5, "x": 0.5, "y": 0.5, "z": 0.5},
"ee_target": {"x": 0.4, "y": 0.0, "z": 0.6},
"ee_target_orientation": {"roll": 0.0, "pitch": 1.57, "yaw": 0.0},
"gripper": 128,
"joint_positions": [-1.57, -1.57, 1.57, -1.57, -1.57, 0.0],
"joint_targets": [-1.57, -1.57, 1.57, -1.57, -1.57, 0.0]
},
"control_mode": "ik",
"steps": 1234,
"reward": -0.25,
"teleop_action": {"vx": 0.02, "vy": 0.0, "vz": 0.0, "vyaw": 0.0, "vrx": 0.0, "vry": 0.0, "vrz": 0.0, "j1": 0.0, "j2": 0.0, "j3": 0.0, "j4": 0.0, "j5": 0.0, "j6": 0.0, "gripper": 128.0},
"trainer_connected": true,
"nova_api": {
"connected": true,
"state_streaming": true,
"ik": false
}
}
}
```
**Field descriptions:**
*Common fields (all robots):*
- `observation`: Contains robot-specific sensor data and state information
- `steps`: Number of simulation steps since last reset
- `reward`: The integrated task reward from the simulator that external clients can consume
- `teleop_action`: The canonical action/velocity stream that drives locomotion or arm movement; the UI and every external client should read this field as the unified action record. Always present with zero values when idle
- Cartesian velocities: `vx` (forward/back or X-axis), `vy` (strafe or Y-axis), `vz` (vertical for UR5), `vyaw` (rotation for locomotion)
- Cartesian rotation velocities (UR5 only): `vrx`, `vry`, `vrz` (rad/s)
- Joint velocities (UR5 only): `j1`, `j2`, `j3`, `j4`, `j5`, `j6` (rad/s)
- Gripper: `gripper` (0-255 for UR5, 0 for others)
- Locomotion robots: Use `vx`, `vy`, `vyaw` (other fields are 0)
- UR5: Use `vx`/`vy`/`vz` for Cartesian translation, `vrx`/`vry`/`vrz` for rotation, `j1`-`j6` for joint velocities, and `gripper` for gripper control
- `connected_clients`: List of connected external client IDs (e.g., `["trainer_v1", "monitor"]`)
- `scene_objects`: List of scene objects with their positions and orientations. Each object has:
- `name`: Object identifier (e.g., "t_object", "t_target", "box")
- `position`: Object position in meters (x, y, z)
- `orientation`: Object orientation as quaternion (w, x, y, z)
*Locomotion observation fields (inside `observation`):*
- `position`: Robot base position in world coordinates (x, y, z) in meters
- `orientation`: Robot base orientation as quaternion (w, x, y, z)
*UR5 observation fields (inside `observation`):*
- `end_effector`: Current end-effector position in meters (x, y, z)
- `ee_orientation`: Current end-effector orientation as quaternion (w, x, y, z)
- `ee_target`: Target end-effector position in meters (x, y, z)
- `ee_target_orientation`: Target end-effector orientation as Euler angles in radians (roll, pitch, yaw)
- `gripper`: Gripper position (0-255, where 0 is open and 255 is closed)
- `joint_positions`: Current joint angles in radians
- `joint_targets`: Target joint angles in radians (in joint control mode)
*UR5-specific fields (outside observation):*
- `control_mode`: Current control mode ("ik" for inverse kinematics or "joint" for joint control)
- `nova_api`: Nova API integration status (displays which controllers are active)
- `connected`: Whether Nova API client is connected
- `state_streaming`: Whether using Nova API for robot state streaming (vs. internal)
- `ik`: Whether using Nova API for inverse kinematics (vs. internal)
**Note:** Static environment information (robot name, scene name, has_gripper, action/observation spaces, camera feeds) has been moved to the `GET /env` endpoint and is no longer included in the state stream.
**`connected_clients`** (broadcast to all clients):
```json
{
"type": "connected_clients",
"data": {
"clients": ["trainer_v1", "monitor"]
}
}
```
- `clients`: Array of connected external client IDs
**`client_notification`** (broadcast to all clients):
```json
{
"type": "client_notification",
"data": {
"message": "Starting epoch 5",
"level": "info"
}
}
```
- `message`: Notification text from external client
- `level`: `"info"`, `"warning"`, or `"error"`
### State broadcasts and client notifications
Every `/ws` client receives a `state` message roughly every 100 ms. The examples above show the locomotion (`spot`) and arm (`ur5`) payloads; the payload also now includes:
- `teleop_action`: The latest action/teleoperation stream (includes `vx`, `vy`, `vz`, `vyaw`, `vrx`, `vry`, `vrz`, `j1`-`j6`, `gripper`) so external clients and the UI read a single canonical action payload. Always present with zero values when idle.
- `reward`: The integrated task reward that external clients can consume without sending a separate `step`.
- `connected_clients`: Array of connected external client IDs (used to display which clients are connected).
External clients (trainers, monitors, etc.) announce themselves by sending a `client_identity` payload when the socket opens. The server mirrors that information into the `connected_clients` broadcasts (`connected_clients` messages flow to all clients) and lets external clients emit `client_notification` payloads that all clients receive.
### HTTP Endpoints
| Endpoint | Method | Description |
|----------|--------|-------------|
| `/nova-sim/api/v1` | GET | Web interface (HTML/JS) |
| `/nova-sim/api/v1/env` | GET | Static environment info (robot, scene, spaces, camera feeds) |
| `/nova-sim/api/v1/metadata` | GET | Available robots, scenes, actions, and system configuration |
| `/nova-sim/api/v1/video_feed` | GET | MJPEG video stream (main camera) |
| `/nova-sim/api/v1/camera/<name>/video_feed` | GET | MJPEG video stream (auxiliary cameras) |
**Video stream usage:**
```html
<img src="http://localhost:3004/nova-sim/api/v1/video_feed" />
```
**Note:** Robot switching, reset, and other dynamic operations are performed via WebSocket messages, not HTTP endpoints. See the WebSocket Messages section for details.
### Metadata & Camera Feeds
- `GET /nova-sim/api/v1/metadata` returns JSON describing every available robot/scene pair and the supported actions
- `GET /nova-sim/api/v1/env` returns scene-specific camera feeds - the `camera_feeds` array lists all available video streams for the current robot/scene configuration including the main camera and any auxiliary cameras you registered via `POST /nova-sim/api/v1/cameras`
- `GET /nova-sim/api/v1/camera/<name>/video_feed` streams MJPEG for a specific camera feed
- `pytest tests/` exercises the HTTP metadata/video endpoints, the `/ws` control socket, and every camera feed. Keep Nova-Sim running at `http://localhost:3004` when you run it so the suite can talk to the live server.
## Wandelbots Nova API Integration
The UR5 environment supports optional integration with the Wandelbots Nova API v2 for real-time robot state streaming, cloud-based inverse kinematics, and robot jogging control.
Nova API integration provides three key features:
- **Robot State Streaming**: Real-time synchronization of joint positions from physical robots via WebSocket
- **Inverse Kinematics**: Cloud-based IK computation using Nova's kinematic solver
- **Robot Jogging**: Direct velocity control of robot joints and cartesian motion via unified v2 API
### Quick Setup
1. **Copy the environment template:**
```bash
cp .env.example .env.local
```
2. **Configure your Nova credentials in `.env.local`:**
```bash
NOVA_INSTANCE_URL=https://your-instance.wandelbots.io
NOVA_ACCESS_TOKEN=your_access_token
NOVA_CELL_ID=cell
NOVA_CONTROLLER_ID=your_controller_id
NOVA_MOTION_GROUP_ID=your_motion_group_id
NOVA_MOTION_GROUP_MODEL=ur5e # or your robot model
NOVA_TCP_NAME=Flange
NOVA_RESPONSE_RATE_MS=200
```
3. **Discover available robots in your Nova instance:**
```bash
python3 scripts/discover_nova_simple.py
```
4. **Test your connection:**
```bash
cd nova-sim
python3 scripts/test_nova_connection.py
```
### Usage Modes
Nova API integration supports three distinct modes:
1. **Digital Twin Mode** (State Streaming Only - Recommended): The simulation mirrors a real robot's state. Robot movements come from the physical robot via WebSocket. **Important**: In this mode, keyboard controls, jogging buttons, and internal target controls are disabled because the robot state is being synchronized from the real robot. This is the default when `.env.local` is detected.
2. **Nova IK Mode** (IK Only): Use Nova's cloud-based IK solver while controlling the simulation robot locally. Useful for validating IK solutions or when you want to use Nova's kinematic model. Keyboard controls and jogging work normally in this mode.
3. **Hybrid Mode** (Both): Uses Nova state streaming and Nova IK. Generally not recommended since the real robot is controlled externally. Keyboard controls are disabled in this mode.
### Usage Examples
#### Digital Twin Mode (State Streaming Only - Default)
Mirror a real robot's state in the simulation:
```python
import os
from pathlib import Path
from nova_sim.robots.ur5.ur5_env import UR5Env
# Load environment variables
def load_env(filepath):
with open(filepath) as f:
for line in f:
if line.strip() and not line.startswith('#') and '=' in line:
key, val = line.split('=', 1)
os.environ[key.strip()] = val.strip()
load_env(Path("nova-sim/.env.local"))
# Create environment with state streaming enabled
env = UR5Env(
render_mode="human",
scene_name="scene",
nova_api_config={
"use_state_stream": True, # Mirror real robot state
"use_ik": False # Real robot controlled externally
}
)
obs, info = env.reset()
for _ in range(1000):
obs = env.step_with_controller(dt=0.002)
env.render()
env.close()
```
#### Nova IK Mode (IK Only)
Use Nova's cloud-based IK solver while controlling the simulation robot locally:
```python
env = UR5Env(
render_mode="human",
nova_api_config={
"use_state_stream": False,
"use_ik": True # Use Nova IK
}
)
# IK will be computed by Nova API
env.set_target(x=0.4, y=0.2, z=0.6)
```
#### Hybrid Mode (Not Recommended)
Enable both state streaming and Nova IK. Generally not useful since the real robot is controlled externally:
```python
env = UR5Env(
render_mode="human",
nova_api_config={
"use_state_stream": True, # Mirror real robot
"use_ik": True # Also use Nova IK (usually not needed)
}
)
```
**Note**: When state streaming is enabled, the simulation becomes a digital twin that mirrors the real robot's state. The robot can still be controlled via Nova API jogging commands (when `use_jogging` is enabled). Local IK target updates are ignored in favor of the real robot's state, but the robot can be moved through Nova API commands.
### Environment Variables Reference
| Variable | Required | Default | Description |
|----------|----------|---------|-------------|
| `NOVA_INSTANCE_URL` | Yes | - | Nova instance URL (e.g., `https://nova.wandelbots.io`) |
| `NOVA_ACCESS_TOKEN` | Yes | - | Nova API access token |
| `NOVA_CELL_ID` | No | `cell` | Cell ID |
| `NOVA_CONTROLLER_ID` | Yes | - | Controller ID |
| `NOVA_MOTION_GROUP_ID` | Yes | - | Motion group ID |
| `NOVA_MOTION_GROUP_MODEL` | No | Auto-detected | Motion group model (e.g., `ur5e`, `KUKA_KR16_R2010_2`) |
| `NOVA_TCP_NAME` | No | `Flange` | Tool Center Point name |
| `NOVA_RESPONSE_RATE_MS` | No | `200` | State stream response rate in milliseconds |
**Note:** `NOVA_API` is also supported as an alias for `NOVA_INSTANCE_URL` for backward compatibility.
### How It Works
#### State Streaming
When `use_state_stream` is enabled:
1. A background thread connects to Nova's WebSocket state stream
2. Robot state (joint positions) is continuously received at the configured rate
3. Each time the environment queries robot state, the latest data from Nova is synced
4. The simulation updates its joint positions to match the real robot
5. MuJoCo forward kinematics computes the end-effector pose
**Note:** When state streaming is active, the simulation becomes a digital twin that mirrors the real robot's state. The robot can still be moved via Nova API commands (e.g., jogging).
#### Inverse Kinematics
When `use_ik` is enabled:
1. Target poses are sent to Nova's IK API endpoint: `POST /api/v2/cells/{cell_id}/kinematic/inverse`
2. Nova computes joint angles using the robot's kinematic model
3. Joint targets are returned and applied to the simulation
4. If Nova IK fails, the system automatically falls back to local IK computation
### Getting Nova Credentials
To obtain your Nova instance credentials:
1. Log in to the [Wandelbots Portal](https://portal.wandelbots.io/)
2. Navigate to your Nova instance
3. Generate an API access token in the settings
4. Note your controller ID and motion group ID from the API documentation
5. Use the discovery script to find available robots:
```bash
python3 scripts/discover_nova_simple.py
```
For more details, see the [Nova API Documentation](https://portal.wandelbots.io/docs/api/v2/ui/).
### Troubleshooting
#### "Missing required environment variables"
Ensure all required variables are set in `.env.local`. Verify loading with:
```python
import os
print("NOVA_INSTANCE_URL:", os.getenv("NOVA_INSTANCE_URL"))
```
#### "websockets is required for Nova state streaming"
Install the websockets package:
```bash
pip install websockets
```
#### "Nova API error 401"
Your access token may be invalid or expired. Generate a new token from the Wandelbots Portal.
#### State Stream Errors
- Verify your instance URL is correct
- Check that controller and motion group IDs are valid
- Ensure your network can reach the Nova instance
- Confirm your access token has not expired
#### IK Falls Back to Local Solver
If you see "Nova IK failed, falling back to local IK":
- Check that the motion group model matches your robot
- Verify the TCP name matches a TCP defined in your Nova instance
- Ensure the target pose is reachable by the robot
### Performance Considerations
- **State Stream Rate**: Default is 200ms (5Hz). Lower values provide more responsive streaming but increase bandwidth usage
- **IK Latency**: Nova IK requires a network round-trip (~50-200ms depending on connection quality)
- **Simulation Rate**: When using state streaming, simulation rate matches the Nova stream rate
### Dependencies
- `websockets` (for state streaming): `pip install websockets`
- `python-dotenv` (optional, for easier `.env` loading): `pip install python-dotenv`
### Helpful Scripts
Located in `scripts/`:
- **`discover_nova_simple.py`**: Discover available controllers and motion groups in your Nova instance
- **`test_nova_connection.py`**: Verify your Nova API configuration is working correctly
### Implementation Details
The Nova API integration is implemented in:
- [robots/ur5/nova_api.py](robots/ur5/nova_api.py) - API client and configuration
- [robots/ur5/ur5_env.py](robots/ur5/ur5_env.py) - Environment integration (lines 123-203, 499-520)
## Testing
1. Start the Nova Sim server (e.g. `python nova-sim/mujoco_server.py` or via `docker-compose`).
2. Keep it running at `http://localhost:3004` so the HTTP/websocket endpoints stay reachable.
3. Run `pytest nova-sim/tests` to exercise:
- API endpoints (`/metadata`, `/camera/<name>/video_feed`, `/video_feed`)
- Unified WebSocket control (`/ws`)
- Auxiliary MJPEG overlays after switching to the T-push UR5 scene
The tests assume the server is accessible via `http://localhost:3004/nova-sim/api/v1` and will skip automatically if the API is unreachable.
## License
This project uses models from:
- [MuJoCo Menagerie](https://github.com/google-deepmind/mujoco_menagerie) (BSD-3-Clause)
- [unitree_mujoco](https://github.com/unitreerobotics/unitree_mujoco) (BSD-3-Clause)
- [unitree_rl_gym](https://github.com/unitreerobotics/unitree_rl_gym)
- [Quadruped-PyMPC](https://github.com/iit-DLSLab/Quadruped-PyMPC) (BSD-3-Clause)
**`teleop_action`:**
```json
{"type": "teleop_action", "data": {"vx": 0.01, "vy": 0.0, "vz": -0.01}}
```
- `vx`, `vy`, `vz`: Velocity/delta values for UR5 Cartesian movement (WASD + RF from the UI) or locomotion robot velocity (`vx`, `vy`, `vyaw`)
- These values appear in the `teleop_action` field of each `/ws` `state` broadcast, which is the canonical action stream for both the UI and any RL trainer
- The field always contains zero values when idle (never null)
|