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

L20Lite Dexterous Hand

Quick Start

from realhand import L20lite

with L20lite(side="left", interface_name="can0") as hand:
    # Set angles
    hand.angle.set_angles([50, 30, 60, 60, 60, 60, 20, 20, 20, 20])

    # Read angles
    data = hand.angle.get_blocking(timeout_ms=500)
    print(data.angles)

Constructor parameters

ParameterTypeDescription
side"left" | "right"Left hand or right hand
interface_namestrCAN interface name, such as "can0"
interface_typestrCAN interface type, default "socketcan". See CAN Bus for Windows usage

Joint Definition

IndexNameIdentifier
0Thumb flexionthumb_flex
1Thumb abductionthumb_abd
2Index flexionindex_flex
3Middle flexionmiddle_flex
4Ring flexionring_flex
5Pinky flexionpinky_flex
6Index abductionindex_abd
7Ring abductionring_abd
8Pinky abductionpinky_abd
9Thumb rotationthumb_yaw

Functional Modules

ModuleDescription
hand.angleJoint angle control and read
hand.speedSpeed control and read
hand.torqueTorque control and read
hand.temperatureTemperature reading
hand.force_sensorForce sensor data
hand.faultFault reading
hand.versionDevice version information

Unified Streaming Reads

L20Lite provides a unified event stream interface. Use hand.stream() and hand.start_polling() to retrieve data from all sensors. Polling starts automatically at initialization using default intervals (angles at 60 Hz, force sensors at 30 Hz), so you do not need to call start_polling() manually.

from realhand import L20lite
from realhand.hand.l20lite import SensorSource, AngleEvent, TemperatureEvent

with L20lite(side="left", interface_name="can0") as hand:
    # You can set multiple sensors and polling intervals (seconds)
    # Calling start_polling() again overrides the previous settings
    hand.start_polling({SensorSource.ANGLE: 0.05, SensorSource.TEMPERATURE: 1.0})

    for event in hand.stream():
        match event:
            case AngleEvent(data=ad):
                print(f"Angles: {ad.angles.to_list()}")
            case TemperatureEvent(data=td):
                print(f"Temperature: {td.temperatures.to_list()}")

    hand.stop_polling()
    hand.stop_stream()

Available SensorSource values and default rates

ValueDescriptionDefault rate
SensorSource.ANGLEAngles60 Hz
SensorSource.SPEEDSpeedNot polled by default
SensorSource.TORQUETorqueNot polled by default
SensorSource.TEMPERATURETemperatureNot polled by default
SensorSource.FORCE_SENSORForce sensors30 Hz

Snapshot

Get the latest cached data from all sensors:

snap = hand.get_snapshot()
print(snap.angle)  # AngleData | None
print(snap.speed)  # SpeedData | None
print(snap.torque)  # TorqueData | None
print(snap.temperature)  # TemperatureData | None
print(snap.force_sensor)  # AllFingersData | None