Isaac Sim Version
4.2.0
Operating System
Ubuntu 22.04
GPU Information
- Model: RTX 4080
- Driver Version: 570.124.06
I tried modifying start_isaac_sim_franka.py
to load my own robot and implement the Isaac Manipulator example. However, my ROS2 Publish Joint States cannot recognize the robot and returning the error:
[Error] [omni.graph.core.plugin] /ActionGraph/PublishJointState: [/ActionGraph] Prim is not an articulation.
Using the Filter, I can see the articulation, joints, and drivers as the picture below. I also tried loading the robot directly via URDF in the UI and reconfiguring the targetPrim
, but it still returns “Prim is not an articulation.”
Can anyone help me resolve this issue?
Error Messages
[Error] [omni.graph.core.plugin] /ActionGraph/PublishJointState: [/ActionGraph] Prim is not an articulation.
Screenshots or Videos
My Python Script
from isaacsim import SimulationApp
CONFIG = {"renderer": "RayTracedLighting", "headless": False}
simulation_app = SimulationApp(CONFIG)
from omni.isaac.core.utils import extensions
extensions.enable_extension("omni.isaac.ros2_bridge")
from omni.isaac.core import SimulationContext
simulation_context = SimulationContext(stage_units_in_meters=1.0)
# loading the robot USD
from omni.isaac.core.utils import prims, rotations
from pxr import Gf
import omni.isaac.core.utils
import numpy as np
ROBOT_STAGE_PATH = "/tcr6"
prims.create_prim(ROBOT_STAGE_PATH, "Xform",
position=np.array([0, -0.64, 0]),
orientation=rotations.gf_rotation_to_np_array(Gf.Rotation(Gf.Vec3d(0, 0, 1), -90)),
usd_path="/home/user/Documents/IsaacManipulatorProject/tcr6/urdf/tcr6/tcr6.usd",
)
# update view after loading
simulation_app.update()
# set ros domain ID
import os
try:
ros_domain_id = int(os.environ["ROS_DOMAIN_ID"])
except ValueError:
ros_domain_id = 0
except KeyError:
ros_domain_id = 0
# create an action graph with ROS component nodes
import omni.graph.core as og
GRAPH_PATH = "/ActionGraph"
try:
# setting input and output for nodes
og_keys_set_values = [
# ROS2 Context
("Context.inputs:domain_id", ros_domain_id),
# Articulation Controller Node
("ArticulationController.inputs:robotPath", ROBOT_STAGE_PATH), # Set the /TCR6_V600 target prim to Articulation Controller node
# ROS2 Publish Joint State
("PublishJointState.inputs:topicName", "isaac_joint_states"),
# ROS2 Subscribe Joint State
("SubscribeJointState.inputs:topicName", "isaac_joint_commands"),
]
# create nodes
og.Controller.edit(
# create ActionGraph tree node and execution
{"graph_path": GRAPH_PATH, "evaluator_name": "execution"},
{
# create and set input and output for nodes
og.Controller.Keys.CREATE_NODES: [
("OnImpulseEvent", "omni.graph.action.OnImpulseEvent"), # On Impulse Event
("ReadSimTime", "omni.isaac.core_nodes.IsaacReadSimulationTime"), # Isaac Read Simulation Time
("Context", "omni.isaac.ros2_bridge.ROS2Context"), # ROS2 COntext
("PublishJointState", "omni.isaac.ros2_bridge.ROS2PublishJointState"), # ROS2 Publish Joint State
("SubscribeJointState", "omni.isaac.ros2_bridge.ROS2SubscribeJointState",), # ROS2 Subscribe Joint State
("ArticulationController", "omni.isaac.core_nodes.IsaacArticulationController",), # Articulation Controller
("PublishClock", "omni.isaac.ros2_bridge.ROS2PublishClock"), # ROS2 Publish Clock
],
# setting nodes connect
og.Controller.Keys.CONNECT: [
# ("previouse node output", "connect to node input")
# On Impulse Event Node connect to ...
("OnImpulseEvent.outputs:execOut", "PublishJointState.inputs:execIn"),
("OnImpulseEvent.outputs:execOut", "SubscribeJointState.inputs:execIn"),
("OnImpulseEvent.outputs:execOut", "PublishClock.inputs:execIn"),
("OnImpulseEvent.outputs:execOut", "ArticulationController.inputs:execIn",),
# ROS2 Context Node connect to ...
("Context.outputs:context", "PublishJointState.inputs:context"),
("Context.outputs:context", "SubscribeJointState.inputs:context"),
("Context.outputs:context", "PublishClock.inputs:context"),
# Isaac Read Simulation Time Node connect to ...
("ReadSimTime.outputs:simulationTime", "PublishJointState.inputs:timeStamp",),
("ReadSimTime.outputs:simulationTime", "PublishClock.inputs:timeStamp"),
# ROS2 Subscribe Joint State Node connect to ...
("SubscribeJointState.outputs:jointNames", "ArticulationController.inputs:jointNames",),
("SubscribeJointState.outputs:positionCommand", "ArticulationController.inputs:positionCommand",),
("SubscribeJointState.outputs:velocityCommand", "ArticulationController.inputs:velocityCommand",),
("SubscribeJointState.outputs:effortCommand", "ArticulationController.inputs:effortCommand",),
],
# ActionGraph inilization
og.Controller.Keys.SET_VALUES: og_keys_set_values,
},
)
except Exception as e:
print(e)
# update view after add nodes in ActionGraph
simulation_app.update()
# setting the /Franka target prim to Publish JointState node
from omni.isaac.core.utils.prims import set_targets
from omni.isaac.core.utils import stage
set_targets(prim=stage.get_current_stage().GetPrimAtPath("/ActionGraph/PublishJointState"), attribute="inputs:targetPrim", target_prim_paths=[ROBOT_STAGE_PATH])
# update view after setting ROS2 Publish Joint State and
simulation_app.update()
# need to initialize physics getting any articulation..etc
simulation_context.initialize_physics()
# play simulation
simulation_context.play()
# do somthing while simulation
while simulation_app.is_running():
# run with a fixed step size
simulation_context.step(render=True)
# tick the Publish/Subscribe JointState, Publish TF and Publish Clock nodes each frame via Impulse signal of On Impulse Event Node
og.Controller.set(og.Controller.attribute("/ActionGraph/OnImpulseEvent.state:enableImpulse"), True)
# stop simulation
simulation_context.stop()
# close Isaac Sim
simulation_app.close()