# Reachy Mini

## Main class[[reachy_mini.ReachyMini]]

#### reachy_mini.ReachyMini[[reachy_mini.ReachyMini]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L74)

Reachy Mini class for controlling a simulated or real Reachy Mini robot.

acquire_mediareachy_mini.ReachyMini.acquire_mediahttps://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L217[]
Tell the daemon to re-acquire camera and audio hardware.

The SDK's media_manager is re-created with the original backend
auto-detection logic.

Idempotent: safe to call multiple times.

**Parameters:**

robot_name : Name of the robot, defaults to "reachy_mini".

host : Hostname or IP of the daemon. Defaults to "reachy-mini.local". In `"auto"` mode this is only used as a fallback when localhost is unreachable, so the default works out of the box for local development.

port : Port of the daemon's FastAPI server. Defaults to 8000.

connection_mode : Select how to connect to the daemon. Use *"localhost_only"* to restrict connections to daemons running on localhost, *"network"* to connect to a remote daemon at *host:port*, or *"auto"* (default) to try localhost first then fall back to *host:port*.

spawn_daemon (bool) : If True, will spawn a daemon to control the robot, defaults to False.

use_sim (bool) : If True and spawn_daemon is True, will spawn a simulated robot, defaults to True.
#### async_play_move[[reachy_mini.ReachyMini.async_play_move]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L1038)

Asynchronously play a Move.

**Parameters:**

move (Move) : The Move object to be played.

play_frequency (float) : The frequency at which to evaluate the move (in Hz).

initial_goto_duration (float) : Duration for the initial goto to the starting position of the move (in seconds). If 0, no initial goto is performed.

sound (bool) : If True, play the sound associated with the move (if any).
#### cancel_move[[reachy_mini.ReachyMini.cancel_move]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L1028)

Cancel the currently playing move.

This will cause any running play_move or async_play_move to stop
at the next iteration of the playback loop. Audio is also stopped.
#### disable_gravity_compensation[[reachy_mini.ReachyMini.disable_gravity_compensation]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L1015)

Disable gravity compensation for the head motors.
#### disable_motors[[reachy_mini.ReachyMini.disable_motors]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L997)

Disable the motors.

**Parameters:**

ids (List[str] | None) : List of motor names to disable. If None, all motors will be disabled. Valid names match `src/reachy_mini/assets/config/hardware_config.yaml`: `body_rotation`, `stewart_1` … `stewart_6`, `right_antenna`, `left_antenna`.
#### disable_wobbling[[reachy_mini.ReachyMini.disable_wobbling]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L260)

Disable audio-reactive head wobbling and reset offsets to zero.
#### enable_gravity_compensation[[reachy_mini.ReachyMini.enable_gravity_compensation]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L1011)

Enable gravity compensation for the head motors.
#### enable_motors[[reachy_mini.ReachyMini.enable_motors]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L986)

Enable the motors.

**Parameters:**

ids (List[str] | None) : List of motor names to enable. If None, all motors will be enabled. Valid names match `src/reachy_mini/assets/config/hardware_config.yaml`: `body_rotation`, `stewart_1` … `stewart_6`, `right_antenna`, `left_antenna`.
#### enable_wobbling[[reachy_mini.ReachyMini.enable_wobbling]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L237)

Enable audio-reactive head wobbling.

When enabled, audio played through `media.play_sound()` or
`media.push_audio_sample()` is analysed and converted into
subtle head movements that are composed with the current target
pose on the daemon side.

For LOCAL backend: wobbling runs on the SDK side; offsets are sent
over WebSocket.  For all backends the daemon is also told to enable
wobbling so that daemon-side sounds (wake-up, sleep, etc.) and
incoming WebRTC audio also produce head movement.
#### get_current_head_pose[[reachy_mini.ReachyMini.get_current_head_pose]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L876)

Get the current head pose as a 4x4 matrix.

Get the current head pose as a 4x4 matrix.

**Returns:**

`np.ndarray`

A 4x4 matrix representing the current head pose.
#### get_current_joint_positions[[reachy_mini.ReachyMini.get_current_joint_positions]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L852)

Get the current joint positions of the head and antennas.

Get the current joint positions of the head and antennas (in rad)

**Returns:**

`tuple`

A tuple containing two lists:
- List of head joint positions (rad) (length 7).
- List of antennas joint positions (rad) (length 2).
#### get_present_antenna_joint_positions[[reachy_mini.ReachyMini.get_present_antenna_joint_positions]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L865)

Get the present joint positions of the antennas.

Get the present joint positions of the antennas (in rad)

**Returns:**

`list`

A list of antennas joint positions (rad) (length 2).
#### goto_sleep[[reachy_mini.ReachyMini.goto_sleep]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L627)

Put the robot to sleep by moving the head and antennas to a predefined sleep position.
#### goto_target[[reachy_mini.ReachyMini.goto_target]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L559)

Go to a target head pose and/or antennas position using task space interpolation, in "duration" seconds.

**Parameters:**

head (Optional[np.ndarray]) : 4x4 pose matrix representing the target head pose.

antennas (Optional[Union[np.ndarray, List[float]]]) : 1D array with two elements representing the angles of the antennas in radians.

duration (float) : Duration of the movement in seconds.

method (InterpolationTechnique) : Interpolation method to use ("linear", "minjerk", "ease_in_out", "cartoon"). Default is "minjerk".

body_yaw (float | None) : Body yaw angle in radians. Use None to keep the current yaw.
#### look_at_image[[reachy_mini.ReachyMini.look_at_image]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L659)

Make the robot head look at a point defined by a pixel position (u,v).

# TODO image of reachy mini coordinate system

**Parameters:**

u (int) : Horizontal coordinate in image frame.

v (int) : Vertical coordinate in image frame.

duration (float) : Duration of the movement in seconds. If 0, the head will snap to the position immediately.

perform_movement (bool) : If True, perform the movement. If False, only calculate and return the pose.

**Returns:**

`np.ndarray`

The calculated head pose as a 4x4 matrix.
#### look_at_world[[reachy_mini.ReachyMini.look_at_world]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L724)

Look at a specific point in 3D space in Reachy Mini's reference frame.

TODO include image of reachy mini coordinate system

**Parameters:**

x (float) : X coordinate in meters.

y (float) : Y coordinate in meters.

z (float) : Z coordinate in meters.

duration (float) : Duration of the movement in seconds. If 0, the head will snap to the position immediately.

perform_movement (bool) : If True, perform the movement. If False, only calculate and return the pose.

**Returns:**

`np.ndarray`

The calculated head pose as a 4x4 matrix.
#### async_play_move[[reachy_mini.ReachyMini.play_move]]

Asynchronously play a Move.

**Parameters:**

move (Move) : The Move object to be played.

play_frequency (float) : The frequency at which to evaluate the move (in Hz).

initial_goto_duration (float) : Duration for the initial goto to the starting position of the move (in seconds). If 0, no initial goto is performed.

sound (bool) : If True, play the sound associated with the move (if any).
#### release_media[[reachy_mini.ReachyMini.release_media]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L198)

Tell the daemon to release camera and audio hardware.

After calling this, the camera and microphone are available for direct
access via OpenCV / sounddevice / etc.  The SDK's media_manager is
switched to NO_MEDIA.

Idempotent: safe to call multiple times.
#### set_automatic_body_yaw[[reachy_mini.ReachyMini.set_automatic_body_yaw]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L1019)

Enable or disable automatic body yaw.

**Parameters:**

enabled (bool) : Whether automatic body yaw is enabled.
#### set_target[[reachy_mini.ReachyMini.set_target]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L497)

Set the target pose of the head and/or the target position of the antennas.

Note:
*enable_motors()* pins all targets to the present pose before flipping
torque on, so the pattern `set_target(X); enable_motors()` no longer
drives the robot to `X`. Call `set_target` *after* `enable_motors`.

**Parameters:**

head (Optional[np.ndarray]) : 4x4 pose matrix representing the head pose.

antennas (Optional[Union[np.ndarray, List[float]]]) : 1D array with two elements representing the angles of the antennas in radians.

body_yaw (Optional[float]) : Body yaw angle in radians.
#### set_target_antenna_joint_positions[[reachy_mini.ReachyMini.set_target_antenna_joint_positions]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L941)

Set the target joint positions of the antennas.
#### set_target_body_yaw[[reachy_mini.ReachyMini.set_target_body_yaw]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L945)

Set the target body yaw.

**Parameters:**

body_yaw (float) : The yaw angle of the body in radians.
#### set_target_head_pose[[reachy_mini.ReachyMini.set_target_head_pose]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L921)

Set the head pose to a specific 4x4 matrix.

**Parameters:**

pose (np.ndarray) : A 4x4 matrix representing the desired head pose.

body_yaw (float) : The yaw angle of the body, used to adjust the head pose.
#### start_recording[[reachy_mini.ReachyMini.start_recording]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L954)

Start recording data.
#### stop_recording[[reachy_mini.ReachyMini.stop_recording]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L959)

Stop recording data and return the recorded data.
#### wake_up[[reachy_mini.ReachyMini.wake_up]]

[Source](https://github.com/pollen-robotics/reachy_mini/blob/v1.8.2/src/reachy_mini/reachy_mini.py#L611)

Wake up the robot - go to the initial head position and play the wake up emote and sound.

