MiniArmClient API

The MiniArmClient class provides a complete interface for controlling the Mini-Arm robot via serial communication.

class MiniArmClient(name='MiniArmClient', port='COM3', baudrate=115200, command_delimiter=';', timeout=1.0, verbose=False)[source]

Bases: object

A client for the Mini-Arm robot arm that handles serial communication.

This class provides methods for connecting to and controlling the Mini-Arm robot via serial communication. It can send commands and receive responses from the Raspberry Pi Pico running the Mini-Arm firmware.

Parameters:
  • name (str, optional) – Name identifier for the client instance. Default is ‘MiniArmClient’.

  • port (str, optional) – Serial port to connect to. Default is ‘COM3’ (Windows). Use ‘/dev/ttyACM0’ for Linux.

  • baudrate (int, optional) – Baudrate for the serial connection. Default is 115200.

  • command_delimiter (str, optional) – Character(s) used to terminate commands. Default is ‘;’.

  • timeout (float, optional) – Serial read timeout in seconds. Default is 1.0.

  • verbose (bool, optional) – Enable/disable verbose output logging. Default is False.

connected

True if serial connection is established and open.

Type:

bool

s

The underlying serial connection object.

Type:

serial.Serial

Examples

Basic usage:

>>> from mini_arm import MiniArmClient
>>> client = MiniArmClient(port='COM3')
>>> client.home()
>>> pose = client.get_pose()
>>> print(f"Current position: {pose}")
>>> client.disconnect()

Using context manager:

>>> with MiniArmClient(port='COM3') as client:
...     client.home()
...     client.set_pose(0.135, 0.0, 0.22)
HOME_POSITION = [0.135, 0.0, 0.215]
WORKSPACE_LIMITS = {'x': (0.05, 0.25), 'y': (-0.15, 0.15), 'z': (0.1, 0.3)}
logger(*argv, warning=False)[source]

Log messages with timestamp.

Parameters:
  • *argv (str) – Message components to join and log.

  • warning (bool, optional) – If True, prefix message with ‘(Warning)’. Default is False.

send_message(message)[source]

Send a message to the Pico over serial.

Automatically adds the command terminator if not present.

Parameters:

message (str) – The command message to send.

Return type:

None

send(command)[source]

Send a command and optionally read the response.

Parameters:

command (str) – Command string to send to Mini-Arm.

Returns:

Response from the device, if any.

Return type:

str or None

get_buffer()[source]

Read all available bytes from the serial connection.

Returns:

The buffer contents as a string, or None if no data available.

Return type:

str or None

wait_for_response(timeout=2.0)[source]

Wait for a response from the device.

Parameters:

timeout (float) – Maximum time to wait in seconds.

Returns:

Response string or None if timeout.

Return type:

str or None

home()[source]

Move the robot arm to its home position.

Return type:

None

ik_home()[source]

Move to IK home position (all joints at 0).

Return type:

None

set_pose(x, y, z, roll=0.0, pitch=0.0, yaw=0.0)[source]

Move the end-effector to a Cartesian position.

Parameters:
  • x (float) – X coordinate in meters.

  • y (float) – Y coordinate in meters.

  • z (float) – Z coordinate in meters.

  • roll (float, optional) – Roll angle in radians. Default is 0.0.

  • pitch (float, optional) – Pitch angle in radians. Default is 0.0.

  • yaw (float, optional) – Yaw angle in radians. Default is 0.0.

Return type:

None

set_pose_xyz(position)[source]

Move to XYZ position (convenience method).

Parameters:

position (list or tuple) – [x, y, z] coordinates in meters.

Return type:

None

set_delta_pose(dx=0.0, dy=0.0, dz=0.0, droll=0.0, dpitch=0.0, dyaw=0.0)[source]

Move the end-effector by a relative delta.

Parameters:
  • dx (float) – Delta X in meters.

  • dy (float) – Delta Y in meters.

  • dz (float) – Delta Z in meters.

  • droll (float, optional) – Delta roll in radians.

  • dpitch (float, optional) – Delta pitch in radians.

  • dyaw (float, optional) – Delta yaw in radians.

Return type:

None

get_pose()[source]

Get the current end-effector pose.

Returns:

Array [x, y, z, roll, pitch, yaw] or None if reading fails.

Return type:

np.ndarray or None

get_current_pose()[source]

Alias for get_pose() for backward compatibility.

Return type:

Optional[ndarray]

set_joint(joint_index, angle)[source]

Move a single joint to a specified angle.

Parameters:
  • joint_index (int) – Joint index (0-5 for arm joints, 6 for gripper).

  • angle (float) – Target angle in degrees.

Return type:

None

set_joints(angles)[source]

Set all joint angles.

Parameters:

angles (list of float) – Joint angles in degrees [j0, j1, j2, j3, j4, j5] or [j0, j1, j2, j3, j4, j5, gripper].

Return type:

None

get_joints()[source]

Get current joint angles.

Returns:

Joint angles in degrees, or None if reading fails.

Return type:

list of float or None

set_gripper(value)[source]

Control the gripper.

Parameters:

value (float or str) – Gripper position (0-180 degrees) or state (‘open’, ‘close’).

Return type:

None

gripper_open()[source]

Open the gripper fully.

Return type:

None

gripper_close()[source]

Close the gripper fully.

Return type:

None

set_led(r, g, b)[source]

Set the RGB LED color.

Parameters:
  • r (int) – Red value (0-255).

  • g (int) – Green value (0-255).

  • b (int) – Blue value (0-255).

Return type:

None

led_off()[source]

Turn off the LED.

Return type:

None

led_red()[source]

Set LED to red.

Return type:

None

led_green()[source]

Set LED to green.

Return type:

None

led_blue()[source]

Set LED to blue.

Return type:

None

start_trajectory(trajectory='circle', repeat=False)[source]

Start a predefined trajectory.

Parameters:
  • trajectory (str) – Trajectory name (e.g., ‘circle’) or list of points.

  • repeat (bool) – Whether to repeat the trajectory continuously.

Return type:

None

stop_trajectory()[source]

Stop any running trajectory.

Return type:

None

get_info()[source]

Get robot system information.

Returns:

Robot info string.

Return type:

str or None

get_help()[source]

Get list of available commands.

Returns:

Help text with available commands.

Return type:

str or None

set_debug(enabled)[source]

Enable or disable debug mode on the robot.

Parameters:

enabled (bool) – True to enable debug output, False to disable.

Return type:

None

set_debug_mode(mode)[source]

Alias for set_debug() for backward compatibility.

Return type:

None

Parameters:

mode (bool | str)

set_rate(hz)[source]

Set the main loop rate on the robot.

Parameters:

hz (int) – Loop rate in Hz.

Return type:

None

test()[source]

Send a test command to verify communication.

Return type:

None

play_music(song)[source]

Play a music file on the robot.

Parameters:

song (str) – Name of the song to play.

Return type:

None

read_fsr()[source]

Read force-sensitive resistor values.

Returns:

FSR sensor values.

Return type:

str or None

send_controller_data(controller_data)[source]

Send Xbox controller data for teleoperation.

Parameters:

controller_data (str) – Formatted controller state string.

Return type:

None

send_ctrl_c()[source]

Send Ctrl+C to interrupt current operation.

Return type:

None

send_ctrl_d()[source]

Send Ctrl+D (soft reset).

Return type:

None

reconnect()[source]

Attempt to reconnect to the robot.

Returns:

True if reconnection successful.

Return type:

bool

disconnect()[source]

Close the serial connection.

Return type:

None

Quick Reference

from miniarm_core import MiniArmClient

# Connect to Mini-Arm
client = MiniArmClient(port='COM3', baudrate=115200)

# Or use context manager
with MiniArmClient(port='COM3') as client:
    client.home()
    client.set_pose(0.135, 0.0, 0.22)

Constructor

MiniArmClient(
    name: str = 'MiniArmClient',
    port: str = 'COM3',
    baudrate: int = 115200,
    command_delimiter: str = ';',
    timeout: float = 1.0,
    verbose: bool = False
)

Parameters:

  • name (str) - Identifier for the client instance

  • port (str) - Serial port (COM3 on Windows, /dev/ttyACM0 on Linux)

  • baudrate (int) - Serial baud rate. Default: 115200

  • timeout (float) - Read timeout in seconds. Default: 1.0

  • verbose (bool) - Enable verbose logging. Default: False

Motion Commands

home()

Move the robot arm to its home position.

client.home()

set_pose(x, y, z, roll=0, pitch=0, yaw=0)

Move the end-effector to a Cartesian position.

param x:

X coordinate in meters

param y:

Y coordinate in meters

param z:

Z coordinate in meters

param roll:

Roll angle in radians (optional)

param pitch:

Pitch angle in radians (optional)

param yaw:

Yaw angle in radians (optional)

# Move to position
client.set_pose(0.135, 0.0, 0.22)

# With orientation
client.set_pose(0.15, 0.05, 0.20, roll=0, pitch=0.5, yaw=0)

set_delta_pose(dx=0, dy=0, dz=0, droll=0, dpitch=0, dyaw=0)

Move the end-effector by a relative delta.

# Move 1cm in X direction
client.set_delta_pose(dx=0.01)

# Move diagonally
client.set_delta_pose(dx=0.01, dy=0.01, dz=-0.005)

get_pose()

Get the current end-effector position.

returns:

numpy array [x, y, z] or None

pose = client.get_pose()
print(f"Position: x={pose[0]:.3f}, y={pose[1]:.3f}, z={pose[2]:.3f}")

Joint Commands

set_joint(joint_index, angle)

Move a single joint to a specified angle.

param joint_index:

Joint index (0-5 for arm, 6 for gripper)

param angle:

Target angle in degrees

client.set_joint(0, 45)   # Base joint to 45°
client.set_joint(2, 90)   # Elbow to 90°

set_joints(angles)

Set all joint angles simultaneously.

param angles:

List of joint angles in degrees

client.set_joints([0, 45, 90, 0, 45, 0])

# Include gripper position
client.set_joints([0, 45, 90, 0, 45, 0, 90])

get_joints()

Get current joint angles.

returns:

List of joint angles in degrees

joints = client.get_joints()
for i, angle in enumerate(joints):
    print(f"Joint {i}: {angle}°")

Gripper Commands

set_gripper(value)

Control the gripper position.

param value:

Position (0-180 degrees) or state (‘open’, ‘close’)

client.set_gripper(90)      # Set to 90°
client.set_gripper('open')  # Fully open
client.set_gripper('close') # Fully close

gripper_open() / gripper_close()

Convenience methods for gripper control.

client.gripper_open()
client.gripper_close()

LED Commands

set_led(r, g, b)

Set the RGB LED color.

param r:

Red value (0-255)

param g:

Green value (0-255)

param b:

Blue value (0-255)

client.set_led(255, 0, 0)    # Red
client.set_led(0, 255, 0)    # Green
client.set_led(0, 0, 255)    # Blue

Convenience methods:

client.led_red()
client.led_green()
client.led_blue()
client.led_off()

Trajectory Commands

start_trajectory(trajectory, repeat=False)

Start a predefined trajectory.

param trajectory:

Trajectory name (e.g., ‘circle’)

param repeat:

Whether to loop continuously

client.start_trajectory('circle')
client.start_trajectory('circle', repeat=True)

stop_trajectory()

Stop any running trajectory.

client.stop_trajectory()

System Commands

get_info()

Get robot system information.

client.get_info()

get_help()

Display available firmware commands.

client.get_help()

set_debug(enabled)

Enable or disable debug output on the robot.

client.set_debug(True)   # Enable
client.set_debug(False)  # Disable

set_rate(hz)

Set the main loop rate on the robot.

client.set_rate(100)  # 100 Hz

read_fsr()

Read force-sensitive resistor values from the gripper.

fsr_values = client.read_fsr()
print(fsr_values)

Connection Management

disconnect()

Close the serial connection.

client.disconnect()

reconnect()

Attempt to reconnect after disconnect.

returns:

True if successful

if not client.connected:
    success = client.reconnect()

Context Manager

Use with statement for automatic cleanup:

with MiniArmClient(port='COM3') as client:
    client.home()
    client.set_pose(0.135, 0.0, 0.22)
# Connection automatically closed

Class Attributes

  • HOME_POSITION - Default home position [0.135, 0.0, 0.215]

  • WORKSPACE_LIMITS - Dictionary of workspace bounds

  • connected - Boolean indicating connection status