Using ROS JointState with different joint names than in topic

I’ve imported a robot using the URDF importer (via Python API) and now want to control it via ROS. The robot originally had /'s in its joint names, so to do the import, I had to replace the /'s with _'s. However, this means that the JointState messages getting sent out still have /'s in the joint names, and so won’t be able to interface with the robot. One solution I’ve got is to create a ROS node that takes in the JointState messages and publishes the exact same messages, just with the cleaned names. Is there any other way of controlling the robot with the ROS messages with different joint names than the ones I am using in Isaac? Eg defining some sort of correspondence between the names with /'s in them and the cleaned ones.

Additionally, what does the articulation_prim_rel parameter do in the ROSCreateJointState command?

can you share a minimal urdf that reproduces this issue?

articulation_prim_rel is a usd reference to the root of the articulation. Basically it tells the joint control component what robot to control. The easiest way to determine this is to check which prim has the following under the properties tab
image

Its a list of strings, but only the first element is used.
articulation_prim_rel = ["/path/to/root/prim"]

python_samples/ros/moveit.py has an example of usage as well.

Setting up an example will take a bit of effort – might be a while before I can send one.

The idea is that I pre-processed the URDF by changing all the /'s in names to _'s. However, I have existing code that’s publishing joint commands for the robot in the URDF. The existing code uses the old joint names though, with the /'s.

I’ve succeeded in controlling the robot regardless by using an intermediary node that takes the joint command messages and changes the names to have _'s instead of /'s, then republishing. However, I wanted to know if it was possible to do this without the intermediate, instead entirely using Isaac’s Python API.

Also just to clarify – would the main purpose of articulation_prim_rel thus be to differentiate between different robots with the same joint names?

Ahh ok, I understand now, no repro is needed.

You could bypass the joint control component entirely and add a custom rospy subscriber + dynamic_control’s python api to drive the joint targets each frame. Thats what happens internally but at a c++ level. See here

Yes articulation_prim_rel is basically to point a ros component at a specific robot, so if you have multiple components and robots things stay unique even if the robot’s themselves have the same joint names.

1 Like

Ah alright, I think I understand! So the process for the subscriber would be something like:

  1. Receive the JointState message.
  2. For each joint name in the list, clean it to have _'s.
  3. Use dc.find_articulation_dof() to get a pointer to the joint with that cleaned name in Isaac.
  4. Manually set that joint’s angle to the one in the message using dc.set_dof_position_target().

Does that sound right? Thanks so much for your help!!!

  1. Receive the JointState message.
  2. call dc.wake_up_articulation(art) once per frame if you are changing a joint angle. Physx will put an articulation to sleep if its not moving or interacted with to save on computation, this forces it to wake back up to guarantee any state changes go through
  3. Use dc.find_articulation_dof() to get a pointer to the joint with that cleaned name in Isaac. (This can be done once at the start to reduce computations, a frame after .play() is called so physics is initialized. The handles will remain valid after that (even if you .stop(), and .play() again)
  4. For each joint name in the list, clean it to have _'s.
  5. Manually set that joint’s angle to the one in the message using dc.set_dof_position_target().
1 Like

Just wondering, when getting art, is the string you input into dc.get_articulation() the same as the path returned by:

 omni.kit.commands.execute(
            "URDFParseAndImportFile",
            urdf_path=urdf_path,
            import_config=import_config,
        )

I’m trying this and it’s not working.

I’ve minimally modified the existing urdf_import.py script. Does this answer the question?
for me it prints something like
Got articulation /carter with handle 1116691496961
urdf_import.py (4.2 KB)

diff is below:

--- a/python_samples/simple/urdf_import.py
+++ b/python_samples/simple/urdf_import.py
@@ -19,6 +19,7 @@ if __name__ == "__main__":
     # URDF import, configuration and simualtion sample
     kit = OmniKitHelper(config=CONFIG)
     import omni.kit.commands
+    from omni.isaac.dynamic_control import _dynamic_control
     from pxr import Sdf, Gf, UsdPhysics, UsdLux, PhysxSchema
 
     # Setting up import configuration:
@@ -32,8 +33,8 @@ if __name__ == "__main__":
     ext_manager = omni.kit.app.get_app().get_extension_manager()
     ext_id = ext_manager.get_enabled_extension_id("omni.isaac.urdf")
     extension_path = ext_manager.get_extension_path(ext_id)
-    # Import URDF
-    omni.kit.commands.execute(
+    # Import URDF, stage_path contains the path the path to the usd prim in the stage.
+    status, stage_path = omni.kit.commands.execute(
         "URDFParseAndImportFile",
         urdf_path=extension_path + "/data/urdf/robots/carter/urdf/carter.urdf",
         import_config=import_config,
@@ -87,8 +88,18 @@ if __name__ == "__main__":
     left_wheel_drive.GetStiffnessAttr().Set(0)
     right_wheel_drive.GetStiffnessAttr().Set(0)
 
+    dc = _dynamic_control.acquire_dynamic_control_interface()
+
     # Start simulation
     kit.play()
+    # perform one simulation step so physics is loaded and dynamic control works.
+    kit.update(1.0 / 60.0)
+    art = dc.get_articulation(stage_path)
+
+    if art == _dynamic_control.INVALID_HANDLE:
+        print(f"{stage_path} is not an articulation")
+    else:
+        print(f"Got articulation {stage_path} with handle {art}")
 
     # perform simulation
     for frame in range(100):
1 Like

Yep, that worked. It seems like my code didn’t work because it didn’t have kit.play() before the get articulation call. I missed the part at the top of the docs saying “Start physics simulation, at least one frame of simulation must occur before the Dynamic Control interface will become fully active.”

Thanks so much for your help!

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