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()
Exemplo n.º 2
0
    def __init__(self,
                 config_file,
                 mode='headless',
                 action_timestep=1 / 10.0,
                 physics_timestep=1 / 240.0,
                 device_idx=0,
                 automatic_reset=False):
        super(InteractiveNavigateEnv,
              self).__init__(config_file,
                             mode=mode,
                             action_timestep=action_timestep,
                             physics_timestep=physics_timestep,
                             automatic_reset=automatic_reset,
                             device_idx=device_idx)
        door = InteractiveObj(os.path.join(gibson2.assets_path, 'models',
                                           'scene_components',
                                           'realdoor.urdf'),
                              scale=1.35)
        self.simulator.import_interactive_object(door)

        wall1 = InteractiveObj(os.path.join(gibson2.assets_path, 'models',
                                            'scene_components', 'walls.urdf'),
                               scale=1)
        self.simulator.import_interactive_object(wall1)
        wall1.set_position_rotation([0, -1.5, 1], [0, 0, 0, 1])

        wall2 = InteractiveObj(os.path.join(gibson2.assets_path, 'models',
                                            'scene_components', 'walls.urdf'),
                               scale=1)
        self.simulator.import_interactive_object(wall2)
        wall2.set_position_rotation([0, 1.5, 1], [0, 0, 0, 1])
        door.set_position_rotation(
            [0, 0, -0.02],
            [0, 0, np.sqrt(0.5), np.sqrt(0.5)])
Exemplo n.º 3
0
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()