Roarm.Robot (RoArm v0.1.1)

View Source

Core robot control module for Waveshare RoArm robot arms.

Provides high-level functions for controlling robot movement, positioning, and features while handling the underlying communication protocol.

Summary

Connection

Connect to the robot arm.

Disconnect from the robot arm.

Movement

Get the current joint angles.

Get the current position of the robot.

Move the robot to its home position.

Move the base joint (j1) to a specific angle.

Move the elbow joint (j3) to a specific angle.

Move a single joint to a specific angle.

Move individual joints to specific angles.

Move the shoulder joint (j2) to a specific angle.

Move the robot to a specific position.

Move the wrist rotation joint (j4) to a specific angle.

Move the wrist X-axis joint (j5) to a specific angle.

Move the wrist Y-axis joint (j6) to a specific angle.

LED Control

Turn off the gripper LED.

Turn on the gripper LED to specified brightness (0-255).

Teaching

Replay a recorded drag teach movement.

Start drag teach mode - disables torque so you can manually move the arm.

Stop drag teach recording and save the data.

Missions

Add current position as a step to the mission.

Create a new step recording mission.

Play/execute a recorded mission.

Functions

Add a delay step to the mission.

Returns a specification to start this module under a supervisor.

Check if the robot is connected.

Get the robot type that this server is configured for.

Control the LED mounted on the gripper with simple on/off commands.

Send a custom JSON command string to the robot (bypass validation).

Send a validated command to the robot.

Control the robot's LED.

Enable or disable torque on all joints.

Enable or disable torque lock.

Start a new robot control process.

gripper

Close the gripper.

Control the gripper position.

Open the gripper to specified position.

Connection

connect(opts \\ [])

Connect to the robot arm.

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Examples

Roarm.Robot.connect()
Roarm.Robot.connect(server_name: :robot1)

disconnect(opts \\ [])

Disconnect from the robot arm.

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Examples

Roarm.Robot.disconnect()
Roarm.Robot.disconnect(server_name: :robot1)

Movement

get_joints(opts \\ [])

Get the current joint angles.

Returns the robot's current joint angles in degrees.

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Returns

  • {:ok, %{j1: float, j2: float, j3: float, j4: float}} - Current joint angles
  • {:error, reason} - Error occurred

Examples

{:ok, joints} = Roarm.Robot.get_joints()
{:ok, %{j1: 0.0, j2: 45.0, j3: -30.0, j4: 0.0}} = Roarm.Robot.get_joints()

get_position(opts \\ [])

Get the current position of the robot.

Returns the robot's current XYZ position and tool angle.

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Returns

  • {:ok, %{x: float, y: float, z: float, t: float}} - Current position
  • {:error, reason} - Error occurred

Examples

{:ok, position} = Roarm.Robot.get_position()
{:ok, %{x: 150.0, y: 0.0, z: 200.0, t: 0.0}} = Roarm.Robot.get_position()

home(opts \\ [])

Move the robot to its home position.

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :timeout - Command timeout in milliseconds (default: from config or 5000)

Examples

{:ok, response} = Roarm.Robot.home()
{:ok, response} = Roarm.Robot.home(server_name: :robot1, timeout: 10000)

move_base(angle, opts \\ [])

@spec move_base(
  number(),
  keyword()
) :: {:ok, any()} | {:error, any()}

Move the base joint (j1) to a specific angle.

The base joint controls rotation around the vertical axis, allowing the robot to rotate left and right.

Parameters

  • angle - Target angle in degrees (-180.0 to 180.0)
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Rotate base to the right by 45 degrees
Roarm.Robot.move_base(45.0)

# Rotate base to the left by 90 degrees with custom speed
Roarm.Robot.move_base(-90.0, speed: 2000)

# Move base to center position
Roarm.Robot.move_base(0.0)

move_elbow(angle, opts \\ [])

@spec move_elbow(
  number(),
  keyword()
) :: {:ok, any()} | {:error, any()}

Move the elbow joint (j3) to a specific angle.

The elbow joint controls the forearm angle, allowing the robot to bend and extend its forearm relative to the upper arm.

Parameters

  • angle - Target angle in degrees (-180.0 to 180.0)
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Bend the elbow inward by 90 degrees
Roarm.Robot.move_elbow(90.0)

# Extend the elbow outward by 45 degrees with custom speed
Roarm.Robot.move_elbow(-45.0, speed: 800)

# Move elbow to straight position
Roarm.Robot.move_elbow(0.0)

move_joint(joint, angle, opts \\ [])

@spec move_joint(1 | 2 | 3 | 4 | 5 | 6, number(), keyword()) ::
  {:ok, any()} | {:error, any()}

Move a single joint to a specific angle.

Parameters

  • joint - Joint number (1-6):
    • 1: Base joint (j1) - controls rotation around vertical axis
    • 2: Shoulder joint (j2) - controls arm lift/lower
    • 3: Elbow joint (j3) - controls forearm angle
    • 4: Wrist joint (j4) - controls end effector rotation
    • 5: Additional joint (j5) - for extended robot models
    • 6: Additional joint (j6) - for extended robot models
  • angle - Target angle in degrees (-180.0 to 180.0)
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Move base joint (j1) to 45 degrees
Roarm.Robot.move_joint(1, 45.0)

# Move shoulder joint (j2) to -30 degrees with custom speed
Roarm.Robot.move_joint(2, -30.0, speed: 2000)

# Move wrist joint (j4) to 90 degrees
Roarm.Robot.move_joint(4, 90.0)

move_joints(joints, opts \\ [])

Move individual joints to specific angles.

Supports partial joint updates - only specify the joints you want to change, and the robot will maintain its current values for unspecified joints.

Parameters

  • joints - Joint angles map with the following joints (all in degrees):
    • :j1 - Base joint (-180.0 to 180.0°) - controls rotation around vertical axis
    • :j2 - Shoulder joint (-180.0 to 180.0°) - controls arm lift/lower
    • :j3 - Elbow joint (-180.0 to 180.0°) - controls forearm angle
    • :j4 - Wrist joint (-180.0 to 180.0°) - controls end effector rotation
    • :j5 - Additional joint (-180.0 to 180.0°) - for extended robot models
    • :j6 - Additional joint (-180.0 to 180.0°) - for extended robot models
          Can be partial - e.g., %{j1: 45.0} will only change joint 1
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Move all primary joints
Roarm.Robot.move_joints(%{j1: 0.0, j2: 45.0, j3: -30.0, j4: 0.0})

# Partial update - only change j1 and j3, maintain current j2 and j4
Roarm.Robot.move_joints(%{j1: 30.0, j3: -45.0})

# Single joint update
Roarm.Robot.move_joints(%{j2: 90.0})

# With custom speed
Roarm.Robot.move_joints(%{j1: 45.0, j4: -30.0}, speed: 2000)

move_shoulder(angle, opts \\ [])

@spec move_shoulder(
  number(),
  keyword()
) :: {:ok, any()} | {:error, any()}

Move the shoulder joint (j2) to a specific angle.

The shoulder joint controls the arm's lift and lower movement, raising and lowering the entire arm assembly.

Parameters

  • angle - Target angle in degrees (-180.0 to 180.0)
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Raise the arm by 45 degrees
Roarm.Robot.move_shoulder(45.0)

# Lower the arm by 30 degrees with custom speed
Roarm.Robot.move_shoulder(-30.0, speed: 1500)

# Move shoulder to neutral position
Roarm.Robot.move_shoulder(0.0)

move_to_position(position, opts \\ [])

Move the robot to a specific position.

Supports partial position updates - only specify the coordinates you want to change, and the robot will maintain its current values for unspecified coordinates.

Parameters

  • position - Target position map with the following coordinates (all in mm except t):
    • :x - X coordinate (-500.0 to 500.0 mm)
    • :y - Y coordinate (-500.0 to 500.0 mm)
    • :z - Z coordinate (0.0 to 500.0 mm)
    • :t - Tool rotation angle (-180.0 to 180.0 degrees)
         Represents the rotation angle of the EoAT (End of Arm Tooling)
         Can be partial - e.g., %{y: 50.0} will only change Y coordinate
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :acceleration - Movement acceleration (1-254, default: 100)
    • :timeout - Command timeout in milliseconds (default: 8000)
    • :server_name - Robot server name (default: MODULE)

Examples

# Move to complete position
Roarm.Robot.move_to_position(%{x: 100.0, y: 0.0, z: 150.0, t: 0.0})

# Partial update - only change Y and Z, maintain current X and T
Roarm.Robot.move_to_position(%{y: 50.0, z: 200.0})

# Single coordinate update
Roarm.Robot.move_to_position(%{x: 75.0})

# With custom speed and acceleration
Roarm.Robot.move_to_position(%{x: 200.0, z: 300.0}, speed: 2000, acceleration: 150)

move_wrist(angle, opts \\ [])

@spec move_wrist(
  number(),
  keyword()
) :: {:ok, any()} | {:error, any()}

Move the wrist rotation joint (j4) to a specific angle.

The wrist joint controls the rotation of the end effector around its axis, allowing the gripper or tool to rotate.

Parameters

  • angle - Target angle in degrees (-180.0 to 180.0)
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Rotate wrist clockwise by 90 degrees
Roarm.Robot.move_wrist(90.0)

# Rotate wrist counter-clockwise by 45 degrees with custom speed
Roarm.Robot.move_wrist(-45.0, speed: 1200)

# Reset wrist to neutral position
Roarm.Robot.move_wrist(0.0)

move_wrist_x(angle, opts \\ [])

@spec move_wrist_x(
  number(),
  keyword()
) :: {:ok, any()} | {:error, any()}

Move the wrist X-axis joint (j5) to a specific angle.

The wrist X-axis joint provides additional wrist movement for extended robot models (M3, M3 Pro). This joint controls wrist movement along the X-axis.

Note: This function is only available on robot models with 6 degrees of freedom.

Parameters

  • angle - Target angle in degrees (-180.0 to 180.0)
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Move wrist X-axis by 30 degrees
Roarm.Robot.move_wrist_x(30.0)

# Move wrist X-axis with custom speed
Roarm.Robot.move_wrist_x(-60.0, speed: 1500)

# Reset wrist X-axis to neutral position
Roarm.Robot.move_wrist_x(0.0)

move_wrist_y(angle, opts \\ [])

@spec move_wrist_y(
  number(),
  keyword()
) :: {:ok, any()} | {:error, any()}

Move the wrist Y-axis joint (j6) to a specific angle.

The wrist Y-axis joint provides additional wrist movement for extended robot models (M3, M3 Pro). This joint controls wrist movement along the Y-axis.

Note: This function is only available on robot models with 6 degrees of freedom.

Parameters

  • angle - Target angle in degrees (-180.0 to 180.0)
  • opts - Optional parameters:
    • :speed - Movement speed (1-4096, default: 1000)
    • :timeout - Command timeout in milliseconds (default: from config)
    • :server_name - Robot server name (default: MODULE)

Examples

# Move wrist Y-axis by 45 degrees
Roarm.Robot.move_wrist_y(45.0)

# Move wrist Y-axis with custom speed
Roarm.Robot.move_wrist_y(-30.0, speed: 2000)

# Reset wrist Y-axis to neutral position
Roarm.Robot.move_wrist_y(0.0)

LED Control

led_off(opts \\ [])

Turn off the gripper LED.

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :timeout - Command timeout in milliseconds (default: from config or 5000)

Examples

{:ok, response} = Roarm.Robot.led_off()
{:ok, response} = Roarm.Robot.led_off(server_name: :robot1)

led_on(brightness \\ 255, opts \\ [])

Turn on the gripper LED to specified brightness (0-255).

Parameters

  • brightness - LED brightness level (0-255, default: 255)

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :timeout - Command timeout in milliseconds (default: from config or 5000)

Examples

{:ok, response} = Roarm.Robot.led_on(200)
{:ok, response} = Roarm.Robot.led_on()  # Full brightness
{:ok, response} = Roarm.Robot.led_on(200, server_name: :robot1)

Teaching

drag_teach_replay(filename, opts \\ [])

Replay a recorded drag teach movement.

Parameters

  • filename - Path to the recorded movement file

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :speed_multiplier - Playback speed multiplier (default: 1.0)

Examples

{:ok, response} = Roarm.Robot.drag_teach_replay("my_movement.json")
{:ok, response} = Roarm.Robot.drag_teach_replay("fast.json", speed_multiplier: 2.0)

drag_teach_start(filename, opts \\ [])

Start drag teach mode - disables torque so you can manually move the arm.

Parameters

  • filename - Path to save the recorded movement data

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :sample_rate - Recording frequency in milliseconds (default: 100)

Examples

{:ok, response} = Roarm.Robot.drag_teach_start("my_movement.json")
{:ok, response} = Roarm.Robot.drag_teach_start("precise.json", sample_rate: 50)

drag_teach_stop(opts \\ [])

Stop drag teach recording and save the data.

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Returns

  • {:ok, num_samples} - Number of recorded samples
  • {:error, reason} - Error occurred

Examples

{:ok, 150} = Roarm.Robot.drag_teach_stop()

Missions

add_mission_step(name, speed \\ 0.25, opts \\ [])

Add current position as a step to the mission.

Parameters

  • name - Mission name
  • speed - Movement speed for this step (0.1-1.0, default: 0.25)

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Examples

{:ok, response} = Roarm.Robot.add_mission_step("pickup_sequence")
{:ok, response} = Roarm.Robot.add_mission_step("fast_moves", 0.8)

create_mission(name, description \\ "", opts \\ [])

Create a new step recording mission.

Parameters

  • name - Mission name/identifier
  • description - Optional description of the mission (default: "")

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Examples

{:ok, response} = Roarm.Robot.create_mission("pickup_sequence")
{:ok, response} = Roarm.Robot.create_mission("complex_task", "Multi-step operation")

play_mission(name, times \\ 1, opts \\ [])

Play/execute a recorded mission.

Parameters

  • name - Mission name
  • times - Number of times to repeat (1-1000, default: 1)

Options

  • :server_name - Name of the robot process (default: __MODULE__)

Examples

{:ok, response} = Roarm.Robot.play_mission("pickup_sequence")
{:ok, response} = Roarm.Robot.play_mission("loop_task", 5)

Types

joints()

@type joints() :: %{j1: float(), j2: float(), j3: float(), j4: float()}

position()

@type position() :: %{x: float(), y: float(), z: float(), t: float()}

rgb()

@type rgb() :: %{r: integer(), g: integer(), b: integer()}

robot_type()

@type robot_type() :: :roarm_m2 | :roarm_m2_pro | :roarm_m3 | :roarm_m3_pro

Functions

add_mission_delay(name, delay_ms, opts \\ [])

Add a delay step to the mission.

Parameters

  • name - Mission name
  • delay_ms - Delay in milliseconds
  • opts - Options including :server_name

child_spec(init_arg)

Returns a specification to start this module under a supervisor.

See Supervisor.

connected?(opts \\ [])

Check if the robot is connected.

get_robot_type(opts \\ [])

Get the robot type that this server is configured for.

Options

Examples

{:ok, :roarm_m2} = Roarm.Robot.get_robot_type()
{:ok, :roarm_m3} = Roarm.Robot.get_robot_type(server_name: :robot1)

led(action, value \\ nil, opts \\ [])

Control the LED mounted on the gripper with simple on/off commands.

Parameters

  • action - :on or :off
  • value - LED brightness (0-255, where 0=off, 255=full brightness)
  • opts - Options including :server_name

Examples

Roarm.Robot.led(:on, 200)                    # Set LED brightness to 200/255
Roarm.Robot.led(:off, 50)                    # Set LED brightness to 50/255 (dim)
Roarm.Robot.led(:on)                         # LED at full brightness (255)
Roarm.Robot.led(:off)                        # LED completely off (0)
Roarm.Robot.led(:on, 200, server_name: :robot1) # Control specific robot

send_custom_command(command, opts \\ [])

Send a custom JSON command string to the robot (bypass validation).

For direct control when you need to send raw commands.

send_valid_command(command_map, opts \\ [])

Send a validated command to the robot.

Takes a command map with atom or string keys, validates all parameters, applies range limits and symbolic values (:min, :mid, :max), then sends the command to the robot.

Examples

# Single joint control with validation
Robot.send_valid_command(%{t: 121, joint: 4, angle: 90, spd: :max})

# Position control with clamping
Robot.send_valid_command(%{t: 1041, x: 200, y: 100, z: 150, spd: 5000})  # spd clamped to 4096

# LED control with symbolic values
Robot.send_valid_command(%{t: 114, led: :max, r: 255, g: 0, b: 0})

# With custom server and timeout
Robot.send_valid_command(%{t: 100}, server_name: :robot1, timeout: 10000)

set_led(color, opts \\ [])

Control the robot's LED.

Parameters

  • color - RGB color as %{r: integer, g: integer, b: integer} (0-255 each)

Example

Roarm.Robot.set_led(%{r: 255, g: 0, b: 0})  # Red

set_torque_enabled(enabled, opts \\ [])

Enable or disable torque on all joints.

Parameters

  • enabled - true to enable torque (lock joints), false to disable (allow manual movement)
  • opts - Options including :server_name and :timeout

set_torque_lock(enabled, opts \\ [])

Enable or disable torque lock.

start_link(opts \\ [])

Start a new robot control process.

Options

  • :robot_type - Type of robot (default: from config or :roarm_m2)
  • :port - Serial port path (default: from config)
  • :baudrate - Communication speed (default: from config or 115200)

gripper

gripper_close(opts \\ [])

Close the gripper.

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :timeout - Command timeout in milliseconds (default: from config or 5000)
  • :speed - Movement speed (1-4096, default: 2000)

Examples

{:ok, response} = Roarm.Robot.gripper_close()
{:ok, response} = Roarm.Robot.gripper_close(speed: 1000)

gripper_control(position, opts \\ [])

Control the gripper position.

Uses the appropriate gripper control method based on robot model:

  • M2: Uses joint 4 control (T:121)
  • M3: Uses dedicated gripper command (T:222)

Parameters

  • position - Gripper position (0-100%, where 0=fully open, 100=closed)
             Note: Due to physical constraints, 30 is effectively as open as possible

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :timeout - Command timeout in milliseconds (default: from config or 5000)
  • :speed - Movement speed (1-4096, default: 2000)

Examples

{:ok, response} = Roarm.Robot.gripper_control(100)   # Close gripper
{:ok, response} = Roarm.Robot.gripper_control(50)    # Half open
{:ok, response} = Roarm.Robot.gripper_control(30)    # Fully open (physical limit)
{:ok, response} = Roarm.Robot.gripper_control(0)     # Fully open (theoretical)
{:ok, response} = Roarm.Robot.gripper_control(75, speed: 1000)

gripper_open(position \\ 30, opts \\ [])

Open the gripper to specified position.

Parameters

  • position - How far to open (0-100%, default: 30% which is maximum practical opening)
             Note: Due to physical constraints, 30 is effectively as open as possible

Options

  • :server_name - Name of the robot process (default: __MODULE__)
  • :timeout - Command timeout in milliseconds (default: from config or 5000)
  • :speed - Movement speed (1-4096, default: 2000)

Examples

{:ok, response} = Roarm.Robot.gripper_open()      # Fully open (30%)
{:ok, response} = Roarm.Robot.gripper_open(50)    # Half open (50%)