Angle Control
Use hand.angle to control and read the 16 joint motor angles of the L20 dexterous hand.
- Angle range: 0-100
- Unit: Unitless, mapped to actual joint motor angles
Set Angles
from realhand import L20
from realhand.hand.l20 import L20Angle
# Using a list (16 joints)
hand.angle.set_angles([50.0] * 16)
# Using an L20Angle object
angles = L20Angle(
thumb_abd=50.0, # Thumb abduction
thumb_yaw=30.0, # Thumb rotation
thumb_root1=60.0, # Thumb root
thumb_tip=40.0, # Thumb tip
index_abd=50.0, # Index abduction
index_root1=60.0, # Index root
index_tip=40.0, # Index tip
middle_abd=50.0, # Middle abduction
middle_root1=60.0, # Middle root
middle_tip=40.0, # Middle tip
ring_abd=50.0, # Ring abduction
ring_root1=60.0, # Ring root
ring_tip=40.0, # Ring tip
pinky_abd=50.0, # Pinky abduction
pinky_root1=60.0, # Pinky root
pinky_tip=40.0, # Pinky tip
)
hand.angle.set_angles(angles)
Read Angles
Blocking Read
from realhand import L20
from realhand.exceptions import TimeoutError
try:
data = hand.angle.get_blocking(timeout_ms=500)
print(f"Thumb abduction: {data.angles.thumb_abd}")
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.l20 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 L20
with L20(side="left", interface_name="can0") as hand:
# Set angles
hand.angle.set_angles([0.0] * 16)
# 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)] * 16)