pyrcareworld.envs package

Contents

pyrcareworld.envs package#

Submodules#

pyrcareworld.envs.base_env module#

class pyrcareworld.envs.base_env.RCareWorld(executable_file: str = None, scene_file: str = None, assets: list = [], graphics: bool = True, port: int = 5004, proc_id=0, log_level=0, ext_attr: list = [], check_version: bool = True)[source]#

Bases: ABC

RCareWorld base environment class.

Parameters:
  • executable_file – Str, the absolute path of the Unity executable file. Use None to use config.json; use “@editor” to use Unity Editor.

  • scene_file – Str, the absolute path of the Unity scene JSON file. All JSON files are located at <PlayerName>_Data/StreamingAssets/SceneData by default. This is located in the build for the executable files.

  • assets – List, the list of pre-loaded assets. All assets in the list will be pre-loaded in Unity when the environment is initialized, saving time during instantiation.

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

  • port – Int, the port for communication.

  • proc_id – Int, the process ID for the Unity environment. 0 for the first process, 1 for the second process, and so on.

  • log_level – Int, the log level for the Unity environment. 0 for no log, 1 for error logs, 2 for warnings and errors, 3 for all logs.

  • ext_attr – List, the list of extended attributes. All extended attributes will be added to the environment. (Deprecated in RCareWorld 1.5.0)

  • check_version – Bool, True for checking the version of the Unity environment and the pyrcareworld library, False for not checking the version.

AddListener(message: str, fun)[source]#

Add a listener.

Parameters:
  • message – Str, the message head.

  • fun – Callable, the callback function.

AddListenerObject(head: str, fun)[source]#

Add an object listener.

Parameters:
  • head – Str, the message head.

  • fun – Callable, the callback function.

AlignCamera(camera_id: int) None[source]#

Align the current GUI view to a given camera.

Parameters:

camera_id – Int, camera id.

ClearScene() None[source]#

Clear the current scene.

Collect()[source]#

Collect environment data.

CopyPhysicsScene(new_id: int, copy_id: int) None[source]#

Copy a physics scene.

Parameters:
  • new_id – int, new physics scene id.

  • copy_id – int, copy physics scene id.

Debug2DBBox(enabled: bool = True) None[source]#

Show or hide the 2D bounding box of objects for debugging.

Parameters:

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

Debug3DBBox(enabled: bool = True) None[source]#

Show or hide the 3D bounding box of objects for debugging.

Parameters:

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

DebugColliderBound(enabled: bool = True) None[source]#

Show or hide the collider bounding box for debugging.

Parameters:

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

DebugCollisionPair(enabled: bool = True) None[source]#

Show or hide collision pairs for debugging.

Parameters:

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

DebugGraspPoint(enabled: bool = True) None[source]#

Show or hide the end effector of the robot arm for debugging.

Parameters:

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

Show or hide joint information of articulation for debugging.

Parameters:

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

DebugObjectID(enabled: bool = True) None[source]#

Show or hide the object ID for debugging.

Parameters:

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

DebugObjectPose(enabled: bool = True) None[source]#

Show or hide the object base point for debugging.

Parameters:

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

EnabledGroundObiCollider(enabled: bool) None[source]#

Enable or disable the Ground ObiCollider.

Parameters:

enabled – Bool, the Ground ObiCollider enabled.

ExportOBJ(items_id: list, save_path: str) None[source]#

Export the specified object list to an 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.

GetAttr(id: int)[source]#

Get the attribute instance by object ID.

Parameters:

id – Int, object ID.

Returns:

pyrcareworld.attributes.BaseAttr, an instance of the attribute.

Raises:

AssertionError – If the ID does not exist.

GetCurrentCollisionPairs() None[source]#

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

GetRFMoveColliders() None[source]#

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

GetViewTransform() None[source]#

Get the GUI view transform.

After calling this method and stepping once, the result will be saved in env.data[‘view_position’] / env.data[‘view_rotation’] / env.data[‘view_quaternion’].

IgnoreLayerCollision(layer1: int, layer2: int, ignore: bool) None[source]#

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.

InstanceObject(name: str, id: int = None, attr_type: type = <class 'pyrcareworld.attributes.base_attr.BaseAttr'>)[source]#

Instantiate an object.

Built-in assets:

BaseAttr:
  • “Empty”

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:
ControllerAttr:
Gripper:
  • “allegro_hand_right”

  • “bhand”

  • “svh”

  • “robotiq_arg2f_85_model”

  • “dh_robotics_ag95_gripper”

  • “shadowhand”

Robot arm:
  • “kinova_gen3”

  • “ur5”

  • “flexivArm”

  • “tobor_r300”

Robot arm and gripper:
  • “franka_panda”

  • “kinova_gen3_robotiq85”

  • “ur5_robotiq85”

  • “tobor_r300_ag95_ag95”

  • “tobor_r300_robotiq85_robotiq85”

  • “flexivArm_ag95”

  • “yumi”

CameraAttr:
  • “Camera”

LightAttr:
  • “Light”

PointCloudAttr:
  • “PointCloud”

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

  • id – Int, object id.

  • attr_type – type, the attribute type. This parameter helps the editor identify types/completion codes.

Returns:

type(attr_type), the object attribute instance.

Return type:

attr_type

LoadCloth(path: str, id: int = None) ClothAttr[source]#

Load a mesh to Cloth.

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

  • id – Int, object id.

Returns:

pyrcareworld.attributes.ClothAttr, the cloth attribute instance.

LoadMesh(path: str, id: int = None, collider_mode: str = 'VHACD') RigidbodyAttr[source]#

Load a model from a Mesh file.

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

  • id – Int, object id.

  • collider_mode – Str, how to generate collisions for the model. Can be “VHACD”/”CoACD”/”Convex”/Any other is None Collider.

Returns:

pyrcareworld.attributes.RigidbodyAttr, the object attribute instance.

LoadSceneAsync(file: str, auto_wait: bool = False) None[source]#

Load the scene asynchronously.

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

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

LoadURDF(path: str, id: int = None, native_ik: bool = False, axis: str = 'y') ControllerAttr[source]#

Load a model from a 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 True, use the IKTargetDo*** interface for end pose; when False, use the SetJoint*** interface for joint movement.

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

Returns:

pyrcareworld.attributes.ControllerAttr, the object attribute instance.

NewPhysicsScene(physics_scene_id: int) None[source]#

Place all current scene objects into the new physics scene, and all objects are prefixed with the ID of the physical scene.

Parameters:

physics_scene_id – int, physics scene id.

Pend(simulate: bool = True, collect: bool = True) None[source]#

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

Parameters:
  • simulate – Bool, if True, simulate physics.

  • collect – Bool, if True, collect data.

PreLoadAssetsAsync(names: list, auto_wait: bool = False) None[source]#

Pre-load the assets.

Parameters:
  • names – List, the names of assets.

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

RemoveListener(message: str, fun)[source]#

Remove a listener.

Parameters:
  • message – Str, the message head.

  • fun – Callable, the callback function.

RemoveListenerObject(type: str)[source]#

Remove an object listener.

Parameters:

type – Str, the message head.

SaveScene(file: str) None[source]#

Save the current scene.

Parameters:

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

SendLog(log: str) None[source]#

Send a log message and show it on the Unity GUI window.

Parameters:

log – Str, log message.

SendMessage(message: str, *args) None[source]#

Send a 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[source]#

Send an 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.

SetGravity(x: float, y: float, z: float) None[source]#

Set the gravity of the environment.

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

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

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

SetGroundActive(active: bool) None[source]#

Set the ground to be 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[source]#

Set the physics material of the ground in the 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 as friction_combine.

SetResolution(resolution_x: int, resolution_y: int) None[source]#

Set the resolution of the windowed GUI.

Parameters:
  • resolution_x – Int, window width.

  • resolution_y – Int, window height.

SetShadowDistance(distance: float) None[source]#

Set the shadow distance for rendering in the environment.

Parameters:

distance – Float, the shadow distance measured in meters.

SetTimeScale(time_scale: float) None[source]#

Set the time scale in Unity.

Parameters:

time_scale – Float, the time scale in Unity.

SetTimeStep(delta_time: float) None[source]#

Set the time for a step in Unity.

Parameters:

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

SetViewBackGround(color: list = None) None[source]#

Set the GUI view background.

Parameters:

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

SetViewTransform(position: list = None, rotation: list = None) None[source]#

Set the GUI view.

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

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

ShowArticulationParameter(controller_id: int) None[source]#

Show Articulation Parameter on the Unity GUI window.

Parameters:

controller_id – int, controller_attr id.

Simulate(time_step: float = -1, count: int = 1)[source]#

Physics simulation.

Parameters:
  • time_step – Float, the delta time of simulation per step. Default is -1.

  • count – Int, the number of simulation steps. Default is 1.

SimulatePhysicsScene(physics_scene_id: int, time_step: float = -1, count: int = 1) None[source]#

Physics scene simulation.

Parameters:
  • physics_scene_id – int, physics scene id.

  • time_step – Float, delta time of simulation per step.

  • count – Int, count of simulations.

SwitchSceneAsync(name: str, auto_wait: bool = False) None[source]#

Switch the scene asynchronously.

Parameters:
  • name – Str, the scene name.

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

ViewLookAt(target: list, world_up: list = None) None[source]#

Rotate the transform so the forward vector points at the 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.

WaitLoadDone() None[source]#

Wait for the loading to be done.

WaitSceneInit() None[source]#

Wait for the scene initialization to be done.

close()[source]#

Close the environment

metadata = {'render.modes': ['human', 'rgb_array']}#
step(count: int = 1, simulate: bool = True, collect: bool = True)[source]#

Send the messages of called functions to Unity and simulate for a step, then accept the data from Unity. The difference of this function with _step is that this function is designed to be overwritten if there is a new class inherited from RCareWorld.

Parameters:
  • count – Int, the number of steps for executing Unity simulation.

  • simulate – Bool, True to simulate physics, False otherwise.

  • collect – Bool, True to collect data, False otherwise.

Raises:

Exception – If the Unity environment is not connected.

pyrcareworld.envs.gym_wrapper_env module#

Module contents#