L20 Dexterous Hand
Quick Start
from realhand import L20
with L20(side="left", interface_name="can0") as hand:
# Set angles
hand.angle.set_angles([50.0] * 16)
# Read angles
data = hand.angle.get_blocking(timeout_ms=500)
print(data.angles)
Constructor parameters
| Parameter | Type | Description |
|---|---|---|
side | "left" | "right" | Left hand or right hand |
interface_name | str | CAN interface name, such as "can0" |
interface_type | str | CAN interface type, default "socketcan". See CAN Bus for Windows usage |
Joint Definition
L20 has 16 degrees of freedom distributed across 5 fingers.
| Index | Name | Identifier |
|---|---|---|
| 0 | Thumb abduction | thumb_abd |
| 1 | Thumb rotation | thumb_yaw |
| 2 | Thumb root | thumb_root1 |
| 3 | Thumb tip | thumb_tip |
| 4 | Index abduction | index_abd |
| 5 | Index root | index_root1 |
| 6 | Index tip | index_tip |
| 7 | Middle abduction | middle_abd |
| 8 | Middle root | middle_root1 |
| 9 | Middle tip | middle_tip |
| 10 | Ring abduction | ring_abd |
| 11 | Ring root | ring_root1 |
| 12 | Ring tip | ring_tip |
| 13 | Pinky abduction | pinky_abd |
| 14 | Pinky root | pinky_root1 |
| 15 | Pinky tip | pinky_tip |
Functional Modules
| Module | Description |
|---|---|
hand.angle | Joint angle control and read |
hand.speed | Speed control and read |
hand.torque | Torque control and read |
hand.temperature | Temperature reading |
hand.force_sensor | Force sensor data |
hand.fault | Fault reading and clearing |
hand.version | Device version information |
Unified Streaming Reads
L20 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 L20
from realhand.hand.l20 import SensorSource, AngleEvent, TemperatureEvent
with L20(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()
start_polling parameter
| Parameter | Type | Default | Description |
|---|---|---|---|
intervals | dict[SensorSource, float] | All defaults | Polling interval in seconds per sensor |
Available SensorSource values and default rates
| Value | Description | Default rate |
|---|---|---|
SensorSource.ANGLE | Angles | 60 Hz |
SensorSource.SPEED | Speed | Not polled by default |
SensorSource.TORQUE | Torque | Not polled by default |
SensorSource.TEMPERATURE | Temperature | Not polled by default |
SensorSource.FAULT | Fault | Not polled by default |
SensorSource.FORCE_SENSOR | Force sensors | 30 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.fault) # FaultData | None
print(snap.force_sensor) # AllFingersData | None