File size: 2,159 Bytes
599da71 |
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 |
left:
type: vector
urdf_path: unitree_hand/unitree_dex3_left.urdf
# Target refers to the retargeting target, which is the robot hand
# target_joint_names:
target_joint_names:
[
"left_hand_thumb_0_joint",
"left_hand_thumb_1_joint",
"left_hand_thumb_2_joint",
"left_hand_middle_0_joint",
"left_hand_middle_1_joint",
"left_hand_index_0_joint",
"left_hand_index_1_joint",
]
wrist_link_name: None
target_origin_link_names: ["base_link_thumb","base_link_index","base_link_middle"]
target_task_link_names: ["thumb_tip","index_tip","middle_tip"]
target_link_human_indices: [[0, 0, 0], [4, 9, 14]]
# Currently, the scaling factor for each finger is individually distinguished in the robot_hand_unitree.py file.
# The Unitree Dex3 has three fingers with the same specifications, so the retarget scaling factors need to be adjusted separately.
# The relevant code is as follows:
# ref_left_value[0] = ref_left_value[0] * 1.15
# ref_left_value[1] = ref_left_value[1] * 1.05
# ref_left_value[2] = ref_left_value[2] * 0.95
# ref_right_value[0] = ref_right_value[0] * 1.15
# ref_right_value[1] = ref_right_value[1] * 1.05
# ref_right_value[2] = ref_right_value[2] * 0.95
scaling_factor: 1.0
# A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
low_pass_alpha: 0.2
right:
type: vector
urdf_path: unitree_hand/unitree_dex3_right.urdf
# Target refers to the retargeting target, which is the robot hand
target_joint_names:
[
"right_hand_thumb_0_joint",
"right_hand_thumb_1_joint",
"right_hand_thumb_2_joint",
"right_hand_index_0_joint",
"right_hand_index_1_joint",
"right_hand_middle_0_joint",
"right_hand_middle_1_joint",
]
wrist_link_name: None
target_origin_link_names: ["base_link_thumb","base_link_index","base_link_middle"]
target_task_link_names: ["thumb_tip", "index_tip", "middle_tip"]
target_link_human_indices: [[0, 0, 0], [4, 9, 14]]
scaling_factor: 1.0
# A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
low_pass_alpha: 0.2
|