Robot Interface

class aiofranka.robot.RobotInterface(ip=None)[source]

Bases: object

High-level interface for Franka FR3 robot control.

This class provides a unified interface for both real robot control (via pylibfranka) and simulation (via MuJoCo). It handles low-level communication, state synchronization, and kinematics/dynamics computation.

real

True if connected to real robot, False for simulation

Type:

bool

model

MuJoCo model for kinematics/dynamics

Type:

mujoco.MjModel

data

MuJoCo data structure with current state

Type:

mujoco.MjData

robot

Real robot interface (if real=True)

Type:

pylibfranka.Robot

torque_controller

Active torque control interface

site_name

Name of end-effector site in MuJoCo model

Type:

str

site_id

MuJoCo site ID for end-effector

Type:

int

viewer

MuJoCo viewer window (if real=False)

Type:

mujoco.viewer

Examples

Real robot:
>>> robot = RobotInterface("172.16.0.2")
>>> robot.start()
>>> state = robot.state
>>> robot.step(np.zeros(7))  # Send zero torques
>>> robot.stop()
Simulation:
>>> robot = RobotInterface(None)
>>> state = robot.state
>>> robot.step(np.zeros(7))  # Updates MuJoCo simulation
Caveats:
  • Must call start() before step() on real robot

  • Collision behavior is set to high thresholds by default

  • State is synced from robot on every access (thread-safe)

  • MuJoCo model must match real robot configuration

__init__(ip=None)[source]

Initialize robot interface.

Parameters:

ip (str | None) – Robot IP address (e.g., “172.16.0.2”) for real robot, or None for simulation mode.

Raises:

Note

In real mode, collision thresholds are set to [100.0] * 7 for joints and [100.0] * 6 for Cartesian space. Adjust via robot.robot.set_collision_behavior() for more conservative behavior.

start()[source]

Start torque control mode on the real robot.

This must be called before sending torque commands. Does nothing in simulation.

Raises:

RuntimeError – If robot is not ready or already in control mode

Caveat:

After calling start(), you must send torque commands at ~1kHz to maintain control. Use FrankaController for automatic control loop management.

stop()[source]

Stop torque control mode on the real robot.

This gracefully terminates the control session. Does nothing in simulation.

Caveat:

Robot will hold position briefly then release brakes. Ensure robot is in a safe configuration before stopping.

sync_mj()[source]

Sync mujoco state with real robot state

property state

Get current robot state with kinematics and dynamics.

Returns:

Dictionary containing:
  • qpos (np.ndarray): Joint positions [rad] (7,)

  • qvel (np.ndarray): Joint velocities [rad/s] (7,)

  • ee (np.ndarray): End-effector pose as 4x4 homogeneous transform

    [[R, p], [0, 1]] where R is rotation, p is position

  • jac (np.ndarray): End-effector Jacobian (6, 7) - [linear; angular]

  • mm (np.ndarray): Joint-space mass matrix (7, 7)

  • last_torque (np.ndarray): Last commanded torques [Nm] (7,)

Return type:

dict

Note

State is synchronized from real robot on every access. MuJoCo model is updated with latest robot state before computing kinematics/dynamics.

Example

>>> state = robot.state
>>> print(f"Joint 1 position: {state['qpos'][0]:.3f} rad")
>>> print(f"EE position: {state['ee'][:3, 3]}")
>>> print(f"EE orientation: {state['ee'][:3, :3]}")
step(torque)[source]

Send torque command to robot or step simulation.

Parameters:

torque (np.ndarray) – Joint torques [Nm] (7,)

Raises:

RuntimeError – If real robot not started or communication error

Note

  • Real robot: Sends torque command via pylibfranka at current timestep

  • Simulation: Updates MuJoCo with torques and advances one timestep

Caveats:
  • Must be called at ~1kHz for real robot to maintain control

  • Large torque changes may trigger safety limits

  • Torques should respect robot limits: |tau_i| < 87 Nm for joints 1-4, |tau_i| < 12 Nm for joints 5-7

Example

>>> # Send gravity compensation torques
>>> torque = robot.state['mm'] @ np.array([0, 0, 0, 0, 0, 0, -9.81])
>>> robot.step(torque)