Angle Control
Use hand.angle to control and read the 10 joint motor angles of the L20Lite dexterous hand.
- Angle range: 0-100
- Unit: Unitless, mapped to actual joint motor angles
Set Angles
from realhand import L20lite
from realhand.hand.l20lite import L20liteAngle
# Using a list
hand.angle.set_angles([50.0, 30.0, 60.0, 60.0, 60.0, 60.0, 20.0, 20.0, 20.0, 20.0])
# Using an L20liteAngle object
angles = L20liteAngle(
thumb_flex=50.0, # Thumb flexion
thumb_abd=30.0, # Thumb abduction
index_flex=60.0, # Index flexion
middle_flex=60.0, # Middle flexion
ring_flex=60.0, # Ring flexion
pinky_flex=60.0, # Pinky flexion
index_abd=20.0, # Index abduction
ring_abd=20.0, # Ring abduction
pinky_abd=20.0, # Pinky abduction
thumb_yaw=20.0, # Thumb rotation
)
hand.angle.set_angles(angles)
Read Angles
Blocking Read
from realhand import L20lite
from realhand.exceptions import TimeoutError
try:
data = hand.angle.get_blocking(timeout_ms=500)
print(f"Thumb flexion: {data.angles.thumb_flex}")
print(f"All angles: {data.angles.to_list()}")
except TimeoutError:
print("Read timed out")
Cached Read
data = hand.angle.get_snapshot()
if data:
print(f"Angles: {data.angles.to_list()}")
print(f"Timestamp: {data.timestamp}")
Streaming Read
Receive all sensor events through the top-level hand.stream() interface:
from realhand.hand.l20lite import SensorSource, AngleEvent
hand.start_polling({SensorSource.ANGLE: 0.1})
try:
for event in hand.stream():
match event:
case AngleEvent(data=data):
print(f"Angles: {data.angles.to_list()}")
finally:
hand.stop_polling()
hand.stop_stream()
Complete Example
from realhand import L20lite
with L20lite(side="left", interface_name="can0") as hand:
# Set angles
hand.angle.set_angles([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
# Read current angles
data = hand.angle.get_blocking(timeout_ms=500)
print(f"Current angles: {data.angles.to_list()}")
# Incremental motion
for i in range(0, 101, 10):
hand.angle.set_angles([float(i)] * 10)