diff --git a/README.md b/README.md index f621381..e34c0f7 100644 --- a/README.md +++ b/README.md @@ -40,7 +40,8 @@ This command will output the joint trajectory as a pickle file at the `output_pa The pickle file is a python dictionary with two keys: `meta_data` and `data`. `meta_data`, a dictionary, includes details about the robot, while `data`, a list, contains the robotic joint positions for each frame. For additional -options, refer to the help information. +options, refer to the help information. Note that the time cost here includes both the hand pose detection from video, +and the hand pose retargeting in single process mode. ```shell python3 example/detect_from_video.py --help diff --git a/dex_retargeting/configs/teleop/schunk_svh_hand_right.yml b/dex_retargeting/configs/teleop/schunk_svh_hand_right.yml index bf622e3..11a084a 100644 --- a/dex_retargeting/configs/teleop/schunk_svh_hand_right.yml +++ b/dex_retargeting/configs/teleop/schunk_svh_hand_right.yml @@ -7,7 +7,7 @@ retargeting: target_joint_names: null target_origin_link_names: [ "right_hand_base_link","right_hand_base_link", "right_hand_base_link", "right_hand_base_link", "right_hand_base_link", ] target_task_link_names: [ "right_hand_c", "right_hand_t", "right_hand_s", "right_hand_r", "right_hand_q" ] - scaling_factor: 1.1 + scaling_factor: 1.2 # Source refers to the retargeting input, which usually corresponds to the human hand # The joint indices of human hand joint which corresponds to each link in the target_link_names diff --git a/dex_retargeting/configs/teleop/schunk_svh_hand_right_dexpilot.yml b/dex_retargeting/configs/teleop/schunk_svh_hand_right_dexpilot.yml index 920dc22..b6df2b3 100644 --- a/dex_retargeting/configs/teleop/schunk_svh_hand_right_dexpilot.yml +++ b/dex_retargeting/configs/teleop/schunk_svh_hand_right_dexpilot.yml @@ -7,7 +7,7 @@ retargeting: target_joint_names: null wrist_link_name: "right_hand_base_link" finger_tip_link_names: [ "right_hand_c", "right_hand_t", "right_hand_s", "right_hand_r", "right_hand_q" ] - scaling_factor: 1.1 + scaling_factor: 1.2 # Source refers to the retargeting input, which usually corresponds to the human hand # The joint indices of human hand joint which corresponds to each link in the target_link_names