Skip to content

Commit

Permalink
[update] update test function to support panda gripper
Browse files Browse the repository at this point in the history
  • Loading branch information
Dingry committed Jul 19, 2024
1 parent e58b877 commit 07ab762
Showing 1 changed file with 15 additions and 3 deletions.
18 changes: 15 additions & 3 deletions tests/test_optimizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,10 @@ def generate_position_retargeting_data_gt(robot: RobotWrapper, optimizer: Positi
def test_position_optimizer(self, robot_name, hand_type):
config_path = get_default_config_path(robot_name, RetargetingType.position, hand_type)

if not config_path.exists():
print(f"Skip the test for {robot_name.name} as the config file does not exist.")
return

# Note: The parameters below are adjusted solely for this test
# The smoothness penalty is deactivated here, meaning no low pass filter and no continuous joint value
# This is because the test is focused solely on the efficiency of single step optimization
Expand Down Expand Up @@ -97,7 +101,7 @@ def test_position_optimizer(self, robot_name, hand_type):
computed_target_pos = np.array([robot.get_link_pose(i)[:3, 3] for i in optimizer.target_link_indices])

# Position difference
error = np.mean(np.linalg.norm(computed_target_pos - random_target_pos, axis=1))
error = np.mean(np.linalg.norm(computed_target_pos - random_target_pos, axis=-1))
errors["pos"].append(error)

tac = time()
Expand All @@ -110,6 +114,10 @@ def test_position_optimizer(self, robot_name, hand_type):
def test_vector_optimizer(self, robot_name, hand_type):
config_path = get_default_config_path(robot_name, RetargetingType.vector, hand_type)

if not config_path.exists():
print(f"Skip the test for {robot_name.name} as the config file does not exist.")
return

# Note: The parameters below are adjusted solely for this test
# For retargeting from human to robot, their values should remain the default in the retargeting config
# The smoothness penalty is deactivated here, meaning no low pass filter and no continuous joint value
Expand Down Expand Up @@ -146,7 +154,7 @@ def test_vector_optimizer(self, robot_name, hand_type):
computed_target_vector = computed_task_pos - computed_origin_pos

# Vector difference
error = np.mean(np.linalg.norm(computed_target_vector - random_target_vector, axis=1))
error = np.mean(np.linalg.norm(computed_target_vector - random_target_vector, axis=-1))
errors["pos"].append(error)

tac = time()
Expand All @@ -159,6 +167,10 @@ def test_vector_optimizer(self, robot_name, hand_type):
def test_dexpilot_optimizer(self, robot_name, hand_type):
config_path = get_default_config_path(robot_name, RetargetingType.dexpilot, hand_type)

if not config_path.exists():
print(f"Skip the test for {robot_name.name} as the config file does not exist.")
return

# Note: The parameters below are adjusted solely for this test
# For retargeting from human to robot, their values should remain the default in the retargeting config
# The smoothness penalty is deactivated here, meaning no low pass filter and no continuous joint value
Expand Down Expand Up @@ -194,7 +206,7 @@ def test_dexpilot_optimizer(self, robot_name, hand_type):
computed_target_vector = computed_task_pos - computed_origin_pos

# Vector difference
error = np.mean(np.linalg.norm(computed_target_vector - random_target_vector, axis=1))
error = np.mean(np.linalg.norm(computed_target_vector - random_target_vector, axis=-1))
errors["pos"].append(error)

tac = time()
Expand Down

0 comments on commit 07ab762

Please sign in to comment.