This documentation provides a comprehensive overview of the Mini Arm Controller software, from the high-level API down to the low-level hardware communication and IK solver implementation.
git clone https://github.com/terrorproforma/GradientOS.git --verbose
cd GradientOS
# Preferred: automated setup (system deps + uv env + project install)
./setup.sh
# Manual fallback (custom envs / troubleshooting):
# uv venv .venv
# source ./start.sh # activates venv, adjusts PYTHONPATH, adds aliases only if neededThe package provides command-line tools (available after install):
gradient-controller # Main controller for UDP commands
gradient-ui # Graphical user interface
gradient-cli # Command-line interface
gradient-vision # Vision module CLI (cameras, processing, streaming)
gradient-api # FastAPI proxy that exposes REST/SSE telemetryComponent extras:
- Core (
gradient-controller,gradient-api) are installed by default. - UI/CLI tooling requires the
uiextra:uv pip install -e .[ui]. - Camera/vision tooling (including telemetry capture) lives behind the
visionextra:uv pip install -e .[vision]. - Raspberry Pi CSI cameras need the separate
picameraextra:uv pip install -e .[picamera]. - Combine extras as needed, e.g.
uv pip install -e .[ui,vision,ai]for full tooling. - Raspberry Pi camera support still needs the system
picamera2stack (typically installed viasudo apt install -y python3-libcamera python3-picamera2).
Notes:
- If you prefer not to install console scripts yet, aliases are provided after activation:
- gradient-vision → python -m gradient_os.vision
- gradient-ui → python -m gradient_os.ui_start
- gradient-controller → python -m gradient_os.run_controller
- gradient-cli → python -m gradient_os.cli_controller
- Always activate with
source ./start.sh. Executing the script will not persist the environment.
gradient-ui can be run remotely and can connect to your pi or other board via UDP. gradient-controller must run locally on your pi or board connected to the motor controller. The HTTP proxy (gradient-api) fans out telemetry over Server-Sent Events and is typically co-hosted with the controller.
- Start the proxy manually once the environment is prepared:
With no
gradient-api --host 0.0.0.0 --port 4000
GRADIENT_API_CORSset, the API allows requests from any origin. OverrideGRADIENT_CONTROLLER_HOST/PORTif the UDP controller runs elsewhere. - A React-based telemetry dashboard lives under
web-ui/. During development:Visitingcd web-ui npm install npm run dev -- --host 0.0.0.0 --port 8000http://<pi-ip>:8000auto-fills the API endpoint tohttp://<pi-ip>:4000; click Connect to subscribe to the/monitorSSE stream. - For unattended setups, install the API as a systemd service using the helper scripts in
web-ui/systemd/(mirrors the arm-controller tooling):The unit runscd web-ui/systemd ./install.sh # ./status.sh / ./restart.sh / ./stop.sh / ./uninstall.sh as needed
gradient-apifrom the repo virtualenv and binds to0.0.0.0:4000by default.
- The floating control card rendered by
web-ui/src/ControlPanel.tsxuses the same Cartesian jog buttons for both incremental and realtime jog, depending on whether realtime is started. - With realtime jog off (default), each Cartesian button press issues a single incremental move whose step size is fully controlled by the numeric fields in the jog card:
- Translation buttons call
/control/move-line-relativewith a step ofLinearmillimeters (from theLinear (mm/s)input) along the selected axis, converted to meters in the payload. The request includes the current speed multiplier from the UI slider asspeed_multiplier, and setsclosed: trueso the controller handles the interpolation. - Orientation buttons call
/control/rotatewith a step ofAngulardegrees (from theAngular (deg/s)input) about the requested axis (roll,pitch, oryaw). The API fetches the current pose, composes aSET_ORIENTATIONcommand, and therefore follows the same solver path as the desktop PySide UI.
- Translation buttons call
- With realtime jog on (press the Start button in the Realtime Jog block), the same buttons switch to press‑and‑hold behavior and the UI streams velocity vectors through
/control/jog/velocity. TheDeadmancheckbox still gates whether any motion is commanded in this mode, and theLinear/Angularfields are interpreted as base linear and angular rates for the realtime vector. - Jog start/stop avoids re‑issuing servo commands when the jog vector is zero: the controller caches the last posture, skips IK work whenever both linear and angular rates are zero, and only sends new setpoints when an axis is actually pressed. This prevents the robot from creeping when operators simply toggle realtime on/off.
For unattended deployments on Raspberry Pi, bundled systemd units live under
systemd/. See systemd/README.md for installation scripts and details for
both the controller (systemd/controller/) and the HTTP API proxy
(systemd/api/).
The command-line interface, gradient-cli, for real-time control of the robot arm. The UI is built with the standard curses library for a lightweight, terminal-based experience.
Features include:
- Mode switching (Tab key) between Cartesian "pan" and tool "orient" control.
- Intuitive W/A/S/D and Shift key bindings for jogging the arm.
- Keys R/F open and close the gripper.
- Hotkeys (1, 2, 3) for sending the arm to preset Rest, Home, and Zero positions.
- A live display of the robot's current X/Y/Z position.
This checklist tracks the progress of documenting each component of the system at a granular level.
- System Overview and Data Flow
- Non-Blocking Command Architecture
File-Level Documentation:
-
run_controller.py- Main Entry Point -
command_api.py- UDP Command Handlers -
trajectory_execution.py- Path Planning & Execution -
servo_driver.py- High-Level Servo Control -
servo_protocol.py- Low-Level Servo Communication -
utils.py- Shared Constants and Helpers -
__init__.py- Package Initializer (This file makessrc/arm_controllera Python package, allowing its modules to be imported.)
Function and Variable-Level Documentation (Docstrings):
-
utils.py -
servo_protocol.py -
servo_driver.py -
trajectory_execution.py -
command_api.py -
run_controller.py
- Python Wrapper (
ik_solver.py) - C++ IKFast Implementation Overview & End-Effector Offset
-
trajectory_planner.py
-
tests/test_protocol.py -
tests/test_driver.py -
tests/test_planning.py -
tests/test_end_to_end.py(Mocked Hardware)
For camera setup, streaming, and image processing, see the Vision README:
- Vision README:
src/gradient_os/vision/README.md
Quick usage (after activation and install):
gradient-vision # Streams with Pi defaults (cam0, 1280x720@30)
gradient-vision list
gradient-vision init --camera 0 --width 640 --height 480 --fps 30
gradient-vision stream --camera 0 --width 640 --height 480 --fps 30 --duration 10
gradient-vision mjpeg # HTTP server (auto-dual if 2 cams). Visit http://<host>:8080/
gradient-vision mjpeg img-proc --object-detection --color red --vflip --hflip
gradient-vision mjpeg ai --weights yolo11n.pt --conf 0.25 --imgsz 640 --device cpu --vflip --hflip
gradient-vision mjpeg ai-seg --weights yolo11n-seg.pt --conf 0.25 --imgsz 640 --device cpu
gradient-vision mjpeg ai-pose --weights yolo11n-pose.pt --conf 0.25 --imgsz 640 --device cpuThe Mini Arm Controller software is designed with a modular, layered architecture to separate concerns and improve maintainability. The system's primary responsibility is to accept high-level commands via UDP, translate them into low-level hardware instructions, and manage the real-time execution of complex motion paths.
The following diagram illustrates how a command flows through the system, from the initial UDP packet to the final motor movement.
graph TD
subgraph User
A["UDP Command<br/>e.g., 'MOVE_LINE,...'"]
end
subgraph Raspberry Pi
subgraph run_controller.py
B["Main Loop<br/>Listens for commands"]
end
subgraph arm_controller Package
C["command_api.py<br/>handle_move_line"]
D["trajectory_execution.py<br/>_plan_... / _closed_loop_..."]
E["servo_driver.py<br/>set_servo_positions"]
F["servo_protocol.py<br/>sync_write_..."]
G["utils.py<br/>Shared State & Constants"]
end
subgraph External Libraries
H["ik_solver.py<br/>(Python Wrapper)"]
I["ikfast_solver<br/>(C++ Module)"]
end
J(("Servos"))
end
A --> B;
B --> C;
C --> D;
D --"Plans Path"--> H;
H --"Solves IK"--> I;
D --"Executes Path"--> E;
E --> F;
F --> J;
J --"Feedback"--> F;
F --"Feedback"--> E;
E --"Feedback"--> D;
G -.-> C;
G -.-> D;
G -.-> E;
G -.-> F;
-
User: The user sends a command as a simple string over UDP (e.g.,
"MOVE_LINE,0.3,0.1,0.2"). -
run_controller.py: This is the main entry point of the application. Itsmain()function contains a simple, non-blocking loop that listens for UDP packets. When a packet is received, it is parsed and dispatched to the appropriate handler in thecommand_api. -
arm_controllerPackage: This is the core of the controller logic.command_api.py: Receives the dispatched command. It interprets the command's parameters and orchestrates the other modules to fulfill the request. For aMOVE_LINEcommand, it calls upon thetrajectory_executionmodule.trajectory_execution.py: This module contains the most complex logic. It takes high-level goals (like "move from A to B in a straight line") and performs two key steps:- Planning: It calls the
ik_solverto plan the entire path, converting the Cartesian trajectory into a dense series of joint angle solutions. - Execution: It starts a background thread (
_closed_loop_executor_thread) to execute this path, using feedback from the servos to correct for errors in real time.
- Planning: It calls the
ik_solver.py: This is a Python wrapper that provides a clean interface to the high-performance C++ IKFast solver.ikfast_solver(C++): The compiled IKFast library that can solve for the robot's joint angles for a given end-effector pose with extreme speed.servo_driver.py: Provides a hardware abstraction layer. It takes simple commands like "set these joint angles in radians" and translates them into the raw 0-4095 values the servos understand.servo_protocol.py: The lowest level of the software stack. It is responsible for constructing the exact byte-for-byte packets (including headers, IDs, and checksums) required by the Feetech servo communication protocol. It sends these packets over the serial port.utils.py: A shared module containing global state (like the current trajectory status) and configuration constants (like joint limits and servo IDs) that are needed by all other modules.
-
Servos: The physical hardware receives the command packets and moves to the specified positions. The closed-loop control relies on the
sync_readcommand to get position feedback from the servos, which flows back up the stack to thetrajectory_executionmodule.
The high performance of the system's motion planning is made possible by the C++ IKFast solver. This is not a generic numerical solver; it's a specialized, analytically-derived solver created specifically for this robot's unique geometry.
-
IKFast: The core of the solver is auto-generated by OpenRAVE's IKFast tool. We provide our robot's
.urdffile to IKFast, and it produces a C++ file containing the complex trigonometric equations that analytically solve for the joint angles. Because it's an analytic solution, it is extremely fast (on the order of microseconds) and can return all possible valid solutions. -
ikfast_solver.cpp: This file contains the primaryIKFastSolverC++ class. It#includes the auto-generated solver code and provides clean C++ methods (solve_ik,compute_fk,solve_ik_path) that our Python wrapper can bind to. Thesolve_ik_pathmethod is particularly important, as it contains an optimized C++ loop for solving sequential points, which is much faster than iterating in Python. -
ik_wrapper.cpp: This file uses the pybind11 library to create the Python bindings for ourIKFastSolverclass. It exposes the C++ methods so that they can be called directly from Python as if they were native Python functions. This is what allowsik_solver.pyto callIK_SOLVER.solve_ik_path(...). -
CMakeLists.txt: This is the build script for the C++ module. It handles finding thepybind11andPython.hlibraries and compiling the C++ source files into a single.so(shared object) file that Python can import as a native module.
A critical feature of the controller is its non-blocking, responsive design. The main command loop must never be blocked by a long-running move, as this would prevent it from processing urgent commands, such as an emergency stop.
The following sequence diagram illustrates how a move is initiated in a background thread, leaving the main loop free to handle other commands.
sequenceDiagram
participant Client
participant MainLoop as "run_controller.py"
participant CommandAPI as "command_api.py"
participant ExecutorThread as "_closed_loop_executor_thread"
Client->>+MainLoop: Send "MOVE_LINE,..."
MainLoop->>+CommandAPI: handle_move_line(...)
CommandAPI->>+ExecutorThread: Start thread
Note over CommandAPI, ExecutorThread: The executor starts its high-frequency<br/>error correction loop in the background.
ExecutorThread-->>-CommandAPI: Returns immediately
CommandAPI-->>-MainLoop: Returns immediately
MainLoop-->>-Client: (Ready for next command)
loop For Every Point in Path
ExecutorThread->>ExecutorThread: Correct Error (Target - Actual)
end
Client->>+MainLoop: Send "STOP"
MainLoop->>+CommandAPI: handle_stop_command()
Note over CommandAPI: Sets the stop flag
CommandAPI-->>-MainLoop: Returns immediately
ExecutorThread->>ExecutorThread: Loop sees stop flag is set and exits
Note over ExecutorThread: The move is safely aborted.
- When a
MOVE_LINEcommand is received, thehandle_move_linefunction incommand_api.pystarts the_closed_loop_executor_thread. - Crucially, the handler returns immediately after starting the thread. It does not wait for the move to finish. This frees the
MainLoopinrun_controller.pyto listen for the next command. - The
ExecutorThreadruns independently in the background, managing the high-frequency (~50 Hz) loop of reading servo feedback, calculating error, and sending corrected position commands. - If the user sends a
STOPcommand, theMainLoopis available to receive it instantly. It callshandle_stop_command, which sets a global flag (trajectory_state["should_stop"] = True). - On its very next cycle, the
ExecutorThreadchecks this flag, sees that it isTrue, and cleanly exits its control loop, stopping the robot's motion. - For situations where blocking behavior is desired (e.g., scripting a sequence of moves), the
WAIT_FOR_IDLEcommand can be used. This command will pause the client-side script by.join()ing the currently running motion thread, waiting for it to complete before allowing the script to proceed.