Keyboard shortcuts

Press or to navigate between chapters

Press S or / to search in the book

Press ? to show this help

Press Esc to hide this help

Speed Control

Use hand.speed to control and read the motion speed of each joint motor on the L20 dexterous hand.

  • Speed range: 0-100
  • Unit: Unitless

Set Speed

from realhand import L20
from realhand.hand.l20 import L20Speed

# Using a list (16 joints)
hand.speed.set_speeds([50.0] * 16)

# Using an L20Speed object
speed = L20Speed(
    thumb_abd=30.0,  # Thumb abduction
    thumb_yaw=30.0,  # Thumb rotation
    thumb_root1=30.0,  # Thumb root
    thumb_tip=30.0,  # Thumb tip
    index_abd=80.0,  # Index abduction
    index_root1=80.0,  # Index root
    index_tip=80.0,  # Index tip
    middle_abd=80.0,  # Middle abduction
    middle_root1=80.0,  # Middle root
    middle_tip=80.0,  # Middle tip
    ring_abd=80.0,  # Ring abduction
    ring_root1=80.0,  # Ring root
    ring_tip=80.0,  # Ring tip
    pinky_abd=80.0,  # Pinky abduction
    pinky_root1=80.0,  # Pinky root
    pinky_tip=80.0,  # Pinky tip
)
hand.speed.set_speeds(speed)

Read Speed

Blocking Read

from realhand import L20
from realhand.exceptions import TimeoutError

try:
    data = hand.speed.get_blocking(timeout_ms=500)
    print(f"Thumb abduction speed: {data.speeds.thumb_abd}")
    print(f"All speeds: {data.speeds.to_list()}")
except TimeoutError:
    print("Read timed out")

Cached Read

data = hand.speed.get_snapshot()
if data:
    print(f"Speed: {data.speeds.to_list()}")
    print(f"Timestamp: {data.timestamp}")

Streaming Read

Receive all sensor events through the top-level hand.stream() interface:

from realhand.hand.l20 import SensorSource, SpeedEvent

hand.start_polling({SensorSource.SPEED: 0.1})

try:
    for event in hand.stream():
        match event:
            case SpeedEvent(data=data):
                print(f"Speed: {data.speeds.to_list()}")
finally:
    hand.stop_polling()
    hand.stop_stream()

Complete Example

from realhand import L20
from realhand.hand.l20 import L20Speed

with L20(side="left", interface_name="can0") as hand:
    # Set speed
    speed = L20Speed(
        thumb_abd=30.0,
        thumb_yaw=30.0,
        thumb_root1=30.0,
        thumb_tip=30.0,
        index_abd=80.0,
        index_root1=80.0,
        index_tip=80.0,
        middle_abd=80.0,
        middle_root1=80.0,
        middle_tip=80.0,
        ring_abd=80.0,
        ring_root1=80.0,
        ring_tip=80.0,
        pinky_abd=80.0,
        pinky_root1=80.0,
        pinky_tip=80.0,
    )
    hand.speed.set_speeds(speed)

    # Read current speed
    data = hand.speed.get_blocking(timeout_ms=500)
    print(f"Current speed: {data.speeds.to_list()}")