1. Why SpaceMouse for Teleoperation?
The 3Dconnexion SpaceMouse is a 6-DOF input device that translates hand motion into simultaneous translation (X, Y, Z) and rotation (roll, pitch, yaw) commands. For robot teleoperation, it offers a unique combination of advantages:
- 6-DOF in one hand: A single SpaceMouse controls all six degrees of freedom of a robot end-effector simultaneously. No mode switching, no button combinations. This makes it the most intuitive single-device teleoperation interface for most operators.
- Low cost of entry: The SpaceMouse Compact ($129) provides the same 6-DOF input as systems costing 10-100x more. Compare to: leader-follower arms ($2,000-5,000), VR headsets ($500+ plus controller), haptic devices ($3,000+).
- Widely used in research: SpaceMouse teleoperation is used in the robomimic, MimicGen, and robosuite codebases, and is the default teleoperation method for the DROID dataset (500K+ episodes). If you are collecting data for VLA fine-tuning, SpaceMouse data is the most compatible with existing pre-training datasets.
- No calibration drift: Unlike VR controllers that require room-scale tracking, a SpaceMouse is a USB device that returns to center when released. No IMU drift, no tracking loss, no recalibration between sessions.
- Low operator fatigue: The device sits on a desk. The operator's hand rests naturally on the knob. Compared to holding a VR controller at arm height or physically moving a leader arm, SpaceMouse teleoperation is significantly less fatiguing for long data collection sessions.
Tradeoffs: SpaceMouse provides no force feedback (the operator cannot feel what the robot touches) and lacks the positional intuitiveness of leader-follower arms (where the leader arm mirrors the robot's pose). For tasks requiring fine force control (insertion, polishing) or complex bimanual coordination, leader-follower arms produce higher-quality demonstrations. For general pick-and-place, object rearrangement, and most tabletop manipulation tasks, SpaceMouse is the best cost-quality tradeoff.
2. Hardware Setup
SpaceMouse Models
| Model | Price | DOF | Buttons | Connection | Recommendation |
|---|---|---|---|---|---|
| SpaceMouse Compact | $129 | 6 | 2 | USB | Best value. Use left button for gripper toggle, right for episode save. |
| SpaceMouse Pro | $299 | 6 | 15 | USB | Extra buttons useful for multi-function teleop (speed presets, mode switching). |
| SpaceMouse Pro Wireless | $399 | 6 | 15 | USB/BT | Wireless adds 2-5ms latency. USB mode recommended for data collection. |
| SpaceMouse Enterprise | $529 | 6 | 31 | USB | Overkill for teleoperation. The extra buttons go unused. |
Our recommendation: SpaceMouse Compact ($129) for single-arm teleoperation. Two SpaceMouse Compacts ($258 total) for bimanual setups. The Pro adds comfort for 4+ hour sessions but is not worth 2x the price for most teams. SVRC uses SpaceMouse Compact units across all collection stations.
Physical Setup
- Place the SpaceMouse on a stable surface at desk height, directly in front of the operator
- Position the robot arm visible to the operator (direct line of sight preferred over camera-only view)
- Connect via USB. Avoid USB hubs — connect directly to the workstation motherboard USB ports for lowest latency
- Verify the device appears as
/dev/hidraw*on Linux:ls /dev/hidraw*should show one or more devices
3. ROS2 Driver Installation
The pyspacemouse library provides a pure-Python interface to all 3Dconnexion devices. We wrap it in a ROS2 node for integration with robot control stacks.
Step 1: Install pyspacemouse
# Install the library and its hidapi dependency
pip install pyspacemouse hidapi
# On Ubuntu, you also need the udev rules for non-root access
sudo tee /etc/udev/rules.d/99-spacemouse.rules <<'EOF'
SUBSYSTEM=="usb", ATTR{idVendor}=="256f", MODE="0666"
SUBSYSTEM=="hidraw", ATTRS{idVendor}=="256f", MODE="0666"
EOF
sudo udevadm control --reload-rules && sudo udevadm trigger
# Verify the device is detected
python3 -c "import pyspacemouse; print(pyspacemouse.list_devices())"
Step 2: Create the ROS2 Teleoperation Node
#!/usr/bin/env python3
"""spacemouse_teleop_node.py - ROS2 node for SpaceMouse teleoperation."""
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
import pyspacemouse
import numpy as np
class SpaceMouseTeleop(Node):
def __init__(self):
super().__init__('spacemouse_teleop')
# Parameters (tune these per-robot)
self.declare_parameter('linear_scale', 0.15) # m/s per unit
self.declare_parameter('angular_scale', 0.3) # rad/s per unit
self.declare_parameter('dead_zone', 0.08) # ignore below this
self.declare_parameter('publish_rate', 50.0) # Hz
self.linear_scale = self.get_parameter('linear_scale').value
self.angular_scale = self.get_parameter('angular_scale').value
self.dead_zone = self.get_parameter('dead_zone').value
rate = self.get_parameter('publish_rate').value
# Publisher
self.pub = self.create_publisher(Twist, 'spacemouse/twist', 10)
self.timer = self.create_timer(1.0 / rate, self.timer_callback)
# Open device
success = pyspacemouse.open()
if not success:
self.get_logger().error('Failed to open SpaceMouse device')
raise RuntimeError('SpaceMouse not found')
self.get_logger().info('SpaceMouse connected successfully')
def apply_dead_zone(self, value):
"""Apply dead zone and normalize."""
if abs(value) < self.dead_zone:
return 0.0
sign = 1.0 if value > 0 else -1.0
return sign * (abs(value) - self.dead_zone) / (1.0 - self.dead_zone)
def timer_callback(self):
state = pyspacemouse.read()
msg = Twist()
# SpaceMouse axes -> robot EEF frame
# NOTE: axis mapping depends on your robot's base frame convention.
# These defaults work for OpenArm 101 and ViperX with Z-up, X-forward.
msg.linear.x = self.apply_dead_zone(state.y) * self.linear_scale
msg.linear.y = self.apply_dead_zone(state.x) * -self.linear_scale
msg.linear.z = self.apply_dead_zone(state.z) * self.linear_scale
msg.angular.x = self.apply_dead_zone(state.roll) * self.angular_scale
msg.angular.y = self.apply_dead_zone(state.pitch) * self.angular_scale
msg.angular.z = self.apply_dead_zone(state.yaw) * self.angular_scale
self.pub.publish(msg)
def main():
rclpy.init()
node = SpaceMouseTeleop()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Step 3: Launch
# Terminal 1: Start the SpaceMouse node
ros2 run your_package spacemouse_teleop_node \
--ros-args -p linear_scale:=0.15 -p angular_scale:=0.3 -p dead_zone:=0.08
# Terminal 2: Verify output
ros2 topic echo /spacemouse/twist
4. Axis Mapping and Configuration
The SpaceMouse outputs six axis values in its own coordinate frame. Your robot uses a different frame. The mapping between them depends on how your robot defines its base coordinate system.
Common Axis Mappings
| SpaceMouse Axis | OpenArm 101 | ViperX-300 / ALOHA | Franka Research 3 |
|---|---|---|---|
| X (push/pull) | +Y (forward) | +X (forward) | +X (forward) |
| Y (left/right) | -X (right) | -Y (right) | +Y (left) |
| Z (up/down) | +Z (up) | +Z (up) | +Z (up) |
| Roll (tilt left/right) | +Roll | +Roll | +Roll |
| Pitch (tilt fwd/back) | +Pitch | +Pitch | -Pitch |
| Yaw (twist) | +Yaw | +Yaw | +Yaw |
How to determine your mapping: Move the SpaceMouse knob in each direction one at a time while watching the robot. If the robot moves in the wrong direction, negate that axis. If it moves on the wrong axis, swap axes. The process takes 5-10 minutes and only needs to be done once per robot configuration.
5. Dead-Zone Tuning and Sensitivity
The SpaceMouse is highly sensitive. Without dead-zone filtering, the robot will drift when the operator's hand rests on the knob. Dead zones are the most important calibration parameter for teleoperation data quality.
# spacemouse_config.yaml - Per-axis configuration
spacemouse_teleop:
ros__parameters:
# Dead zone: ignore input below this threshold (0.0-1.0)
# Higher = less drift, but less responsive to small movements
dead_zone_translation: 0.08 # Good default for most operators
dead_zone_rotation: 0.12 # Rotation is more sensitive; higher DZ needed
# Scaling: how fast the robot moves per unit of SpaceMouse input
# Start conservative (0.1), increase as operator gains confidence
linear_scale_x: 0.15 # m/s - forward/backward
linear_scale_y: 0.15 # m/s - left/right
linear_scale_z: 0.10 # m/s - up/down (slower to prevent table crashes)
angular_scale_roll: 0.25 # rad/s
angular_scale_pitch: 0.25 # rad/s
angular_scale_yaw: 0.30 # rad/s - wrist yaw is the most-used rotation
# Smoothing: exponential moving average (0.0 = no smoothing, 0.95 = very smooth)
# Smoothing reduces jitter but adds latency. 0.3-0.5 is a good range.
smoothing_factor: 0.4
Tuning procedure:
- Set dead zone to 0.15 (conservative). Release the knob. If the robot still drifts, increase dead zone. If not, decrease by 0.02 increments until you find the minimum value that prevents drift.
- Set linear_scale to 0.10. Try to move the robot 10cm. If it takes more than 1 second, increase. If the robot moves too fast to control, decrease. Target: 0.5-1.0 seconds for a 10cm movement.
- Set angular_scale to 0.20. Try to rotate the end-effector 45 degrees. Same tuning logic as linear scale.
- Set smoothing to 0.4. If motions feel jerky, increase. If they feel laggy, decrease.
6. Integration with OpenArm 101
The OpenArm 101 uses Damiao actuators with a CAN-bus interface. The SpaceMouse twist commands are converted to end-effector velocity targets, which an inverse kinematics (IK) solver converts to joint velocity commands.
# openarm_spacemouse_teleop.py - Tested configuration for OpenArm 101
# Requires: openarm_sdk, pyspacemouse, numpy
import numpy as np
from openarm_sdk import OpenArm
from openarm_sdk.ik import DampedLeastSquaresIK
import pyspacemouse
# OpenArm-specific settings (tested at SVRC Mountain View lab)
OPENARM_CONFIG = {
'axis_map': {
'x': ('y', 1.0), # SpaceMouse Y -> OpenArm +X (forward)
'y': ('x', -1.0), # SpaceMouse X -> OpenArm -Y (right)
'z': ('z', 1.0), # SpaceMouse Z -> OpenArm +Z (up)
'roll': ('roll', 1.0),
'pitch': ('pitch', 1.0),
'yaw': ('yaw', 1.0),
},
'linear_scale': 0.12, # m/s - OpenArm is precise; keep speed moderate
'angular_scale': 0.25, # rad/s
'dead_zone': 0.08,
'ik_damping': 0.05, # Damped least-squares regularization
'control_rate': 50, # Hz - matches OpenArm servo rate
}
arm = OpenArm(port='/dev/ttyUSB0')
ik = DampedLeastSquaresIK(arm.urdf_path, damping=OPENARM_CONFIG['ik_damping'])
pyspacemouse.open()
print("SpaceMouse teleop active. Left button = toggle gripper. Right button = e-stop.")
try:
while True:
state = pyspacemouse.read()
# Apply dead zone and scaling
twist = np.zeros(6)
for i, axis in enumerate(['x', 'y', 'z', 'roll', 'pitch', 'yaw']):
raw = getattr(state, OPENARM_CONFIG['axis_map'][axis][0])
raw *= OPENARM_CONFIG['axis_map'][axis][1]
if abs(raw) < OPENARM_CONFIG['dead_zone']:
raw = 0.0
scale = OPENARM_CONFIG['linear_scale'] if i < 3 else OPENARM_CONFIG['angular_scale']
twist[i] = raw * scale
# IK solve: twist -> joint velocities
current_joints = arm.get_joint_positions()
joint_velocities = ik.solve(current_joints, twist)
arm.set_joint_velocities(joint_velocities)
# Button handling
if state.buttons[0]: # Left button -> toggle gripper
arm.toggle_gripper()
if state.buttons[1]: # Right button -> emergency stop
arm.stop()
break
except KeyboardInterrupt:
arm.stop()
7. Integration with ViperX / ALOHA Setup
For ViperX-300 and ALOHA systems, the SpaceMouse integrates through the Interbotix SDK or the ALOHA teleoperation stack. The ALOHA codebase already includes SpaceMouse support as an alternative to leader-follower teleoperation:
# Using the ALOHA codebase with SpaceMouse
cd ~/aloha
python3 scripts/teleop_spacemouse.py \
--robot_config configs/viperx300s.yaml \
--spacemouse_config configs/spacemouse_compact.yaml \
--linear_scale 0.15 \
--angular_scale 0.30 \
--dead_zone 0.08
# For bimanual ALOHA with two SpaceMouse devices:
python3 scripts/teleop_spacemouse_bimanual.py \
--left_device_id 0 \
--right_device_id 1
When using two SpaceMouse devices for bimanual teleoperation, label them physically (tape, stickers) and assign consistent device IDs. Device ID assignment can change between USB reconnections — use the serial number for stable identification:
# List connected SpaceMouse devices with serial numbers
python3 -c "
import pyspacemouse
devices = pyspacemouse.list_devices()
for d in devices:
print(f'Name: {d.name}, Serial: {d.serial}, ID: {d.id}')
"
8. Recording Demonstrations to HDF5
The recording loop captures synchronized camera frames, joint states, actions, and language annotations into HDF5 files — the standard format for robot learning datasets.
#!/usr/bin/env python3
"""record_episode.py - Record a teleoperation episode to HDF5."""
import h5py
import numpy as np
import time
from datetime import datetime
class EpisodeRecorder:
def __init__(self, arm, cameras, save_dir='./episodes'):
self.arm = arm
self.cameras = cameras # dict of {name: camera_object}
self.save_dir = save_dir
self.recording = False
self.episode_data = None
def start_episode(self, task_description=""):
"""Begin recording a new episode."""
self.recording = True
self.episode_data = {
'joint_positions': [],
'joint_velocities': [],
'eef_pos': [],
'eef_quat': [],
'gripper_state': [],
'actions': [], # The twist commands sent to the robot
'timestamps': [],
'task_description': task_description,
}
# Add camera frame lists
for cam_name in self.cameras:
self.episode_data[f'camera_{cam_name}'] = []
print(f"Recording started: '{task_description}'")
def record_step(self, action_twist):
"""Record one timestep of data."""
if not self.recording:
return
t = time.time()
self.episode_data['joint_positions'].append(self.arm.get_joint_positions())
self.episode_data['joint_velocities'].append(self.arm.get_joint_velocities())
self.episode_data['eef_pos'].append(self.arm.get_eef_position())
self.episode_data['eef_quat'].append(self.arm.get_eef_quaternion())
self.episode_data['gripper_state'].append(self.arm.get_gripper_state())
self.episode_data['actions'].append(action_twist)
self.episode_data['timestamps'].append(t)
for cam_name, cam in self.cameras.items():
self.episode_data[f'camera_{cam_name}'].append(cam.get_frame())
def save_episode(self):
"""Save the recorded episode to HDF5."""
if not self.recording:
return None
self.recording = False
n_steps = len(self.episode_data['timestamps'])
if n_steps < 10:
print(f"Episode too short ({n_steps} steps). Discarding.")
return None
timestamp = datetime.now().strftime('%Y%m%d_%H%M%S')
filepath = f"{self.save_dir}/episode_{timestamp}.hdf5"
with h5py.File(filepath, 'w') as f:
# Metadata
f.attrs['task_description'] = self.episode_data['task_description']
f.attrs['n_steps'] = n_steps
f.attrs['timestamp'] = timestamp
f.attrs['control_freq_hz'] = 50
# State data
f.create_dataset('joint_positions',
data=np.array(self.episode_data['joint_positions'], dtype=np.float32))
f.create_dataset('joint_velocities',
data=np.array(self.episode_data['joint_velocities'], dtype=np.float32))
f.create_dataset('eef_pos',
data=np.array(self.episode_data['eef_pos'], dtype=np.float32))
f.create_dataset('eef_quat',
data=np.array(self.episode_data['eef_quat'], dtype=np.float32))
f.create_dataset('gripper_state',
data=np.array(self.episode_data['gripper_state'], dtype=np.float32))
f.create_dataset('actions',
data=np.array(self.episode_data['actions'], dtype=np.float32))
f.create_dataset('timestamps',
data=np.array(self.episode_data['timestamps'], dtype=np.float64))
# Camera data (compressed)
for cam_name in self.cameras:
frames = np.array(self.episode_data[f'camera_{cam_name}'],
dtype=np.uint8)
f.create_dataset(f'camera_{cam_name}', data=frames,
compression='gzip', compression_opts=4)
print(f"Saved episode: {filepath} ({n_steps} steps, "
f"{n_steps/50:.1f}s)")
return filepath
9. Data Quality Tips
High-quality SpaceMouse demonstrations produce smoother policies that generalize better. Key practices:
- Warm up for 5 minutes before recording. The first few demonstrations of a session are always worse than later ones. Discard them.
- Move slowly and smoothly. Jerky motions create noisy action labels. If you need to make a fast movement, release the knob first (zero velocity), then re-engage smoothly. Target 15-30 second episodes for pick-and-place tasks.
- Vary initial conditions. Between episodes, randomize object position (within the workspace), object orientation, and robot starting configuration. This variation is more important than episode count for generalization.
- Reset consistently. Use a scripted reset that returns the robot to a fixed starting pose between episodes. Inconsistent resets introduce noise in the initial state distribution.
- Annotate immediately. Write the task description before or during recording, not after. Post-hoc annotation is error-prone and slows down the collection workflow.
- Session length: Limit collection sessions to 2 hours without a break. After 2 hours, operator fatigue measurably degrades demonstration quality (action jerk increases 20-40% based on SVRC internal benchmarks).
10. Converting to RLDS / LeRobot Format
After recording HDF5 episodes, convert them to RLDS or LeRobot format for VLA training:
# Convert HDF5 episodes to LeRobot format (for SmolVLA, ACT training)
# Requires: pip install lerobot
from lerobot.common.datasets.push_dataset_to_hub import hdf5_to_lerobot
hdf5_to_lerobot(
raw_dir="./episodes/", # Directory of HDF5 files
repo_id="your-org/your-dataset", # Hugging Face Hub repo
fps=50,
video=True, # Encode camera frames as mp4
push_to_hub=True, # Upload to Hugging Face Hub
)
# Convert HDF5 to RLDS format (for OpenVLA fine-tuning)
# Requires: pip install tensorflow-datasets
python3 -m rlds_tools.hdf5_to_rlds \
--input_dir ./episodes/ \
--output_dir ./rlds_dataset/ \
--dataset_name my_spacemouse_data \
--action_key actions \
--state_key joint_positions
11. Common Issues and Fixes
SpaceMouse drift (robot moves when knob is released)
Cause: Dead zone too small, or the device has a slight mechanical bias. Fix: Increase dead_zone to 0.10-0.15. If drift persists, recalibrate the device: unplug, place on a flat surface, plug back in. The device auto-calibrates its center position on power-up.
Axis inversion (robot moves opposite direction)
Cause: Axis sign mismatch between SpaceMouse frame and robot frame. Fix: Negate the offending axis in your config. Move each axis one at a time and verify direction.
USB disconnect during recording
Cause: Loose USB connection, USB hub power management, or OS suspending the device. Fix:
# Disable USB autosuspend for 3Dconnexion devices
echo -1 | sudo tee /sys/bus/usb/devices/*/power/autosuspend_delay_ms
# Or permanently in /etc/udev/rules.d/99-spacemouse.rules:
ACTION=="add", SUBSYSTEM=="usb", ATTR{idVendor}=="256f", \
TEST=="power/autosuspend_delay_ms", \
ATTR{power/autosuspend_delay_ms}="-1"
High action jerk in recordings
Cause: Smoothing factor too low, or operator inexperience. Fix: Increase smoothing_factor to 0.5-0.6. Ensure operator has completed at least 30 minutes of practice before recording production data.
Two SpaceMouse devices getting swapped
Cause: USB device enumeration order is not deterministic. Fix: Use serial numbers for device identification (see code in Section 7). Create a udev rule that assigns consistent symlinks based on serial number.