Skip to content

SpaceMouse API¤

このページでは、SpaceMouse による SO-101 制御に関連する API を説明します。

概要¤

SpaceMouse 統合は以下のコンポーネントで構成されます:

  • SpaceMouseReader: pyspacemouse のスレッドベースラッパー。デバイスをバックグラウンドでポーリングし、最新の 6-DOF 状態を提供
  • SpaceMouseConfig: 速度スケーリング、デッドゾーン等の設定
  • So101SpaceMouseController: SpaceMouse → EE デルタ → IK → Follower の制御パイプライン
  • So101SpaceMouseExpHandler: データ収集用の対話的ハンドラ
graph TD
    A[SpaceMouseReader] -->|SpaceMouseState| B[So101SpaceMouseController]
    C[SpaceMouseConfig] --> B
    D[So101Robot] --> B
    B -->|So101Obs| E[So101SpaceMouseExpHandler]
    E -->|HDF5/GIF| F[So101SaveWorker]

入力デバイス¤

SpaceMouseState¤

SpaceMouseState dataclass ¤

SpaceMouseState(x: float = 0.0, y: float = 0.0, z: float = 0.0, roll: float = 0.0, pitch: float = 0.0, yaw: float = 0.0, buttons: list[bool] = (lambda: [False, False])(), timestamp: float = 0.0)

Snapshot of the SpaceMouse 6-DOF axes and button states.

All axis values are normalised to [-1.0, 1.0].

SpaceMouseReader¤

SpaceMouseReader ¤

SpaceMouseReader()

Thread-based wrapper around pyspacemouse.

A background daemon thread polls pyspacemouse.read() at high frequency and stores the latest state behind a lock so that callers can retrieve it without blocking.

Usage::

reader = SpaceMouseReader()
reader.start()
state = reader.get_state()
reader.stop()
METHOD DESCRIPTION
start

Open the SpaceMouse device and start the polling thread.

stop

Stop the polling thread and close the device.

get_state

Return the latest SpaceMouse state (non-blocking).

ATTRIBUTE DESCRIPTION
is_running

TYPE: bool

Source code in src/robopy/input/spacemouse.py
def __init__(self) -> None:
    self._state = SpaceMouseState()
    self._lock = threading.Lock()
    self._stop_event = threading.Event()
    self._thread: threading.Thread | None = None
    self._is_running = False
    self._device = None

is_running property ¤

is_running: bool

start ¤

start() -> None

Open the SpaceMouse device and start the polling thread.

Source code in src/robopy/input/spacemouse.py
def start(self) -> None:
    """Open the SpaceMouse device and start the polling thread."""
    if self._is_running:
        logger.warning("SpaceMouseReader is already running.")
        return

    try:
        import pyspacemouse
    except ImportError as exc:
        raise ImportError(
            "pyspacemouse is required for SpaceMouse support. "
            "Install it with: pip install pyspacemouse"
        ) from exc

    try:
        self._device = pyspacemouse.open()
    except Exception as exc:
        raise RuntimeError(
            "Failed to open SpaceMouse device. "
            "Check that the device is connected and permissions are set."
        ) from exc

    self._stop_event.clear()
    self._thread = threading.Thread(target=self._poll_loop, daemon=True)
    self._thread.start()
    self._is_running = True
    logger.info("SpaceMouseReader started.")

stop ¤

stop() -> None

Stop the polling thread and close the device.

Source code in src/robopy/input/spacemouse.py
def stop(self) -> None:
    """Stop the polling thread and close the device."""
    if not self._is_running:
        return

    self._stop_event.set()
    if self._thread is not None:
        self._thread.join(timeout=2.0)
        self._thread = None

    if self._device is not None:
        try:
            self._device.close()
        except Exception:
            pass
        self._device = None

    self._is_running = False
    logger.info("SpaceMouseReader stopped.")

get_state ¤

get_state() -> SpaceMouseState

Return the latest SpaceMouse state (non-blocking).

Source code in src/robopy/input/spacemouse.py
def get_state(self) -> SpaceMouseState:
    """Return the latest SpaceMouse state (non-blocking)."""
    with self._lock:
        return SpaceMouseState(
            x=self._state.x,
            y=self._state.y,
            z=self._state.z,
            roll=self._state.roll,
            pitch=self._state.pitch,
            yaw=self._state.yaw,
            buttons=list(self._state.buttons),
            timestamp=self._state.timestamp,
        )

設定¤

SpaceMouseConfig¤

SpaceMouseConfig dataclass ¤

SpaceMouseConfig(linear_speed: float = 0.1, angular_speed: float = 0.5, gripper_speed: float = 50.0, deadzone: float = 0.05, control_hz: int = 50, input_smoothing: float = 0.5, max_joint_delta_deg: float = 5.0)

Configuration for SpaceMouse input device.

ATTRIBUTE DESCRIPTION
linear_speed

Maximum linear velocity in m/s when the SpaceMouse axis is at full deflection (1.0).

TYPE: float

angular_speed

Maximum angular velocity in rad/s when the SpaceMouse axis is at full deflection (1.0).

TYPE: float

gripper_speed

Gripper movement speed in degrees/s per button press.

TYPE: float

deadzone

Axes with absolute values below this threshold are zeroed.

TYPE: float

control_hz

Control loop frequency in Hz.

TYPE: int

input_smoothing

Exponential moving average factor for SpaceMouse axes. 0.0 = no smoothing (raw input), 1.0 = maximum smoothing. Higher values reduce jitter but add latency.

TYPE: float

max_joint_delta_deg

Maximum allowed joint angle change per control step in degrees. Prevents vibration from large IK solution jumps.

TYPE: float

コントローラー¤

So101SpaceMouseController¤

So101SpaceMouseController ¤

So101SpaceMouseController(robot: So101Robot, spacemouse_config: SpaceMouseConfig | None = None)

Control an SO-101 follower arm via a 3Dconnexion SpaceMouse.

The SpaceMouse 6-DOF input (x, y, z, roll, pitch, yaw — all normalised to [-1, 1]) is mapped to incremental end-effector velocity commands. At each control step the current EE pose is updated by the velocity delta, then Inverse Kinematics converts the target pose to joint angles that are sent to the follower arm.

The controller operates without a physical leader arm — the SpaceMouse replaces it. Gripper open/close is driven by the left/right buttons.

PARAMETER DESCRIPTION
robot

A configured :class:So101Robot instance. Only the follower arm is used; a leader arm is not required.

TYPE: So101Robot

spacemouse_config

Optional tuning parameters. Defaults are reasonable for desktop-scale manipulation.

TYPE: SpaceMouseConfig | None DEFAULT: None

METHOD DESCRIPTION
connect

Connect the robot and start the SpaceMouse reader.

disconnect

Stop the SpaceMouse reader and disconnect the robot.

teleoperation

Run real-time SpaceMouse → EE-space teleoperation.

record_parallel

Record a SpaceMouse-driven trajectory with camera observations.

ATTRIBUTE DESCRIPTION
robot

TYPE: So101Robot

is_connected

TYPE: bool

Source code in src/robopy/robots/so101/so101_spacemouse.py
def __init__(
    self,
    robot: So101Robot,
    spacemouse_config: SpaceMouseConfig | None = None,
) -> None:
    self._robot = robot
    self._sm_config = spacemouse_config or SpaceMouseConfig()
    self._reader = SpaceMouseReader()

    # Custom IK config for smoother wrist control
    # Increase orientation weight for better convergence
    self._ik_config = IKConfig(
        max_iterations=100,
        position_tolerance=1e-4,
        orientation_tolerance=5e-3,  # Relaxed from 1e-3
        damping=0.05,
        step_scale=0.5,
        position_weight=1.0,
        orientation_weight=0.5,  # Increased from 0.1
    )

    # EMA-filtered SpaceMouse axes: [x, y, z, pitch, roll]
    self._filtered_axes = np.zeros(5, dtype=np.float64)
    self._filter_initialized = False

robot property ¤

robot: So101Robot

is_connected property ¤

is_connected: bool

connect ¤

connect() -> None

Connect the robot and start the SpaceMouse reader.

Source code in src/robopy/robots/so101/so101_spacemouse.py
def connect(self) -> None:
    """Connect the robot and start the SpaceMouse reader."""
    if not self._robot.is_connected:
        self._robot.connect()
    self._reader.start()
    logger.info("So101SpaceMouseController connected.")

disconnect ¤

disconnect() -> None

Stop the SpaceMouse reader and disconnect the robot.

Source code in src/robopy/robots/so101/so101_spacemouse.py
def disconnect(self) -> None:
    """Stop the SpaceMouse reader and disconnect the robot."""
    self._reader.stop()
    self._robot.disconnect()
    logger.info("So101SpaceMouseController disconnected.")

teleoperation ¤

teleoperation(max_seconds: float | None = None) -> None

Run real-time SpaceMouse → EE-space teleoperation.

The control loop reads the SpaceMouse at control_hz, computes the incremental EE delta, runs IK and sends joint angles to the follower.

PARAMETER DESCRIPTION
max_seconds

If given, stop after this many seconds. Otherwise the loop runs until interrupted (KeyboardInterrupt).

TYPE: float | None DEFAULT: None

Source code in src/robopy/robots/so101/so101_spacemouse.py
def teleoperation(self, max_seconds: float | None = None) -> None:
    """Run real-time SpaceMouse → EE-space teleoperation.

    The control loop reads the SpaceMouse at *control_hz*, computes the
    incremental EE delta, runs IK and sends joint angles to the follower.

    Args:
        max_seconds: If given, stop after this many seconds.  Otherwise
            the loop runs until interrupted (``KeyboardInterrupt``).
    """
    if not self.is_connected:
        raise ConnectionError("Controller is not connected. Call connect() first.")

    cfg = self._sm_config
    dt = 1.0 / cfg.control_hz

    # Initialise current EE pose from the follower's actual position
    current_joints_deg = self._read_follower_joints()
    ee = So101Robot.forward_kinematics(current_joints_deg)
    target_ee = np.array([ee.x, ee.y, ee.z, ee.pitch, ee.roll], dtype=np.float64)
    gripper_deg = float(current_joints_deg[5]) if len(current_joints_deg) > 5 else 0.0
    current_joints_for_ik = current_joints_deg.copy()

    end_time = (time.perf_counter() + max_seconds) if max_seconds is not None else None

    self._reset_filter()
    logger.info("SpaceMouse teleoperation started. Press Ctrl+C to stop.")
    try:
        while True:
            loop_start = time.perf_counter()
            if end_time is not None and loop_start >= end_time:
                break

            target_ee, gripper_deg, current_joints_for_ik = self._control_step(
                target_ee, gripper_deg, current_joints_for_ik, dt
            )

            elapsed = time.perf_counter() - loop_start
            time.sleep(max(0.0, dt - elapsed))

    except KeyboardInterrupt:
        logger.info("SpaceMouse teleoperation stopped by user.")

record_parallel ¤

record_parallel(max_frame: int, fps: int = 20, control_hz: int | None = None, is_async: bool = True) -> So101Obs

Record a SpaceMouse-driven trajectory with camera observations.

Architecture mirrors :meth:So101Robot.record_parallel — a fast control thread drives the arm while the main thread captures camera frames at the requested fps.

The returned So101Obs.arms.leader contains the commanded joint angles (IK output), so the trajectory can be replayed verbatim with So101Robot.send(). So101Obs.arms.follower contains the actual motor readings.

PARAMETER DESCRIPTION
max_frame

Number of sensor frames to record.

TYPE: int

fps

Camera / observation capture rate.

TYPE: int DEFAULT: 20

control_hz

SpaceMouse control loop rate (defaults to config).

TYPE: int | None DEFAULT: None

is_async

Use asynchronous camera reads when available.

TYPE: bool DEFAULT: True

RETURNS DESCRIPTION
So101Obs

So101Obs with arm and camera observations.

Source code in src/robopy/robots/so101/so101_spacemouse.py
def record_parallel(
    self,
    max_frame: int,
    fps: int = 20,
    control_hz: int | None = None,
    is_async: bool = True,
) -> So101Obs:
    """Record a SpaceMouse-driven trajectory with camera observations.

    Architecture mirrors :meth:`So101Robot.record_parallel` — a fast
    control thread drives the arm while the main thread captures camera
    frames at the requested *fps*.

    The returned ``So101Obs.arms.leader`` contains the *commanded* joint
    angles (IK output), so the trajectory can be replayed verbatim with
    ``So101Robot.send()``.  ``So101Obs.arms.follower`` contains the
    actual motor readings.

    Args:
        max_frame: Number of sensor frames to record.
        fps: Camera / observation capture rate.
        control_hz: SpaceMouse control loop rate (defaults to config).
        is_async: Use asynchronous camera reads when available.

    Returns:
        ``So101Obs`` with arm and camera observations.
    """
    if max_frame <= 0:
        raise ValueError("max_frame must be greater than 0.")
    if fps <= 0:
        raise ValueError("fps must be greater than 0.")

    if not self.is_connected:
        raise ConnectionError("Controller is not connected. Call connect() first.")

    hz = control_hz or self._sm_config.control_hz
    dt = 1.0 / hz

    max_processing_time_ms = 1000.0 / fps * 0.9

    arm_obs_queue: queue.Queue[So101ArmObs] = queue.Queue(maxsize=hz * 2)
    stop_event = threading.Event()

    # Initialise EE state
    current_joints_deg = self._read_follower_joints()
    ee = So101Robot.forward_kinematics(current_joints_deg)
    init_target_ee = np.array([ee.x, ee.y, ee.z, ee.pitch, ee.roll], dtype=np.float64)
    init_gripper_deg = float(current_joints_deg[5]) if len(current_joints_deg) > 5 else 0.0
    init_joints_for_ik = current_joints_deg.copy()

    def control_worker() -> None:
        target_ee = init_target_ee.copy()
        gripper_deg = init_gripper_deg
        joints_for_ik = init_joints_for_ik.copy()

        while not stop_event.is_set():
            loop_start = time.perf_counter()

            target_ee, gripper_deg, joints_for_ik = self._control_step(
                target_ee, gripper_deg, joints_for_ik, dt
            )

            # Build observation: commanded joints as leader, actual as follower
            commanded = joints_for_ik.copy()
            try:
                actual = self._read_follower_joints()
            except Exception:
                actual = commanded.copy()

            arm_obs = So101ArmObs(
                leader=commanded.astype(np.float32),
                follower=actual.astype(np.float32),
            )

            try:
                arm_obs_queue.put(arm_obs, timeout=dt)
            except queue.Full:
                pass

            elapsed = time.perf_counter() - loop_start
            time.sleep(max(0.0, dt - elapsed))

    # Start control thread
    self._reset_filter()
    control_thread = threading.Thread(target=control_worker, daemon=True)
    control_thread.start()

    # Main thread: capture sensor data at *fps*
    leader_obs: List[NDArray[np.float32]] = []
    follower_obs: List[NDArray[np.float32]] = []
    camera_obs: DefaultDict[str, List[NDArray[np.float32] | NDArray[np.uint8] | None]] = (
        defaultdict(list)
    )

    get_obs_interval = 1.0 / fps
    max_processing_time = max_processing_time_ms / 1000.0
    frame_count = 0
    skipped_frames = 0
    total_processing_time = 0.0

    logger.info(
        "SpaceMouse parallel recording: frames=%s, fps=%s, control_hz=%s",
        max_frame,
        fps,
        hz,
    )

    try:
        with Progress() as progress:
            task = progress.add_task("[green]Recording SO-101 (SpaceMouse)...", total=max_frame)
            while frame_count < max_frame:
                frame_start = time.perf_counter()

                # Get latest arm observation from control thread
                try:
                    arm_obs = arm_obs_queue.get(timeout=get_obs_interval)
                    while not arm_obs_queue.empty():
                        arm_obs = arm_obs_queue.get_nowait()
                except queue.Empty:
                    logger.warning("No arm observation available in time.")
                    continue

                # Capture cameras
                sensor_data = self._robot.sensors_observation(
                    timeout_ms=max_processing_time_ms / 2.0, async_mode=is_async
                )

                leader_obs.append(arm_obs.leader)
                follower_obs.append(arm_obs.follower)

                for cam_name, frame in sensor_data.items():
                    camera_obs[cam_name].append(frame)

                frame_count += 1
                progress.update(task, advance=1)
                processing_time = time.perf_counter() - frame_start
                total_processing_time += processing_time

                if processing_time > max_processing_time:
                    skipped_frames += 1
                    logger.warning(
                        "Frame %s took %.1f ms (> %.1f ms), skipping sleep",
                        frame_count,
                        processing_time * 1000.0,
                        max_processing_time_ms,
                    )
                    continue

                sleep_time = max(0.0, get_obs_interval - processing_time)
                if sleep_time > 0:
                    time.sleep(sleep_time)
            progress.remove_task(task)

    except KeyboardInterrupt:
        logger.info("SpaceMouse recording interrupted by user.")
        raise
    except Exception as exc:
        logger.error("Error during SpaceMouse parallel recording: %s", exc)
        raise
    finally:
        stop_event.set()
        control_thread.join(timeout=1.0)

    if frame_count == 0:
        raise RuntimeError("No frames captured during SpaceMouse recording.")

    avg_proc = total_processing_time / frame_count * 1000.0
    logger.info(
        "SpaceMouse recording completed: frames=%s, skipped=%s, avg_proc=%.1f ms",
        frame_count,
        skipped_frames,
        avg_proc,
    )

    leader_arr = np.asarray(leader_obs, dtype=np.float32)
    follower_arr = np.asarray(follower_obs, dtype=np.float32)
    arms = So101ArmObs(leader=leader_arr, follower=follower_arr)

    camera_obs_np: Dict[str, NDArray[np.uint8] | NDArray[np.float32] | None] = {}
    for cam_name, frames in camera_obs.items():
        if frames and all(f is not None for f in frames):
            camera_obs_np[cam_name] = np.asarray(frames)
        else:
            camera_obs_np[cam_name] = None

    return So101Obs(arms=arms, cameras=camera_obs_np)

実験ハンドラ¤

So101SpaceMouseExpHandler¤

So101SpaceMouseExpHandler ¤

So101SpaceMouseExpHandler(so101_config: So101Config, metadata_config: MetaDataConfig, spacemouse_config: SpaceMouseConfig | None = None, fps: int = 20)

Bases: ExpHandler[So101Obs, So101Robot, So101Config, So101SaveWorker]

Experiment handler using SpaceMouse for SO-101 data collection.

This handler replaces the leader arm with a SpaceMouse device for teleoperation and data recording. It follows the standard :class:ExpHandler interface so that the interactive record_save() workflow (warmup → record → save) works identically.

METHOD DESCRIPTION
record
send
record_save

Interactive record-and-save loop using SpaceMouse.

close

Disconnect SpaceMouse + robot and shut down the save worker.

ATTRIBUTE DESCRIPTION
controller

TYPE: So101SpaceMouseController

Source code in src/robopy/utils/exp_interface/so101_spacemouse_exp_handler.py
def __init__(
    self,
    so101_config: So101Config,
    metadata_config: MetaDataConfig,
    spacemouse_config: SpaceMouseConfig | None = None,
    fps: int = 20,
) -> None:
    if fps < 1 or fps > 60:
        raise ValueError("FPS must be between 1 and 60")

    super().__init__(metadata_config, fps)
    self._config = so101_config
    self._robot = So101Robot(cfg=self._config)
    self._controller = So101SpaceMouseController(self._robot, spacemouse_config)
    self._save_worker = So101SaveWorker(fps=self.fps)

    try:
        self._controller.connect()
    except Exception as exc:
        raise RuntimeError(f"Failed to connect SpaceMouse controller: {exc}") from exc

controller property ¤

record ¤

record(max_frames: int, if_async: bool = True) -> So101Obs
Source code in src/robopy/utils/exp_interface/so101_spacemouse_exp_handler.py
def record(self, max_frames: int, if_async: bool = True) -> So101Obs:
    if max_frames <= 0:
        raise ValueError("max_frames must be greater than 0")

    try:
        obs = self._controller.record_parallel(
            max_frame=max_frames,
            fps=self.fps,
            is_async=if_async,
        )
    except KeyboardInterrupt as exc:
        sleep(0.5)
        self.close()
        raise RuntimeError("Recording stopped by user") from exc
    except Exception as exc:
        raise RuntimeError(f"Failed to record with SpaceMouse: {exc}") from exc

    return obs

send ¤

send(max_frame: int, fps: int, leader_action: NDArray[float32]) -> None
Source code in src/robopy/utils/exp_interface/so101_spacemouse_exp_handler.py
def send(
    self,
    max_frame: int,
    fps: int,
    leader_action: NDArray[np.float32],
) -> None:
    self._robot.send(max_frame=max_frame, fps=fps, leader_action=leader_action)

record_save ¤

record_save(max_frames: int, save_path: str, if_async: bool = True, save_gif: bool = True, warmup_time: int = 5) -> None

Interactive record-and-save loop using SpaceMouse.

Overrides the base class to use SpaceMouse teleoperation for the warmup phase (instead of the leader-arm-based teleoperation).

Source code in src/robopy/utils/exp_interface/so101_spacemouse_exp_handler.py
def record_save(
    self,
    max_frames: int,
    save_path: str,
    if_async: bool = True,
    save_gif: bool = True,
    warmup_time: int = 5,
) -> None:
    """Interactive record-and-save loop using SpaceMouse.

    Overrides the base class to use SpaceMouse teleoperation for the
    warmup phase (instead of the leader-arm-based teleoperation).
    """
    import os

    try:
        print("Starting SpaceMouse recording session...")
        if not self._controller.is_connected:
            self._controller.connect()

        while True:
            print("Press 'Enter' to warm up, or 'q' to quit")
            input_str = input()
            if input_str.lower() == "q":
                print("Exiting...")
                self.close()
                sleep(0.5)
                return

            print(f"Warming up for {warmup_time} seconds (SpaceMouse active)...")
            self._controller.teleoperation(max_seconds=warmup_time)

            print("Press 'Enter' to start recording...")
            input_str = input()
            print("Recording with SpaceMouse...")

            if if_async:
                print("Using asynchronous recording...")

            obs = self.record(max_frames=max_frames, if_async=if_async)

            print("Recording finished. Print 1~9 to save data, or 'e' to record again")
            input_str = input()

            if input_str.lower() == "e":
                print("Recording again...")
                continue
            elif input_str in [str(i) for i in range(1, 10)]:
                save_dir = os.path.join("data", f"{save_path}", f"{input_str}")
                count = 1
                unique_save_dir = save_dir + f"_{count}"
                while os.path.exists(unique_save_dir):
                    unique_save_dir = f"{save_dir}_{count}"
                    count += 1
                os.makedirs(unique_save_dir)

                self.save_worker.save_all_obs(obs, unique_save_dir, save_gif)
                data_shape = self._extract_data_shapes(obs)
                self.save_metadata(unique_save_dir, data_shape)
            else:
                print("Invalid input. Exiting...")
                self.close()
                return
    except Exception as e:
        self.close()
        raise RuntimeError(f"Failed to record from SpaceMouse: {e}")
    except KeyboardInterrupt:
        print("Recording stopped by user...")
        sleep(0.5)
        self.close()

close ¤

close() -> None

Disconnect SpaceMouse + robot and shut down the save worker.

Source code in src/robopy/utils/exp_interface/so101_spacemouse_exp_handler.py
def close(self) -> None:
    """Disconnect SpaceMouse + robot and shut down the save worker."""
    try:
        self._controller.disconnect()
    except Exception:
        pass
    if self._save_worker:
        try:
            self._save_worker.shutdown()
        except Exception:
            pass

使用例¤

基本的なテレオペレーション¤

from robopy.config.robot_config.so101_config import So101Config
from robopy.robots.so101.so101_robot import So101Robot
from robopy.robots.so101.so101_spacemouse import So101SpaceMouseController

config = So101Config(
    follower_port="/dev/ttyACM0",
    calibration_path="calibration/so101_calib.json",
)

robot = So101Robot(cfg=config)
controller = So101SpaceMouseController(robot)
controller.connect()

# 30秒間操作
controller.teleoperation(max_seconds=30)
controller.disconnect()

カスタム設定でのデータ収集¤

from robopy.config.input_config.spacemouse_config import SpaceMouseConfig

sm_config = SpaceMouseConfig(
    linear_speed=0.05,   # 低速で精密操作
    angular_speed=0.3,
    deadzone=0.08,       # 大きめのデッドゾーン
    control_hz=100,      # 高速な制御ループ
)

controller = So101SpaceMouseController(robot, spacemouse_config=sm_config)
controller.connect()

obs = controller.record_parallel(max_frame=1000, fps=30)

EE デルタの計算式¤

各制御ステップで、SpaceMouse の軸値から EE デルタを計算します:

$$ \Delta x = \text{axis}_x \times \text{linear_speed} \times dt $$

$$ \Delta \text{pitch} = \text{axis}_\text{pitch} \times \text{angular_speed} \times dt $$

ここで $dt = 1 / \text{control_hz}$ です。デッドゾーン内の軸値($|\text{axis}| < \text{deadzone}$)はゼロとして扱われます。