airobot.utils.pb_util

class airobot.utils.pb_util.BulletClient(connection_mode=None, realtime=False, opengl_render=True, options='')[source]

Bases: object

A wrapper for pybullet to manage different clients.

Parameters:
  • connection_mode (pybullet mode) – None connects to an existing simulation or, if fails, creates a new headless simulation, pybullet.GUI creates a new simulation with a GUI, pybullet.DIRECT creates a headless simulation, pybullet.SHARED_MEMORY connects to an existing simulation.
  • realtime (bool) – whether to use realtime mode or not.
  • opengl_render (bool) – use OpenGL (hardware renderer) to render RGB images.
get_body_state(body_id)[source]

Get the body state.

Parameters:body_id (int) – body index.
Returns:4-element tuple containing
  • np.ndarray: x, y, z position of the body (shape: \([3,]\)).
  • np.ndarray: quaternion representation ([qx, qy, qz, qw]) of the body orientation (shape: \([4,]\)).
  • np.ndarray: linear velocity of the body (shape: \([3,]\)).
  • np.ndarray: angular velocity of the body (shape: \([3,]\)).
get_client_id()[source]

Return the pybullet client id.

Returns:int – pybullet client id.
in_realtime_mode()[source]

Check if the pybullet simulation is in step simulation mode or realtime simulation mode.

Returns:bool – whether the pybullet simulation is in step simulation mode or realtime simulation mode.
load_geom(shape_type, size=None, mass=0.5, visualfile=None, collifile=None, mesh_scale=None, rgba=None, specular=None, shift_pos=None, shift_ori=None, base_pos=None, base_ori=None, no_collision=False, **kwargs)[source]

Load a regular geometry (sphere, box, capsule, cylinder, mesh).

Note

Please do not call load_geom(‘capsule’) when you are using robotiq gripper. The capsule generated will be in wrong size if the mimicing thread (_th_mimic_gripper) in the robotiq gripper class starts running. This might be a PyBullet Bug (current version is 2.5.6). Note that other geometries(box, sphere, cylinder, etc.) are not affected by the threading in the robotiq gripper.

Parameters:
  • shape_type (str) – one of [sphere, box, capsule, cylinder, mesh].
  • size (float or list) –

    Defaults to None.

    If shape_type is sphere: size should be a float (radius).

    If shape_type is capsule or cylinder: size should be a 2-element list (radius, length).

    If shape_type is box: size can be a float (same half edge length for 3 dims) or a 3-element list containing the half size of 3 edges

    size doesn’t take effect if shape_type is mesh.

  • mass (float) – mass of the object in kg. If mass=0, then the object is static.
  • visualfile (str) – path to the visual mesh file. only needed when the shape_type is mesh. If it’s None, same collision mesh file will be used as the visual mesh file.
  • collifile (str) – path to the collision mesh file. only needed when the shape_type is mesh. If it’s None, same viusal mesh file will be used as the collision mesh file.
  • mesh_scale (float or list) – scale the mesh. If it’s a float number, the mesh will be scaled in same ratio along 3 dimensions. If it’s a list, then it should contain 3 elements (scales along 3 dimensions).
  • rgba (list) – color components for red, green, blue and alpha, each in range [0, 1] (shape: \([4,]\)).
  • specular (list) – specular reflection color components for red, green, blue and alpha, each in range [0, 1] (shape: \([4,]\)).
  • shift_pos (list) – translational offset of collision shape, visual shape, and inertial frame (shape: \([3,]\)).
  • shift_ori (list) – rotational offset (quaternion [x, y, z, w]) of collision shape, visual shape, and inertial frame (shape: \([4,]\)).
  • base_pos (list) – cartesian world position of the base (shape: \([3,]\)).
  • base_ori (list) – cartesian world orientation of the base as quaternion [x, y, z, w] (shape: \([4,]\)).
Returns:

int – a body unique id, a non-negative integer value or -1 for failure.

load_mjcf(filename, **kwargs)[source]

Load SDF into the pybullet client.

Parameters:filename (str) – a relative or absolute path to the MJCF file on the file system of the physics server.
Returns:int – a body unique id, a non-negative integer value. If the MJCF file cannot be loaded, this integer will be negative and not a valid body unique id.
load_sdf(filename, scaling=1.0, **kwargs)[source]

Load SDF into the pybullet client.

Parameters:
  • filename (str) – a relative or absolute path to the SDF file on the file system of the physics server.
  • scaling (float) – apply a scale factor to the SDF model.
Returns:

int – a body unique id, a non-negative integer value. If the SDF file cannot be loaded, this integer will be negative and not a valid body unique id.

load_urdf(filename, base_pos=None, base_ori=None, scaling=1.0, **kwargs)[source]

Load URDF into the pybullet client.

Parameters:
  • filename (str) – a relative or absolute path to the URDF file on the file system of the physics server.
  • base_pos (list or np.ndarray) – create the base of the object at the specified position in world space coordinates [X,Y,Z]. Note that this position is of the URDF link position.
  • base_ori (list or np.ndarray) – create the base of the object at the specified orientation as world space quaternion [X,Y,Z,W].
  • scaling (float) – apply a scale factor to the URDF model.
Returns:

int – a body unique id, a non-negative integer value. If the URDF file cannot be loaded, this integer will be negative and not a valid body unique id.

remove_body(body_id)[source]

Delete body from the simulation.

Parameters:body_id (int) – body index.
Returns:bool – whether the body is removed.
reset_body(body_id, base_pos, base_quat=None, lin_vel=None, ang_vel=None)[source]

Reset body to the specified pose and specified initial velocity.

Parameters:
  • body_id (int) – body index.
  • base_pos (list or np.ndarray) – position [x,y,z] of the body base.
  • base_ori (list or np.ndarray) – quaternion [qx, qy, qz, qw] of the body base.
  • lin_vel (list or np.ndarray) – initial linear velocity if provided.
  • ang_vel (list or np.ndarray) – initial angular velocity if provided.

Returns:

set_step_sim(step_mode=True)[source]

Turn on/off the realtime simulation mode.

Parameters:step_mode (bool) – run the simulation in step mode if it is True. Otherwise, the simulation will be in realtime.
class airobot.utils.pb_util.TextureModder(pb_client_id)[source]

Bases: object

Modify textures in model.

Parameters:

pb_client_id (int) – pybullet client id.

Variables:
  • texture_dict (dict) – a dictionary that tells the texture of a link on a body.
  • texture_files (list) – a list of texture files (usuallly images).
rand_all(body_id, link_id)[source]

Randomize color, gradient, noise, texture of the specified link.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
rand_gradient(body_id, link_id)[source]

Randomize the gradient of the color of the link.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
rand_noise(body_id, link_id)[source]

Randomly add noise to the foreground.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
rand_rgb(body_id, link_id)[source]

Randomize the color of the link.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
rand_texture(body_id, link_id)[source]

Randomly apply a texture to the link. Call set_texture_path first to set the root path to the texture files.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
randomize(mode='all', exclude=None)[source]

Randomize all the links in the scene.

Parameters:
  • mode (str) – one of all, rgb, noise, gradient.
  • exclude (dict) – exclude bodies or links from randomization. exclude is a dict with body_id as the key, and a list of link ids as the value. If the value (link ids) is an empty list, then all links on the body will be excluded.
set_gradient(body_id, link_id, rgb1, rgb2, vertical=True)[source]

Creates a linear gradient from rgb1 to rgb2.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
  • rgb1 (list or np.ndarray) – first rgb color (shape: \([3,]\)).
  • rgb2 (list or np.ndarray) – second rgb color (shape: \([3,]\)).
  • vertical (bool) – if True, the gradient in the vertical direction, if False it’s in the horizontal direction.
set_noise(body_id, link_id, rgb1, rgb2, fraction=0.9)[source]

Apply noise to the texture.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
  • rgb1 (list or np.ndarray) – background rgb color (shape: \([3,]\)).
  • rgb2 (list or np.ndarray) – color of random noise foreground color (shape: \([3,]\)).
  • fraction (float) – fraction of pixels with foreground color.
set_rgba(body_id, link_id, rgba)[source]

Set color to the link.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
  • rgba (list or np.ndarray) – red, green, blue, alpha channel (opacity of the color), (shape: \([4,]\)).
set_texture(body_id, link_id, texture_file)[source]

Apply texture to a link. You can download texture files from: https://www.robots.ox.ac.uk/~vgg/data/dtd/index.html.

Parameters:
  • body_id (int) – body index.
  • link_id (int) – link index in the body.
  • texture_file (str) – path to the texture files (image, supported format: jpg, png, jpeg, tga, or gif etc.).
set_texture_path(path)[source]

Set the root path to the texture files. It will search all the files in the folder (including subfolders), and find all files that end with .png, jpg, jpeg, tga, or gif.

Parameters:path (str) – root path to the texture files.
whiten_materials(body_id=None, link_id=None)[source]

Helper method for setting all material colors to white.

Parameters:
  • body_id (int) – unique body id when you load the body. If body_id is not provided, all the bodies will be whitened.
  • link_id (int) – the index of the link on the body. If link_id is not provided and body_id is provided, all the links of the body will be whitened.
airobot.utils.pb_util.create_pybullet_client(gui=True, realtime=True, opengl_render=True)[source]

Create a pybullet simulation client.

Parameters:
  • gui (bool) – use GUI mode or non-GUI mode.
  • realtime – use realtime simulation or step simuation.
  • opengl_render (bool) – use OpenGL (hardware renderer) to render RGB images.