|
| 1 | +import numpy as np |
| 2 | +import pytest |
| 3 | + |
| 4 | +import rcs |
| 5 | +from rcs import common |
| 6 | + |
| 7 | +# Map robot types to their end-effector frame names |
| 8 | +ROBOT_FRAME_IDS = { |
| 9 | + common.RobotType.FR3: "attachment_site_0", |
| 10 | + common.RobotType.Panda: "attachment_site_0", |
| 11 | + common.RobotType.XArm7: "attachment_site", |
| 12 | + common.RobotType.SO101: "gripper", |
| 13 | + common.RobotType.UR5e: "attachment_site", |
| 14 | +} |
| 15 | + |
| 16 | + |
| 17 | +# only for scene that have empty_world in key |
| 18 | +@pytest.mark.parametrize("scene_name", [k for k in rcs.scenes if "empty_world" in k]) |
| 19 | +def test_kinematics_identity(scene_name): |
| 20 | + scene = rcs.scenes[scene_name] |
| 21 | + |
| 22 | + # Determine model path and type |
| 23 | + model_path = scene.mjcf_robot |
| 24 | + |
| 25 | + # Get frame ID |
| 26 | + if scene.robot_type not in ROBOT_FRAME_IDS: |
| 27 | + pytest.skip(f"Frame ID not defined for robot type {scene.robot_type}") |
| 28 | + |
| 29 | + frame_id = ROBOT_FRAME_IDS[scene.robot_type] |
| 30 | + |
| 31 | + # Initialize Pinocchio interface |
| 32 | + try: |
| 33 | + pin = common.Pin(model_path, frame_id, False) |
| 34 | + except Exception as e: |
| 35 | + pytest.fail(f"Failed to initialize Pin for {scene_name}: {e}") |
| 36 | + |
| 37 | + # Get home configuration |
| 38 | + try: |
| 39 | + meta_config = common.robots_meta_config(scene.robot_type) |
| 40 | + q_home = meta_config.q_home |
| 41 | + except Exception as e: |
| 42 | + pytest.fail(f"Failed to get meta config for {scene_name}: {e}") |
| 43 | + |
| 44 | + # Test 1: FK at home |
| 45 | + # Identity pose (no TCP offset) |
| 46 | + tcp_offset = common.Pose() |
| 47 | + |
| 48 | + pose_home = pin.forward(q_home, tcp_offset) |
| 49 | + assert isinstance(pose_home, common.Pose) |
| 50 | + |
| 51 | + # Test 2: IK at home pose should return a solution (ideally close to q_home, but IK is redundant) |
| 52 | + # We use q_home as initial guess |
| 53 | + q_sol = pin.inverse(pose_home, q_home, tcp_offset) |
| 54 | + |
| 55 | + assert q_sol is not None, "IK failed for home pose" |
| 56 | + |
| 57 | + # Verify the solution with FK |
| 58 | + pose_sol = pin.forward(q_sol, tcp_offset) |
| 59 | + |
| 60 | + # Check if pose_sol is close to pose_home |
| 61 | + assert pose_sol.is_close( |
| 62 | + pose_home, eps_r=1e-4, eps_t=1e-4 |
| 63 | + ), f"FK(IK(pose)) does not match pose.\nOriginal: {pose_home}\nResult: {pose_sol}" |
| 64 | + |
| 65 | + # Test 3: Perturbed configuration |
| 66 | + # Add small noise to q_home to test non-trivial pose |
| 67 | + # Ensure we stay within limits if possible, but for small noise it should be fine |
| 68 | + np.random.seed(42) |
| 69 | + q_perturbed = q_home + np.random.uniform(-0.1, 0.1, size=q_home.shape) |
| 70 | + |
| 71 | + pose_perturbed = pin.forward(q_perturbed, tcp_offset) # type: ignore |
| 72 | + q_sol_perturbed = pin.inverse(pose_perturbed, q_home, tcp_offset) # Use q_home as seed |
| 73 | + |
| 74 | + assert q_sol_perturbed is not None, "IK failed for perturbed pose" |
| 75 | + |
| 76 | + pose_sol_perturbed = pin.forward(q_sol_perturbed, tcp_offset) |
| 77 | + assert pose_sol_perturbed.is_close( |
| 78 | + pose_perturbed, eps_r=1e-3, eps_t=1e-3 |
| 79 | + ), f"FK(IK(perturbed_pose)) does not match.\nOriginal: {pose_perturbed}\nResult: {pose_sol_perturbed}" |
0 commit comments