Torque Control
Overview
Use hand.torque for torque control. It supports setting target torque values and reading the current torque.
Torque values range from 0-100 (unitless, representing the relative torque percentage of the joint motors) for the 6 joint motors of the L6 dexterous hand:
| Index | Field | Joint |
|---|---|---|
| 0 | thumb_flex | Thumb flexion |
| 1 | thumb_abd | Thumb abduction |
| 2 | index | Index finger |
| 3 | middle | Middle finger |
| 4 | ring | Ring finger |
| 5 | pinky | Pinky |
Set Torque
# Using a list
hand.torque.set_torques([50.0, 30.0, 60.0, 60.0, 60.0, 60.0])
# Using an L6Torque object
from realhand.hand.l6 import L6Torque
target = L6Torque(
thumb_flex=50.0, thumb_abd=30.0, index=60.0, middle=60.0, ring=60.0, pinky=60.0
)
hand.torque.set_torques(target)
Read Torque
Blocking Read
Send a request and wait for the response:
from realhand.exceptions import TimeoutError
try:
data = hand.torque.get_blocking(timeout_ms=500)
print(f"Thumb flexion: {data.torques.thumb_flex}")
print(f"Index finger: {data.torques.index}")
except TimeoutError:
print("Read timed out")
Cached Read
Get the most recent cached value without blocking:
data = hand.torque.get_snapshot()
if data:
print(f"Torque: {data.torques.to_list()}")
Streaming Read
Receive all sensor events through the top-level hand.stream() interface:
from realhand.hand.l6 import SensorSource, TorqueEvent
hand.start_polling({SensorSource.TORQUE: 0.05})
for event in hand.stream():
match event:
case TorqueEvent(data=data):
print(f"Torque: {data.torques.to_list()}")
hand.stop_polling()
hand.stop_stream()
Examples
Full Control Flow
from realhand import L6
from realhand.hand.l6 import L6Torque
with L6(side="left", interface_name="can0") as hand:
# Set torque
hand.torque.set_torques([50.0, 30.0, 60.0, 60.0, 60.0, 60.0])
# Blocking read of current torque
data = hand.torque.get_blocking(timeout_ms=200)
print(f"Current torque: {data.torques.to_list()}")
Real-Time Monitoring
from realhand import L6
from realhand.hand.l6 import SensorSource, TorqueEvent
with L6(side="left", interface_name="can0") as hand:
hand.start_polling({SensorSource.TORQUE: 0.1})
try:
for event in hand.stream():
match event:
case TorqueEvent(data=data):
if data.torques.index > 80:
print("Index joint motor torque is too high")
break
finally:
hand.stop_polling()
hand.stop_stream()