Roarm (RoArm v0.1.1)

View Source

Elixir library for controlling Waveshare RoArm robot arms.

This library provides a high-level interface for controlling Waveshare RoArm robot arms using Circuits.UART for serial communication. It replicates the functionality of the official Waveshare RoArm SDK in Elixir.

Features

  • Serial communication with RoArm devices
  • Position and joint control
  • LED control and torque control
  • Concurrent robot control using GenServer
  • Support for multiple RoArm models

Configuration

Configure Roarm in your config.exs:

config :roarm,
  port: "/dev/cu.usbserial-110",
  baudrate: 115200,
  robot_type: :roarm_m2

Quick Start

# With configuration - just start the robot
{:ok, _pid} = Roarm.start_robot()

# Or override specific options
{:ok, _pid} = Roarm.start_robot(port: "/dev/ttyUSB0", robot_type: :roarm_m3)

# Move to a position (coordinates in mm, t in degrees)
Roarm.Robot.move_to_position(%{x: 100.0, y: 0.0, z: 150.0, t: 0.0})

# Partial position update - only change Y coordinate
Roarm.Robot.move_to_position(%{y: 50.0})

# Control joints (all angles in degrees)
Roarm.Robot.move_joints(%{j1: 0.0, j2: 45.0, j3: -30.0, j4: 0.0})

# Partial joint update - only move joint 1
Roarm.Robot.move_joints(%{j1: 90.0})

# Move a single joint directly
Roarm.Robot.move_joint(1, 45.0)  # Move base joint to 45 degrees
Roarm.Robot.move_joint(4, -30.0, speed: 2000)  # Move wrist joint with custom speed

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

# Control gripper (0=open, 100=closed, 30=practical max opening)
Roarm.Robot.gripper_open()      # Open to maximum practical position (30%)
Roarm.Robot.gripper_close()     # Close gripper completely
Roarm.Robot.gripper_control(50) # Half-way position

# Enable/disable torque (for manual movement)
Roarm.set_torque_enabled(false)  # Allow manual movement
Roarm.set_torque_enabled(true)   # Lock joints in position

Modules

Summary

Functions

List available serial ports on the system.

Get the registry name used by Roarm.

Enable or disable torque control for the robot joints.

Start the Roarm registry.

Convenience function to start a robot with given configuration.

Quick connection test to verify robot communication.

Functions

list_ports()

List available serial ports on the system.

registry_name()

Get the registry name used by Roarm.

set_torque_enabled(enabled, opts \\ [])

Enable or disable torque control for the robot joints.

When torque is enabled, joints are locked in position. When disabled, joints can be moved manually.

Parameters

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

Examples

# Enable torque (lock joints)
Roarm.set_torque_enabled(true)

# Disable torque (allow manual movement)
Roarm.set_torque_enabled(false)

start_registry()

Start the Roarm registry.

start_robot(opts \\ [])

Convenience function to start a robot with given configuration.

Uses application configuration as defaults, with provided options taking precedence.

Parameters

  • opts - Configuration options (overrides config.exs values)
    • :robot_type - Type of robot (:roarm_m2, :roarm_m2_pro, :roarm_m3, :roarm_m3_pro)
    • :port - Serial port path
    • :baudrate - Communication speed (default: 115200)
    • :name - Process name for registry

Examples

# Using configuration from config.exs
Roarm.start_robot()

# Override specific options
Roarm.start_robot(port: "/dev/ttyUSB1", robot_type: :roarm_m3)

test_connection(port, opts \\ [])

Quick connection test to verify robot communication.