@ -114,14 +114,16 @@ KD = [
1 , 1 , 1 , 1 , 1 , 1 , 1 ,
1 , 1 , 1 , 1 , 1 , 1 , 1 ,
]
]
# Inspire hand normalization ranges
# Inspire hand normalization ranges (min=closed fist, max=open hand)
# Inspire convention: 0.0=closed, 1.0=open
# Calibrated from dex-retargeting output with Quest 3 XRHandTracker
INSPIRE_RANGES = [
INSPIRE_RANGES = [
( 0.0 , 1.7 ) , # finger flexion
( 0.0 , 1.7 ) ,
( 0.0 , 1.7 ) ,
( 0.0 , 1.7 ) ,
( 0.0 , 0.5 ) , # thumb pitch
( - 0.1 , 1.3 ) , # thumb yaw
( 0.4 , 1.7 ) , # pinky flexion
( 0.4 , 1.7 ) , # ring flexion
( 0.4 , 1.7 ) , # middle flexion
( 0.4 , 1.7 ) , # index flexion
( 0.2 , 0.5 ) , # thumb pitch
( 0.8 , 1.3 ) , # thumb yaw
]
]
# Body joint indices in shared memory (8 joints x 7 floats = 56)
# Body joint indices in shared memory (8 joints x 7 floats = 56)
@ -567,17 +569,19 @@ def retarget_hands(left_retargeting, right_retargeting,
ref_value = left_hand_pos [ left_indices [ 1 , : ] ] - left_hand_pos [ left_indices [ 0 , : ] ]
ref_value = left_hand_pos [ left_indices [ 1 , : ] ] - left_hand_pos [ left_indices [ 0 , : ] ]
q_rad = left_retargeting . retarget ( ref_value )
q_rad = left_retargeting . retarget ( ref_value )
q_hw = q_rad [ left_hw_map ]
q_hw = q_rad [ left_hw_map ]
retarget_hands . _last_q_hw_l = q_hw . copy ( )
for idx in range ( 6 ) :
for idx in range ( 6 ) :
min_val , max_val = INSPIRE_RANGES [ idx ]
min_val , max_val = INSPIRE_RANGES [ idx ]
hand_cmd [ 6 + idx ] = np . clip ( ( max_val - q_hw [ idx ] ) / ( max_val - min_val ) , 0.0 , 1.0 )
hand_cmd [ 6 + idx ] = np . clip ( ( q_hw [ idx ] - min_val ) / ( max_val - min_val ) , 0.0 , 1.0 )
if right_valid :
if right_valid :
ref_value = right_hand_pos [ right_indices [ 1 , : ] ] - right_hand_pos [ right_indices [ 0 , : ] ]
ref_value = right_hand_pos [ right_indices [ 1 , : ] ] - right_hand_pos [ right_indices [ 0 , : ] ]
q_rad = right_retargeting . retarget ( ref_value )
q_rad = right_retargeting . retarget ( ref_value )
q_hw = q_rad [ right_hw_map ]
q_hw = q_rad [ right_hw_map ]
retarget_hands . _last_q_hw_r = q_hw . copy ( )
for idx in range ( 6 ) :
for idx in range ( 6 ) :
min_val , max_val = INSPIRE_RANGES [ idx ]
min_val , max_val = INSPIRE_RANGES [ idx ]
hand_cmd [ idx ] = np . clip ( ( max_val - q_hw [ idx ] ) / ( max_val - min_val ) , 0.0 , 1.0 )
hand_cmd [ idx ] = np . clip ( ( q_hw [ idx ] - min_val ) / ( max_val - min_val ) , 0.0 , 1.0 )
return hand_cmd
return hand_cmd
@ -825,6 +829,12 @@ def main():
if step_count % 250 == 0 :
if step_count % 250 == 0 :
np . set_printoptions ( precision = 2 , suppress = True )
np . set_printoptions ( precision = 2 , suppress = True )
logger . info ( f " [HAND OUT] R=[{current_hands[0]:.2f},{current_hands[1]:.2f},{current_hands[2]:.2f},{current_hands[3]:.2f},{current_hands[4]:.2f},{current_hands[5]:.2f}] L=[{current_hands[6]:.2f},{current_hands[7]:.2f},{current_hands[8]:.2f},{current_hands[9]:.2f},{current_hands[10]:.2f},{current_hands[11]:.2f}] " )
logger . info ( f " [HAND OUT] R=[{current_hands[0]:.2f},{current_hands[1]:.2f},{current_hands[2]:.2f},{current_hands[3]:.2f},{current_hands[4]:.2f},{current_hands[5]:.2f}] L=[{current_hands[6]:.2f},{current_hands[7]:.2f},{current_hands[8]:.2f},{current_hands[9]:.2f},{current_hands[10]:.2f},{current_hands[11]:.2f}] " )
if step_count % 250 == 0 and hasattr ( retarget_hands , ' _last_q_hw_r ' ) :
q = retarget_hands . _last_q_hw_r
logger . info ( f " [HAND RAW] R_q_hw=[{q[0]:.3f},{q[1]:.3f},{q[2]:.3f},{q[3]:.3f},{q[4]:.3f},{q[5]:.3f}] " )
if step_count % 250 == 0 and hasattr ( retarget_hands , ' _last_q_hw_l ' ) :
q = retarget_hands . _last_q_hw_l
logger . info ( f " [HAND RAW] L_q_hw=[{q[0]:.3f},{q[1]:.3f},{q[2]:.3f},{q[3]:.3f},{q[4]:.3f},{q[5]:.3f}] " )
except Exception as e :
except Exception as e :
logger . warning ( f " Hand retarget failed: {e} " )
logger . warning ( f " Hand retarget failed: {e} " )