Deoxys is a modular, real-time controller library for Franka Emika Panda arm, aiming to facilitate a wide range of robot learning research. Deoxys comes with a user-friendly python interface and real-time controller implementation in C++. If you are a robosuite user, Deoxys APIs provide seamless transfer from you simulation codebase to real robot experiments!
Past.projects.using.Deoxys.mp4
If you use this codebase for your research projects, please cite our codebase based on the following project:
@article{zhu2022viola,
title={VIOLA: Imitation Learning for Vision-Based Manipulation with Object Proposal Priors},
author={Zhu, Yifeng and Joshi, Abhishek and Stone, Peter and Zhu, Yuke},
journal={arXiv preprint arXiv:2210.11339},
doi={10.48550/arXiv.2210.11339},
year={2022}
}
The setup has two machine-specific paths:
- Desktop-side Python setup for the Deoxys client and teleoperation scripts
- Intel NUC setup for the real-time Franka C++ interfaces
The steps below were validated on Ubuntu 22.04 with Python 3.10. For more background, see the Codebase Installation Page.
Clone this repo to your robot workspace (for example /home/USERNAME/robot-control-ws) and move into the build directory:
cd deoxys_control/deoxysUse a named Conda environment for the desktop machine. The examples below use fr3.
Create and activate the environment:
source ~/anaconda3/etc/profile.d/conda.sh
conda create -n fr3 python=3.10 pip setuptools wheel -y
conda activate fr3Generate the protobuf Python modules, install the Python requirements, and install Deoxys from this checkout:
cd deoxys_control/deoxys
make -j build_deoxys=1
pip install -U -r requirements.txt
pip install -e . --no-build-isolationmake -j build_deoxys=1 requires a working Protobuf toolchain. If cmake reports that protoc or Protobuf is missing, run LIBFRANKA_VERSION=0.9.0 ./InstallPackage once first, or install a compatible Protobuf toolchain manually.
After these steps, the examples can be run directly from this checkout.
For the 3Dconnexion SpaceMouse Wireless on Linux, install the bundled udev rule once:
./installation/create_spacemouse.sh
newgrp plugdevThen start a fresh shell, reactivate fr3, and run the SpaceMouse example again.
The NUC-side build expects the following source dependencies to exist inside deoxys/: libfranka, zmqpp, yaml-cpp, spdlog, and protobuf.
The helper script installs the required Ubuntu packages, clones those repositories, and installs Protobuf 3.13.0:
LIBFRANKA_VERSION=0.9.0 ./InstallPackageThe script requires internet access and sudo.
Then build the NUC-side binaries:
make -j build_franka=1- How to turn on/off the robot
- How to install spacemouse
- How to set up the RTOS
- How to record and replay a trajectory
- How to write a simple motor program
Here is a quick guide to run Deoxys.
On the desktop, activate fr3, move into deoxys_control/deoxys, and run:
source ~/anaconda3/etc/profile.d/conda.sh
conda activate fr3
cd deoxys_control/deoxys
python examples/run_deoxys_with_space_mouse.py Use the SpaceMouse right button or Ctrl+C to stop teleoperation cleanly.
For a no-hardware smoke test of the desktop-side Python setup, you can run:
python examples/run_deoxys_with_space_mouse.py --helpFor the default 3Dconnexion SpaceMouse Wireless used during validation, the script uses vendor ID 9583 and product ID 50734.
Change 1) SpaceMouse vendor_id and product_id (here) 2) robot interface config (here) if necessary.
You might also check and change the PC / NUC names here.
Under deoxys_control/deoxys, run two commands. One for real-time control of the arm, one for non
real-time control of the gripper.
bin/franka-interface config/charmander.ymlbin/gripper-interface config/charmander.ymlThe repo now includes a structured data pipeline CLI for RGB-D camera bring-up, reset, teleoperation collection, and HDF5 dataset build. Saved color arrays are RGB in memory and on disk; the pipeline does not expose BGR-D datasets.
Full operator guide:
The calibration folder now includes scripts to:
- export RealSense-native intrinsics/extrinsics
- capture checkerboard calibration samples from the live Redis camera streams
- estimate a static camera extrinsic
- estimate a wrist-camera hand-eye extrinsic
The teleop guide now also documents how to create a new task YAML, how
--task <name> maps to that file, and exactly where raw runN folders and
demo.hdf5 are written on disk. The CLI always uses the YAML filename stem for
task selection, while the YAML name: field controls the saved dataset path.
For shared lab use, the CLI now also includes task/date discovery helpers and a task-template scaffold command so multiple researchers can stay inside the same task-oriented storage layout:
deoxys.data tasks
deoxys.data dates --task fr3_dual_realsense
deoxys.data runs --task fr3_dual_realsense --all-dates
deoxys.data task-create --task bell_pepper_pick --from-task fr3_dual_realsenseThe default dual-camera task config lives at deoxys/config/data_tasks/fr3_dual_realsense.yml.
The default home reset preset lives at deoxys/config/data_resets/home_nominal.yml.
The default task config also sets default_reset_preset: home_nominal, so
plain teleop, data collection, and replay all begin from the same nominal joint
configuration unless you override the preset explicitly.
These files are versioned and are intended to be copied or adapted per task so that controller settings, camera layout, resize policy, and reset behavior are reproducible.
If you need a different home position for a specific experiment, the clean workflow is:
- Create a new task YAML from an existing template.
- Create a new reset preset YAML.
- Test that reset directly.
- Point the new task at that reset as its default.
- Use
teleoporcollecton the new task.
Example:
deoxys.data task-create --task bell_pepper_pick --from-task fr3_dual_realsenseThen create a new reset preset file such as home_bell_pepper_low.yml under deoxys/config/data_resets:
name: home_bell_pepper_low
controller_type: JOINT_POSITION
controller_cfg: joint-position-controller.yml
joint_positions: [0.09, -0.98, 0.03, -2.69, 0.05, 1.86, 0.87]
tolerance_rad: 0.001
timeout_sec: 30.0
allow_jitter: false
jitter_std_rad: 0.0
jitter_clip_rad: 0.0Test it directly:
deoxys.data reset --task bell_pepper_pick --preset home_bell_pepper_lowIf it looks good, set the new task’s default reset in bell_pepper_pick.yml:
default_reset_preset: home_bell_pepper_lowAfter that:
deoxys.data teleop --task bell_pepper_pick
deoxys.data collect --task bell_pepper_pickwill automatically use the new reset preset, while other tasks can keep using their existing defaults.
Activate fr3, move into deoxys_control, and use the installed deoxys.data CLI:
source ~/anaconda3/etc/profile.d/conda.sh
conda activate fr3
cd /home/carl/deoxys_controlCheck Redis and camera stream freshness:
deoxys.data preflight --task fr3_dual_realsenseStart managed Redis and both camera nodes:
deoxys.data up --task fr3_dual_realsenseInspect the task/date/run layout:
deoxys.data tasks
deoxys.data dates --task fr3_dual_realsense
deoxys.data runs --task fr3_dual_realsense --all-datesRun the named reset preset:
deoxys.data reset --task fr3_dual_realsense --preset home_nominalView one or both live Redis camera streams:
deoxys.data view --task fr3_dual_realsense --camera-role allRun plain teleoperation without recording a dataset:
deoxys.data teleop --task fr3_dual_realsense
deoxys.data teleop --task fr3_dual_realsense --no-reset
deoxys.data teleop --task fr3_dual_realsense --inverseCollect one teleoperation run:
deoxys.data collect --task fr3_dual_realsense
deoxys.data collect --task fr3_dual_realsense --no-reset
deoxys.data collect --task fr3_dual_realsense --inverseValidate a raw run before HDF5 build, and optionally replay it:
deoxys.data validate --task fr3_dual_realsense --date 2026-03-15 --run run1
deoxys.data validate --task fr3_dual_realsense --date 2026-03-15 --run run1 --playBuild demo.hdf5 from one task/date directory:
deoxys.data build --task fr3_dual_realsense --date 2026-03-14 --overwriteOr aggregate several collection dates for the same task:
deoxys.data build --task fr3_dual_realsense --all-dates --overwrite
deoxys.data build --task fr3_dual_realsense --dates 2026-03-17 2026-03-18 --overwriteReplay one stored raw run on the robot using its saved delta actions:
deoxys.data replay --task fr3_dual_realsense --date 2026-03-15 --run run1
deoxys.data replay --task fr3_dual_realsense --date 2026-03-15 --run run1 --no-resetExport quick-look MP4 files from a built HDF5 dataset:
deoxys.data video --hdf5 /home/carl/deoxys_control/data/fr3_dual_realsense/2026-03-15/demo.hdf5
python tools/data/export_hdf5_demo_video.py --hdf5 /home/carl/deoxys_control/data/fr3_dual_realsense/2026-03-15/demo.hdf5Add --include-depth if you want depth visualizations beside RGB. If depth is
requested but a demo or camera stream does not have depth, the exporter now
falls back to RGB for that stream and logs that depth was unavailable.
The new collector stores:
- RGB and optional depth for both fixed camera roles
agentviewandwrist - default validated camera resolution is now
640x480at30 Hzfor both streams - camera intrinsics and extrinsics metadata for downstream geometry-aware exports
- camera acquisition settings such as exposure, gain, white balance, and depth emitter settings when available
- one canonical delta-action stream saved as
testing_demo_delta_action.npzin raw runs anddelta_actionsin HDF5 - 10D end-effector state features stored as xyz position plus 6D rotation plus gripper width
- per-camera validity masks so optional-camera placeholders and missing depth stay explicit
- per-camera calibration JSON so RGB-D geometry stays recoverable later without keeping large debug-side metadata archives
Current validated rates for the default task:
- robot state publisher:
100 Hz - policy / teleoperation command loop:
20 Hz - trajectory interpolation on the robot side:
500 Hz - camera capture and publish:
30 Hzper camera - the saved dataset therefore has a nominal action/state rate of about
20 Hz, bounded by the policy loop rather than the camera frame rate
Units and conventions are documented in code comments, run manifests, and HDF5 dataset attributes wherever practical.
The pipeline now stores ee_state_10d as the main learning-facing pose-plus-gripper feature, and it does not store Euler roll/pitch/yaw orientation state features. The raw-run format is intentionally lean now: it keeps the tensors needed for RGB-D imitation learning plus calibration/validity metadata, and drops older debug-heavy arrays like observed deltas, tracking errors, sync archives, and large robot-metadata dumps from newly collected runs.
Collection behavior notes:
- The collector now keeps the imitation-learning pairing contract
obs_t -> delta_action_t -> control_t, so observations are recorded before the current command is sent. - The saved
delta_actionsdataset is the single canonical delta-action stream used for HDF5 export and raw-run replay. - For the default OSC controllers,
delta_actionsstores the controller-space end-effector delta command sent to Franka/Deoxys after SpaceMouse mapping. It is not the raw SpaceMouse HID delta. - The same task config now drives both plain
teleopand datasetcollect, so controller, interface, and SpaceMouse settings stay aligned. - If the task config defines
default_reset_preset,teleop,collect, andreplayall run that preset first so they start from the same joint configuration, unless you pass--no-reset. - Before plain teleop or collection becomes active, the pipeline explicitly opens the gripper and verifies it reached a near-fully-open width. If that cannot be confirmed, startup fails cleanly instead of beginning with a closed hand.
- Near-zero robot state reads can fall back to the previous valid state when
collection.state_zero_fallback: true. - Manual
Ctrl+Cduring collection discards the run and removes the partialrunNdirectory instead of saving partial files or metadata. - The SpaceMouse right button finishes the current collection run and saves it if valid samples were recorded.
- The collector now emits a short terminal bell when it switches into active recording after the first valid motion, and a two-beep confirmation when the SpaceMouse right button is accepted as
finish and save. - When a run is discarded or cleaned up after failure, the CLI reports
run_dir: nullso it does not point at a deleted directory. - Collection failures now return a structured
failure_reasonin CLI output. - Failed runs are deleted by default with
collection.keep_failed_runs: false. This setting applies to genuine collection failures, not user-canceled runs. User-canceled runs are always discarded and removed. - Optional cameras can be declared with
collection.optional_camera_roles; the collector inserts aligned placeholders and writes a validity mask instead of shrinking the run. - Depth-enabled cameras also write a separate depth-validity mask, so zero-filled placeholder depth images are distinguishable from real depth frames.
- Use
--inverseondeoxys.data teleopordeoxys.data collectfor a temporary arm-motion inversion without editing the task YAML. Gripper semantics stay normal. - Use
collection.action_multipliersin the task YAML when you want a persistent custom inversion.
The deoxys.data commands are the canonical teleoperation/data-collection
workflow. Older example scripts under deoxys/examples/ are still available as
references, but they keep their own save prompts and should not be treated as
the authoritative data-pipeline interface.
Action semantics are documented in one place in docs/teleop_data_pipeline.md, including the 7D action layout, gripper sign convention, controller frame, controller-side scaling, and the distinction between 6D orientation state features and the controller-native 3D rotational command channels.
