Attach Robotiq 2f140 gripper to Kuka LBR IIWA robot using program or robot assembler API issue

Hello,
I am trying to attach a Robotiq2f140 gripper asset to a Kuka iiwa robot arm using the robot assembler from the following tutorial. Link here

The gripper is getting attached to the robot end effector as shown in the image and I am saving it as an USD.

But I am getting a missing references error in the console. Also if I try to programitaclly control the robot using a Robot class that I write myself. I am facing issues while adding the saved USD to the world.


import carb
from typing import Optional
import numpy as np

from omni.isaac.core.prims import XFormPrim
from omni.isaac.core.utils.types import ArticulationAction
from omni.isaac.core.robots.robot import Robot
from omni.isaac.core.utils.prims import get_prim_at_path, define_prim
from omni.isaac.core.utils.stage import add_reference_to_stage
from omni.isaac.core.prims.rigid_prim import RigidPrim


class IIWA14(Robot):
    def __init__(self,
                 prim_path : str,
                 usd_path: str,
                 name : Optional[str],
                 end_effector_name: str,
                 position: Optional[np.ndarray] = None,
                 orientation: Optional[np.ndarray] = None,          
    ) -> None:
        add_reference_to_stage(usd_path, prim_path)
        Robot.__init__(self,prim_path=prim_path, name=name, position=position, orientation=orientation, articulation_controller=None)
        # self._gripper_joint_names = ["finger_joint",
        #                         "left_inner_knuckle_joint",
        #                         "right_inner_knuckle_joint",
        #                         "right_outer_knuckle_joint",
        #                         "left_inner_finger_joint",
        #                         "right_inner_finger_joint"]

        self._arm_joint_names = ["iiwa14_joint_1",
                            "iiwa14_joint_2",
                            "iiwa14_joint_3",
                            "iiwa14_joint_4",
                            "iiwa14_joint_5",
                            "iiwa14_joint_6",
                            "iiwa14_joint_7"]


        
        self._arm_dof_idxs = []
        self._gripper_dof_idxs = []

        self._num_dof = len(self._arm_joint_names)  #len(self._gripper_joint_names)
        self._end_effector_prim_path = prim_path + '/' + end_effector_name
        self._base_link_prim_path = prim_path + '/' + 'iiwa14_base_link'



        self.gain_kp = {
            "iiwa14_joint_1": 572957824.0000,
            "iiwa14_joint_2": 572957824.0000,
            "iiwa14_joint_3": 572957824.0000,
            "iiwa14_joint_4": 572957824.0000,
            "iiwa14_joint_5": 572957824.0000,
            "iiwa14_joint_6": 572957824.0000,
            "iiwa14_joint_7": 572957824.0000,
            "finger_joint":572957824.0000,
            "left_inner_knuckle_joint":572957824.0000,
            "right_inner_knuckle_joint":572957824.0000,
            "right_outer_knuckle_joint":572957824.0000,
            "left_inner_finger_joint":572957824.0000,
            "right_inner_finger_joint":572957824.0000,
        }






        self.gain_kd = {
            "iiwa14_joint_1": 5729578.0000,
            "iiwa14_joint_2": 5729578.0000,
            "iiwa14_joint_3": 5729578.0000,
            "iiwa14_joint_4": 5729578.0000,
            "iiwa14_joint_5": 5729578.0000,
            "iiwa14_joint_6": 5729578.0000,
            "iiwa14_joint_7": 5729578.0000,
            "left_inner_knuckle_joint":5729578.0000,
            "right_inner_knuckle_joint":5729578.0000,
            "right_outer_knuckle_joint":5729578.0000,
            "left_inner_finger_joint":5729578.0000,
            "right_inner_finger_joint":5729578.0000,
        }



        self.kd = []
        self.kp = []

        for joints, kps in self.gain_kp.items():
            self.kp.append(kps)

        for joints, kds in self.gain_kd.items():
            self.kd.append(kds)

        self.kd = np.array(self.kd)
        self.kp = np.array(self.kp)




    @property
    def arm_dof_indices(self):
        return self._arm_dof_idxs
   
    @property
    def gripper_dof_indices(self):
        return self._gripper_dof_idxs
   


    # def apply_gripper_actions(self, actions : ArticulationAction) -> None:

    #     actions_length = actions.get_length()
    #     if actions_length is not None and actions_length != self._num_gripper_dof:
    #         raise Exception("ArticulationAction passed should be the same length as the number of gripper joints")
    #     joint_actions = ArticulationAction()

    #     if actions.joint_positions is not None:
    #         joint_actions.joint_positions = np.zeros(self._num_dof)
    #         for i in range(self._num_gripper_dof):
    #             joint_actions.joint_positions[self._gripper_dof_idxs[i]] = actions.joint_positions[i]

    #     if actions.joint_velocities is not None:
    #         joint_actions.joint_velocities = np.zeros(self._num_dof)
    #         for i in range(self._num_gripper_dof):
    #             joint_actions.joint_velocities[self._gripper_dof_idxs[i]] = actions.joint_velocities[i]
       
    #     if actions.joint_efforts is not None:
    #         joint_actions.joint_efforts = np.zeros(self._num_dof)
    #         for i in range(self._num_gripper_dof):
    #             joint_actions.joint_efforts[self._gripper_dof_idxs[i]] = actions.joint_efforts[i]
    #     self.apply_action(control_actions = joint_actions)
    #     return
   



    def apply_arm_actions(self, actions:ArticulationAction) -> None:
        actions_length = actions.get_length()
        if actions_length is not None and actions_length != self._num_arm_dof:
            raise Exception("ArticulationAction passed should be the same length as the number of arm joints")
        joint_actions = ArticulationAction()
       
        if actions.joint_positions is not None:
            joint_actions.joint_positions = np.zeros(self._num_dof)
            for i in range(self._num_arm_dof):
                joint_actions.joint_positions[self._arm_dof_idxs[i]] = actions.joint_positions[i]

        if actions.joint_velocities is not None:
            joint_actions.joint_velocities = np.zeros(self._num_dof)
            for i in range(self._num_arm_dof):
                joint_actions.joint_velocities[self._arm_dof_idxs[i]] = actions.joint_velocities[i]


        if actions.joint_efforts is not None:
            joint_actions.joint_efforts = np.zeros(self._num_dof)
            for i in range(self._num_arm_dof):
                joint_actions.joint_efforts[self._arm_dof_idxs[i]] = actions.joint_efforts[i]

        self.apply_action(control_actions = joint_actions)
        return
   











    def initialize(self, physics_sim_view=None) -> None:

        super().initialize(physics_sim_view=physics_sim_view)


        if self._arm_joint_names is not None:
            self._arm_dof_idxs = [
                self.get_dof_index(self._arm_joint_names[i]) for i in range(len(self._arm_joint_names))
            ]
        elif self._arm_joint_names is None:
            carb.log_error("need to have either arm joint names or joint indices")

        # if self._gripper_joint_names is not None:
        #     self._gripper_dof_idxs = [
        #         self.get_dof_index(self._gripper_joint_names[i]) for i in range(len(self._gripper_joint_names))
        #     ]
        # elif self._gripper_dof_idxs is None:
        #     carb.log_error("need to have either gripper joint names or gripper joint indices")


        self._end_effector = RigidPrim(prim_path = self._end_effector_prim_path, name = self.name + "_end_effector")
        self._end_effector.initialize(physics_sim_view)

        self._base_link = RigidPrim(prim_path = self._base_link_prim_path, name = self.name + "_base_link")
        self._base_link.initialize(physics_sim_view)
       

        self._num_arm_dof = len(self._arm_dof_idxs)
        # self._num_gripper_dof = len(self._gripper_dof_idxs)


        return




    def post_reset(self) -> None:

        Robot.post_reset(self)
      #   self._articulation_controller.set_gains(kps = self.kp, kds = self.kd)
        self._articulation_controller.switch_control_mode(mode="velocity")
        return
   




    @property
    def end_effector(self):
        return self._end_effector
   
    @property
    def base_link(self):
        return self._base_link

    

Please can I know if I can create the USD in such a format that the robot arm Xforms and the gripper Xforms come all under one parent default Prim ??


IIWA14(defaultPrim)
 -joint1
 -joint2
 :
 :
 -joint7
 -gripperjoint1
 -gripperjoint2
 :
 :

in this way and the gripper base having a fixed joint with the robot end effector.

Regards,
Tribikram.