Fluid simulation need the physics scene’s boardphase type to be GPU. But it makes the position type not allowed to be numpy. So I just remove the original physics scene, and create a new one. My code works well in Hello World Extension, However it doesn’t work in standalone python environment. When it come to physical step, it show the error 'raise Exception(“The Physics Context’s physics scene path is invalid, you need to reinit Physics Context”)
Exception: The Physics Context’s physics scene path is invalid, you need to reinit Physics Context
’ .
I just wonder how to set the physics scene to simulate a Franka robot grab a beaker with fluid.
My code is below:
#launch Isaac Sim before any other imports
#default first two lines in any standalone application
from omni.isaac.kit import SimulationApp
simulation_app = SimulationApp({"headless": False})
from omni.isaac.franka.controllers.rmpflow_controller import RMPFlowController
from omni.isaac.core.utils.rotations import euler_angles_to_quat
from pick_move_controller import PickMoveController
from pour_controller import PourController
from omni.physx.scripts import physicsUtils, particleUtils, utils
from pxr import Sdf, Gf, UsdPhysics
import numpy as np
from utils import Utils
from omni.isaac.core import World
from chem_lab_task import Chem_Lab_Task_SL
my_world = World(stage_units_in_meters=1.0)
utils = Utils(my_world)
stage = my_world.scene.stage
scenePath = Sdf.Path("/World/physicsScene")
scene = UsdPhysics.Scene.Define(stage, scenePath)
my_world.add_task(Chem_Lab_Task_SL(name ='Chem_Lab_Task_SL'))
my_world.reset()
stage.RemovePrim(Sdf.Path("physicsScene"))
# particle params
utils._set_particle_parameter()
# Particle System
particleSystemPath1 = Sdf.Path("/World/Room/simple_room/particleSystem1")
particle_system1 = utils._add_particle_system(
particle_system_path=particleSystemPath1,
simulation_owner=scenePath,
)
# Get the material
pbd_particle_material_path1 , glass_material_shader1 = utils.create_and_bind_mdl_material(
mdl_name = "OmniSurfacePresets.mdl",
mtl_name = "OmniSurface_ClearWater",
prim_path = particleSystemPath1,
)
# set the color
glass_material_shader1.CreateInput("specular_transmission_color", Sdf.ValueTypeNames.Color3f).Set((1, 1, 1))
_,cube_material_shader = utils.create_and_bind_mdl_material(
mdl_name = "OmniSurfacePresets.mdl",
mtl_name = "OmniSurface_BrushedMetal",
prim_path = "/World/Room/simple_room/random_cube",
)
cube_material_shader.CreateInput("diffuse_reflection_color", Sdf.ValueTypeNames.Color3f).Set((0.54, 0.27, 0.075))
# Create a pbd particle material and set it on the particle system
particleUtils.add_pbd_particle_material(
stage,
pbd_particle_material_path1,
cohesion=0.01,
viscosity=0.0091,
surface_tension=0.0074,
friction=0.1,
)
physicsUtils.add_physics_material_to_prim(stage, particle_system1.GetPrim(), pbd_particle_material_path1)
utils._set_isosurface_particle_system(particle_system1)
particlesPath1 = Sdf.Path("/World/Room/simple_room/particles1")
utils._add_particle_set(
particle_set_path = particlesPath1,
simulation_owner=scenePath,
particle_system_path = particleSystemPath1,
center = Gf.Vec3f(-0.35-0.01, -0.4-0.02, 0.08)
)
franka = my_world.scene.get_object("fancy_franka")
cube = my_world.scene.get_object("fancy_cube")
print(type(franka))
fancy_beaker1 = my_world.scene.get_object("fancy_beaker1")
fancy_beaker1.set_world_pose(position=np.array([-0.35, -0.4, 0.0]))
fancy_beaker1.set_default_state(position=np.array([-0.35, -0.4, 0.0]))
fancy_beaker2 = my_world.scene.get_object("fancy_beaker2")
fancy_beaker2.set_world_pose(position=np.array([-0.35, -0.08, 0.0]))
fancy_beaker2.set_default_state(position=np.array([-0.35, -0.4, 0.0]))
rbApi1 = UsdPhysics.RigidBodyAPI.Apply(fancy_beaker1.prim.GetPrim() )
rbApi1.CreateRigidBodyEnabledAttr(True)
rbApi2 = UsdPhysics.RigidBodyAPI.Apply(fancy_beaker2.prim.GetPrim())
rbApi2.CreateRigidBodyEnabledAttr(True)
gripper = franka.gripper
# Initialize a pour controller
pour_controller = PourController(
name="pour_controller",
cspace_controller=RMPFlowController(name="pour_cspace_controller", robot_articulation=franka),
gripper=gripper,
)
# Initialize a pour controller
controller = PickMoveController(
name="pickmove_controller",
cspace_controller=RMPFlowController(name="pickmove_cspace_controller", robot_articulation=franka),
gripper=gripper,
)
print(my_world._physics_context.get_current_physics_scene_prim())
while simulation_app.is_running():
my_world.step(render=True)
if my_world.is_playing():
if my_world.current_time_step_index == 0:
my_world.reset()
controller.reset()
print('.......')
current_observations = my_world.get_observations()
actions = controller.forward(
picking_position = current_observations["fancy_beaker1"]["position"],
target_position = np.array([current_observations["fancy_beaker2"]["position"][0], current_observations["fancy_beaker2"]["position"][1]-0.08, current_observations["fancy_beaker2"]["position"][2]+0.1]),
current_joint_positions = current_observations["fancy_franka"]["joint_positions"],
end_effector_offset=np.array([0.01, 0.02, 0.07]),
end_effector_orientation=euler_angles_to_quat(np.array([-np.pi/2, np.pi/2, np.pi/2])),
)
franka.apply_action(actions)
# Only for the pour controller, indicating if the state
# machine reached the final state.
if(controller.is_done()):
actions2 = pour_controller.forward(
franka_art_controller=franka.get_articulation_controller(),
current_joint_velocities=franka.get_joint_velocities(),
)
franka.apply_action(actions2)
if(pour_controller.is_poured()):
glass_material_shader1.CreateInput("specular_transmission_color", Sdf.ValueTypeNames.Color3f).Set((0.60, 0.70, 0.59))
cube_material_shader.CreateInput("diffuse_reflection_color", Sdf.ValueTypeNames.Color3f).Set((0.75, 0.75, 0.75))
if pour_controller.is_done():
my_world.pause()
simulation_app.close()
Here is my simulation scene