Hello, I am preparing to transfer from Isaac Gym to Issac Sim.
Isaac Gym had a simple and user-familiar API for RL, and It has been of great help in my work.
However, transferring to Isaac Sim would be vital to merge visual perception in my workflow.
I think Isaac Sim is more functional, but a bit trickier to do RL tasks with.
One trouble is that the API of Isaac Sim does not enclose all functions included in Isaac Gym API.
Especially, I used acquire_net_contact_force_tensor() in Isaac Gym to model 3-axis force sensors in RL.
So far as I have experienced, it seems like there is no same function in Isaac Sim.
I guess contact sensors do not support the tensor API, and the articulated force sensor was unstable and not related to the contact forces.
Is there any other way to get the contact force tensor that I could not find?
Or, would the future update will include the function?
Hi - I was also making the transition from Isaac Gym to Omniverse Isaac Gym Envs and the documentation is not that clear - but there is access to tensors for rigid body contact force for multiple actors in rl learning.
here is the gist…using the OmbiIsaacGymEnvs task framework e.g. anymal.py but no need anymore for the anymalview import which just serves to confuse and is nor helpful if you are using your own model
from omni.isaac.core.articulations import ArticulationView #if you need an articulation view (likely)
from omni.isaac.core.prims import RigidPrimView
so this example takes the left foot prim from my biped.usd file for my 512 robot instances during training and detects if there is any contact force in the z plain (>0.00) that gives you a bool tensor to see if it is on the floor or not…
in the anymalview example in omniisaacgym look like they do combine the articulation view and the net force contact sensors but this version works for me.
Devs please look at documenting this better!! The two feature in the documentation that really are needed is explaining in general how views are handled, and how to obtain rigid body contact forces which is neede for pretty much all locomation tasks
Devs: does having fewer views/combining views make the rl more efficient?
Hi user15623 really glad to share!
its not really a trick as the contact forces must be calculated in order for the physics to work - it just exposes them which I think is NIVIDA’s intension but isaac sim is still in its maturing phase so they need to understand what we need.
they have now implemented a RigidContactView now (see NVIDIDIA’s reply here)
please share your project if possible(I apreciate you may be limited due to reasearch restrictions) as it sounds really interesting. Presumably a manipulation task.
Hi user15623 and sujitvasanth
As you have already figured out we do have isaac-sim APIs to get the contact data from the physics engine.
See this documentation page which explains about the different Isaac sim views. We are in the process of extending it to include more details. We are also extending the RigidContactView for the next release of Isaac sim to provide more detailed contact data.
I am facing the same problem, but the solution seems not effective for me. I have tried to follow the instruction, but anymal_c 's leg leave away from the body. I could not figure out the reason. This is the modification I tried:
for foot_name, body_name in self._feet_body_name.items():
# create rigid body view to track
feet_body = RigidPrimView(
prim_paths_expr=f"{prim_paths_expr}/{body_name}", name=foot_name, reset_xform_properties=False,
track_contact_forces=True, # enable contact forces
)
feet_body.initialize()
# add to list
self.feet_bodies[foot_name] = feet_body
I just add the track_contact_forces=True, ,and i got the result. When i delete this line, the simulation runs well, but I still could not get the contact force.
I dont know: what should i do to get the contact force between feet and the ground. I just add ’ track_contact_forces=True’, but the simulation gets wrong.
@yinghuile I’m not sure - suggest to check you have added your views to the scene an perhaops add an articulation view to ensure the joints are setup properly within the simulation.
I presume you have no made any changes to the robot model usd? It might be worth looking at the joint properties in an individual robot instance in the stage explorer (top right window) at runtime comparing the working version and the broken version.
Please keep me updated as I’m interested to see what the problem was…
unfortunately there is a lot of spade work done by the api now which may have led to this unintended consequence.
Actually i m using orbit, which is another RL environment based on Isaac sim. I doubt I failed to add the views to the scene. But I have no idea how to do, because there is no scene directly created in orbit from codes, so I could not directly add it to the scene. It seems using view.initialize function to realize the similar function. if I dont set the tracking force to true, everthing is ok. Is there any advice? It seems that there is problem to initialize the contact view. There is another one having succeded, but I still could not figure out. https://github.com/NVIDIA-Omniverse/Orbit/issues/97
In Isaac Sim, the workflow is: you create the simualtion stage, you add views to the scene, and you cal world.reset() that handles playing the simulation and initializing all the views.
In Orbit v0.1, we decided to make these operations more explicit for the user to define, in order to make it clearer what is happening where. So the workflow becomes:
Do sim.reset(): this is done by the base classIsaacEnv automatically
Create and initialize the views: done in the _initialize_views() function in the example environments
It is important to note that, in Omniverse, you cannot add new schemas once the simulation starts playing. This is because PhysX does the scene parsing the first time you do play and it prepares the GPU buffers accordingly. Modifying the prims in the stage afterwards can lead to issues from the PhysX side (similar to what you see above with the anymal example).