[Bug Report] Issue with DifferentialIKController Not Working After Adding rot to InitialStateCfg #1433
Open
2 of 4 tasks
Labels
bug
Something isn't working
Describe the bug
I've encountered an issue where the IK controller stops working after adding the rot attribute to InitialStateCfg when setting up DifferentialIKController. Based on the question in IsaacLab Issue #1350
Steps to reproduce
After adding the rot attribute to the initialstatecfg of the differentialikcontroller, the IK controller fails to function correctly. Adding fix_root_link=True to ArticulationRootPropertiesCfg also does not resolve the issue. There are no errors reported in the terminal. Below is my code
`
#function to get target position and rotation
def get_local_transform_xform(prim: Usd.Prim) -> typing.Tuple[Gf.Vec3d, Gf.Rotation]:#, Gf.Vec3d]:
xform = UsdGeom.Xformable(prim)
local_transformation: Gf.Matrix4d = xform.GetLocalTransformation()
translation: Gf.Vec3d = local_transformation.ExtractTranslation()
rotation: Gf.Rotation = local_transformation.ExtractRotation()
#scale: Gf.Vec3d = Gf.Vec3d(*(v.GetLength() for v in local_transformation.ExtractRotationMatrix()))
return translation, rotation#, scale
#ik target asset config
target2 = AssetBaseCfg(
prim_path="{ENV_REGEX_NS}/hsrTarget",
spawn=sim_utils.UsdFileCfg(usd_path="C:/Users/Administrator/IsaacLab/source/standalone/mydemo/data/frame_prim.usd",
visible=True,collision_props=CollisionPropertiesCfg(collision_enabled=False), scale=(0.07, 0.07, 0.07)),
init_state=AssetBaseCfg.InitialStateCfg(pos=( 1, 3.5, 1),rot=(0,-7.07,-0.707,0)),
debug_vis=True
)
#robot config
robot2 = HSR2_CFG.replace(prim_path="{ENV_REGEX_NS}/HSR1",
init_state=ArticulationCfg.InitialStateCfg(pos=(1,3.5,0),rot=(0.707,0,0,0.707),
joint_pos={"carriage": 0.0,"joint1": 0.0,"joint2": 0.0,"joint3": 0.0,"joint4": 0.0,
"joint5": 1.57,"joint6": 0.0,"hsr_finger1": 0.0,"hsr_finger2": 0.0,},
joint_vel={"carriage":0.5}
))
#Code Outside the while simulation_app.is_running(): Loop:
robot2= scene["robot2"]
diff_ik_cfg2 = DifferentialIKControllerCfg(command_type="pose", use_relative_mode=False, ik_method="dls")
diff_ik_controller2 = DifferentialIKController(diff_ik_cfg2, num_envs=scene.num_envs, device=sim.device)
frame_marker_cfg2 = VisualizationMarkersCfg(
markers={"frame2": sim_utils.UsdFileCfg(
usd_path="C:/Users/Administrator/IsaacLab/source/standalone/mydemo/data/frame_prim.usd",
scale=(0.5, 0.5, 0.5), )})
frame_marker_cfg2.markers["frame2"].scale = (0.07, 0.07, 0.07)
ee_marker2 = VisualizationMarkers(frame_marker_cfg2.replace(prim_path="/Visuals/ee_current2"))
goal_marker2 = VisualizationMarkers(frame_marker_cfg2.replace(prim_path="/Visuals/ee_goal2"))
ik_commands2 = torch.zeros(scene.num_envs, diff_ik_controller2.action_dim, device=robot2.device)
robot_entity_cfg2 = SceneEntityCfg("robot2", joint_names=["carriage","joint.*"], body_names=["gripcenter"])
robot_entity_cfg2.resolve(scene)
ee_jacobi_idx2 = robot_entity_cfg2.body_ids[0] - 1
joint_pos2 = robot2.data.default_joint_pos.clone()
joint_vel2 = robot2.data.default_joint_vel.clone()
robot2.write_joint_state_to_sim(joint_pos2, joint_vel2)
#Code Inside the Loop:
jacobian2 = robot2.root_physx_view.get_jacobians()[:, ee_jacobi_idx2, :, robot_entity_cfg2.joint_ids]
ee_pose_w2 = robot2.data.body_state_w[:, robot_entity_cfg2.body_ids[0], 0:7]
root_pose_w2 = robot2.data.root_state_w[:, 0:7]
joint_pos2 = robot2.data.joint_pos[:, robot_entity_cfg2.joint_ids]
translation2, rotation2 =get_local_transform_xform (sim_utils.utils.find_first_matching_prim("/World/envs/env_0/hsrTarget"))
target_tensor2 = torch.tensor([translation2[0]-1, translation2[1]-3.5, translation2[2],rotation2.GetQuat().GetReal(),
rotation2.GetQuat().GetImaginary()[0], rotation2.GetQuat().GetImaginary()[1],
rotation2.GetQuat().GetImaginary()[2]], device=sim.device)
ee_pos_b2, ee_quat_b2 = subtract_frame_transforms(root_pose_w2[:, 0:3], root_pose_w2[:, 3:7], ee_pose_w2[:, 0:3],
ee_pose_w2[:, 3:7])
joint_pos_des2= joint_pos2[:, robot_entity_cfg2.joint_ids].clone()
ik_commands2[:] = target_tensor2
diff_ik_controller2.reset()
diff_ik_controller2.set_command(ik_commands2)
robot2.reset()
joint_pos_des2 = diff_ik_controller2.compute(ee_pos_b2, ee_quat_b2, jacobian2, joint_pos2)
robot2.set_joint_position_target(joint_pos_des2, joint_ids=robot_entity_cfg2.joint_ids)
ee_marker2.visualize(ee_pose_w2[:, 0:3], ee_pose_w2[:, 3:7])
goal_marker2.visualize(ik_commands2[:, 0:3] + scene.env_origins+root_pose_w2[:, 0:3], ik_commands2[:, 3:7])
`
With rot:
Without rot:
There is still a bug in asset display. It returns to normal after moving the asset.
System Info
Describe the characteristic of your environment:
Additional context
Add any other context about the problem here.
Checklist
Acceptance Criteria
Add the criteria for which this task is considered done. If not known at issue creation time, you can add this once the issue is assigned.
The text was updated successfully, but these errors were encountered: