Building Your Own Environments

Building Your Own Environments#

robosuite offers great flexibility in creating your own environments. Atask typically involves the participation of arobot withgrippers as its end-effectors, anarena (workspace), andobjects that the robot interacts with. For a detailed overview of our design architecture, please check out theOverview page in Modules. Our Modeling APIs provide methods of composing these modularized elements into a scene, which can be loaded in MuJoCo for simulation. To build your own environments, we recommend you take a look at theEnvironment classes which have used these APIs to define robotics environments and tasks and thesource code of our standardized environments. Below we walk through a step-by-step example of building a new tabletop manipulation environment with our APIs.

Step 1: Creating the world. All mujoco object definitions are housed in an xml. We create aMujocoWorldBase class to do it.

fromrobosuite.modelsimportMujocoWorldBaseworld=MujocoWorldBase()

Step 2: Creating the robot. The class housing the xml of a robot can be created as follows.

fromrobosuite.models.robotsimportPandamujoco_robot=Panda()

We can add a gripper to the robot by creating a gripper instance and calling the add_gripper method on a robot.

fromrobosuite.models.grippersimportgripper_factorygripper=gripper_factory('PandaGripper')mujoco_robot.add_gripper(gripper)

To add the robot to the world, we place the robot on to a desired position and merge it into the world

mujoco_robot.set_base_xpos([0,0,0])world.merge(mujoco_robot)

Step 3: Creating the table. We can initialize theTableArena instance that creates a table and the floorplane

fromrobosuite.models.arenasimportTableArenamujoco_arena=TableArena()mujoco_arena.set_origin([0.8,0,0])world.merge(mujoco_arena)

Step 4: Adding the object. For details ofMujocoObject, refer to the documentation aboutMujocoObject, we can create a ball and add it to the world.

fromrobosuite.models.objectsimportBallObjectfromrobosuite.utils.mjcf_utilsimportnew_jointsphere=BallObject(name="sphere",size=[0.04],rgba=[0,0.5,0.5,1]).get_obj()sphere.set('pos','1.0 0 1.0')world.worldbody.append(sphere)

Step 5: Running Simulation. Once we have created the object, we can obtain amujoco.MjModel model by running

model=world.get_model(mode="mujoco")

This is anMjModel instance that can then be used for simulation. For example,

importmujocodata=mujoco.MjData(model)whiledata.time<1:mujoco.mj_step(model,data)