Unable to set childFrameId value for ROS1PublishOdometry [Standalone-IsaacSim]

I am unable to set the childFrameId value for the ROS1PublishOdometry graph node using the IsaacSim-Standalone workflow.

I get the following error:
OmniGraphError: Failed trying to look up attribute with (/ROS_Clock/publishOdom.inputs:childFrameId, node=None, graph=None)

Here is how the issue can be replicated with one of the examples from Isaac Sim, start with : standalone_examples/api/omni.isaac.quadruped/a1_direct_ros1_standalone.py

Modifications: Add two nodes omni.isaac.ros_bridge.ROS1PublishOdometry and omni.isaac.core_nodes.IsaacComputeOdometry to publish odom.

Modified Code (No Errors):

# Copyright (c) 2021-2023, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#


"""
Introduction
We start a runner which publishes robot sensor data as ROS1 topics and listens to outside ROS1 topic "isaac_a1/joint_torque_cmd".
The runner set robot joint torques directly using the external ROS1 topic "isaac_a1/joint_torque_cmd".
The runner instantiate robot UnitreeDirect, which directly takes in joint torques and sends torques to lowlevel joint controllers
This is a very simple example to demonstrate how to treat Isaac Sim as a simulation component with in the ROS1 ecosystem
"""

from omni.isaac.kit import SimulationApp

simulation_app = SimulationApp({"headless": False})

import carb
import numpy as np
import omni.appwindow  # Contains handle to keyboard
import omni.graph.core as og
from omni.isaac.core import World
from omni.isaac.core.utils.extensions import enable_extension
from omni.isaac.core.utils.nucleus import get_assets_root_path
from omni.isaac.core.utils.prims import define_prim, get_prim_at_path
from omni.isaac.quadruped.robots import UnitreeDirect
from omni.isaac.quadruped.utils.a1_classes import A1Measurement

# enable ROS bridge extension
enable_extension("omni.isaac.ros_bridge")

simulation_app.update()

# check if rosmaster node is running
# this is to prevent this sample from waiting indefinetly if roscore is not running
# can be removed in regular usage
import rosgraph

if not rosgraph.is_master_online():
    carb.log_error("Please run roscore before executing this script")
    simulation_app.close()
    exit()
# ros-python and ROS1 messages
import geometry_msgs.msg as geometry_msgs
import rospy
import sensor_msgs.msg as sensor_msgs


class A1_direct_runner(object):
    def __init__(self, physics_dt, render_dt) -> None:
        """
        [Summary]

        creates the simulation world with preset physics_dt and render_dt and creates a unitree a1 robot inside the warehouse

        Argument:
        physics_dt {float} -- Physics downtime of the scene.
        render_dt {float} -- Render downtime of the scene.

        """

        self._world = World(stage_units_in_meters=1.0, physics_dt=physics_dt, rendering_dt=render_dt)

        assets_root_path = get_assets_root_path()
        if assets_root_path is None:
            carb.log_error("Could not find Isaac Sim assets folder")

        prim = get_prim_at_path("/World/Warehouse")
        if not prim.IsValid():
            prim = define_prim("/World/Warehouse", "Xform")
            asset_path = assets_root_path + "/Isaac/Environments/Simple_Warehouse/warehouse.usd"
            prim.GetReferences().AddReference(asset_path)

        self._a1 = self._world.scene.add(
            UnitreeDirect(
                prim_path="/World/A1", name="A1", position=np.array([0, 0, 0.40]), physics_dt=physics_dt, model="A1"
            )
        )

        self._world.reset()

        # Creating an ondemand push graph with ROS Clock, everything in the ROS environment must synchronize with this clock
        try:
            keys = og.Controller.Keys
            (self._clock_graph, _, _, _) = og.Controller.edit(
                {
                    "graph_path": "/ROS_Clock",
                    "evaluator_name": "push",
                    "pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
                },
                {
                    keys.CREATE_NODES: [
                        ("OnTick", "omni.graph.action.OnTick"),
                        ("readSimTime", "omni.isaac.core_nodes.IsaacReadSimulationTime"),
                        ("computeOdom", "omni.isaac.core_nodes.IsaacComputeOdometry"),
                        ("publishOdom", "omni.isaac.ros_bridge.ROS1PublishOdometry"),
                        ("publishClock", "omni.isaac.ros_bridge.ROS1PublishClock"),
                    ],
                    keys.CONNECT: [
                        ("OnTick.outputs:tick", "publishClock.inputs:execIn"),
                        ("readSimTime.outputs:simulationTime", "publishClock.inputs:timeStamp"),
                        ("OnTick.outputs:tick", "computeOdom.inputs:execIn"),
                        ("OnTick.outputs:tick", "publishOdom.inputs:execIn"),
                        ("readSimTime.outputs:simulationTime", "publishOdom.inputs:timeStamp"),
                        ("computeOdom.outputs:linearVelocity", "publishOdom.inputs:linearVelocity"),
                        ("computeOdom.outputs:angularVelocity", "publishOdom.inputs:angularVelocity"),
                        ("computeOdom.outputs:position", "publishOdom.inputs:position"),
                        ("computeOdom.outputs:orientation", "publishOdom.inputs:orientation"),
                    ],

                    keys.SET_VALUES: [
                        # ("publishOdom.inputs:odomFrameId", "/odom"),
                        # ("publishOdom.inputs:childFrameId", "/base_link"),
                        ("publishOdom.inputs:nodeNamespace", "isaac_sim"),
                        ("computeOdom.inputs:chassisPrim", "/World/A1"), #? This is the articulation root of the robot
                    ],
                },
            )
        except Exception as e:
            print(e)
            simulation_app.close()
            exit()

        ##
        # ROS publishers
        ##
        # a) ground truth body pose
        self._pub_body_pose = rospy.Publisher("isaac_a1/gt_body_pose", geometry_msgs.PoseStamped, queue_size=21)
        self._msg_body_pose = geometry_msgs.PoseStamped()
        self._msg_body_pose.header.frame_id = "base_link"
        # b) joint angle and foot force
        self._pub_joint_state = rospy.Publisher("isaac_a1/joint_foot", sensor_msgs.JointState, queue_size=21)
        self._msg_joint_state = sensor_msgs.JointState()
        self._msg_joint_state.name = [
            "FL0",
            "FL1",
            "FL2",
            "FR0",
            "FR1",
            "FR2",
            "RL0",
            "RL1",
            "RL2",
            "RR0",
            "RR1",
            "RR2",
            "FL_foot",
            "FR_foot",
            "RL_foot",
            "RR_foot",
        ]
        self._msg_joint_state.position = [0.0] * 16
        self._msg_joint_state.velocity = [0.0] * 16
        self._msg_joint_state.effort = [0.0] * 16
        # c) IMU measurements
        self._pub_imu_debug = rospy.Publisher("isaac_a1/imu_data", sensor_msgs.Imu, queue_size=21)
        self._msg_imu_debug = sensor_msgs.Imu()
        self._msg_imu_debug.header.frame_id = "base_link"

        # d) ground truth body pose with a fake covariance
        self._pub_body_pose_with_cov = rospy.Publisher(
            "isaac_a1/gt_body_pose_with_cov", geometry_msgs.PoseWithCovarianceStamped, queue_size=21
        )
        self._msg_body_pose_with_cov = geometry_msgs.PoseWithCovarianceStamped()
        self._msg_body_pose_with_cov.header.frame_id = "base_link"

        ##
        # ROS subscribers
        ##
        self._sub_joint_cmd = rospy.Subscriber(
            "isaac_a1/joint_torque_cmd", sensor_msgs.JointState, self.joint_command_callback
        )
        # buffer to store the robot command
        self._ros_command = np.zeros(12)

    def setup(self):
        """
        [Summary]

        add physics callback

        """
        self._app_window = omni.appwindow.get_default_app_window()
        self._world.add_physics_callback("robot_sim_step", callback_fn=self.robot_simulation_step)

        # start ROS publisher and subscribers

    def run(self):
        """
        [Summary]

        Step simulation based on rendering downtime

        """
        # change to sim running
        while simulation_app.is_running():
            self._world.step(render=True)
        return

    def publish_ros_data(self, measurement: A1Measurement):
        """
        [Summary]

        Publish body pose, joint state, imu data

        """
        # update all header timestamps
        ros_timestamp = rospy.get_rostime()
        self._msg_body_pose.header.stamp = ros_timestamp
        self._msg_joint_state.header.stamp = ros_timestamp
        self._msg_imu_debug.header.stamp = ros_timestamp
        self._msg_body_pose_with_cov.header.stamp = ros_timestamp

        # a) ground truth pose
        self._update_body_pose_msg(measurement)
        self._pub_body_pose.publish(self._msg_body_pose)
        # b) joint state and contact force
        self._update_msg_joint_state(measurement)
        self._pub_joint_state.publish(self._msg_joint_state)
        # c) IMU
        self._update_imu_msg(measurement)
        self._pub_imu_debug.publish(self._msg_imu_debug)
        # d) ground truth pose with covariance
        self._update_body_pose_with_cov_msg(measurement)
        self._pub_body_pose_with_cov.publish(self._msg_body_pose_with_cov)
        return

    """call backs"""

    def robot_simulation_step(self, step_size):
        """
        [Summary]

        Call robot update and advance, and tick ros bridge

        """
        self._a1.update()
        self._a1.advance()

        # Tick the ROS Clock
        og.Controller.evaluate_sync(self._clock_graph)

        # Publish ROS data
        self.publish_ros_data(self._a1._measurement)

    def joint_command_callback(self, data):
        """
        [Summary]

        Joint command call back, set command torque for the joints

        """
        for i in range(12):
            self._ros_command[i] = data.effort[i]

        self._a1.set_command_torque(self._ros_command)

    """
    Utilities functions.
    """

    def _update_body_pose_msg(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the body pose message.

        """
        # base position
        self._msg_body_pose.pose.position.x = measurement.state.base_frame.pos[0]
        self._msg_body_pose.pose.position.y = measurement.state.base_frame.pos[1]
        self._msg_body_pose.pose.position.z = measurement.state.base_frame.pos[2]
        # base orientation
        self._msg_body_pose.pose.orientation.w = measurement.state.base_frame.quat[3]
        self._msg_body_pose.pose.orientation.x = measurement.state.base_frame.quat[0]
        self._msg_body_pose.pose.orientation.y = measurement.state.base_frame.quat[1]
        self._msg_body_pose.pose.orientation.z = measurement.state.base_frame.quat[2]

    def _update_msg_joint_state(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the joint state message.

        """
        # joint position and velocity
        for i in range(12):
            self._msg_joint_state.position[i] = measurement.state.joint_pos[i]
            self._msg_joint_state.velocity[i] = measurement.state.joint_vel[i]
        # foot force
        for i in range(4):
            # notice this order is: FL, FR, RL, RR
            self._msg_joint_state.effort[12 + i] = measurement.foot_forces[i]

    def _update_imu_msg(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the IMU message.

        """
        # accelerometer data
        self._msg_imu_debug.linear_acceleration.x = measurement.base_lin_acc[0]
        self._msg_imu_debug.linear_acceleration.y = measurement.base_lin_acc[1]
        self._msg_imu_debug.linear_acceleration.z = measurement.base_lin_acc[2]
        # gyroscope data
        self._msg_imu_debug.angular_velocity.x = measurement.base_ang_vel[0]
        self._msg_imu_debug.angular_velocity.y = measurement.base_ang_vel[1]
        self._msg_imu_debug.angular_velocity.z = measurement.base_ang_vel[2]

    def _update_body_pose_with_cov_msg(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the body pose with fake covariance message.

        """
        # base position
        self._msg_body_pose_with_cov.pose.pose.position.x = measurement.state.base_frame.pos[0]
        self._msg_body_pose_with_cov.pose.pose.position.y = measurement.state.base_frame.pos[1]
        self._msg_body_pose_with_cov.pose.pose.position.z = measurement.state.base_frame.pos[2]
        # base orientation
        self._msg_body_pose_with_cov.pose.pose.orientation.w = measurement.state.base_frame.quat[3]
        self._msg_body_pose_with_cov.pose.pose.orientation.x = measurement.state.base_frame.quat[0]
        self._msg_body_pose_with_cov.pose.pose.orientation.y = measurement.state.base_frame.quat[1]
        self._msg_body_pose_with_cov.pose.pose.orientation.z = measurement.state.base_frame.quat[2]

        # Setting fake covariance
        for i in range(6):
            self._msg_body_pose_with_cov.pose.covariance[i * 6 + i] = 0.001


def main():
    """
    [Summary]

    The function launches the simulator, creates the robot, and run the simulation steps

    """
    # first enable ros node, make sure using simulation time
    rospy.init_node("isaac_a1", anonymous=False, disable_signals=True, log_level=rospy.ERROR)
    rospy.set_param("use_sim_time", True)
    physics_downtime = 1 / 400.0
    runner = A1_direct_runner(physics_dt=physics_downtime, render_dt=physics_downtime)
    simulation_app.update()
    runner.setup()

    # an extra reset is needed to register
    runner._world.reset()
    runner._world.reset()
    runner.run()
    rospy.signal_shutdown("a1 direct complete")
    simulation_app.close()


if __name__ == "__main__":
    main()

The above code runs fine with no errors, rostopic list shows /isaac_sim/odom and echo of the topic gives the following output, as expected:

---
header: 
  seq: 2954
  stamp: 
    secs: 7
    nsecs: 407499834
  frame_id: "isaac_sim/odom"
child_frame_id: "isaac_sim/base_link"
pose: 
  pose: 
    position: 
      x: -0.014982803724706173
      y: -0.0002793380990624428
      z: -0.3429388105869293
    orientation: 
      x: -0.0
      y: 0.0
      z: 0.0
      w: 1.0
  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
twist: 
  twist: 
    linear: 
      x: 5.456177314044908e-05
      y: -0.00010797857248689979
      z: 0.0
    angular: 
      x: 0.0
      y: 0.0
      z: -0.00015063433966133744
  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
---

Now adding a single change ("publishOdom.inputs:childFrameId", "base"), such that the childFrameId is set to anything else than the default (I have tried “base”, “/base” , “trunk” and so on) causes the following error:

OmniGraphError: Failed trying to look up attribute with (/ROS_Clock/publishOdom.inputs:childFrameId, node=None, graph=None)

Modified code with childFrameId set (Throws Error):

# Copyright (c) 2021-2023, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#


"""
Introduction
We start a runner which publishes robot sensor data as ROS1 topics and listens to outside ROS1 topic "isaac_a1/joint_torque_cmd".
The runner set robot joint torques directly using the external ROS1 topic "isaac_a1/joint_torque_cmd".
The runner instantiate robot UnitreeDirect, which directly takes in joint torques and sends torques to lowlevel joint controllers
This is a very simple example to demonstrate how to treat Isaac Sim as a simulation component with in the ROS1 ecosystem
"""

from omni.isaac.kit import SimulationApp

simulation_app = SimulationApp({"headless": False})

import carb
import numpy as np
import omni.appwindow  # Contains handle to keyboard
import omni.graph.core as og
from omni.isaac.core import World
from omni.isaac.core.utils.extensions import enable_extension
from omni.isaac.core.utils.nucleus import get_assets_root_path
from omni.isaac.core.utils.prims import define_prim, get_prim_at_path
from omni.isaac.quadruped.robots import UnitreeDirect
from omni.isaac.quadruped.utils.a1_classes import A1Measurement

# enable ROS bridge extension
enable_extension("omni.isaac.ros_bridge")

simulation_app.update()

# check if rosmaster node is running
# this is to prevent this sample from waiting indefinetly if roscore is not running
# can be removed in regular usage
import rosgraph

if not rosgraph.is_master_online():
    carb.log_error("Please run roscore before executing this script")
    simulation_app.close()
    exit()
# ros-python and ROS1 messages
import geometry_msgs.msg as geometry_msgs
import rospy
import sensor_msgs.msg as sensor_msgs


class A1_direct_runner(object):
    def __init__(self, physics_dt, render_dt) -> None:
        """
        [Summary]

        creates the simulation world with preset physics_dt and render_dt and creates a unitree a1 robot inside the warehouse

        Argument:
        physics_dt {float} -- Physics downtime of the scene.
        render_dt {float} -- Render downtime of the scene.

        """

        self._world = World(stage_units_in_meters=1.0, physics_dt=physics_dt, rendering_dt=render_dt)

        assets_root_path = get_assets_root_path()
        if assets_root_path is None:
            carb.log_error("Could not find Isaac Sim assets folder")

        prim = get_prim_at_path("/World/Warehouse")
        if not prim.IsValid():
            prim = define_prim("/World/Warehouse", "Xform")
            asset_path = assets_root_path + "/Isaac/Environments/Simple_Warehouse/warehouse.usd"
            prim.GetReferences().AddReference(asset_path)

        self._a1 = self._world.scene.add(
            UnitreeDirect(
                prim_path="/World/A1", name="A1", position=np.array([0, 0, 0.40]), physics_dt=physics_dt, model="A1"
            )
        )

        self._world.reset()

        # Creating an ondemand push graph with ROS Clock, everything in the ROS environment must synchronize with this clock
        try:
            keys = og.Controller.Keys
            (self._clock_graph, _, _, _) = og.Controller.edit(
                {
                    "graph_path": "/ROS_Clock",
                    "evaluator_name": "push",
                    "pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
                },
                {
                    keys.CREATE_NODES: [
                        ("OnTick", "omni.graph.action.OnTick"),
                        ("readSimTime", "omni.isaac.core_nodes.IsaacReadSimulationTime"),
                        ("computeOdom", "omni.isaac.core_nodes.IsaacComputeOdometry"),
                        ("publishOdom", "omni.isaac.ros_bridge.ROS1PublishOdometry"),
                        ("publishClock", "omni.isaac.ros_bridge.ROS1PublishClock"),
                    ],
                    keys.CONNECT: [
                        ("OnTick.outputs:tick", "publishClock.inputs:execIn"),
                        ("readSimTime.outputs:simulationTime", "publishClock.inputs:timeStamp"),
                        ("OnTick.outputs:tick", "computeOdom.inputs:execIn"),
                        ("OnTick.outputs:tick", "publishOdom.inputs:execIn"),
                        ("readSimTime.outputs:simulationTime", "publishOdom.inputs:timeStamp"),
                        ("computeOdom.outputs:linearVelocity", "publishOdom.inputs:linearVelocity"),
                        ("computeOdom.outputs:angularVelocity", "publishOdom.inputs:angularVelocity"),
                        ("computeOdom.outputs:position", "publishOdom.inputs:position"),
                        ("computeOdom.outputs:orientation", "publishOdom.inputs:orientation"),
                    ],

                    keys.SET_VALUES: [
                        # ("publishOdom.inputs:odomFrameId", "odom"),
                        ("publishOdom.inputs:childFrameId", "base"),
                        ("publishOdom.inputs:nodeNamespace", "isaac_sim"),
                        ("computeOdom.inputs:chassisPrim", "/World/A1"), #? This is the articulation root of the robot
                    ],
                },
            )
        except Exception as e:
            print(e)
            simulation_app.close()
            exit()

        ##
        # ROS publishers
        ##
        # a) ground truth body pose
        self._pub_body_pose = rospy.Publisher("isaac_a1/gt_body_pose", geometry_msgs.PoseStamped, queue_size=21)
        self._msg_body_pose = geometry_msgs.PoseStamped()
        self._msg_body_pose.header.frame_id = "base_link"
        # b) joint angle and foot force
        self._pub_joint_state = rospy.Publisher("isaac_a1/joint_foot", sensor_msgs.JointState, queue_size=21)
        self._msg_joint_state = sensor_msgs.JointState()
        self._msg_joint_state.name = [
            "FL0",
            "FL1",
            "FL2",
            "FR0",
            "FR1",
            "FR2",
            "RL0",
            "RL1",
            "RL2",
            "RR0",
            "RR1",
            "RR2",
            "FL_foot",
            "FR_foot",
            "RL_foot",
            "RR_foot",
        ]
        self._msg_joint_state.position = [0.0] * 16
        self._msg_joint_state.velocity = [0.0] * 16
        self._msg_joint_state.effort = [0.0] * 16
        # c) IMU measurements
        self._pub_imu_debug = rospy.Publisher("isaac_a1/imu_data", sensor_msgs.Imu, queue_size=21)
        self._msg_imu_debug = sensor_msgs.Imu()
        self._msg_imu_debug.header.frame_id = "base_link"

        # d) ground truth body pose with a fake covariance
        self._pub_body_pose_with_cov = rospy.Publisher(
            "isaac_a1/gt_body_pose_with_cov", geometry_msgs.PoseWithCovarianceStamped, queue_size=21
        )
        self._msg_body_pose_with_cov = geometry_msgs.PoseWithCovarianceStamped()
        self._msg_body_pose_with_cov.header.frame_id = "base_link"

        ##
        # ROS subscribers
        ##
        self._sub_joint_cmd = rospy.Subscriber(
            "isaac_a1/joint_torque_cmd", sensor_msgs.JointState, self.joint_command_callback
        )
        # buffer to store the robot command
        self._ros_command = np.zeros(12)

    def setup(self):
        """
        [Summary]

        add physics callback

        """
        self._app_window = omni.appwindow.get_default_app_window()
        self._world.add_physics_callback("robot_sim_step", callback_fn=self.robot_simulation_step)

        # start ROS publisher and subscribers

    def run(self):
        """
        [Summary]

        Step simulation based on rendering downtime

        """
        # change to sim running
        while simulation_app.is_running():
            self._world.step(render=True)
        return

    def publish_ros_data(self, measurement: A1Measurement):
        """
        [Summary]

        Publish body pose, joint state, imu data

        """
        # update all header timestamps
        ros_timestamp = rospy.get_rostime()
        self._msg_body_pose.header.stamp = ros_timestamp
        self._msg_joint_state.header.stamp = ros_timestamp
        self._msg_imu_debug.header.stamp = ros_timestamp
        self._msg_body_pose_with_cov.header.stamp = ros_timestamp

        # a) ground truth pose
        self._update_body_pose_msg(measurement)
        self._pub_body_pose.publish(self._msg_body_pose)
        # b) joint state and contact force
        self._update_msg_joint_state(measurement)
        self._pub_joint_state.publish(self._msg_joint_state)
        # c) IMU
        self._update_imu_msg(measurement)
        self._pub_imu_debug.publish(self._msg_imu_debug)
        # d) ground truth pose with covariance
        self._update_body_pose_with_cov_msg(measurement)
        self._pub_body_pose_with_cov.publish(self._msg_body_pose_with_cov)
        return

    """call backs"""

    def robot_simulation_step(self, step_size):
        """
        [Summary]

        Call robot update and advance, and tick ros bridge

        """
        self._a1.update()
        self._a1.advance()

        # Tick the ROS Clock
        og.Controller.evaluate_sync(self._clock_graph)

        # Publish ROS data
        self.publish_ros_data(self._a1._measurement)

    def joint_command_callback(self, data):
        """
        [Summary]

        Joint command call back, set command torque for the joints

        """
        for i in range(12):
            self._ros_command[i] = data.effort[i]

        self._a1.set_command_torque(self._ros_command)

    """
    Utilities functions.
    """

    def _update_body_pose_msg(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the body pose message.

        """
        # base position
        self._msg_body_pose.pose.position.x = measurement.state.base_frame.pos[0]
        self._msg_body_pose.pose.position.y = measurement.state.base_frame.pos[1]
        self._msg_body_pose.pose.position.z = measurement.state.base_frame.pos[2]
        # base orientation
        self._msg_body_pose.pose.orientation.w = measurement.state.base_frame.quat[3]
        self._msg_body_pose.pose.orientation.x = measurement.state.base_frame.quat[0]
        self._msg_body_pose.pose.orientation.y = measurement.state.base_frame.quat[1]
        self._msg_body_pose.pose.orientation.z = measurement.state.base_frame.quat[2]

    def _update_msg_joint_state(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the joint state message.

        """
        # joint position and velocity
        for i in range(12):
            self._msg_joint_state.position[i] = measurement.state.joint_pos[i]
            self._msg_joint_state.velocity[i] = measurement.state.joint_vel[i]
        # foot force
        for i in range(4):
            # notice this order is: FL, FR, RL, RR
            self._msg_joint_state.effort[12 + i] = measurement.foot_forces[i]

    def _update_imu_msg(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the IMU message.

        """
        # accelerometer data
        self._msg_imu_debug.linear_acceleration.x = measurement.base_lin_acc[0]
        self._msg_imu_debug.linear_acceleration.y = measurement.base_lin_acc[1]
        self._msg_imu_debug.linear_acceleration.z = measurement.base_lin_acc[2]
        # gyroscope data
        self._msg_imu_debug.angular_velocity.x = measurement.base_ang_vel[0]
        self._msg_imu_debug.angular_velocity.y = measurement.base_ang_vel[1]
        self._msg_imu_debug.angular_velocity.z = measurement.base_ang_vel[2]

    def _update_body_pose_with_cov_msg(self, measurement: A1Measurement):
        """
        [Summary]

        Updates the body pose with fake covariance message.

        """
        # base position
        self._msg_body_pose_with_cov.pose.pose.position.x = measurement.state.base_frame.pos[0]
        self._msg_body_pose_with_cov.pose.pose.position.y = measurement.state.base_frame.pos[1]
        self._msg_body_pose_with_cov.pose.pose.position.z = measurement.state.base_frame.pos[2]
        # base orientation
        self._msg_body_pose_with_cov.pose.pose.orientation.w = measurement.state.base_frame.quat[3]
        self._msg_body_pose_with_cov.pose.pose.orientation.x = measurement.state.base_frame.quat[0]
        self._msg_body_pose_with_cov.pose.pose.orientation.y = measurement.state.base_frame.quat[1]
        self._msg_body_pose_with_cov.pose.pose.orientation.z = measurement.state.base_frame.quat[2]

        # Setting fake covariance
        for i in range(6):
            self._msg_body_pose_with_cov.pose.covariance[i * 6 + i] = 0.001


def main():
    """
    [Summary]

    The function launches the simulator, creates the robot, and run the simulation steps

    """
    # first enable ros node, make sure using simulation time
    rospy.init_node("isaac_a1", anonymous=False, disable_signals=True, log_level=rospy.ERROR)
    rospy.set_param("use_sim_time", True)
    physics_downtime = 1 / 400.0
    runner = A1_direct_runner(physics_dt=physics_downtime, render_dt=physics_downtime)
    simulation_app.update()
    runner.setup()

    # an extra reset is needed to register
    runner._world.reset()
    runner._world.reset()
    runner.run()
    rospy.signal_shutdown("a1 direct complete")
    simulation_app.close()


if __name__ == "__main__":
    main()

Full log of the terminal can be found below

➜  isaac_sim-2023.1.1 ipython standalone_examples/api/omni.isaac.quadruped/a1_direct_ros1_standalone.py
Starting kit application with the following args:  ['/home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/exts/omni.isaac.kit/omni/isaac/kit/simulation_app.py', '/home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/apps/omni.isaac.sim.python.kit', '--/app/tokens/exe-path=/home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/kit', '--/persistent/app/viewport/displayOptions=3094', '--/rtx/materialDb/syncLoads=True', '--/rtx/hydra/materialSyncLoads=True', '--/omni.kit.plugin/syncUsdLoads=True', '--/app/renderer/resolution/width=1280', '--/app/renderer/resolution/height=720', '--/app/window/width=1440', '--/app/window/height=900', '--/renderer/multiGpu/enabled=True', '--/app/fastShutdown=True', '--ext-folder', '/home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/exts', '--ext-folder', '/home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/apps', '--/physics/cudaDevice=0', '--portable']
Passing the following args to the base kit application:  []
Loading user config located at: '/home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/kit/data/Kit/Isaac-Sim/2023.1/user.config.json'
[Info] [carb] Logging to file: /home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/kit/logs/Kit/Isaac-Sim/2023.1/kit_20240610_181541.log
2024-06-11 01:15:41 [0ms] [Warning] [omni.kit.app.plugin] No crash reporter present, dumps uploading isn't available.
[0.079s] [ext: omni.kit.async_engine-0.0.0] startup
[0.471s] [ext: omni.activity.core-1.0.1] startup
[0.475s] [ext: omni.assets.plugins-0.0.0] startup
[0.476s] [ext: omni.stats-0.0.0] startup
[0.477s] [ext: omni.client-1.0.1] startup
[0.485s] [ext: omni.activity.profiler-1.0.2] startup
[0.488s] [ext: omni.gpu_foundation-0.0.0] startup
[0.500s] [ext: omni.rtx.shadercache.vulkan-1.0.0] startup
[0.501s] [ext: carb.windowing.plugins-1.0.0] startup
[0.523s] [ext: omni.kit.renderer.init-0.0.0] startup

|---------------------------------------------------------------------------------------------|
| Driver Version: 535.171.04    | Graphics API: Vulkan
|=============================================================================================|
| GPU | Name                             | Active | LDA | GPU Memory | Vendor-ID | LUID       |
|     |                                  |        |     |            | Device-ID | UUID       |
|     |                                  |        |     |            | Bus-ID    |            |
|---------------------------------------------------------------------------------------------|
| 0   | NVIDIA RTX A6000                 | Yes: 0 |     | 49140   MB | 10de      | 0          |
|     |                                  |        |     |            | 2230      | 5c01443c.. |
|     |                                  |        |     |            | af        |            |
|=============================================================================================|
| OS: 20.04.6 LTS (Focal Fossa) ubuntu, Version: 20.04.6, Kernel: 5.4.0-182-generic
| XServer Vendor: The X.Org Foundation, XServer Version: 12013000 (1.20.13.0)
| Processor: Intel(R) Xeon(R) Silver 4214R CPU @ 2.40GHz | Cores: 24 | Logical: 48
|---------------------------------------------------------------------------------------------|
| Total Memory (MB): 257554 | Free Memory: 242274
| Total Page/Swap (MB): 8191 | Free Page/Swap: 8191
|---------------------------------------------------------------------------------------------|
[1.419s] [ext: omni.kit.pipapi-0.0.0] startup
[1.421s] [ext: omni.kit.pip_archive-0.0.0] startup
[1.422s] [ext: omni.pip.compute-1.2.0] startup
[1.422s] [ext: omni.pip.cloud-1.0.1] startup
[1.427s] [ext: omni.isaac.core_archive-2.2.1] startup
[1.427s] [ext: omni.pip.torch-2_0_1-2.0.2] startup
[1.487s] [ext: omni.kit.telemetry-0.5.0] startup
[1.524s] [ext: omni.kit.loop-isaac-1.1.0] startup
[1.526s] [ext: omni.kit.test-0.0.0] startup
[1.528s] [ext: omni.isaac.ml_archive-1.1.3] startup
[1.529s] [ext: omni.mtlx-0.1.0] startup
[1.530s] [ext: omni.usd.config-1.0.3] startup
[1.536s] [ext: omni.gpucompute.plugins-0.0.0] startup
[1.537s] [ext: omni.usd.libs-1.0.0] startup
[1.671s] [ext: omni.appwindow-1.1.5] startup
[1.681s] [ext: omni.kit.renderer.core-0.0.0] startup
[1.837s] [ext: omni.kit.renderer.capture-0.0.0] startup
[1.839s] [ext: omni.kit.renderer.imgui-0.0.0] startup
[1.998s] [ext: carb.audio-0.1.0] startup
[2.003s] [ext: omni.ui-2.18.5] startup
[2.018s] [ext: omni.uiaudio-1.0.0] startup
[2.019s] [ext: omni.kit.mainwindow-1.0.1] startup
[2.021s] [ext: omni.kit.uiapp-0.0.0] startup
[2.021s] [ext: omni.usd.schema.physics-0.0.0] startup
[2.206s] [ext: omni.usd.schema.audio-0.0.0] startup
[2.213s] [ext: omni.usd.schema.forcefield-0.0.0] startup
[2.220s] [ext: omni.usd.schema.omnigraph-1.0.0] startup
[2.228s] [ext: omni.usd.schema.scene.visualization-2.0.2] startup
[2.230s] [ext: omni.usd.schema.semantics-0.0.0] startup
[2.240s] [ext: omni.usd.schema.physx-0.0.0] startup
[2.276s] [ext: omni.usd.schema.anim-0.0.0] startup
[2.297s] [ext: omni.anim.navigation.schema-105.2.0] startup
[2.301s] [ext: omni.anim.graph.schema-105.2.2] startup
[2.310s] [ext: omni.usd.schema.isaac-2.0.1] startup
[2.318s] [ext: omni.usd.schema.geospatial-0.0.0] startup
[2.324s] [ext: omni.usd.schema.omniscripting-1.0.0] startup
[2.330s] [ext: omni.resourcemonitor-105.0.0] startup
[2.332s] [ext: omni.timeline-1.0.9] startup
[2.334s] [ext: omni.usd_resolver-1.0.1] startup
[2.340s] [ext: omni.kit.window.popup_dialog-2.0.23] startup
[2.345s] [ext: omni.graph.exec-0.3.0] startup
[2.345s] [ext: omni.kit.actions.core-1.0.0] startup
[2.348s] [ext: omni.usd.core-1.1.8] startup
[2.352s] [ext: omni.kit.widget.nucleus_connector-1.1.4] startup
[2.355s] [ext: omni.kit.audiodeviceenum-1.0.1] startup
[2.357s] [ext: omni.kit.exec.core-0.5.0] startup
[2.359s] [ext: omni.kit.commands-1.4.6] startup
[2.363s] [ext: omni.hydra.usdrt_delegate-7.2.34] startup
[2.380s] [ext: omni.hydra.scene_delegate-0.3.2] startup
[2.388s] [ext: omni.usd-1.10.18] startup
[2.451s] [ext: omni.kit.widget.versioning-1.4.6] startup
[2.453s] [ext: omni.kit.helper.file_utils-0.1.6] startup
[2.482s] [ext: omni.kit.widget.nucleus_info-1.0.2] startup
[2.483s] [ext: omni.kit.widget.filebrowser-2.3.35] startup
[2.489s] [ext: omni.kit.search_core-1.0.5] startup
[2.490s] [ext: omni.kit.widget.path_field-2.0.8] startup
[2.490s] [ext: omni.kit.widget.search_delegate-1.0.4] startup
[2.492s] [ext: omni.kit.widget.browser_bar-2.0.9] startup
[2.493s] [ext: omni.kit.collaboration.telemetry-1.0.0] startup
[2.494s] [ext: omni.kit.menu.utils-1.5.6] startup
[2.505s] [ext: omni.kit.collaboration.channel_manager-1.0.11] startup
[2.506s] [ext: omni.ui.scene-1.7.0] startup
[2.512s] [ext: omni.kit.notification_manager-1.0.6] startup
[2.514s] [ext: omni.kit.clipboard-1.0.3] startup
[2.515s] [ext: omni.kit.widget.options_menu-1.0.5] startup
[2.517s] [ext: omni.kit.usd.layers-2.1.27] startup
[2.528s] [ext: omni.kit.window.filepicker-2.10.13] startup
[2.540s] [ext: omni.kit.widget.filter-1.1.2] startup
[2.541s] [ext: omni.kit.menu.create-1.0.11] startup
[2.543s] [ext: omni.kit.window.file_exporter-1.0.22] startup
[2.545s] [ext: omni.kit.hotkeys.core-1.3.0] startup
[2.550s] [ext: omni.kit.context_menu-1.6.8] startup
[2.552s] [ext: omni.kit.widget.stage-2.9.6] startup
[2.563s] [ext: omni.kit.primitive.mesh-1.0.15] startup
[2.566s] [ext: omni.kit.usd_undo-0.1.2] startup
[2.567s] [ext: omni.kit.stage_templates-1.1.20] startup
[2.569s] [ext: omni.kit.widget.searchfield-1.1.3] startup
[2.570s] [ext: omni.kit.widget.highlight_label-1.0.1] startup
[2.571s] [ext: omni.kit.window.file_importer-1.0.22] startup
[2.572s] [ext: omni.kit.window.property-1.9.6] startup
[2.575s] [ext: omni.ui_query-1.1.1] startup
[2.576s] [ext: omni.inspect-1.0.1] startup
[2.578s] [ext: usdrt.scenegraph-7.2.34] startup
[2.629s] [ext: omni.graph.tools-1.41.3] startup
[2.650s] [ext: omni.graph.core-2.139.12] startup
[2.655s] [ext: omni.kit.window.file-1.3.44] startup
[2.658s] [ext: omni.graph-1.106.1] startup
[2.808s] [ext: omni.kvdb-0.0.0] startup
[2.811s] [ext: omni.convexdecomposition-105.1.12-5.1] startup
[2.818s] [ext: omni.localcache-0.0.0] startup
[2.821s] [ext: omni.iray.libs-0.0.0] startup
[2.826s] [ext: omni.physx.foundation-105.1.12-5.1] startup
[2.827s] [ext: omni.usdphysics-105.1.12-5.1] startup
[2.831s] [ext: omni.mdl.neuraylib-0.2.0] startup
[2.833s] [ext: omni.isaac.version-1.0.3] startup
[2.835s] [ext: omni.physx.cooking-105.1.12-5.1] startup
[2.846s] [ext: omni.mdl-0.2.1] startup
[2.873s] [ext: omni.physics.tensors-0.1.0] startup
[2.883s] [ext: omni.physx-105.1.12-5.1] startup
2024-06-11 01:15:44 [2,879ms] [Warning] [omni.stageupdate.plugin] Deprecated: direct use of IStageUpdate callbacks is deprecated. Use IStageUpdate::getStageUpdate instead.
[2.900s] [ext: omni.kit.material.library-1.3.41] startup
[2.907s] [ext: omni.volume-0.4.0] startup
[2.911s] [ext: omni.physx.tensors-0.1.0] startup
[2.917s] [ext: omni.kit.numpy.common-0.1.2] startup
[2.920s] [ext: omni.hydra.rtx-0.1.0] startup
[2.932s] [ext: omni.warp.core-1.0.0-beta.2] startup
Warp 1.0.0-beta.2 initialized:
   CUDA Toolkit: 11.5, Driver: 12.2
   Devices:
     "cpu"    | x86_64
     "cuda:0" | NVIDIA RTX A6000 (sm_86)
   Kernel cache: /home/jai/.cache/warp/1.0.0-beta.2
[3.105s] [ext: omni.isaac.dynamic_control-1.2.6] startup
[3.119s] [ext: omni.debugdraw-0.1.2] startup
[3.126s] [ext: omni.isaac.core-3.3.2] startup
[4.519s] [ext: omni.hydra.pxr-1.1.6] startup
[4.527s] [ext: omni.kit.collaboration.presence_layer-1.0.8] startup
[4.533s] [ext: omni.kit.widget.prompt-1.0.6] startup
[4.535s] [ext: omni.kit.hydra_texture-1.1.12] startup
[4.543s] [ext: omni.hydra.engine.stats-1.0.1] startup
[4.549s] [ext: omni.kit.viewport.legacy_gizmos-1.0.14] startup
[4.555s] [ext: omni.kit.widget.viewport-105.1.7] startup
[4.561s] [ext: omni.kit.widget.searchable_combobox-1.0.5] startup
[4.564s] [ext: omni.kit.window.drop_support-1.0.1] startup
[4.565s] [ext: omni.kit.viewport.registry-104.0.5] startup
[4.567s] [ext: omni.kit.widget.settings-1.0.6] startup
[4.570s] [ext: omni.kit.window.content_browser_registry-0.0.1] startup
[4.572s] [ext: omni.kit.viewport.window-105.1.12] startup
[4.600s] [ext: omni.kit.window.preferences-1.3.23] startup
[4.609s] [ext: omni.kit.widget.graph-1.8.4] startup
[4.615s] [ext: omni.kit.window.content_browser-2.7.17] startup
[4.631s] [ext: omni.kit.viewport.utility-1.0.16] startup
[4.634s] [ext: omni.kit.widget.live_session_management-1.2.22] startup
[4.643s] [ext: omni.kit.window.extensions-1.3.0] startup
[4.651s] [ext: omni.kit.widget.text_editor-1.0.2] startup
[4.653s] [ext: omni.kit.property.usd-3.21.15] startup
[4.667s] [ext: omni.kit.manipulator.viewport-104.0.9] startup
[4.669s] [ext: omni.graph.ui-1.48.0] startup
[4.693s] [ext: omni.kit.ui_test-1.2.13] startup
[4.695s] [ext: omni.graph.visualization.nodes-2.1.1] startup
[4.721s] [ext: omni.graph.action-1.55.1] startup
[4.836s] [ext: omni.isaac.ui-0.13.5] startup
[4.865s] [ext: omni.isaac.surface_gripper-0.7.0] startup
[4.885s] [ext: omni.isaac.lula-2.1.0] startup
[4.897s] [ext: omni.kit.graph.delegate.default-1.1.1] startup
[4.899s] [ext: omni.isaac.manipulators-1.1.0] startup
[4.908s] [ext: omni.isaac.motion_generation-6.1.0] startup
[4.919s] [ext: omni.kit.graph.editor.core-1.5.1] startup
[4.923s] [ext: omni.kit.graph.delegate.modern-1.9.1] startup
[4.926s] [ext: omni.isaac.franka-0.4.0] startup
[4.931s] [ext: omni.kit.graph.widget.variables-2.1.0] startup
[4.933s] [ext: omni.kit.graph.usd.commands-1.3.0] startup
[4.936s] [ext: omni.isaac.universal_robots-0.3.3] startup
[4.941s] [ext: omni.isaac.cortex-0.3.5] startup
[4.945s] [ext: omni.graph.window.core-1.84.0] startup
[4.961s] [ext: omni.isaac.dofbot-0.3.1] startup
[4.965s] [ext: omni.isaac.cortex.sample_behaviors-1.0.4] startup
[4.970s] [ext: omni.graph.window.generic-1.9.3] startup
[4.978s] [ext: omni.isaac.kit-1.4.7] startup
[4.979s] [ext: omni.graph.window.action-1.11.2] startup
[4.989s] [ext: omni.kit.widget.zoombar-1.0.5] startup
[4.990s] [ext: omni.graph.image.core-0.1.0] startup
[4.992s] [ext: omni.kit.window.cursor-1.1.2] startup
[4.994s] [ext: omni.kit.browser.core-2.3.10] startup
[5.000s] [ext: omni.kit.widget.spinner-1.0.6] startup
[5.003s] [ext: omni.graph.nodes-1.106.3] startup
[5.635s] [ext: omni.kit.widget.material_preview-1.0.8] startup
[5.646s] [ext: omni.kit.browser.folder.core-1.9.7] startup
[5.657s] [ext: omni.kit.viewport.menubar.core-105.0.19] startup
[5.686s] [ext: omni.kit.renderer.cuda_interop-1.0.1] startup
[5.691s] [ext: omni.kit.window.material_graph-1.8.11] startup
[5.723s] [ext: omni.kit.browser.sample-1.4.6] startup
[5.728s] [ext: omni.syntheticdata-0.4.10] startup
[5.770s] [ext: omni.kit.livestream.core-2.3.0] startup
[5.774s] [ext: omni.kit.streamsdk.plugins-2.5.2] startup
[5.775s] [ext: omni.warp-1.0.0-beta.2] startup
[5.893s] [ext: omni.graph.scriptnode-1.1.6] startup
[5.904s] [ext: omni.command.usd-1.0.2] startup
[5.907s] [ext: omni.kit.livestream.native-2.4.0] startup

Active user not found. Using default user [kiosk]Streaming server started.
[6.066s] [ext: omni.replicator.core-1.10.20] startup
2024-06-11 01:15:47 [6,092ms] [Warning] [omni.replicator.core.scripts.annotators] Annotator PostProcessDispatch is already registered, overwriting annotator template
[6.386s] [ext: omni.kit.viewport.menubar.lighting-105.0.7] startup
[6.392s] [ext: omni.isaac.urdf-1.1.0] startup
2024-06-11 01:15:47 [6,375ms] [Warning] [omni.isaac.urdf] The extension omni.isaac.urdf has been deprecated. Please use omni.importer.urdf instead.
[6.393s] [ext: omni.isaac.core_nodes-1.7.1] startup
[6.444s] [ext: omni.isaac.cloner-0.7.2] startup
[6.447s] [ext: omni.isaac.utils-0.6.0] startup
[6.462s] [ext: omni.isaac.wheeled_robots-0.9.0] startup
[6.493s] [ext: omni.isaac.gym-0.10.0] startup
[6.496s] [ext: omni.kit.selection-0.1.3] startup
[6.499s] [ext: omni.kit.menu.common-1.1.4] startup
[6.502s] [ext: omni.kit.widget.layers-1.6.32] startup
[6.517s] [ext: omni.kit.menu.edit-1.1.14] startup
[6.522s] [ext: omni.kit.menu.file-1.1.7] startup
[6.525s] [ext: omni.kit.property.layer-1.1.5] startup
[6.529s] [ext: semantics.schema.editor-0.3.4] startup
[6.533s] [ext: omni.kit.property.camera-1.0.5] startup
[6.537s] [ext: omni.kit.property.audio-1.0.9] startup
[6.543s] [ext: omni.kit.profiler.window-2.1.2] startup
2024-06-11 01:15:48 [6,676ms] [Warning] [omni.kit.profiler.window] remove _SpanInstance.__lt__ and use insort 'key' arg instead
[6.697s] [ext: omni.kit.widget.stage_icons-1.0.4] startup
[6.699s] [ext: omni.hydra.scene_api-0.1.2] startup
[6.709s] [ext: omni.kit.property.light-1.0.8] startup
[6.713s] [ext: omni.kit.property.skel-1.0.4] startup
[6.717s] [ext: omni.kit.window.stage-2.4.4] startup
[6.724s] [ext: omni.kit.property.transform-1.3.10] startup
[6.730s] [ext: omni.kit.property.render-1.1.1] startup
[6.733s] [ext: omni.kit.property.material-1.8.36] startup
[6.739s] [ext: omni.kit.property.geometry-1.2.11] startup
[6.744s] [ext: omni.isaac.debug_draw-0.6.1] startup
2024-06-11 01:15:48 [6,733ms] [Warning] [omni.stageupdate.plugin] Deprecated: direct use of IStageUpdate callbacks is deprecated. Use IStageUpdate::getStageUpdate instead.
2024-06-11 01:15:48 [6,733ms] [Warning] [omni.stageupdate.plugin] Deprecated: direct use of IStageUpdate callbacks is deprecated. Use IStageUpdate::getStageUpdate instead.
[6.757s] [ext: omni.kit.menu.stage-1.2.3] startup
[6.761s] [ext: omni.kit.property.bundle-1.2.9] startup
[6.764s] [ext: omni.kit.property.isaac-0.2.2] startup
[6.768s] [ext: omni.isaac.occupancy_map-0.3.2] startup
[6.802s] [ext: omni.isaac.mjcf-1.0.0] startup
2024-06-11 01:15:48 [6,785ms] [Warning] [omni.isaac.mjcf] The extension omni.isaac.mjcf has been deprecated. Please use omni.importer.mjcf instead.
[6.803s] [ext: omni.kit.viewport.actions-105.1.6] startup
[6.811s] [ext: omni.kit.widget.toolbar-1.5.6] startup
[6.822s] [ext: omni.kit.raycast.query-1.0.1] startup
[6.833s] [ext: omni.kit.manipulator.transform-104.6.15] startup
[6.836s] [ext: omni.rtx.window.settings-0.6.9] startup
[6.844s] [ext: omni.kit.viewport.menubar.display-105.1.0] startup
[6.848s] [ext: omni.kit.manipulator.tool.snap-1.4.2] startup
[6.858s] [ext: omni.hydra.pxr.settings-1.0.5] startup
[6.861s] [ext: omni.activity.pump-1.0.0] startup
[6.863s] [ext: omni.physx.commands-105.1.12-5.1] startup
[6.868s] [ext: omni.usdphysics.ui-105.1.12-5.1] startup
[6.912s] [ext: omni.kit.widget.live-2.1.6] startup
[6.916s] [ext: omni.kit.viewport.pxr-104.0.1] startup
[6.916s] [ext: omni.kit.viewport.ready-1.0.5] startup
[6.919s] [ext: omni.kit.viewport.rtx-104.0.0] startup
[6.919s] [ext: omni.physx.ui-105.1.12-5.1] startup
[6.960s] [ext: omni.kit.widget.cache_indicator-2.0.8] startup
[6.963s] [ext: usdrt.gf-1.0.2] startup
[6.964s] [ext: omni.kit.manipulator.selector-1.0.1] startup
[6.968s] [ext: omni.kit.window.commands-0.2.4] startup
[6.971s] [ext: omni.kit.window.console-0.2.10] startup
[6.986s] [ext: omni.kit.property.physx-0.1.0] startup
[7.092s] [ext: omni.kit.actions.window-1.1.0] startup
[7.097s] [ext: omni.physx.demos-105.1.12-5.1] startup
[7.103s] [ext: omni.kit.manipulator.prim-105.0.11] startup
[7.112s] [ext: omni.kit.window.toolbar-1.5.4] startup
[7.117s] [ext: omni.kit.manipulator.selection-104.0.8] startup
[7.119s] [ext: omni.kit.window.script_editor-1.7.4] startup
[7.124s] [ext: omni.kit.hotkeys.window-1.4.1] startup
[7.130s] [ext: omni.physx.camera-105.1.12-5.1] startup
[7.141s] [ext: omni.physx.cct-105.1.12-5.1] startup
[7.163s] [ext: omni.physx.graph-105.1.12-5.1] startup
[7.178s] [ext: omni.physx.supportui-105.1.12-5.1] startup
[7.199s] [ext: omni.physx.vehicle-105.1.12-5.1] startup
[7.216s] [ext: omni.kit.stage_column.payload-1.0.12] startup
[7.219s] [ext: omni.graph.ui_nodes-1.5.10] startup
[7.281s] [ext: omni.sensors.nv.common-1000.0.0-isaacsim.2023.1.1] startup
[7.302s] [ext: omni.sensors.nv.materials-1000.0.0-isaacsim.2023.1.1] startup
[7.305s] [ext: omni.sensors.nv.wpm-1000.0.0-isaacsim.2023.1.1] startup
[7.306s] [ext: omni.kit.window.status_bar-0.1.6] startup
[7.314s] [ext: omni.physx.bundle-105.1.12-5.1] startup
[7.314s] [ext: omni.graph.bundle.action-2.0.4] startup
[7.314s] [ext: omni.isaac.range_sensor-2.0.2] startup
[7.381s] [ext: omni.sensors.nv.lidar-1000.0.1-isaacsim.2023.1.1] startup
[7.388s] [ext: omni.sensors.nv.radar-1000.0.0-isaacsim.2023.1.1] startup
[7.394s] [ext: omni.kit.window.title-1.1.3] startup
[7.396s] [ext: omni.replicator.composer-1.2.17] startup
[7.427s] [ext: omni.replicator.isaac-1.11.3] startup
[7.471s] [ext: omni.kit.manipulator.camera-105.0.4] startup
[7.475s] [ext: omni.kit.viewport.menubar.camera-105.1.9] startup
[7.483s] [ext: omni.isaac.sensor-9.11.1] startup
[7.594s] [ext: omni.kit.viewport.menubar.render-105.1.1] startup
[7.599s] [ext: omni.kit.viewport.menubar.settings-105.0.9] startup
[7.606s] [ext: omni.replicator.replicator_yaml-2.0.4] startup
[7.622s] [ext: omni.rtx.settings.core-0.5.13] startup
[7.629s] [ext: omni.kit.stage_column.variant-1.0.13] startup
[7.632s] [ext: omni.isaac.quadruped-1.4.1] startup
[7.652s] [ext: semantics.schema.property-1.0.2] startup
[7.655s] [ext: omni.kit.viewport.bundle-104.0.1] startup
[7.656s] [ext: omni.isaac.scene_blox-0.1.0] startup
[7.660s] [ext: omni.importer.urdf-1.6.1] startup
[7.723s] [ext: omni.importer.mjcf-1.1.0] startup
[7.735s] [ext: omni.kit.window.stats-0.1.4] startup
[7.737s] [ext: omni.isaac.sim.python-2023.1.1] startup
[7.739s] Simulation App Starting
2024-06-11 01:15:49 [7,754ms] [Warning] [omni.kit.widget.settings.settings_model] a value for setting /rtx/ecoMode/enabled has been requested but is not available
2024-06-11 01:15:49 [7,754ms] [Warning] [omni.kit.widget.settings.settings_model] a value for setting /rtx/directLighting/enabled has been requested but is not available
2024-06-11 01:15:49 [7,755ms] [Warning] [omni.kit.widget.settings.settings_model] a value for setting /rtx/reflections/enabled has been requested but is not available
2024-06-11 01:15:49 [7,755ms] [Warning] [omni.kit.widget.settings.settings_model] a value for setting /rtx/translucency/enabled has been requested but is not available
2024-06-11 01:15:49 [7,755ms] [Warning] [omni.kit.widget.settings.settings_model] a value for setting /rtx/raytracing/subsurface/enabled has been requested but is not available
2024-06-11 01:15:49 [7,755ms] [Warning] [omni.kit.widget.settings.settings_model] a value for setting /rtx/caustics/enabled has been requested but is not available
2024-06-11 01:15:51 [9,956ms] [Warning] [omni.kit.hotkeys.core.registry] [Hotkey] duplicated action as SPACE (On Press) with omni.kit.widget.toolbar.omni.kit.widget.toolbar::toolbar::play!
2024-06-11 01:15:51 [9,956ms] [Warning] [omni.kit.hotkeys.core.registry] [Hotkey] Cannot register Global [omni.kit.widget.toolbar] omni.kit.widget.toolbar::toolbar::play.SPACE, error code: Duplicated action definition
[11.862s] app ready
2024-06-11 01:15:54 [12,539ms] [Warning] [omni.kit.hotkeys.core.registry] [Hotkey] duplicated action as SPACE (On Press) with omni.kit.widget.toolbar.omni.kit.widget.toolbar::toolbar::play!
2024-06-11 01:15:54 [12,539ms] [Warning] [omni.kit.hotkeys.core.registry] [Hotkey] Cannot register Global [omni.kit.widget.toolbar] omni.kit.widget.toolbar::toolbar::play.SPACE, error code: Duplicated action definition
[12.917s] RTX ready
[13.362s] Simulation App Startup Complete
[13.387s] [ext: omni.isaac.ros_bridge-1.15.0] startup
2024-06-11 01:17:36 [115,354ms] [Warning] [omni.isaac.quadruped.robots.unitree_direct] asset path is: omniverse://localhost/NVIDIA/Assets/Isaac/2023.1.1/Isaac/Robots/Unitree/a1.usd
2024-06-11 01:17:37 [115,426ms] [Warning] [omni.isaac.sensor.scripts.imu_sensor] Creating a new IMU prim at path /World/A1/imu_link/imu_sensor
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/FL_hip/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/FL_thigh_shoulder/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/FR_hip/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/FR_thigh_shoulder/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/RL_hip/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/RL_thigh_shoulder/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/RR_hip/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,843ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/A1/RR_thigh_shoulder/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2024-06-11 01:17:53 [131,922ms] [Warning] [omni.physx.plugin] Detected an articulation at /World/A1 with more than 4 velocity iterations being added to a TGS scene.The related behavior changed recently, please consult the changelog. This warning will only print once.
2024-06-11 01:17:55 [134,179ms] [Warning] [omni.timeline.plugin] Deprecated: direct use of ITimeline callbacks is deprecated. Use ITimeline::getTimeline (Python: omni.timeline.get_timeline_interface) instead.
OmniGraphError: Failed trying to look up attribute with (/ROS_Clock/publishOdom.inputs:childFrameId, node=None, graph=None)
2024-06-11 01:17:56 [134,488ms] [Warning] [omni.usd] Unexpected reference count of 2 for UsdStage 'anon:0x13ce25b0:World0.usd' while being closed in UsdContext (this may indicate it is still resident in memory).
[134.625s] Simulation App Shutting Down
2024-06-11 01:17:56 [134,629ms] [Warning] [carb] [Plugin: omni.spectree.delegate.plugin] Module /home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/kit/exts/omni.usd_resolver/bin/libomni.spectree.delegate.plugin.so remained loaded after unload request
2024-06-11 01:17:56 [134,655ms] [Warning] [omni.core.ITypeFactory] Module /home/jai/.local/share/ov/pkg/isaac_sim-2023.1.1/kit/exts/omni.activity.core/bin/libomni.activity.core.plugin.so remained loaded after unload request.

Another thing I have noticed is that setting only odomFrameId doesn’t seem to throw any error, the error only pops up when I try to set the childFrameId

Thanks in advance,
Jai

Hi @textzip ,

The child frame field in the Omnigraph Odom node is actually called chassisFrameId.

Could you try running ("publishOdom.inputs:chassisFrameId", "base"), and seeing if that fixes it?

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.