Using ISAAC SIM as a graphical viewer without physics calculation?

I have an analysis model of a 60dof manipulator in MATLAB which gives the resultant angular positions. I’d like to use ISAAC SIM as a viewer of the calculated result, that is, no Physics engine calculation required.
I saw a few proposals to do it by reduing the mass and increase the stiffness to make the system to have a fast dynamics than the real manipulator.
It helped but after some extent it did not reduce the simulation time and became unstable, that is, joint constraint violated, etc. If proper mass and stiffness values are set, then the simulation is not fast enough. I think it is because of the calculation time for the 60dofs.

Is there a way to bypass the Physics engine and give the angular positions directly to each joint?
Or is there any way to make the simulation faster?

I am not sure whether there is a better way, but the issues is dealt with by using WritePrimAttribute and JointState as in the following ActionGraph.

ROS2 gets the jointstate message → Convert it to float → Get a joint value from the joint state by using the ArrayIndex → Write the joint value to the Joint State property directly by using the WritePrimAttribute such as
state:linear:physics:position or state:angular:physics:position

By doing this it updates the JointStates every simulation tick.

In Python Code, (Not exactly matching with the above graph, but same concept.)
og.Controller.edit(
{“graph_path”: “/ActionGraph”, “evaluator_name”: “execution”},
{
og.Controller.Keys.CREATE_NODES: [
(“OnTick”, “omni.graph.action.OnTick”),
(“SubscribeJointState”, “omni.isaac.ros2_bridge.ROS2SubscribeJointState”),
(“ToFloat”, “omni.graph.nodes.ToFloat”),
(“ArrayIndex1”, “omni.graph.nodes.ArrayIndex”),
(“ArrayIndex2”, “omni.graph.nodes.ArrayIndex”),
(“ArrayIndex3”, “omni.graph.nodes.ArrayIndex”),
(“WritePrimAttribute1”, “omni.graph.nodes.WritePrimAttribute”),
(“WritePrimAttribute2”, “omni.graph.nodes.WritePrimAttribute”),
(“WritePrimAttribute3”, “omni.graph.nodes.WritePrimAttribute”),
],
og.Controller.Keys.CONNECT: [
(“OnTick.outputs:tick”, “SubscribeJointState.inputs:execIn”),
(“SubscribeJointState.outputs:execOut”, “WritePrimAttribute1.inputs:execIn”),
(“SubscribeJointState.outputs:execOut”, “WritePrimAttribute2.inputs:execIn”),
(“SubscribeJointState.outputs:execOut”, “WritePrimAttribute3.inputs:execIn”),
(“SubscribeJointState.outputs:positionCommand”, “ToFloat.inputs:value”),
(“ToFloat.outputs:converted”, “ArrayIndex1.inputs:array”),
(“ToFloat.outputs:converted”, “ArrayIndex2.inputs:array”),
(“ToFloat.outputs:converted”, “ArrayIndex3.inputs:array”),
(“ArrayIndex1.outputs:value”, “WritePrimAttribute1.inputs:value”),
(“ArrayIndex2.outputs:value”, “WritePrimAttribute2.inputs:value”),
(“ArrayIndex3.outputs:value”, “WritePrimAttribute3.inputs:value”),
],
og.Controller.Keys.SET_VALUES: [
(“SubscribeJointState.inputs:topicName”, “/cmd_pos”),
(“ArrayIndex1.inputs:index”, 0),
(“ArrayIndex2.inputs:index”, 1),
(“ArrayIndex3.inputs:index”, 2),
(“WritePrimAttribute1.inputs:prim”, “/ART/ART_TRANSPORTER/D6J1/J1”),
(“WritePrimAttribute2.inputs:prim”, “/ART/ART_TRANSPORTER/D6J1/J2”),
(“WritePrimAttribute3.inputs:prim”, “/ART/ART_TRANSPORTER/D6J1/J3”),
(“WritePrimAttribute1.inputs:name”, “state:linear:physics:position”),
(“WritePrimAttribute2.inputs:name”, “state:linear:physics:position”),
(“WritePrimAttribute3.inputs:name”, “state:linear:physics:position”),
],
},
)

In my case, I used OnPhysicsStep node.
This works on physics step, not graphical fps.
So this will control the robot faster than OnTick node.

Note: the OnPhysicsStep needs to set in on-demand graph.
Don’t forget “pipeline_stage”: og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND in og.Controller.edit().

Example Graph:

   import omni.graph.core as og

    (ros_control_graph, _, _, _) = og.Controller.edit(
        {"graph_path": "/World/" + robot_name + "/ActionGraph", "evaluator_name": "execution", "pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND},
        {
            og.Controller.Keys.CREATE_NODES: [
                ("OnPhysicsStep", "omni.isaac.core_nodes.OnPhysicsStep"),
                ("PublishJointState", "omni.isaac.ros2_bridge.ROS2Publisher"),
                ("ArticulationState", "omni.isaac.core_nodes.IsaacArticulationState"),
                ("SubscribeJointState", "omni.isaac.ros2_bridge.ROS2Subscriber"),
                ("ArticulationController", "omni.isaac.core_nodes.IsaacArticulationController"),
                ("ReadSimTime", "omni.isaac.core_nodes.IsaacReadSimulationTime"),
                ("TimeSplitter", "omni.isaac.core_nodes.IsaacTimeSplitter"),
            ],
            og.Controller.Keys.CONNECT: [
                ("OnPhysicsStep.outputs:step", "PublishJointState.inputs:execIn"),
                ("OnPhysicsStep.outputs:step", "ArticulationState.inputs:execIn"),
                ("OnPhysicsStep.outputs:step", "SubscribeJointState.inputs:execIn"),
                ("OnPhysicsStep.outputs:step", "ArticulationController.inputs:execIn"),

                ("ReadSimTime.outputs:simulationTime", "TimeSplitter.inputs:time"),
            ],
            og.Controller.Keys.SET_VALUES: [
                # Providing path to /panda robot to Articulation Controller node
                # Providing the robot path is equivalent to setting the targetPrim in Articulation Controller node
                # ("ArticulationController.inputs:usePath", True),      # if you are using an older version of Isaac Sim, you may need to uncomment this line
                ("ArticulationController.inputs:targetPrim", art_path),
                ("ArticulationState.inputs:targetPrim", art_path),
                ("PublishJointState.inputs:messageName", "JointState"),
                ("PublishJointState.inputs:messagePackage", "sensor_msgs"),
                ("PublishJointState.inputs:topicName", joint_states_topic_name),
                ("SubscribeJointState.inputs:messageName", "JointState"),
                ("SubscribeJointState.inputs:messagePackage", "sensor_msgs"),
                ("SubscribeJointState.inputs:topicName", joint_commands_topic_name),
            ],
        },
    )
        
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/SubscribeJointState.outputs:name", "/World/" + robot_name + "/ActionGraph/ArticulationController.inputs:jointNames")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/SubscribeJointState.outputs:position", "/World/" + robot_name + "/ActionGraph/ArticulationController.inputs:positionCommand")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/SubscribeJointState.outputs:velocity", "/World/" + robot_name + "/ActionGraph/ArticulationController.inputs:velocityCommand")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/SubscribeJointState.outputs:effort", "/World/" + robot_name + "/ActionGraph/ArticulationController.inputs:effortCommand")

    og.Controller.connect("/World/" + robot_name + "/ActionGraph/TimeSplitter.outputs:seconds", "/World/" + robot_name + "/ActionGraph/PublishJointState.inputs:header:stamp:sec")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/TimeSplitter.outputs:nanoseconds", "/World/" + robot_name + "/ActionGraph/PublishJointState.inputs:header:stamp:nanosec")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/ArticulationState.outputs:jointNames", "/World/" + robot_name + "/ActionGraph/PublishJointState.inputs:name")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/ArticulationState.outputs:jointPositions", "/World/" + robot_name + "/ActionGraph/PublishJointState.inputs:position")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/ArticulationState.outputs:jointVelocities", "/World/" + robot_name + "/ActionGraph/PublishJointState.inputs:velocity")
    og.Controller.connect("/World/" + robot_name + "/ActionGraph/ArticulationState.outputs:measuredJointEfforts", "/World/" + robot_name + "/ActionGraph/PublishJointState.inputs:effort")
        
    og.Controller.evaluate_sync(ros_control_graph)