pyrfuniverse.envs package

pyrfuniverse.envs.base_env module

class pyrfuniverse.envs.base_env.RFUniverseBaseEnv(executable_file: str | None = None, scene_file: str | None = None, assets: list = [], graphics: bool = True, port: int = 5004, proc_id=0, log_level=1)

Bases: ABC

RFUniverse base environment class.

Parameters:
  • executable_file – Str, the absolute path of Unity executable file. None for last used executable file; “@editor” for using Unity Editor.

  • scene_file – Str, the absolute path of Unity scene JSON file. All JSON files locate at StraemingAssets/SceneData by default.

  • assets – List, the list of pre-load assets. All assets in the list will be pre-loaded in Unity when the environment is initialized, which will save time during instanciating.

  • graphics – Bool, True for showing GUI and False for headless mode.

step(count: int = 1)

Send the messages of called functions to Unity and simulate for a step, then accept the data from Unity.

Parameters:

count – the number of steps for executing Unity simulation.

close()

Close the environment

GetAttr(id: int)

Get the attribute instance by object id.

Parameters:

id – Int, object id.

Returns:

An instance of attribute.

Return type:

pyrfuniverse.attributes.BaseAttr

PreLoadAssetsAsync(names: list, auto_wait: bool = False) None

PreLoad the asset.

Parameters:
  • names – list, the name of assets.

  • auto_wait – Bool, if True, this function will not return until the loading is done.

LoadSceneAsync(file: str, auto_wait: bool = False) None

Load the scene asynchronisely.

Parameters:
  • file – Str, the scene JSON file. If it’s a relative path, it will load from StraemingAssets.

  • auto_wait – Bool, if True, this function will not return until the loading is done.

SwitchSceneAsync(name: str, auto_wait: bool = False) None

Switch the scene asynchronisely.

Parameters:
  • name – Str, the scene name.

  • auto_wait – Bool, if True, this function will not return until the loading is done.

WaitLoadDone() None

Wait for the loading is done.

Pend() None

Pend the program until the EndPend button in UnityPlayer is clicked.

SendMessage(message: str, *args) None

Send message to Unity.

Parameters:
  • message – Str, the message head.

  • *args – List, the list of parameters. We support str, bool, int, float and List[float] types.

SendObject(head: str, *args) None

Send object to Unity.

Parameters:
  • head – Str, the message head.

  • *args – List, the list of parameters. We support str, bool, int, float and List[float] types.

AddListener(message: str, fun)

Add listener.

Parameters:
  • message – Str, the message head.

  • fun – Callable, the callback function.

RemoveListener(message: str, fun)

Remove listener.

Parameters:
  • message – Str, the message head.

  • fun – Callable, the callback function.

AddListenerObject(type: str, fun)

Add object listener.

Parameters:
  • type – Str, the message head.

  • fun – Callable, the callback function.

RemoveListenerObject(type: str)

Remove object listener.

Parameters:

type – Str, the message head.

InstanceObject(name: str, id: int | None = None, attr_type: type = <class 'pyrfuniverse.attributes.base_attr.BaseAttr'>)

Instanciate an object.

Built-in assets:

GameObjectAttr:
Basic Objects:

“GameObject_Box”, “GameObject_Capsule”, “GameObject_Cylinder”, “GameObject_Sphere”, “GameObject_Quad”,

IGbison Meshes:

“Hainesburg_mesh_texture”, “Halfway_mesh_texture”, “Hallettsville_mesh_texture”, “Hambleton_mesh_texture”, “Hammon_mesh_texture”, “Hatfield_mesh_texture”, “Haxtun_mesh_texture”, “Haymarket_mesh_texture”, “Hendrix_mesh_texture”, “Hercules_mesh_texture”, “Highspire_mesh_texture”, “Hitchland_mesh_texture”,

ColliderAttr:

“Collider_Box”, “Collider_ObiBox”, “Collider_Capsule”, “Collider_Cylinder”, “Collider_Sphere”, “Collider_Quad”,

RigidbodyAttr:
Basic Objects:

“Rigidbody_Box”, “GameObject_Capsule”, “Rigidbody_Cylinder”, “Rigidbody_Sphere”,

YCB dataset:

77 models in YCB dataset. See YCB Object and Model Set for detail: https://rse-lab.cs.washington.edu/projects/posecnn/

ControllerAttr:
gripper:

“allegro_hand_right”, “bhand”, “svh”, “robotiq_arg2f_85_model”, “dh_robotics_ag95_gripper”,

robot:

“kinova_gen3”, “kinova_gen3_robotiq85”, “ur5”, “ur5_robotiq85”, “franka_panda”, “franka_hand”, “tobor_robotiq85_robotiq85”, “flexivArm”, “flexivArm_ag95”, “yumi”,

CameraAttr:

“Camera”,

LightAttr:

“Light”,

Parameters:
  • name – Str, object name. Please check the above built-in assets list for names.

  • id – Int, object id.

  • attr_type – type(pyrfuniverse.attributes.BaseAttr), the attribute type.

Returns:

The object attribute instance.

Return type:

type(attr_type)

LoadURDF(path: str, id: int | None = None, native_ik: bool = False, axis: str = 'y') ControllerAttr

Load a model from URDF file.

Parameters:
  • path – Str, the URDF file path.

  • id – Int, object id.

  • native_ik – Bool, True for enabling native IK; False for using custom IK.When it is True, through the IKTargetDo*** interface, according to the end pose.When it is False, through the SetJoint*** interface, according to the joint movement.

  • axis – Str, import axis, This can be ‘z’ or ‘y’, depending on the URDF file

Returns:

The object attribute intance.

Return type:

pyrfuniverse.attributes.ControllerAttr

LoadMesh(path: str, id: int | None = None) RigidbodyAttr

Load a model from Mesh file.

Parameters:
  • path – Str, the Mesh file path.

  • id – Int, object id.

Returns:

The object attribute intance.

Return type:

pyrfuniverse.attributes.RigidbodyAttr

IgnoreLayerCollision(layer1: int, layer2: int, ignore: bool) None

Ignore or enable the collision between two layers.

Parameters:
  • layer1 – Int, the layer number of the first layer.

  • layer2 – Int, the layer number of the second layer.

  • ignore – Bool, True for ignoring collision between two layers; False for enabling collision between two layers.

GetCurrentCollisionPairs() None

Get the collision pairs of current collision. After calling this method and stepping once, the result will be saved in env.data[‘CurrentCollisionPairs’]

GetRFMoveColliders() None

Get the RFMove colliders. After calling this method and stepping once, the result will be saved in env.data[‘RFMoveColliders’]

SetGravity(x: float, y: float, z: float) None

Set the gravity of environment.

Parameters:
  • x – Float, gravity on global x-axis (right).

  • y – Float, gravity on global y-axis (up).

  • z – Float, gravity on global z-axis (forward).

SetGroundActive(active: bool) None

Set the ground active or inactive.

Parameters:

active – Bool, active or inactive the ground.

SetGroundPhysicMaterial(bounciness: float, dynamic_friction: float, static_friction: float, friction_combine: int, bounce_combine: int) None

Set the physics material of ground in environment.

Parameters:
  • bounciness – Float, the bounciness.

  • dynamic_friction – Float, the dynamic friction coefficient (0-1).

  • static_friction – Float, the static friction coefficient (0-1).

  • friction_combine – Int, how friction of two colliding objects is combined. 0 for Average, 1 for Minimum, 2 for Maximum and 3 for Multiply. See https://docs.unity3d.com/Manual/class-PhysicMaterial.html for more details.

  • bounce_combine – Int, how bounciness of two colliding objects is combined. The value representation is the same with friction_combine.

SetTimeStep(delta_time: float) None

Set the time for a step in Unity.

Parameters:

delta_time – Float, the time for a step in Unity.

SetTimeScale(time_scale: float) None

Set the time scale in Unity.

Parameters:

time_scale – Float, the time scale in Unity.

SetResolution(resolution_x: int, resolution_y: int) None

Set the resolution of windowed GUI.

Parameters:
  • resolution_x – Int, window width.

  • resolution_y – Int, window height.

ExportOBJ(items_id: list, save_path: str) None

Export the specified object list to OBJ file. For native bundle models, the Read/Write must be checked in Unity Editor.

Parameters:
  • items_id – List, the object ids.

  • save_path – Str, the path to save the OBJ files.

SetShadowDistance(distance: float) None

Set the shadow distance for rendering in environment.

Parameters:

distance – Float, the shadow distance measured in meter.

SaveScene(file: str) None

Save current scene.

Parameters:

file – Str, the file path to save current scene. Default saving to StreamingAssets folder.

ClearScene() None

Clear current scene.

AlignCamera(camera_id: int) None

Align current GUI view to a given camera.

Parameters:

camera_id – Int, camera id.

SetViewTransform(position: list | None = None, rotation: list | None = None) None

Set the GUI view.

Parameters:
  • position – A list of length 3, representing the position of GUI view.

  • rotation – A list of length 3, representing the rotation of GUI view.

ViewLookAt(target: list, world_up: list | None = None) None

Rotates the transform so the forward vector points at target’s current position.

Parameters:
  • target – A list of length 3, target to point towards.

  • world_up – A list of length 3, vector specifying the upward direction.

SetViewBackGround(color: list | None = None) None

Set the GUI view.

Parameters:

color – A list of length 3, background color of GUI view. None : default skybox.

DebugGraspPoint(enabled: bool = True) None

Show or hide end effector of robot arm for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

DebugObjectPose(enabled: bool = True) None

Show or hide object base point for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

DebugCollisionPair(enabled: bool = True) None

Show or hide collision pairs for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

DebugColliderBound(enabled: bool = True) None

Show or hide collider bounding box for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

DebugObjectID(enabled: bool = True) None

Show or hide object id for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

Debug3DBBox(enabled: bool = True) None

Show or hide 3d bounding box of objects for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

Debug2DBBox(enabled: bool = True) None

Show or hide 2d bounding box of objects for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

Show or hide joint information of articulation for debug.

Parameters:

enabled – Bool, True for showing and False for hiding.

SendLog(log: str) None

Send log messange and show it on Unity GUI window.

Parameters:

log – Str, log message.

ShowArticulationParameter(controller_id: int) None

Show Articulation Parameter on Unity GUI window.

Parameters:

controller_id – int, controller_attr id.

pyrfuniverse.envs.gym_wrapper_env module

class pyrfuniverse.envs.gym_wrapper_env.RFUniverseGymWrapper(executable_file: str | None = None, scene_file: str | None = None, assets: list = [], **kwargs)

Bases: RFUniverseBaseEnv, Env

close()

Close the environment

pyrfuniverse.envs.gym_goal_wrapper_env module

class pyrfuniverse.envs.gym_goal_wrapper_env.RFUniverseGymGoalWrapper(executable_file: str | None = None, scene_file: str | None = None, assets: list = [], **kwargs)

Bases: GoalEnv, RFUniverseBaseEnv

reset()

Resets the environment to an initial state and returns an initial observation.

Note that this function should not reset the environment’s random number generator(s); random variables in the environment’s state should be sampled independently between multiple calls to reset(). In other words, each call of reset() should yield an environment suitable for a new episode, independent of previous episodes.

Returns:

the initial observation.

Return type:

observation (object)

close()

Override close in your subclass to perform any necessary cleanup.

Environments will automatically close() themselves when garbage collected or when the program exits.