Index out of range - Modifying Jetbot Class to include Carter V1 Model instead of Jetbot Model

Hello,

I am have made modifications to the jetbot.py file located in /isaac_sim-2021.2.1/exts/omni.isaac.jetbot/omni/isaac/jetbot/
to replace the jetbot.usd model with the carter_v1.usd model. I have also changed the camera reference path to match that of the carter v1. When I load up the RL example, as shown in this tutorial: 19. Reinforcement Learning using Stable Baselines — Omniverse Robotics documentation , I can see that the Carter Robot loaded in properly but the program exits out after loading the environment and I get this error in the jetbot.py code:

Traceback (most recent call last):
  File "standalone_examples/api/omni.isaac.jetbot/stable_baselines_example/eval.py", line 19, in <module>
    obs = my_env.reset()
  File "/home/omniverse02/.local/share/ov/pkg/isaac_sim-2021.2.1/standalone_examples/api/omni.isaac.jetbot/stable_baselines_example/env.py", line 91, in reset
    self._my_world.reset()
  File "/home/omniverse02/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.core/omni/isaac/core/world/world.py", line 174, in reset
    self.scene.post_reset()
  File "/home/omniverse02/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.core/omni/isaac/core/scenes/scene.py", line 186, in post_reset
    prim_registery[prim_name].post_reset()
  File "/home/omniverse02/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.jetbot/omni/isaac/jetbot/jetbot.py", line 153, in post_reset
    self._articulation_controller.set_gains(kds=[1e2, 1e2])
  File "/home/omniverse02/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.core/omni/isaac/core/controllers/articulation_controller.py", line 159, in set_gains
    self._dof_controllers[i].set_gains(dof_props, kp=kps[i], kd=kds[i])
IndexError: list index out of range

I have found the error regarding the set_gains for the jetbot.py code, but I’m not sure how to modify it to fit the Carter V1 bot. I have included my modifications below including the original code values in the comments. A video of my error is linked as well: Isaac Sim Crash - YouTube Thanks for your time.

from typing import Optional, Tuple
import numpy as np
from omni.isaac.core.robots.robot import Robot
from omni.isaac.core.utils.nucleus import find_nucleus_server
from omni.isaac.core.utils.types import ArticulationAction
from omni.isaac.core.utils.prims import get_prim_at_path, define_prim
import carb


class Jetbot(Robot):
    """[summary]

        Args:
            stage (Usd.Stage): [description]
            prim_path (str): [description]
            name (str): [description]
            usd_path (str, optional): [description]
            position (Optional[np.ndarray], optional): [description]. Defaults to None.
            orientation (Optional[np.ndarray], optional): [description]. Defaults to None.
        """

    def __init__(
        self,
        prim_path: str,
        name: str = "jetbot",
        usd_path: Optional[str] = None,
        position: Optional[np.ndarray] = None,
        orientation: Optional[np.ndarray] = None,
    ) -> None:
        prim = get_prim_at_path(prim_path)
        if not prim.IsValid():
            prim = define_prim(prim_path, "Xform")
            if usd_path:
                prim.GetReferences().AddReference(usd_path)
            else:
                result, nucleus_server = find_nucleus_server()
                if result is False:
                    carb.log_error("Could not find nucleus server with /Isaac folder")
                    return
		# Edited this asset path to replace jetbot with carter v1
		# original path: /Isaac/Robots/Jetbot/jetbot.usd
                asset_path = nucleus_server + "/Isaac/Robots/Carter/carter_v1.usd"
                prim.GetReferences().AddReference(asset_path)
        super().__init__(
            prim_path=prim_path, name=name, position=position, orientation=orientation, articulation_controller=None
        )
	# Original Links for _wheel_dof_names
	# ["left_wheel_joint", "right_wheel_joint"]
        self._wheel_dof_names = ["left_wheel", "right_wheel"]
        self._wheel_dof_indices = None
        # TODO: check the default state and how to reset
        return

    @property
    def wheel_dof_indices(self) -> Tuple[int, int]:
        """[summary]

        Returns:
            int: [description]
        """
        return self._wheel_dof_indices

    def get_wheel_positions(self) -> Tuple[float, float]:
        """[summary]

        Returns:
            Tuple[float, float]: [description]
        """
        joint_positions = self.get_joint_positions()
        return joint_positions[self._wheel_dof_indices[0]], joint_positions[self._wheel_dof_indices[1]]

    def set_wheel_positions(self, positions: Tuple[float, float]) -> None:
        """[summary]

        Args:
            positions (Tuple[float, float]): [description]
        """
        joint_positions = [None, None]
        joint_positions[self._wheel_dof_indices[0]] = positions[0]
        joint_positions[self._wheel_dof_indices[1]] = positions[1]
        self.set_joint_positions(positions=np.array(joint_positions))
        return

    def get_wheel_velocities(self) -> Tuple[float, float]:
        """[summary]

        Returns:
            Tuple[np.ndarray, np.ndarray]: [description]
        """
        joint_velocities = self.get_joint_velocities()
        return joint_velocities[self._wheel_dof_indices[0]], joint_velocities[self._wheel_dof_indices[1]]

    def set_wheel_velocities(self, velocities: Tuple[float, float]) -> None:
        """[summary]

        Args:
            velocities (Tuple[float, float]): [description]
        """
        joint_velocities = [None, None]
        joint_velocities[self._wheel_dof_indices[0]] = velocities[0]
        joint_velocities[self._wheel_dof_indices[1]] = velocities[1]
        self.set_joint_velocities(velocities=np.array(joint_velocities))
        return

    def apply_wheel_actions(self, actions: ArticulationAction) -> None:
        """[summary]

        Args:
            actions (ArticulationAction): [description]
        """
        actions_length = actions.get_length()
        if actions_length is not None and actions_length != 2:
            raise Exception("ArticulationAction passed should be equal to 2")
        joint_actions = ArticulationAction()
        if actions.joint_positions is not None:
            joint_actions.joint_positions = np.zeros(self.num_dof)
            joint_actions.joint_positions[self._wheel_dof_indices[0]] = actions.joint_positions[0]
            joint_actions.joint_positions[self._wheel_dof_indices[1]] = actions.joint_positions[1]
        if actions.joint_velocities is not None:
            joint_actions.joint_velocities = np.zeros(self.num_dof)
            joint_actions.joint_velocities[self._wheel_dof_indices[0]] = actions.joint_velocities[0]
            joint_actions.joint_velocities[self._wheel_dof_indices[1]] = actions.joint_velocities[1]
        if actions.joint_efforts is not None:
            joint_actions.joint_efforts = np.zeros(self.num_dof)
            joint_actions.joint_efforts[self._wheel_dof_indices[0]] = actions.joint_efforts[0]
            joint_actions.joint_efforts[self._wheel_dof_indices[1]] = actions.joint_efforts[1]

        self.apply_action(control_actions=joint_actions)
        return

    def initialize(self) -> None:
        """[summary]
        """
        super().initialize()
        self._wheel_dof_indices = (
            self.get_dof_index(self._wheel_dof_names[0]),
            self.get_dof_index(self._wheel_dof_names[1]),
        )
        return

    def post_reset(self) -> None:
        """[summary]
        """
        super().post_reset()
        self._articulation_controller.set_gains(kds=[1e2, 1e2])
        self._articulation_controller.switch_control_mode(mode="velocity")
        return