def test_jr2(): s = Simulator(mode='gui') try: scene = BuildingScene('Ohoopee') s.import_scene(scene) jr2 = JR2_Kinova(config) s.import_robot(jr2) jr2.set_position([-6, 0, 0.1]) obj3 = InteractiveObj(os.path.join(gibson2.assets_path, 'models', 'scene_components', 'door.urdf'), scale=2) s.import_interactive_object(obj3) obj3.set_position_rotation( [-5, -1, 0], [0, 0, np.sqrt(0.5), np.sqrt(0.5)]) jr2.apply_action([0.005, 0.005, 0, 0, 0, 0, 0, 0, 0, 0]) for _ in range(400): s.step() jr2.apply_action([ 0, 0, 0, 0, 3.1408197119196117, -1.37402907967774, -0.8377005721485424, -1.9804208517373096, 0.09322135043256494, 2.62937740156038 ]) for _ in range(400): s.step() finally: s.disconnect()
def test_import_rbo_object(): s = Simulator(mode='headless') try: scene = StadiumScene() s.import_scene(scene) obj = RBOObject('book') s.import_interactive_object(obj) obj2 = RBOObject('microwave') s.import_interactive_object(obj2) obj.set_position([0, 0, 2]) obj2.set_position([0, 1, 2]) obj3 = InteractiveObj( os.path.join(gibson2.assets_path, 'models', 'scene_components', 'door.urdf')) s.import_interactive_object(obj3) for i in range(100): s.step() finally: s.disconnect()
from gibson2.utils.utils import parse_config from gibson2.core.physics.interactive_objects import InteractiveObj import gibson2 import os import numpy as np import pybullet as p if __name__ == '__main__': s = Simulator(mode='gui') scene = BuildingScene('Ohoopee') s.import_scene(scene) door = InteractiveObj(os.path.join(gibson2.assets_path, 'models', 'scene_components', 'realdoor.urdf'), scale=0.3) s.import_interactive_object(door) x = p.addUserDebugParameter('x', -10, 10, 0) y = p.addUserDebugParameter('y', -10, 10, 0) z = p.addUserDebugParameter('z', -5, 5, 0) rotate = p.addUserDebugParameter('rotate', -np.pi, np.pi, 0) while True: x_pos = p.readUserDebugParameter(x) y_pos = p.readUserDebugParameter(y) z_pos = p.readUserDebugParameter(z) rotate_pos = p.readUserDebugParameter(rotate) door.set_position_rotation([x_pos, y_pos, z_pos], p.getQuaternionFromEuler([0, 0, rotate_pos])) s.step()
config = parse_config('../configs/jr_interactive_nav.yaml') s = Simulator(mode='headless', timestep=1 / 240.0) scene = EmptyScene() s.import_scene(scene) jr = JR2_Kinova(config) s.import_robot(jr) jr.robot_body.reset_position([0, 0, 0]) jr.robot_body.reset_orientation([0, 0, 1, 0]) fetch = Fetch(config) s.import_robot(fetch) fetch.robot_body.reset_position([0, 1, 0]) fetch.robot_body.reset_orientation([0, 0, 1, 0]) obj = InteractiveObj( filename='/data4/mdv0/cabinet/0007/part_objs/cabinet_0007.urdf') s.import_interactive_object(obj) obj.set_position([-2, 0, 0.5]) obj = InteractiveObj( filename='/data4/mdv0/cabinet/0007/part_objs/cabinet_0007.urdf') s.import_interactive_object(obj) obj.set_position([-2, 2, 0.5]) obj = InteractiveObj( filename='/data4/mdv0/cabinet/0004/part_objs/cabinet_0004.urdf') s.import_interactive_object(obj) obj.set_position([-2.1, 1.6, 2]) obj = InteractiveObj( filename='/data4/mdv0/cabinet/0004/part_objs/cabinet_0004.urdf') s.import_interactive_object(obj) obj.set_position([-2.1, 0.4, 2]) obj = BoxShape([-2.05, 1, 0.5], [0.35, 0.6, 0.5]) s.import_interactive_object(obj)