Merge pull request #332 from tahsinkose/tahsin/fix-get-link-transform

Fix get_link_transform API method
This commit is contained in:
Balakumar Sundaralingam
2024-07-12 07:52:54 -07:00
committed by GitHub
2 changed files with 7 additions and 1 deletions

View File

@@ -412,7 +412,7 @@ class CudaRobotModel(CudaRobotModelConfig):
return mesh return mesh
def get_link_transform(self, link_name: str) -> Pose: def get_link_transform(self, link_name: str) -> Pose:
mat = self._kinematics_config.fixed_transforms[self._name_to_idx_map[link_name]] mat = self.kinematics_config.fixed_transforms[self.kinematics_config.link_name_to_idx_map[link_name]]
pose = Pose(position=mat[:3, 3], rotation=mat[:3, :3]) pose = Pose(position=mat[:3, 3], rotation=mat[:3, :3])
return pose return pose

View File

@@ -134,3 +134,9 @@ def test_cu_robot_batch_world_collision():
) )
assert d_world.shape[0] == b assert d_world.shape[0] == b
assert torch.sum(d_world) == 0.0 assert torch.sum(d_world) == 0.0
def test_cu_robot_get_link_transform():
model = load_robot_world()
world_T_panda_hand = model.kinematics.get_link_transform("panda_hand")
# It seems the panda hand is initialized at the origin.
assert torch.sum(world_T_panda_hand.position) == 0.0