FrankaRemoteController (Server Mode)

Synchronous remote controller client for aiofranka.

Communicates with the aiofranka server process via shared memory (state reads) and ZMQ (commands). Drop-in replacement for FrankaController with a sync API.

class aiofranka.remote.FrankaRemoteController(robot_ip=None, *, home=True)[source]

Bases: object

Synchronous remote controller for Franka robots.

Connects to a running aiofranka server process and provides the same API as FrankaController, but fully synchronous (no async/await needed).

The 1kHz control loop runs in the server process. This client sends commands via ZMQ and reads state from shared memory (zero-copy).

Examples

>>> controller = FrankaRemoteController()  # default IP
>>> controller.start()
>>> controller.switch("impedance")
>>> controller.set_freq(50)
>>> for i in range(100):
...     state = controller.state
...     controller.set("q_desired", target)
>>> controller.stop()
Parameters:
__init__(robot_ip=None, *, home=True)[source]
Parameters:
start()[source]

Start the server subprocess and connect.

Spawns a 1kHz control loop in a child process, then connects to it via shared memory and ZMQ. The subprocess terminates automatically when this script exits.

The robot must already be unlocked with FCI active. If not, prints a status summary and raises RuntimeError.

Raises:

RuntimeError – If the robot is not ready or the server fails to start.

stop()[source]

Stop the server subprocess and disconnect.

property state: dict

Read current robot state from shared memory (zero-copy, no IPC overhead).

property q_desired: ndarray

Current desired joint positions (7,) from shared memory.

property ee_desired: ndarray

Current desired end-effector pose (4,4) from shared memory.

property torque: ndarray

Current commanded torque (7,) from shared memory.

property initial_qpos: ndarray

Initial joint positions (7,) set at last switch() from shared memory.

property initial_ee: ndarray

Initial end-effector pose (4,4) set at last switch() from shared memory.

property running: bool
switch(controller_type)[source]

Switch control mode on the server (“impedance”, “pid”, “osc”, “torque”).

Parameters:

controller_type (str)

set_freq(freq)[source]

Set update frequency for rate-limited set() calls (Hz).

Parameters:

freq (float)

set(attr, value)[source]

Rate-limited setter for controller attributes.

Sends value to server and sleeps to maintain frequency from set_freq().

Parameters:
  • attr (str) – “q_desired”, “ee_desired”, or “torque”

  • value – numpy array

move(qpos=None)[source]

Move to target joint position. Blocks until complete.

Parameters:

qpos – Target joint positions (7,). Default: home position.

initialize()[source]

Re-initialize controller state to current robot position.