You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
61 lines
2.7 KiB
61 lines
2.7 KiB
left:
|
|
type: DexPilot # or vector
|
|
urdf_path: brainco_hand/brainco_left.urdf
|
|
|
|
# Target refers to the retargeting target, which is the robot hand
|
|
target_joint_names:
|
|
[
|
|
"left_thumb_metacarpal_joint",
|
|
"left_thumb_proximal_joint",
|
|
"left_index_proximal_joint",
|
|
"left_middle_proximal_joint",
|
|
"left_ring_proximal_joint",
|
|
"left_pinky_proximal_joint",
|
|
]
|
|
|
|
# for DexPilot type
|
|
wrist_link_name: "base_link"
|
|
finger_tip_link_names: [ "left_thumb_tip", "left_index_tip", "left_middle_tip", "left_ring_tip", "left_pinky_tip" ]
|
|
# If you do not know exactly how it is used, please leave it to None for default.
|
|
target_link_human_indices_dexpilot: [[ 9, 14, 19, 24, 14, 19, 24, 19, 24, 24, 0, 0, 0, 0, 0], [ 4, 4, 4, 4, 9, 9, 9, 14, 14, 19, 4, 9, 14, 19, 24]]
|
|
|
|
# for vector type
|
|
target_origin_link_names: ["base_link", "base_link", "base_link", "base_link", "base_link"]
|
|
target_task_link_names: [ "left_thumb_tip", "left_index_tip", "left_middle_tip", "left_ring_tip", "left_pinky_tip" ]
|
|
target_link_human_indices_vector: [ [ 0, 0, 0, 0, 0 ], [ 4, 9, 14, 19, 24 ] ]
|
|
|
|
# Scaling factor for vector retargeting only
|
|
# For example, Allegro is 1.6 times larger than normal human hand, then this scaling factor should be 1.6
|
|
scaling_factor: 1.00
|
|
# A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
|
|
low_pass_alpha: 0.2
|
|
|
|
right:
|
|
type: DexPilot # or vector
|
|
urdf_path: brainco_hand/brainco_right.urdf
|
|
|
|
# Target refers to the retargeting target, which is the robot hand
|
|
target_joint_names:
|
|
[
|
|
"right_thumb_metacarpal_joint",
|
|
"right_thumb_proximal_joint",
|
|
"right_index_proximal_joint",
|
|
"right_middle_proximal_joint",
|
|
"right_ring_proximal_joint",
|
|
"right_pinky_proximal_joint",
|
|
]
|
|
# for DexPilot type
|
|
wrist_link_name: "base_link"
|
|
finger_tip_link_names: [ "right_thumb_tip", "right_index_tip", "right_middle_tip", "right_ring_tip", "right_pinky_tip" ]
|
|
target_link_human_indices_dexpilot: [[ 9, 14, 19, 24, 14, 19, 24, 19, 24, 24, 0, 0, 0, 0, 0], [ 4, 4, 4, 4, 9, 9, 9, 14, 14, 19, 4, 9, 14, 19, 24]]
|
|
|
|
# for vector type
|
|
target_origin_link_names: ["base_link", "base_link", "base_link", "base_link", "base_link"]
|
|
target_task_link_names: [ "right_thumb_tip", "right_index_tip", "right_middle_tip", "right_ring_tip", "right_pinky_tip" ]
|
|
target_link_human_indices_vector: [ [ 0, 0, 0, 0, 0 ], [ 4, 9, 14, 19, 24 ] ]
|
|
|
|
# Scaling factor for vector retargeting only
|
|
# For example, Allegro is 1.6 times larger than normal human hand, then this scaling factor should be 1.6
|
|
scaling_factor: 1.00
|
|
# A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
|
|
low_pass_alpha: 0.2
|