pyrfuniverse.attributes package

pyrfuniverse.attributes.activelightsensor_attr module

class pyrfuniverse.attributes.activelightsensor_attr.ActiveLightSensorAttr(env, id: int, data=None)

Bases: CameraAttr

Class of IR-based depth sensor, which can simulate the noise of real-world depth camera and produce depth image in similar pattern.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘active_depth’]: IR-based depth, shape = (w,h)

Return type:

Dict

GetActiveDepth(main_intrinsic_matrix_local: ndarray, ir_intrinsic_matrix_local: ndarray)

Get IR-based depth image.

Parameters:
  • main_intrinsic_matrix_local – np.ndarray The intrinsic matrix of main camera.

  • ir_intrinsic_matrix_local – np.ndarray The intrinsic matrix of IR-based camera.

pyrfuniverse.attributes.base_attr module

class pyrfuniverse.attributes.base_attr.BaseAttr(env, id: int, data=None)

Bases: object

Base attribute class, which includes general functions such as object loading, deleting and transforming.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘name’]: The name of the object.

self.data[‘position’]: The position of the object in world coordinate.

self.data[‘rotation’]: The euler angle of the object in world coordinate.

self.data[‘quaternion’]: The quaternion of the object in world coordinate.

self.data[‘local_position’]: The position of the object in its parent’s local coordinate.

self.data[‘local_rotation’]: The euler angle of the object in its parent’s local coordinate.

self.data[‘local_quaternion’]: The quaternion of the object in its parent’s local coordinate.

self.data[‘local_to_world_matrix’]: The transformation matrix from local to world coordinate.

self.data[‘result_local_point’]: The result of transforming object from local to world coordinate.

self.data[‘result_world_point’]: The result of transforming object from world to local coordinate.

Return type:

Dict

SetType(attr_type: type)

Set the attribute type of this object

Parameters:

attr_type – Any attribute in pyrfuniverse.attributes.

Returns:

The target attribute.

SetTransform(position: list | None = None, rotation: list | None = None, scale: list | None = None, is_world: bool = True)

Set the transform of this object, including position, rotation, scale and coordinate.

Parameters:
  • position – A list of length 3, representing the target position value of object.

  • rotation – A list of length 3, representing the target euler angle value of object.

  • scale – A list of length 3, representing the target scale value of object.

  • is_world – Bool, True for world coordinate, False for local coordinate.

SetPosition(position: list | None = None, is_world: bool = True)

Set the position of this object

Parameters:
  • position – A list of length 3, representing the target position value of object.

  • is_world – Bool, True for world coordinate, False for local coordinate.

SetRotation(rotation: list | None = None, is_world: bool = True)

Set the rotation of this object

Parameters:
  • rotation – A list of length 3, representing the target euler angle value of object.

  • is_world – Bool, True for world coordinate, False for local coordinate.

SetRotationQuaternion(quaternion: list | None = None, is_world: bool = True)

Rotate this object using quaternion.

Parameters:
  • quaternion – A list of length 4, representing the quaternion from current pose.

  • is_world – Bool, True for world coordinate, False for local coordinate.

SetScale(scale: list | None = None)

Set the scale of this object

Parameters:

scale – A list of length 3, representing the target scale value of object.

Translate(translation: list, is_world: bool = True)

Translate this object.

Parameters:
  • translation – A list of length 3, representing the translation from current position.

  • is_world – Bool, True for world coordinate, False for local coordinate.

Rotate(rotation: list, is_world: bool = True)

Rotate this object.

Parameters:
  • rotation – A list of length 3, representing the euler-angle-format rotation from current euler angle.

  • is_world – Bool, True for world coordinate, False for local coordinate.

LookAt(target: list, world_up: list | 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.

SetActive(active: bool)

Set the activeness of this obeject.

Parameters:

active – Bool, True for active, False for inactive.

SetParent(parent_id: int, parent_name: str = '')

Set the parent of this object.

Parameters:
  • parent_id – Int, the id of parent object.

  • parent_name – Str, the name of parent object.

SetLayer(layer: int)

Set the layer in Unity of this object.

Parameters:

layer – Int, the number of layer.

Copy(new_id: int)

Duplicate an object.

Parameters:

new_id – Int, the id of new object.

Destroy()

Destroy this object in Unity.

GetLocalPointFromWorld(point: list)

Transform a point from local coordinate to world coordinate. After calling this method and stepping once, the result will be saved in self.data[‘result_local_point’]

Parameters:

point – A list of length 3, representing the position of a point.

GetWorldPointFromLocal(point: list)

Transform a point from world coordinate to local coordinate. After calling this method and stepping once, the result will be saved in self.data[‘result_world_point’]

Parameters:

point – A list of length 3, representing the position of a point.

pyrfuniverse.attributes.camera_attr module

class pyrfuniverse.attributes.camera_attr.CameraAttr(env, id: int, data=None)

Bases: BaseAttr

Camera attribute class, which can capture many kinds of screenshot of the scene in RFUniverse.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘width’]: The width of image.

self.data[‘height’]: The height of image.

self.data[‘fov’]: The field of view of camera.

self.data[‘rgb’]: The bytes of rgb image.

self.data[‘normal’]: The bytes of normal image.

self.data[‘id_map’]: The bytes of instance segmentation mask image.

self.data[‘depth’]: The bytes of depth image.

self.data[‘depth_exr’]: The bytes of depth image in exr format.

self.data[‘amodal_mask’]: The bytes of amodal mask image.

self.data[‘heat_map’]: The bytes of heat map image.

self.data[‘2d_bounding_box’]: The 2d bouding box of objects in camera (image) coordinate.

self.data[‘3d_bounding_box’]: The 3d bounding box of objects in world coordinate.

Return type:

Dict

AlignView()

Make the camera in RFUniverse align the current view in GUI.

GetRGB(width: int = 512, height: int = 512, fov: float = 60.0, intrinsic_matrix: ndarray | None = None)

Get the camera RGB image.

Parameters:
  • width – Int, the width of image.

  • height – Int, the height of image.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

GetNormal(width: int = 512, height: int = 512, fov: float = 60.0, intrinsic_matrix: ndarray | None = None)

Get the normal image in world coordinate.

Parameters:
  • width – Int, the width of image.

  • height – Int, the height of image.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

GetID(width: int = 512, height: int = 512, fov: float = 60.0, intrinsic_matrix: ndarray | None = None)

Get the instance segmentation mask image. The color for each pixel is computed from object ID, see pyrfuniverse.utils.rfuniverse_utility.GetColorFromID for more details.

Parameters:
  • width – Int, the width of image.

  • height – Int, the height of image.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

GetDepth(zero_dis: float, one_dis: float, width: int = 512, height: int = 512, fov: float = 60.0, intrinsic_matrix: ndarray | None = None)

Get the depth image from camera. Since eacg pixel of depth image returned from this function is 8-bit, user should limit the depth range (zero_dis and one_dis) for more accurate results.

Parameters:
  • zero_dis – The minimum distance in calculation.

  • one_dis – The maximum distance in calculation.

  • width – Int, the width of image.

  • height – Int, the height of image.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

GetDepthEXR(width: int = 512, height: int = 512, fov: float = 60.0, intrinsic_matrix: ndarray | None = None)

Get the depth image from camera. This function returns EXR format image bytes and each pixel is 32-bit.

Parameters:
  • width – Int, the width of image.

  • height – Int, the height of image.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

GetAmodalMask(target_id: int, width: int = 512, height: int = 512, fov: float = 60, intrinsic_matrix: ndarray | None = None)

Get the amodal mask image for target object.

Parameters:
  • target_id – The target object ID.

  • width – Int, the width of image.

  • height – Int, the height of image.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

GetHeatMap(width: int = 512, height: int = 512, radius: int = 50, fov: float = 60.0, intrinsic_matrix: ndarray | None = None)

Get the heat map image.

Parameters:
  • width – Int, the width of image.

  • height – Int, the height of image.

  • radius – The radius of heat map.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

Get2DBBox(width: int = 512, height: int = 512, fov: float = 60.0, intrinsic_matrix: ndarray | None = None)

Get the 2d bounding box of objects in current camera view.

Parameters:
  • width – Int, the width of image.

  • height – Int, the height of image.

  • radius – The radius of heat map.

  • fov – Float, the field of view for camera.

  • intrinsic_matrix – A ndarray of shape 3*3, representing the camera intrinsic matrix. When this parameter is passed, width, height and fov will be ignroed.

Get3DBBox()

Get the 3d bounding box of objects in world coordinate.

pyrfuniverse.attributes.cloth_attr module

class pyrfuniverse.attributes.cloth_attr.ClothAttr(env, id: int, data=None)

Bases: BaseAttr

Obi cloth class.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

Return type:

Dict

pyrfuniverse.attributes.collider_attr module

class pyrfuniverse.attributes.collider_attr.ColliderAttr(env, id: int, data=None)

Bases: GameObjectAttr

Collider class for objects who have collider in Unity.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

Return type:

Dict

EnabledAllCollider(enabled: bool)

Set the collider enabled or unenabled.

Parameters:

active – Bool, True for enable and False for unenable.

SetPhysicMaterial(bounciness: float, dynamicFriction: float, staticFriction: float, frictionCombine: int, bounceCombine: int)

Set the collider physical material.

Parameters:
  • bounciness (float) – The coefficient of restitution or “bounciness” of the collider. It determines how much kinetic energy is retained after a collision. A value of 0 means no bounce, while a value of 1 means a perfect bounce.

  • dynamicFriction (float) – The coefficient of friction when the collider is in motion relative to another collider. It determines how much resistance there is when the collider is sliding against another surface.

  • staticFriction (float) – The coefficient of friction when the collider is at rest relative to another collider. It determines the resistance to initiating motion between the collider and another surface.

  • frictionCombine (int) – An integer representing how friction values should be combined when multiple colliders interact. It can take on values such as: - 0: Average - 1: Minimum - 2: Maximum - 3: Multiply These values define how friction will be calculated when multiple colliders are in contact.

  • bounceCombine (int) – An integer representing how bounce values should be combined when multiple colliders interact. It can take on values such as: - 0: Average - 1: Minimum - 2: Maximum - 3: Multiply These values define how bounciness will be calculated when multiple colliders are in contact.

SetRFMoveColliderActive(active: bool)

Set the collider active or inactive in RFMove.

Parameters:

active – Bool, True for active and False for inactive.

GenerateVHACDColider()

Generate convex colliders using VHACD algorithm.

pyrfuniverse.attributes.controller_attr module

class pyrfuniverse.attributes.controller_attr.ControllerAttr(env, id: int, data=None)

Bases: ColliderAttr

Robot controller class, which will control robot arms, hands and embodied robots.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘number_of_joints’]: The number of joints in an articulation.

self.data[‘positions’]: The position of each part in an articulation.

self.data[‘rotations’]: The rotation of each part in an articulation.

self.data[‘quaternion’]: The quaternion of each part in an articulation.

self.data[‘local_positions’]: The local position of each part in an articulation.

self.data[‘local_rotations’]: The local rotation of each part in an articulation.

self.data[‘local_quaternion’]: The local quaternion of each part in an articulation.

self.data[‘velocities’]: The velocity of each part in an articulation.

self.data[‘number_of_moveable_joints’]: The number of moveable joints in an articulation.

self.data[‘joint_positions’]: The joint position of each moveable joint in an articulation.

self.data[‘joint_velocities’]: The joint velocity of each moveable joint in an articulation.

self.data[‘all_stable’]: Whether all joints have finished moving.

self.data[‘move_done’]: Whether robot arm IK has finished moving.

self.data[‘rotate_done’]: Whether robot arm IK has finished rotating.

self.data[‘gravity_forces’]: Inverse Dynamics force needed to counteract gravity.

self.data[‘coriolis_centrifugal_forces’]: Inverse Dynamics force needed to counteract coriolis centrifugal forces.

self.data[‘drive_forces’]: Inverse Dynamics drive forces.

Return type:

Dict

SetJointPosition(joint_positions: list, speed_scales: list | None = None)

Set the target joint position for each moveable joint and move with PD control.

Parameters:
  • joint_positions – A list of float, representing the target joint positions.

  • speed_scales – A list of float, representing the speed scale.

SetJointPositionDirectly(joint_positions: list)

Set the target joint position for each moveable joint and move directly.

Parameters:

joint_positions – A list of float, representing the target joint positions.

SetIndexJointPosition(index: int, joint_position: float)

Set the target joint position for a given joint and move with PD control.

Parameters:
  • index – Int, joint index.

  • joint_position – Float, the target joint position.

SetIndexJointPositionDirectly(index: int, joint_position: float)

Set the target joint position for a given joint and move directly.

Parameters:
  • index – Int, joint index.

  • joint_position – Float, the target joint position.

SetJointPositionContinue(interval: int, time_joint_positions: list)

Set the target joint position for each moveable joint and move with PD control continuously.

Parameters:
  • interval – Float, the time interval.

  • time_joint_positions – A list of float list, representing the target joint positions at each time step.

SetJointVelocity(joint_velocitys: list)

Set the target joint velocity for each moveable joint.

Parameters:

joint_velocitys – A list of float, representing the target joint velocities.

SetIndexJointVelocity(index: int, joint_velocity: float)

Set the target joint velocity for a given joint.

Parameters:
  • index – Int, joint index.

  • joint_velocity – A list of float, representing the target joint velocities.

AddJointForce(joint_forces: list)

Add force to each moveable joint.

Parameters:

joint_forces – A list of forces, representing the added forces.

AddJointForceAtPosition(joint_forces: list, force_positions: list)

Add force to each moveable joint at a given position.

Parameters:
  • joint_forces – A list of forces, representing the added forces.

  • force_positions – A list of positions, representing the positions for forces.

AddJointTorque(joint_torques: list)

Add torque to each moveable joint.

Parameters:

joint_torques – A list of torques, representing the added torques.

GetJointInverseDynamicsForce()

Get the joint inverse dynamic force of each moveable joint. Note that this function only works in Unity version >= 2022.1.

SetImmovable(immovable: bool)

Set whether the base of articulation is immovable.

Parameters:

immovable – Bool, True for immovable, False for movable.

MoveForward(distance: float, speed: float)

Move robot forward. Only works if the robot controller has implemented functions inherited from ICustomMove.cs. See https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ICustomMove.cs and https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ToborMove.cs for more details.

Parameters:
  • distance – Float, distance.

  • speed – Float, velocity.

MoveBack(distance: float, speed: float)

Move robot backword. Only works if the robot controller has implemented functions inherited from ICustomMove.cs. See https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ICustomMove.cs and https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ToborMove.cs for more details.

Parameters:
  • distance – Float, distance.

  • speed – Float, velocity.

TurnLeft(angle: float, speed: float)

Turn robot left. Only works if the robot controller has implemented functions inherited from ICustomMove.cs. See https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ICustomMove.cs and https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ToborMove.cs for more details.

Parameters:
  • angle – Float, rotation angle.

  • speed – Float, velocity.

TurnRight(angle: float, speed: float)

Turn robot right. Only works if the robot controller has implemented functions inherited from ICustomMove.cs. See https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ICustomMove.cs and https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ToborMove.cs for more details.

Parameters:
  • angle – Float, rotation angle.

  • speed – Float, velocity.

GripperOpen()

Open the gripper. Only works if the robot controller has implemented functions inherited from ICustomGripper.cs. See https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ICustomGripper.cs and https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/GeneralGripper.cs for more details.

GripperClose()

Close the gripper. Only works if the robot controller has implemented functions inherited from ICustomGripper.cs. See https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/ICustomGripper.cs and https://github.com/mvig-robotflow/rfuniverse/blob/main/Assets/RFUniverse/Scripts/Utils/GeneralGripper.cs for more details.

EnabledNativeIK(enabled: bool)

Enable or disable the native IK algorithm.

Parameters:

enabled – Bool, True for enable and False for disable.When it is True, through the IKTatGetDo*** interface, according to the end pose.When it is False, through the SetJoint*** interface, according to the joint movement.NativeIK can only take effect when it is started during initialization.

IKTargetDoMove(position: list, duration: float, speed_based: bool = True, relative: bool = False)

Native IK target movement.

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

  • duration – Float, if speed_based is True, it represents movement duration; otherwise, it represents movement speed.

  • speed_based – Bool.

  • relative – Bool, if True, position is relative; otherwise, position is absolute.

IKTargetDoRotate(rotation: list, duration: float, speed_based: bool = True, relative: bool = False)

Native IK target rotation.

Parameters:
  • rotation – A list of length 3, representing the rotation.

  • duration – Float, if speed_based is True, it represents movement duration; otherwise, it represents movement speed.

  • speed_based – Bool.

  • relative – Bool, if True, rotation is relative; otherwise, rotation is absolute.

IKTargetDoRotateQuaternion(quaternion: list, duration: float, speed_based: bool = True, relative: bool = False)

Native IK target rotation using quaternion.

Parameters:
  • quaternion – A list of length 4, representing the quaternion.

  • duration – Float, if speed_based is True, it represents movement duration; otherwise, it represents movement speed.

  • speed_based – Bool.

  • relative – Bool, if True, quaternion is relative; otherwise, quaternion is absolute.

IKTargetDoComplete()

Make native IK target movement / rotation complete directly.

IKTargetDoKill()

Make native IK target movement / rotation stop.

SetIKTargetOffset(position: list = [0.0, 0.0, 0.0], rotation: list = [0.0, 0.0, 0.0], quaternion: list | None = None)

Set the new IK target by setting offset to the original target of native IK.

Parameters:
  • position – A list of length 3, representing the position offset to original target.

  • rotation – A list of length 3, representing the rotation offset to original target.

  • quaternion – A list of length 4, representing the quaternion offset to original target. If this parameter is specified, rotation will be ignored.

WaitDo()

Wait for the native IK target movement / rotation complete.

pyrfuniverse.attributes.digit_attr module

class pyrfuniverse.attributes.digit_attr.DigitAttr(env, id: int, data=None)

Bases: BaseAttr

Class for simulating DIGIT tactile sensor.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘light’]: Bytes of RGB light image in DIGIT.

self.data[‘depth’]: Bytes of depth image in DIGIT.

Return type:

Dict

GetData()

Get data from DIGIT in RFUniverse.

pyrfuniverse.attributes.gameobject_attr module

class pyrfuniverse.attributes.gameobject_attr.GameObjectAttr(env, id: int, data=None)

Bases: BaseAttr

Basic game object attribute class.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘3d_bounding_box’]: The 3d bounding box of objects.

Return type:

Dict

SetColor(color: list)

Set object color.

Parameters:

color – A list of length 4, represenging r, g, b and a. Each float is in range (0, 1).

EnabledRender(enabled: bool)

Enable or disable rendering system.

Parameters:

enabled – Bool, Ture for enable rendering and False for disable rendering.

SetTexture(path: str)

Set the texture of object.

Parameters:

path – Str, the absolute path for texture file.

Get3DBBox()

Get the 3d bounding box of this object.

pyrfuniverse.attributes.graspsim_attr module

class pyrfuniverse.attributes.graspsim_attr.GraspSimAttr(env, id: int, data=None)

Bases: BaseAttr

Grasp pose simulation class.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘done’]: Whether the simulation is done

self.data[‘points’]: The list of grasp points.

self.data[‘quaternions’]: The list of grasping pose quaternions.

self.data[‘width’]: The list of gripper width of grasping pose.

self.data[‘success’]: The list of success or failure of the grasing pose.

Return type:

Dict

StartGraspSim(mesh: str, gripper: str, points: list, normals: list, depth_range_min: float, depth_range_max: float, depth_lerp_count: int, angle_lerp_count: int, parallel_count: int = 100)

Start simulating grasping.

Parameters:
  • mesh – Str, the absolute path to .obj file.

  • gripper – Str, the name of the gripper.

  • points – A list of float, representing the grasping points.

  • normals – A list of float, representing the normals.

  • depth_range_min – Float, the minimum depth of grasp pose.

  • depth_range_max – Float, the maximum depth of grasp pose.

  • depth_lerp_count – Int, the interpolation count of depth.

  • angle_lerp_count – Int, the interpolation count of angle.

  • parallel_count – Int, the count of parallel grasping.

GenerateGraspPose(mesh: str, gripper: str, points: list, normals: list, depth_range_min: float, depth_range_max: float, depth_lerp_count: int, angle_lerp_count: int)

Generate grasp poses and visualize grasp results.

Parameters:
  • mesh – Str, the absolute path to .obj file.

  • gripper – Str, the name of the gripper.

  • points – A list of float, representing the grasping points.

  • normals – A list of float, representing the normals.

  • depth_range_min – Float, the minimum depth of grasp pose.

  • depth_range_max – Float, the maximum depth of grasp pose.

  • depth_lerp_count – Int, the interpolation count of depth.

  • angle_lerp_count – Int, the interpolation count of angle.

StartGraspTest(mesh: str, gripper: str, points: list, quaternions: list, parallel_count: int = 100)

Start testing the grasp based on current grasp poses.

Parameters:
  • mesh – Str, the absolute path to .obj file.

  • gripper – Str, the name of the gripper.

  • points – A list of float, representing the grasping points.

  • quaternions – A list of float, representing the quaternions.

  • parallel_count – Int, the interpolation count of angle.

ShowGraspPose(mesh: str, gripper: str, positions: list, quaternions: list)

Display grasp poses.

Parameters:
  • mesh – Str, the absolute path to .obj file.

  • gripper – Str, the name of the gripper.

  • points – A list of float, representing the grasping points.

  • quaternions – A list of float, representing the quaternions.

pyrfuniverse.attributes.humanbody_attr module

class pyrfuniverse.attributes.humanbody_attr.HumanbodyAttr(env, id: int, data=None)

Bases: BaseAttr

Human body Inverse Kinematic class.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘move_done’]: Whether the movement has finished.

self.data[‘rotate_done’]: Whether the rotation has finished.

Return type:

Dict

HumanIKTargetDoMove(index: int, position: list, duration: float, speed_based: bool = True, relative: bool = False)

Human body Inverse Kinematics target movement.

Parameters:
  • index – Int, the target for movement. 0 for left hand, 1 for right hand,2 for left foot, 3 for right foot, 4 for head.

  • position – A list of length 3, representing the position.

  • duration – Float, if speed_based is True, it represents movement duration; otherwise, it represents movement speed.

  • speed_based – Bool.

  • relative – Bool, if True, position is relative; otherwise, position is absolute.

HumanIKTargetDoRotate(index: int, rotation: list, duration: float, speed_based: bool = True, relative: bool = False)

Human body Inverse Kinematics target rotation.

Parameters:
  • index – Int, the target for movement. 0 for left hand, 1 for right hand,2 for left foot, 3 for right foot, 4 for head.

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

  • duration – Float, if speed_based is True, it represents movement duration; otherwise, it represents movement speed.

  • speed_based – Bool.

  • relative – Bool, if True, rotation is relative; otherwise, rotation is absolute.

HumanIKTargetDoRotateQuaternion(index: int, quaternion: list, duration: float, speed_based: bool = True, relative: bool = False)

Human body Inverse Kinematics target rotation using quaternion.

Parameters:
  • index – Int, the target for movement. 0 for left hand, 1 for right hand,2 for left foot, 3 for right foot, 4 for head.

  • quaternion – A list of length 4, representing the quaternion.

  • duration – Float, if speed_based is True, it represents movement duration; otherwise, it represents movement speed.

  • speed_based – Bool.

  • relative – Bool, if True, quaternion is relative; otherwise, quaternion is absolute.

HumanIKTargetDoComplete(index: int)

Make the human body IK target movement / rotation complete directly.

Parameters:

index – Int, the target for movement. 0 for left hand, 1 for right hand,2 for left foot, 3 for right foot, 4 for head.

HumanIKTargetDoKill(index: int)

Make the human body IK target movement / rotation stop.

Parameters:

index – Int, the target for movement. 0 for left hand, 1 for right hand,2 for left foot, 3 for right foot, 4 for head.

WaitDo()

Wait for the human body IK target movement / rotation complete.

pyrfuniverse.attributes.light_attr module

class pyrfuniverse.attributes.light_attr.LightType(value)

Bases: Enum

The type of light, keeping same name with LightType (https://docs.unity3d.com/ScriptReference/LightType.html) in Unity.

class pyrfuniverse.attributes.light_attr.LightShadow(value)

Bases: Enum

The type of shadow, keeping same name with LightShadows (https://docs.unity3d.com/ScriptReference/LightShadows.html) in Unity.

class pyrfuniverse.attributes.light_attr.LightAttr(env, id: int, data=None)

Bases: BaseAttr

Light attribute class.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

Return type:

Dict

SetColor(color: list)

Set the color of light.

Parameters:

color – A list of length 3, representing the R, G and B channel, in range [0, 1].

SetType(light_type: LightType)

Set the type of light.

Parameters:

light_type – LightType, the type of light.

SetShadow(light_shadow: LightShadow)

Set the type of shadow.

Parameters:

light_shadow – LightShadow, the type of the shadow.

SetIntensity(light_intensity: float)

Set the intensity of light.

Parameters:

light_intensity – Float, the intensity of light.

SetRange(light_range: float)

Set the range of light. (Only available when the LightType is LightType.Spot or LightType.Point)

Parameters:

light_range – Float, the range of light.

SetSpotAngle(spot_angle: float)

Set the angle of light. (Only available when the LightType is LightType.Spot)

Parameters:

spot_angle – Float, the angle of light.

pyrfuniverse.attributes.pointcloud_attr module

class pyrfuniverse.attributes.pointcloud_attr.PointCloudAttr(env, id: int, data=None)

Bases: BaseAttr

Point cloud rendering class.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

Return type:

Dict

ShowPointCloud(positions: ndarray | None = None, colors: ndarray | None = None, ply_path: str | None = None, radius: float = 0.01)

Display point cloud in Unity.

Parameters:
  • positions – A list of positions of points in a point cloud.

  • colors – A list of colors of points (range [0, 1]) in a point cloud.

  • ply_path – Str, the absolute path of .ply file. If this parameter is specified, positions and colors will be ignored.

  • radius – Float, the radius of the point cloud.

SetRadius(radius: float)

Set the radius for points in a point cloud.

Parameters:

radius – Float, the radius.

pyrfuniverse.attributes.rigidbody_attr module

class pyrfuniverse.attributes.rigidbody_attr.RigidbodyAttr(env, id: int, data=None)

Bases: ColliderAttr

Rigid body class.

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

self.data[‘velocity’]: The velocity of the object.

self.data[‘angular_vel’]: The angular velcity of the object.

Return type:

Dict

SetMass(mass: float)

Set the mass of this rigid body object

Parameters:

mass – Float, representing the mass of this rigid body.

AddForce(force: list)

Add force to this rigid body object.

Parameters:

force – A list of length 3, representing the force added to this rigid body.

SetVelocity(velocity: list)

Set the velocity of this rigid body object.

Parameters:

velocity – A list of length 3, representing the velocity of this rigid body.

SetKinematic(is_kinematic: bool)

Set the Rigidbody is kinematic or not.

Parameters:

is_kinematic – is kinematic or not.

pyrfuniverse.attributes.softbody_attr module

class pyrfuniverse.attributes.softbody_attr.SoftbodyAttr(env, id: int, data=None)

Bases: BaseAttr

Obi Softbody class

parse_message(data: dict)

Parse messages. This function is called by internal function.

Returns:

A dict containing useful information of this class.

Return type:

Dict