Articulation Controller not working

Hello,

I’m experiencing serious problems with articulations in Isaac Sim 2022.1.1.
I simply cannot get my models to respond to JointState messages from ROS in neither drive type.

I built an isolated test scenario consisting of two cubes linked by a revolute joint with an angular drive component, which you can find attached.
The ActionGraph is built accordingly to 9. Joint Control: Extension Python Scripting — Omniverse Robotics documentation.
I can manually set a target velocity to the drive component and the lower cube starts turning. However when sending JointState message from ROS there is no reaction at all. The PrintText node shows seemingly correct data from the Subscriber Node.

It would be great to get some help here as it’s probably just a minor problem I’m struggling with.
Thank you very much!

Joint_test.usd (12.0 KB)

Hello,
You have to add Articulation Root (Add->Physics->Articulation Root) for one of the cubes. For some reason I can’t do that for your scene. Try to rebuild the scene.

Articulation Controller has to to apply to an articulation chain, so you need to add an Articulation Root to one of your cubes to indicate that your object is an articulation. It is strange that we can’t add an articulation root to either of your cubes, did you build your scene via a python script? Try to rebuild the scene like @pme1976 mentioned, but do it in the UI, and you should be able to find the Articulation Root option under Add → Physics list.

Thank you guys for your help!
Regarding the articulation root: You couldn’t add one because one was already present in the “world” prim.

I still rebuilt the scene and added the articulation root to one of the cubes like you mentioned, however with no improvement. You can find the new scene attached.
What I find interesting is that the JointState Publisher, targeted towards the same prim, works just fine.

Joint_test_V2.usd (7.9 KB)

@qwan @pme1976
To rule out potential errors when building the scene I now also tried using a provided model (the forklift).
Forklift_Test.usd (7.9 KB)
I tried controlling the “back_wheel_drive” joint via ROS but once again without success.
Do you have any further suggestions on what to try? Would you be able to quickly test it on your own system?
Thanks a lot!

There is an error in the Articulation Controller code. Here is the code OgnIsaacArticulationController.py:

if joint_positions != []:
    joint_actions.joint_positions = joint_positions
elif joint_velocities != []:
    joint_actions.joint_velocities = joint_velocities
elif joint_efforts != []:
    joint_actions.joint_efforts = joint_efforts

if, for example, joint_velocities = np.array([1.0]), the expression:

joint_velocities != [] 

returns

[]

But if joint_velocities = np.array([1.0, 2.0]) for another model, this expression returns

True

Change code in Articulation Controller:

if joint_positions.size > 0:
    joint_actions.joint_positions = joint_positions
elif joint_velocities.size > 0:
    joint_actions.joint_velocities = joint_velocities
elif joint_efforts.size > 0:
    joint_actions.joint_efforts = joint_efforts

and everything will be OK.

Yes, that did it!
Thank you so much!

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