Skip to main content
Control robotic arms for automated pick-and-place operations, positioning, and test fixture manipulation.

Import

from lager.arm.rotrics import Dexarm

# For exception handling
from lager.arm.arm_net import ArmBase, MovementTimeoutError
The lager.arm module’s __init__.py is empty. Import Dexarm directly from lager.arm.rotrics.

Methods

MethodDescription
position()Get current arm position (x, y, z)
move_to()Move to absolute coordinates
delta()Move relative to current position
go_home()Return arm to home position
enable_motor()Enable arm motors
disable_motor()Disable arm motors
read_and_save_position()Save current position to memory
get_current_position()Get full position including joint angles
sliding_rail_init()Initialize the sliding rail

Method Reference

Dexarm(port, serial_number)

Create a Dexarm robotic arm instance.
from lager.arm.rotrics import Dexarm

# Auto-detect arm
with Dexarm() as arm:
    print(arm.position())

# Specify serial port
with Dexarm(port='/dev/ttyACM0') as arm:
    print(arm.position())

# Specify by serial number
with Dexarm(serial_number='ABCD1234') as arm:
    print(arm.position())
Parameters:
ParameterTypeDescription
portstrSerial port path (optional, auto-detected)
serial_numberstrUSB serial number for identification
Returns: Dexarm instance (context manager supported)

position()

Get the current arm position.
x, y, z = arm.position()
print(f"Position: X={x}, Y={y}, Z={z}")
Returns: tuple[float, float, float] - (x, y, z) coordinates in mm

move_to(x, y, z, timeout=5.0)

Move the arm to absolute coordinates with blocking wait.
# Move to specific position
arm.move_to(100, 200, 50)

# Move with longer timeout
arm.move_to(100, 200, 50, timeout=10.0)
Parameters:
ParameterTypeDescription
xfloatTarget X coordinate (mm)
yfloatTarget Y coordinate (mm)
zfloatTarget Z coordinate (mm)
timeoutfloatMaximum wait time in seconds (default: 5.0)
Raises: MovementTimeoutError if position not reached within timeout

delta(dx=0, dy=0, dz=0, timeout=5.0)

Move relative to current position.
# Move 10mm in X direction
new_x, new_y, new_z = arm.delta(dx=10)

# Move diagonally
new_x, new_y, new_z = arm.delta(dx=10, dy=10, dz=-5)
Parameters:
ParameterTypeDescription
dxfloatRelative X movement (mm)
dyfloatRelative Y movement (mm)
dzfloatRelative Z movement (mm)
timeoutfloatMaximum wait time (default: 5.0)
Returns: tuple[float, float, float] - New (x, y, z) position after move

go_home()

Return the arm to its home position (X=0, Y=300, Z=0).
arm.go_home()

enable_motor()

Enable the arm motors.
arm.enable_motor()

disable_motor()

Disable the arm motors (arm will be loose).
arm.disable_motor()

read_and_save_position()

Save the current position to the arm’s internal memory.
arm.read_and_save_position()

get_current_position()

Get the full position including joint angles.
x, y, z, e, a, b, c = arm.get_current_position()
print(f"Cartesian: ({x}, {y}, {z})")
print(f"Joint angles: A={a}, B={b}, C={c}")
Returns: tuple[float, ...] - (x, y, z, e, a, b, c) where a, b, c are joint angles

End Effector Methods

Soft Gripper

arm.soft_gripper_pick()    # Activate gripper to pick
arm.soft_gripper_place()   # Release gripper to place
arm.soft_gripper_nature()  # Return to neutral state
arm.soft_gripper_stop()    # Stop gripper action

Air Picker

arm.air_picker_pick()      # Activate vacuum to pick
arm.air_picker_place()     # Release vacuum to place
arm.air_picker_nature()    # Return to neutral state
arm.air_picker_stop()      # Stop vacuum action

Laser Module

arm.laser_on(value=0)      # Turn laser on with power level
arm.laser_off()            # Turn laser off

Conveyor Belt Methods

arm.conveyor_belt_forward(speed=0)    # Move belt forward (speed 0-100)
arm.conveyor_belt_backward(speed=0)   # Move belt backward (speed 0-100)
arm.conveyor_belt_stop()              # Stop belt

Sliding Rail Methods

arm.sliding_rail_init()  # Initialize the sliding rail

Utility Methods

delay_ms(value) / delay_s(value)

Add delay to the arm’s command queue.
arm.delay_ms(500)  # 500ms delay
arm.delay_s(2)     # 2 second delay

set_acceleration(acceleration, travel_acceleration, retract_acceleration=60)

Configure acceleration settings.
arm.set_acceleration(100, 100, 60)

set_module_type(module_type)

Set the attached module type.
# 0=PEN, 1=LASER, 2=PNEUMATIC, 3=3D
arm.set_module_type(0)  # Set to PEN module

get_module_type()

Get the currently detected module type.
module = arm.get_module_type()
print(f"Module: {module}")  # 'PEN', 'LASER', 'PUMP', or '3D'

Examples

Basic Movement

from lager.arm.rotrics import Dexarm

with Dexarm() as arm:
    # Go to home position
    arm.go_home()

    # Get current position
    x, y, z = arm.position()
    print(f"Home position: ({x}, {y}, {z})")

    # Move to test position
    arm.move_to(100, 250, 0)

    # Move up
    arm.delta(dz=50)

    # Return home
    arm.go_home()

Pick and Place

from lager.arm.rotrics import Dexarm

with Dexarm() as arm:
    arm.go_home()

    # Move to pick position
    arm.move_to(100, 200, 50)   # Above target
    arm.delta(dz=-30)           # Lower to pick height

    # Pick up object
    arm.soft_gripper_pick()
    arm.delay_ms(500)

    # Lift
    arm.delta(dz=30)

    # Move to place position
    arm.move_to(150, 200, 50)
    arm.delta(dz=-30)

    # Place object
    arm.soft_gripper_place()
    arm.delay_ms(500)

    # Return home
    arm.delta(dz=30)
    arm.go_home()

Automated Test Positioning

from lager.arm.rotrics import Dexarm
from lager import Net
from lager.pcb.constants import NetType

# Test positions for probe points
PROBE_POSITIONS = [
    (100, 200, -10),  # Test point 1
    (120, 200, -10),  # Test point 2
    (140, 200, -10),  # Test point 3
]

with Dexarm() as arm:
    arm.go_home()

    adc = Net.get('PROBE', type=NetType.ADC)

    results = []
    for i, (x, y, z) in enumerate(PROBE_POSITIONS):
        # Move above position
        arm.move_to(x, y, z + 20)

        # Lower probe
        arm.move_to(x, y, z)
        arm.delay_ms(200)  # Settle time

        # Take measurement
        voltage = adc.input()
        results.append((i, voltage))
        print(f"Point {i}: {voltage}V")

        # Lift
        arm.delta(dz=20)

    arm.go_home()

Error Handling

from lager.arm.rotrics import Dexarm
from lager.arm.arm_net import MovementTimeoutError

try:
    with Dexarm() as arm:
        arm.move_to(100, 200, 50, timeout=3.0)
except MovementTimeoutError:
    print("Arm movement timed out - check for obstructions")
except RuntimeError as e:
    print(f"Arm not found or cannot be opened: {e}")
except Exception as e:
    print(f"Error: {e}")

Supported Hardware

ManufacturerModelFeatures
RotricsDexarm4-axis, multiple end effectors, conveyor support

Exceptions

ExceptionModuleDescription
MovementTimeoutErrorlager.arm.arm_netArm didn’t reach target position in time
RuntimeErrorbuiltinArm device not found or cannot be opened

Notes

  • Always use the context manager (with statement) to ensure proper cleanup
  • The arm must be homed before accurate movements
  • Movement timeout errors may indicate obstructions or out-of-bounds coordinates
  • Joint angles (a, b, c) are in the arm’s internal coordinate system
  • Default tolerance for position verification is 0.5mm
  • The arm auto-detects via USB VID/PID (0x0483:0x5740)