L6 Dexterous Hand
Quick Start
from realhand import L6
with L6(side="left", interface_name="can0") as hand:
# Set angles
hand.angle.set_angles((10, 20, 30, 40, 50, 60))
# 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
| Index | Name | Identifier |
|---|---|---|
| 0 | Thumb flexion | thumb_flex |
| 1 | Thumb abduction | thumb_abd |
| 2 | Index finger | index |
| 3 | Middle finger | middle |
| 4 | Ring finger | ring |
| 5 | Pinky | pinky |
Functional Modules
| Module | Description | Docs |
|---|---|---|
hand.angle | Joint angle control and read | angle |
hand.speed | Motion speed control | speed |
hand.torque | Torque control | torque |
hand.force_sensor | Force sensor data | force-sensor |
hand.temperature | Temperature monitoring | temperature |
hand.current | Current monitoring | current |
hand.fault | Fault detection and clearing | fault |
hand.version | Device version information | version |
Unified Streaming Reads
L6 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 L6
from realhand.hand.l6 import SensorSource, AngleEvent, TemperatureEvent
with L6(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
| Value | Description | Default rate |
|---|---|---|
SensorSource.ANGLE | Angles | 60 Hz |
SensorSource.TORQUE | Torque | Not polled by default |
SensorSource.TEMPERATURE | Temperature | Not polled by default |
SensorSource.CURRENT | Current | 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.temperature) # TemperatureData | None